diff --git a/.github/workflows/test-graph-jacobian.yml b/.github/workflows/test-graph-jacobian.yml index 94f49d7..5fd81e0 100644 --- a/.github/workflows/test-graph-jacobian.yml +++ b/.github/workflows/test-graph-jacobian.yml @@ -26,7 +26,7 @@ jobs: - name: Install dependencies run: | - python -m pip install --break-system-packages --no-cache-dir --target /tmp/pydeps pytest warp-lang + python -m pip install --break-system-packages --no-cache-dir --target /tmp/pydeps pytest warp-lang matplotlib python -m pip install --break-system-packages --no-cache-dir --target /tmp/pydeps --no-deps --no-build-isolation "git+https://github.com/pypose/pypose.git" env: PIP_CACHE_DIR: /tmp/pip-cache diff --git a/.gitignore b/.gitignore index 16d9ef3..5f2f66a 100644 --- a/.gitignore +++ b/.gitignore @@ -13,3 +13,4 @@ task.md *.png .DS_Store tmp/* +examples/module/pgo/data/* diff --git a/bae/__init__.py b/bae/__init__.py index e69de29..057e015 100644 --- a/bae/__init__.py +++ b/bae/__init__.py @@ -0,0 +1,3 @@ +from .utils.pypose_ambient_grad import maybe_install_pypose_ambient_grad_monkeypatch + +maybe_install_pypose_ambient_grad_monkeypatch() diff --git a/bae/autograd/graph.py b/bae/autograd/graph.py index e041ee5..a069159 100644 --- a/bae/autograd/graph.py +++ b/bae/autograd/graph.py @@ -1,5 +1,6 @@ from typing import Optional +import warnings import pypose as pp import torch @@ -172,13 +173,18 @@ def update_from_trace(bsrt: torch.Tensor, arg, new_col: Optional[torch.Tensor]=N ) return jac_trace -def backward(output_): +def backward(output_, is_root=False): + # For non-root recursion, no incoming trace means no contribution to + # propagate. This avoids re-initializing identity traces on revisits. + if (not is_root) and (not hasattr(output_, 'jactrace')): + return + if output_.optrace[id(output_)][0] == 'map': func = output_.optrace[id(output_)][1] args = output_.optrace[id(output_)][2] argnums = tuple(idx for idx, arg in enumerate(args) if hasattr(arg, 'optrace') or isinstance(arg, torch.nn.Parameter)) if len(argnums) == 0: - warning("No upstream parameters to compute jacobian") + warnings.warn("No upstream parameters to compute jacobian", stacklevel=2) return with pp.retain_ltype(): jac_blocks = torch.vmap(jacrev(func, argnums=argnums))(*args) @@ -207,9 +213,22 @@ def backward(output_): elif isinstance(output_.jactrace, torch.Tensor) and output_.jactrace.layout == torch.sparse_bsr: jac_trace = update_from_trace(output_.jactrace, arg, new_val=jac_block) amend_trace(arg, jac_trace) + # Recurse once per unique upstream tensor after all local contributions + # have been accumulated. + seen = set() for argidx in argnums: - if isinstance(args[argidx], torch.Tensor) and hasattr(args[argidx], 'optrace'): - backward(args[argidx]) + arg = args[argidx] + if isinstance(arg, torch.Tensor) and hasattr(arg, 'optrace'): + arg_id = id(arg) + if arg_id in seen: + continue + seen.add(arg_id) + backward(arg, is_root=False) + + # Consume intermediate trace to avoid re-propagating it when this node is + # reached again from another downstream branch (e.g. two index ops on one cat). + if hasattr(output_, 'jactrace'): + delattr(output_, 'jactrace') elif output_.optrace[id(output_)][0] == 'index': @@ -220,6 +239,8 @@ def backward(output_): # populate Jacobian values. In this case, the Jacobian block values are # identity matrices placed at the indexed columns. if not hasattr(output_, 'jactrace'): + if not is_root: + return if output_.ndim == 1: eye_blocks = torch.ones((output_.shape[0], 1, 1), device=output_.device, dtype=output_.dtype) else: @@ -242,7 +263,10 @@ def backward(output_): amend_trace(arg, jac_trace) if isinstance(arg, torch.Tensor) and hasattr(arg, 'optrace'): - backward(arg) + backward(arg, is_root=False) + + if hasattr(output_, 'jactrace'): + delattr(output_, 'jactrace') elif output_.optrace[id(output_)][0] == 'cat': dim = output_.optrace[id(output_)][1] @@ -251,6 +275,8 @@ def backward(output_): raise NotImplementedError("Only torch.cat(..., dim=0) is supported") if not hasattr(output_, 'jactrace'): + if not is_root: + return if output_.ndim == 1: eye_blocks = torch.ones((output_.shape[0], 1, 1), device=output_.device, dtype=output_.dtype) else: @@ -265,6 +291,12 @@ def backward(output_): n = arg.shape[0] start, end = offset, offset + n + # Fixed/non-optimizable tensors (e.g., gauge-fixed first pose) do + # not need Jacobian traces. + if not (hasattr(arg, 'optrace') or isinstance(arg, torch.nn.Parameter)): + offset = end + continue + if type(upstream) is tuple: jac_trace = _slice_upstream_tuple_columns( upstream[0], upstream[1], start, end, out_cols_blocks=n @@ -278,23 +310,31 @@ def backward(output_): amend_trace(arg, jac_trace) if isinstance(arg, torch.Tensor) and hasattr(arg, 'optrace'): - backward(arg) + backward(arg, is_root=False) offset = end + if hasattr(output_, 'jactrace'): + delattr(output_, 'jactrace') + def jacobian(output, params): assert output.optrace[id(output)][0] in ('map', 'index', 'cat'), "Unsupported last operation in compute graph" _clear_jactrace(output, params) try: - backward(output) + backward(output, is_root=True) res = [] for param in params: if hasattr(param, 'jactrace'): if isinstance(param.jactrace, tuple): - values = trim_parameter_jacobian_values(param, param.jactrace[1]) - param.jactrace = (param.jactrace[0], values) + indices, values = param.jactrace + values = trim_parameter_jacobian_values(param, values, block_indices=indices) + param.jactrace = (indices, values) elif isinstance(param.jactrace, torch.Tensor) and param.jactrace.layout == torch.sparse_bsr: - values = trim_parameter_jacobian_values(param, param.jactrace.values()) + values = trim_parameter_jacobian_values( + param, + param.jactrace.values(), + block_indices=param.jactrace.col_indices(), + ) if values.shape != param.jactrace.values().shape: param.jactrace = torch.sparse_bsr_tensor( col_indices=param.jactrace.col_indices(), diff --git a/bae/optim/optimizer.py b/bae/optim/optimizer.py index 1fcb4a5..6aa5e3f 100644 --- a/bae/optim/optimizer.py +++ b/bae/optim/optimizer.py @@ -32,7 +32,10 @@ def step(self, input, target=None, weight=None): self.reject_count = 0 J_T = J_T.to_sparse_csr() J = J.to_sparse_csr() - A = self.mm(J_T, J) + if J.dtype == torch.float64: + A = self.mm(J_T, J) + else: + A = J_T @ J diagonal_op_(A, op=partial(torch.clamp_, min=pg['min'], max=pg['max'])) diff --git a/bae/sparse/py_ops.py b/bae/sparse/py_ops.py index 142903f..1fd2521 100644 --- a/bae/sparse/py_ops.py +++ b/bae/sparse/py_ops.py @@ -114,6 +114,7 @@ def diagonal_op_(input, offset: int=0, op: Optional[Callable]=None): #simple case(block is square and offset is 0) if dm == dn and offset == 0: + indices = None if not USE_TRITON: dummy_val = torch.zeros(bsr_values.shape[0], device='cpu') dummy = torch.sparse_csr_tensor(crow_indices=crow_indices.to('cpu'), @@ -134,17 +135,35 @@ def diagonal_op_(input, offset: int=0, op: Optional[Callable]=None): n_diag_blocks = sm if sm < sn else sn if diag_indices.shape[-1] == n_diag_blocks: results = values + diag_rows = None else: + # Triton path only computes a mask over existing entries. If some diagonal + # blocks are structurally missing, we need row indices to scatter into a + # dense diagonal buffer. + if indices is None: + dummy_val = torch.zeros(bsr_values.shape[0], device='cpu') + dummy = torch.sparse_csr_tensor(crow_indices=crow_indices.to('cpu'), + col_indices=col_indices.to('cpu'), + values=dummy_val) + indices = dummy.to_sparse(layout=torch.sparse_coo).coalesce().indices().to(input.device) results_shape = (n_diag_blocks, dm) results = torch.zeros(results_shape, dtype=values.dtype, device=values.device) - results[indices[0, diag_indices]] = values - assert op is None, "op is not supported for diagonal that has empty values." + diag_rows = indices[0, diag_indices] + if values.ndim == 1: + results[diag_rows, 0] = values + else: + results[diag_rows] = values if bsr_values.ndim > 1: results = torch.flatten(results, start_dim=-2, end_dim=-1) # apply the inplace op if op is not None: results = op(results) - block_diags[diag_indices] = results.view(n_diag_blocks, dm) if bsr_values.ndim > 1 else results + if diag_rows is None: + block_diags[diag_indices] = results.view(n_diag_blocks, dm) if bsr_values.ndim > 1 else results + else: + if diag_indices.numel() > 0: + dense_results = results.view(n_diag_blocks, dm) if bsr_values.ndim > 1 else results + block_diags[diag_indices] = dense_results[diag_rows] return results else: raise NotImplementedError('Only square block and offset 0 is supported.') @@ -231,4 +250,3 @@ def bsr2bsc(J): sparse_lib = Library('aten', 'IMPL') sparse_lib.impl('diagonal', diagonal_op_, 'SparseCsrCPU') sparse_lib.impl('diagonal', diagonal_op_, 'SparseCsrCUDA') - diff --git a/bae/utils/ceres_pose.py b/bae/utils/ceres_pose.py new file mode 100644 index 0000000..02644d2 --- /dev/null +++ b/bae/utils/ceres_pose.py @@ -0,0 +1,59 @@ +import torch + + +def skew_symmetric(v: torch.Tensor) -> torch.Tensor: + x, y, z = v.unbind(dim=-1) + zero = torch.zeros_like(x) + rows = ( + torch.stack((zero, -z, y), dim=-1), + torch.stack((z, zero, -x), dim=-1), + torch.stack((-y, x, zero), dim=-1), + ) + return torch.stack(rows, dim=-2) + + +def quat_mul_xyzw(q1: torch.Tensor, q2: torch.Tensor) -> torch.Tensor: + x1, y1, z1, w1 = q1.unbind(dim=-1) + x2, y2, z2, w2 = q2.unbind(dim=-1) + return torch.stack(( + w1 * x2 + x1 * w2 + y1 * z2 - z1 * y2, + w1 * y2 - x1 * z2 + y1 * w2 + z1 * x2, + w1 * z2 + x1 * y2 - y1 * x2 + z1 * w2, + w1 * w2 - x1 * x2 - y1 * y2 - z1 * z2, + ), dim=-1) + + +def quat_conj_xyzw(q: torch.Tensor) -> torch.Tensor: + return torch.cat((-q[..., :3], q[..., 3:4]), dim=-1) + + +def quat_inv_xyzw(q: torch.Tensor) -> torch.Tensor: + return quat_conj_xyzw(q) / q.square().sum(dim=-1, keepdim=True) + + +def quat_rotate_xyzw(q: torch.Tensor, v: torch.Tensor) -> torch.Tensor: + qv = torch.cat((v, torch.zeros_like(v[..., :1])), dim=-1) + return quat_mul_xyzw(quat_mul_xyzw(q, qv), quat_inv_xyzw(q))[..., :3] + + +def quaternion_plus_jacobian_xyzw(quat: torch.Tensor) -> torch.Tensor: + qx, qy, qz, qw = quat.unbind(dim=-1) + rows = ( + torch.stack((qw, qz, -qy), dim=-1), + torch.stack((-qz, qw, qx), dim=-1), + torch.stack((qy, -qx, qw), dim=-1), + torch.stack((-qx, -qy, -qz), dim=-1), + ) + return 0.5 * torch.stack(rows, dim=-2) + + +def se3_pose_plus_jacobian_xyzw(pose: torch.Tensor) -> torch.Tensor: + if pose.shape[-1] != 7: + raise ValueError(f"Expected 7D pose blocks, got {pose.shape[-1]}.") + + J = torch.zeros(*pose.shape[:-1], 7, 6, dtype=pose.dtype, device=pose.device) + eye = torch.eye(3, dtype=pose.dtype, device=pose.device) + J[..., :3, :3] = eye + J[..., :3, 3:6] = -skew_symmetric(pose[..., :3]) + J[..., 3:7, 3:6] = quaternion_plus_jacobian_xyzw(pose[..., 3:7]) + return J diff --git a/bae/utils/parameter.py b/bae/utils/parameter.py index 53e9c6f..3ffbe17 100644 --- a/bae/utils/parameter.py +++ b/bae/utils/parameter.py @@ -1,6 +1,9 @@ import pypose as pp import torch +from .ceres_pose import quaternion_plus_jacobian_xyzw, se3_pose_plus_jacobian_xyzw +from .pypose_ambient_grad import pypose_ambient_grad_enabled + def parameter_update_shape(param: torch.Tensor) -> torch.Size: if param.ndim == 0: @@ -12,12 +15,30 @@ def parameter_update_shape(param: torch.Tensor) -> torch.Size: return param.shape -def trim_parameter_jacobian_values(param: torch.Tensor, values: torch.Tensor) -> torch.Tensor: +def trim_parameter_jacobian_values( + param: torch.Tensor, + values: torch.Tensor, + block_indices: torch.Tensor | None = None, +) -> torch.Tensor: if param.ndim == 0 or values.shape[-1] != param.shape[-1]: return values if getattr(param, 'trim_SE3_grad', False): - return torch.cat([values[..., :6], values[..., 7:]], dim=-1) + pose = param[..., :7].detach() + if block_indices is not None: + pose = pose[block_indices.to(torch.long)] + pose_values = values[..., :7] @ se3_pose_plus_jacobian_xyzw(pose) + if param.shape[-1] == 7: + return pose_values + return torch.cat([pose_values, values[..., 7:]], dim=-1) if isinstance(param, pp.LieTensor): + if pypose_ambient_grad_enabled(): + lie_param = param.detach() + if block_indices is not None: + lie_param = lie_param[block_indices.to(torch.long)] + if param.ltype == pp.SO3_type: + return values @ quaternion_plus_jacobian_xyzw(lie_param) + if param.ltype == pp.SE3_type: + return values @ se3_pose_plus_jacobian_xyzw(lie_param) step_dim = int(param.ltype.manifold[0]) if step_dim != param.shape[-1]: return values[..., :step_dim] diff --git a/bae/utils/pgo.py b/bae/utils/pgo.py index e396a05..8bbc220 100644 --- a/bae/utils/pgo.py +++ b/bae/utils/pgo.py @@ -1,35 +1,78 @@ import matplotlib.pyplot as plt -import torch import numpy as np +import torch +from io import BytesIO +from PIL import Image + + +def _set_equal_axes(ax): + # Keep the 3D plot balanced while letting each frame fit itself. + x_limits = ax.get_xlim3d() + y_limits = ax.get_ylim3d() + z_limits = ax.get_zlim3d() + + ranges = np.array([x_limits, y_limits, z_limits]) + span = ranges[:, 1] - ranges[:, 0] + max_span = max(span) + centers = np.mean(ranges, axis=1) + half_span = max_span / 2.0 + ax.set_xlim3d(centers[0] - half_span, centers[0] + half_span) + ax.set_ylim3d(centers[1] - half_span, centers[1] + half_span) + ax.set_zlim3d(centers[2] - half_span, centers[2] + half_span) + @torch.no_grad() -def plot_and_save(points, pngname, title='', axlim=None): +def render_frame(points, title='', axlim=None): points = points.detach().cpu().numpy() - plt.figure(figsize=(7, 7)) + fig = plt.figure(figsize=(7, 7)) ax = plt.axes(projection='3d') - ax.plot3D(points[:,0], points[:,1], points[:,2], 'b') + ax.plot3D(points[:, 0], points[:, 1], points[:, 2], 'b') plt.title(title) if axlim is not None: ax.set_xlim(axlim[0]) ax.set_ylim(axlim[1]) ax.set_zlim(axlim[2]) + _set_equal_axes(ax) + buffer = BytesIO() + fig.savefig(buffer, format='png') + image = Image.open(buffer).convert('RGB') + image.load() + buffer.close() + limits = (ax.get_xlim(), ax.get_ylim(), ax.get_zlim()) + plt.close(fig) + return image, limits - # Manually enforce the same range in all directions: - x_limits = ax.get_xlim3d() - y_limits = ax.get_ylim3d() - z_limits = ax.get_zlim3d() - ranges = np.array([x_limits, y_limits, z_limits]) - span = ranges[:,1] - ranges[:,0] - max_span = max(span) - centers = np.mean(ranges, axis=1) +def save_gif(frames, gifname, duration=250, loop=0): + if not frames: + raise ValueError('save_gif requires at least one frame') - # Update limits so that each axis has the same length: - # ax.set_xlim3d(centers[0] - max_span/2, centers[0] + max_span/2) - # ax.set_ylim3d(centers[1] - max_span/2, centers[1] + max_span/2) - # ax.set_zlim3d(centers[2] - max_span/2, centers[2] + max_span/2) + first, *rest = frames + first.save( + gifname, + save_all=True, + append_images=rest, + duration=duration, + loop=loop, + ) + print('Saving to', gifname) + +@torch.no_grad() +def plot_and_save(points, pngname, title='', axlim=None): + points = points.detach().cpu().numpy() + fig = plt.figure(figsize=(7, 7)) + ax = plt.axes(projection='3d') + ax.plot3D(points[:,0], points[:,1], points[:,2], 'b') + plt.title(title) + if axlim is not None: + ax.set_xlim(axlim[0]) + ax.set_ylim(axlim[1]) + ax.set_zlim(axlim[2]) + _set_equal_axes(ax) + limits = (ax.get_xlim(), ax.get_ylim(), ax.get_zlim()) plt.savefig(pngname) + plt.close(fig) print('Saving to', pngname) - return ax.get_xlim(), ax.get_ylim(), ax.get_zlim() \ No newline at end of file + return limits diff --git a/bae/utils/pypose_ambient_grad.py b/bae/utils/pypose_ambient_grad.py new file mode 100644 index 0000000..c51e5b0 --- /dev/null +++ b/bae/utils/pypose_ambient_grad.py @@ -0,0 +1,179 @@ +import os + +import torch + +_ENV_FLAG = "BAE_USE_PYPOSE_AMBIENT_GRAD" +_PATCH_INSTALLED = False + + +def pypose_ambient_grad_enabled() -> bool: + value = os.environ.get(_ENV_FLAG, "") + return value.lower() in {"1", "true", "yes", "on"} + + +def _pm(input: torch.Tensor) -> torch.Tensor: + return torch.sign(torch.sign(input) * 2 + 1) + + +def _so3_act_forward(X: torch.Tensor, p: torch.Tensor) -> torch.Tensor: + Xv, Xw = X[..., :3], X[..., 3:] + uv = torch.linalg.cross(Xv, p, dim=-1) + uv = uv + uv + return p + Xw * uv + torch.linalg.cross(Xv, uv, dim=-1) + + +def _se3_act_forward(X: torch.Tensor, p: torch.Tensor) -> torch.Tensor: + return X[..., :3] + _so3_act_forward(X[..., 3:], p) + + +def _so3_mul_forward(X: torch.Tensor, Y: torch.Tensor) -> torch.Tensor: + Xv, Xw, Yv, Yw = X[..., :3], X[..., 3:], Y[..., :3], Y[..., 3:] + Zv = Xw * Yv + Xv * Yw + torch.linalg.cross(Xv, Yv, dim=-1) + Zw = Xw * Yw - (Xv * Yv).sum(dim=-1, keepdim=True) + return torch.cat([Zv, Zw], dim=-1) + + +def _se3_mul_forward(X: torch.Tensor, Y: torch.Tensor) -> torch.Tensor: + t = X[..., :3] + _so3_act_forward(X[..., 3:], Y[..., :3]) + q = _so3_mul_forward(X[..., 3:], Y[..., 3:]) + return torch.cat((t, q), dim=-1) + + +def _so3_inv_forward(X: torch.Tensor) -> torch.Tensor: + return torch.cat((-X[..., :3], X[..., 3:]), dim=-1) + + +def _se3_inv_forward(X: torch.Tensor) -> torch.Tensor: + q_inv = _so3_inv_forward(X[..., 3:]) + t_inv = -_so3_act_forward(q_inv, X[..., :3]) + return torch.cat((t_inv, q_inv), dim=-1) + + +def _so3_log_forward(input: torch.Tensor) -> torch.Tensor: + eps = torch.finfo(input.dtype).eps + v, w = input[..., :3], input[..., 3:] + v_norm = torch.norm(v, 2, dim=-1, keepdim=True) + w_abs = torch.abs(w) + v_larger_than_eps = v_norm > eps + w_larger_than_eps = w_abs > eps + idx1 = v_larger_than_eps & w_larger_than_eps + idx2 = v_larger_than_eps & (~w_larger_than_eps) + idx3 = ~v_larger_than_eps + + factor = torch.zeros_like(v_norm, requires_grad=False) + factor = factor + idx1 * torch.nan_to_num(2.0 * torch.atan(v_norm / w) / v_norm) + factor = factor + idx2 * torch.nan_to_num(_pm(w) * torch.pi / v_norm) + factor = factor + idx3 * torch.nan_to_num(2.0 * (1.0 / w - v_norm * v_norm / (3 * w**3))) + return factor * v + + +def _se3_log_forward(input: torch.Tensor) -> torch.Tensor: + from pypose.lietensor.operation import so3_Jl_inv + + phi = _so3_log_forward(input[..., 3:]) + Jl_inv = so3_Jl_inv(phi) + tau = (Jl_inv @ input[..., :3].unsqueeze(-1)).squeeze(-1) + return torch.cat([tau, phi], dim=-1) + + +def _so3_act4_forward(X: torch.Tensor, p: torch.Tensor) -> torch.Tensor: + return torch.cat((_so3_act_forward(X, p[..., :3]), p[..., 3:]), dim=-1) + + +def _se3_act4_forward(X: torch.Tensor, p: torch.Tensor) -> torch.Tensor: + t = _so3_act_forward(X[..., 3:], p[..., :3]) + X[..., :3] * p[..., 3:] + return torch.cat((t, p[..., 3:]), dim=-1) + + +def install_pypose_ambient_grad_monkeypatch() -> bool: + global _PATCH_INSTALLED + if _PATCH_INSTALLED: + return False + + import pypose.lietensor.lietensor as lt + import pypose.lietensor.operation as op + + def _ambient_so3_log(self, X): + X = X.tensor() if isinstance(X, lt.LieTensor) else X + return lt.LieTensor(_so3_log_forward(X), ltype=lt.so3_type) + + def _ambient_se3_log(self, X): + X = X.tensor() if isinstance(X, lt.LieTensor) else X + return lt.LieTensor(_se3_log_forward(X), ltype=lt.se3_type) + + def _ambient_so3_act(self, X, p): + assert not self.on_manifold and isinstance(p, torch.Tensor) + assert p.shape[-1] == 3 or p.shape[-1] == 4, "Invalid Tensor Dimension" + X = X.tensor() if isinstance(X, lt.LieTensor) else X + inputs, out_shape = op.broadcast_inputs(X, p) + if p.shape[-1] == 3: + out = _so3_act_forward(*inputs) + else: + out = _so3_act4_forward(*inputs) + dim = -1 if out.nelement() != 0 else p.shape[-1] + return out.view(out_shape + (dim,)) + + def _ambient_se3_act(self, X, p): + assert not self.on_manifold and isinstance(p, torch.Tensor) + assert p.shape[-1] == 3 or p.shape[-1] == 4, "Invalid Tensor Dimension" + X = X.tensor() if isinstance(X, lt.LieTensor) else X + inputs, out_shape = op.broadcast_inputs(X, p) + if p.shape[-1] == 3: + out = _se3_act_forward(*inputs) + else: + out = _se3_act4_forward(*inputs) + dim = -1 if out.nelement() != 0 else p.shape[-1] + return out.view(out_shape + (dim,)) + + def _ambient_so3_mul(self, X, Y): + X = X.tensor() if isinstance(X, lt.LieTensor) else X + if not self.on_manifold and isinstance(Y, lt.LieTensor) and not Y.ltype.on_manifold: + inputs, out_shape = op.broadcast_inputs(X, Y.tensor()) + out = _so3_mul_forward(*inputs) + dim = -1 if out.nelement() != 0 else X.shape[-1] + return lt.LieTensor(out.view(out_shape + (dim,)), ltype=lt.SO3_type) + if not self.on_manifold and isinstance(Y, torch.Tensor): + return self.Act(X, Y) + if self.on_manifold: + return lt.LieTensor(torch.mul(X, Y), ltype=lt.SO3_type) + raise NotImplementedError("Invalid __mul__ operation") + + def _ambient_so3_inv(self, X): + X = X.tensor() if isinstance(X, lt.LieTensor) else X + return lt.LieTensor(_so3_inv_forward(X), ltype=lt.SO3_type) + + def _ambient_se3_mul(self, X, Y): + X = X.tensor() if isinstance(X, lt.LieTensor) else X + if not self.on_manifold and isinstance(Y, lt.LieTensor) and not Y.ltype.on_manifold: + Y = Y.tensor() if hasattr(Y, "ltype") else Y + inputs, out_shape = op.broadcast_inputs(X, Y) + out = _se3_mul_forward(*inputs) + dim = -1 if out.nelement() != 0 else X.shape[-1] + return lt.LieTensor(out.view(out_shape + (dim,)), ltype=lt.SE3_type) + if not self.on_manifold and isinstance(Y, torch.Tensor): + return self.Act(X, Y) + if self.on_manifold: + return lt.LieTensor(torch.mul(X, Y), ltype=lt.SE3_type) + raise NotImplementedError("Invalid __mul__ operation") + + def _ambient_se3_inv(self, X): + X = X.tensor() if isinstance(X, lt.LieTensor) else X + return lt.LieTensor(_se3_inv_forward(X), ltype=lt.SE3_type) + + lt.SO3Type.Log = _ambient_so3_log + lt.SE3Type.Log = _ambient_se3_log + lt.SO3Type.Act = _ambient_so3_act + lt.SE3Type.Act = _ambient_se3_act + lt.SO3Type.Mul = _ambient_so3_mul + lt.SE3Type.Mul = _ambient_se3_mul + lt.SO3Type.Inv = _ambient_so3_inv + lt.SE3Type.Inv = _ambient_se3_inv + + _PATCH_INSTALLED = True + return True + + +def maybe_install_pypose_ambient_grad_monkeypatch() -> bool: + if not pypose_ambient_grad_enabled(): + return False + return install_pypose_ambient_grad_monkeypatch() diff --git a/examples/module/pgo/data/grid3D.g2o b/examples/module/pgo/data/grid3D.g2o new file mode 100644 index 0000000..0dee46a --- /dev/null +++ b/examples/module/pgo/data/grid3D.g2o @@ -0,0 +1,30236 @@ +VERTEX_SE3:QUAT 0 0.000000 0.000000 0.000000 0.0000000 0.0000000 0.0000000 1.0000000 +VERTEX_SE3:QUAT 1 0.939375 -0.022347 -0.028831 0.1175925 -0.3414281 -0.7976288 0.4831016 +VERTEX_SE3:QUAT 2 1.746818 -0.191133 -0.008382 0.4337578 0.5248273 -0.1059368 0.7246985 +VERTEX_SE3:QUAT 3 2.720782 -0.165811 -0.159625 -0.1958045 0.1635685 0.9078083 0.3328513 +VERTEX_SE3:QUAT 4 3.791886 -0.148958 -0.120050 0.1229886 0.5752560 0.5436993 0.5986195 +VERTEX_SE3:QUAT 5 4.928150 -0.116242 -0.016365 -0.1025349 -0.4925818 0.6679443 0.5483614 +VERTEX_SE3:QUAT 6 6.013391 0.010660 -0.171822 -0.3424574 -0.0824968 0.8773775 0.3257699 +VERTEX_SE3:QUAT 7 6.857664 -0.156089 -0.136946 0.2631746 -0.1253842 0.9556860 0.0410147 +VERTEX_SE3:QUAT 8 7.846746 -0.239322 -0.249431 0.2075956 0.5002936 0.2627434 0.7984838 +VERTEX_SE3:QUAT 9 8.786695 -0.360181 -0.536215 -0.5563622 0.0703348 0.4242916 0.7109787 +VERTEX_SE3:QUAT 10 9.735532 -0.567192 -0.710230 -0.0908996 -0.5141906 0.2727595 0.8080517 +VERTEX_SE3:QUAT 11 10.507753 -0.542946 -1.128891 -0.1444552 0.5187077 0.6388540 0.5494913 +VERTEX_SE3:QUAT 12 11.439435 -0.757835 -1.449368 -0.2345523 -0.1500586 0.3873141 0.8788944 +VERTEX_SE3:QUAT 13 12.367948 -0.981498 -1.849201 0.2866483 -0.4575673 -0.2462334 0.8048814 +VERTEX_SE3:QUAT 14 13.105709 -1.029812 -2.027585 -0.5400450 -0.1362953 -0.8097977 0.1843983 +VERTEX_SE3:QUAT 15 13.976081 -1.126091 -2.368120 0.0918170 0.5850540 0.7182932 0.3651524 +VERTEX_SE3:QUAT 16 14.842118 -1.466382 -2.944620 -0.1389766 -0.2178899 -0.5443356 0.7980653 +VERTEX_SE3:QUAT 17 15.642844 -1.696510 -3.455404 0.6392073 0.3973557 -0.4398288 0.4899725 +VERTEX_SE3:QUAT 18 16.671086 -1.754459 -3.840970 0.2165787 0.0400255 0.9751992 0.0218685 +VERTEX_SE3:QUAT 19 17.624280 -2.008896 -4.281798 0.2048876 0.1333039 0.7590177 0.6034428 +VERTEX_SE3:QUAT 20 17.959039 -1.095459 -4.151588 -0.5116514 -0.1379292 0.5069128 0.6798734 +VERTEX_SE3:QUAT 21 17.111385 -0.690113 -3.903073 0.1817128 0.2934992 0.6536097 0.6735228 +VERTEX_SE3:QUAT 22 16.150946 -0.263850 -3.675597 0.5010978 -0.1889020 0.4711188 0.7009023 +VERTEX_SE3:QUAT 23 15.239616 -0.064219 -3.388588 0.2486457 0.5277665 0.7447560 0.3240005 +VERTEX_SE3:QUAT 24 14.330247 0.212448 -2.932582 0.2872344 -0.0251548 0.9176736 0.2733839 +VERTEX_SE3:QUAT 25 13.471115 0.478036 -2.723281 -0.2483975 -0.1850328 0.0995660 0.9455941 +VERTEX_SE3:QUAT 26 12.560326 0.855763 -2.402628 0.2256015 -0.1701906 -0.9526166 0.1125203 +VERTEX_SE3:QUAT 27 11.726812 0.965057 -2.139140 -0.4178806 0.4028349 0.3331925 0.7430226 +VERTEX_SE3:QUAT 28 10.957740 1.332241 -2.009120 -0.0092613 -0.3395739 0.3373693 0.8779440 +VERTEX_SE3:QUAT 29 9.963028 1.625185 -1.819598 0.0698778 0.0148589 -0.3971267 0.9149791 +VERTEX_SE3:QUAT 30 9.110580 1.823535 -1.398338 -0.6628907 0.3012485 -0.6699693 0.1447978 +VERTEX_SE3:QUAT 31 8.298826 1.950716 -1.141008 -0.4473442 0.4709634 -0.7473894 0.1395914 +VERTEX_SE3:QUAT 32 7.245204 2.048219 -0.948159 -0.3972110 0.0556449 -0.9016916 0.1614908 +VERTEX_SE3:QUAT 33 6.402143 2.219491 -0.671721 0.0341390 0.2942934 -0.3886224 0.8724669 +VERTEX_SE3:QUAT 34 5.336081 2.440725 -0.302212 -0.2165170 -0.1195144 -0.1905708 0.9500102 +VERTEX_SE3:QUAT 35 4.430933 2.498526 -0.021830 -0.4482462 0.3139761 -0.7085499 0.4454788 +VERTEX_SE3:QUAT 36 3.528507 2.622725 0.145876 -0.2613290 -0.4339859 -0.7232155 0.4693854 +VERTEX_SE3:QUAT 37 2.527086 2.654341 0.226618 -0.3782502 0.3415010 -0.8603191 0.0124477 +VERTEX_SE3:QUAT 38 1.669698 2.890252 0.587479 0.3497226 -0.2350748 -0.0891021 0.9024937 +VERTEX_SE3:QUAT 39 0.650370 3.172823 0.771981 -0.1963656 0.5830918 -0.3333083 0.7143879 +VERTEX_SE3:QUAT 40 0.787028 4.195528 1.018177 -0.1306972 0.3157430 -0.1750324 0.9233570 +VERTEX_SE3:QUAT 41 1.849286 4.206973 0.584814 -0.2747814 0.7320956 -0.0274001 0.6227202 +VERTEX_SE3:QUAT 42 2.738452 4.161960 0.162797 -0.3258927 -0.0574284 0.0361998 0.9429663 +VERTEX_SE3:QUAT 43 3.683180 4.302577 -0.244726 0.3899987 0.1448717 0.4136654 0.8098112 +VERTEX_SE3:QUAT 44 4.645471 4.331023 -0.624808 0.3899555 0.3599068 0.1459552 0.8349245 +VERTEX_SE3:QUAT 45 5.556663 4.186331 -0.945602 -0.4899380 0.2980038 -0.8017905 0.1681859 +VERTEX_SE3:QUAT 46 6.439611 4.278222 -1.432040 -0.5289507 0.0993271 -0.8136654 0.2197587 +VERTEX_SE3:QUAT 47 7.278956 4.137101 -1.783852 -0.4773987 0.5899737 0.2004521 0.6195486 +VERTEX_SE3:QUAT 48 8.248338 4.228709 -1.985274 0.6484425 0.2372549 0.2857965 0.6644944 +VERTEX_SE3:QUAT 49 9.257701 4.328665 -2.455775 -0.3112609 -0.1260274 0.7640081 0.5509314 +VERTEX_SE3:QUAT 50 10.421746 4.526626 -2.844024 -0.4457494 -0.0473628 -0.7128260 0.5393917 +VERTEX_SE3:QUAT 51 11.329407 4.610717 -3.155736 0.5234372 -0.2854513 -0.4868794 0.6383413 +VERTEX_SE3:QUAT 52 12.159475 4.544441 -3.383160 0.2122718 -0.5431412 0.7984487 0.1497262 +VERTEX_SE3:QUAT 53 13.141154 4.618933 -3.639247 0.5288379 -0.1925570 -0.2362085 0.7921223 +VERTEX_SE3:QUAT 54 14.193284 4.474722 -3.939337 -0.3135652 0.1551898 -0.9275169 0.1315499 +VERTEX_SE3:QUAT 55 15.087523 4.473372 -4.356769 -0.2784943 0.1203624 0.7494446 0.5884612 +VERTEX_SE3:QUAT 56 16.038422 4.584877 -4.603725 0.2095968 0.3299700 -0.4699501 0.7914138 +VERTEX_SE3:QUAT 57 16.938697 4.533065 -5.181415 -0.1060227 -0.3762582 -0.5133229 0.7639951 +VERTEX_SE3:QUAT 58 17.791611 4.575318 -5.504817 0.6098723 0.0565646 0.4280562 0.6645481 +VERTEX_SE3:QUAT 59 18.836149 4.691265 -6.060088 -0.2509340 -0.1249211 -0.2640697 0.9228727 +VERTEX_SE3:QUAT 60 18.750032 5.778874 -5.831635 0.3690476 0.5380262 -0.1974934 0.7316612 +VERTEX_SE3:QUAT 61 17.921946 5.682741 -5.518113 -0.2088405 -0.0736500 -0.1433755 0.9645749 +VERTEX_SE3:QUAT 62 16.991201 5.518829 -5.085838 0.2242896 0.0286423 -0.4609059 0.8581606 +VERTEX_SE3:QUAT 63 16.034724 5.348206 -4.741737 -0.4542474 0.3343888 0.6228980 0.5420714 +VERTEX_SE3:QUAT 64 15.284259 5.108571 -4.261630 0.3236536 0.0286596 -0.5315294 0.7822426 +VERTEX_SE3:QUAT 65 14.499843 4.926595 -3.825441 -0.4621213 0.5515138 -0.0881741 0.6888409 +VERTEX_SE3:QUAT 66 13.741143 4.554504 -3.296370 -0.1914186 -0.2323241 -0.9536034 0.0050020 +VERTEX_SE3:QUAT 67 12.830568 4.305964 -2.944174 0.0825885 -0.5688791 0.7019852 0.4204432 +VERTEX_SE3:QUAT 68 12.033699 3.872010 -2.500184 -0.2095162 -0.5263253 0.8201117 0.0806312 +VERTEX_SE3:QUAT 69 11.320892 3.512379 -2.388339 0.6718003 0.0494895 -0.2477240 0.6963246 +VERTEX_SE3:QUAT 70 10.358921 2.999409 -2.137129 -0.1878475 -0.2830575 0.1807096 0.9230037 +VERTEX_SE3:QUAT 71 9.458250 2.498466 -1.952704 0.1893062 0.2188866 -0.8971581 0.3337052 +VERTEX_SE3:QUAT 72 8.676257 2.161705 -1.759123 -0.3248093 0.3402507 -0.6572444 0.5888617 +VERTEX_SE3:QUAT 73 7.602351 1.700705 -1.633701 0.1920564 0.5592383 -0.4953234 0.6364130 +VERTEX_SE3:QUAT 74 6.716543 1.238176 -1.329723 -0.1562458 -0.1752258 0.7061571 0.6680010 +VERTEX_SE3:QUAT 75 5.913678 0.774663 -1.204383 0.0592223 -0.4819835 -0.6848349 0.5433100 +VERTEX_SE3:QUAT 76 4.938153 0.452697 -0.844591 -0.2749942 -0.0870782 0.4345855 0.8531887 +VERTEX_SE3:QUAT 77 4.204613 0.156590 -0.641983 -0.4047246 -0.0850256 -0.8751000 0.2513337 +VERTEX_SE3:QUAT 78 3.270419 -0.388391 -0.454921 -0.0082817 0.0324334 -0.3098670 0.9501905 +VERTEX_SE3:QUAT 79 2.342166 -0.637124 -0.148898 0.2660615 0.3704824 -0.8796767 0.1346212 +VERTEX_SE3:QUAT 80 1.984175 0.300234 -0.080839 -0.0703153 -0.3019067 0.7253733 0.6146069 +VERTEX_SE3:QUAT 81 2.904399 0.742127 -0.256202 0.5216023 0.1996595 0.6678257 0.4920122 +VERTEX_SE3:QUAT 82 3.917161 1.117406 -0.483764 0.4104451 0.3135988 -0.5636319 0.6446004 +VERTEX_SE3:QUAT 83 4.918962 1.510292 -0.786467 -0.1024524 -0.5587662 0.5685036 0.5950525 +VERTEX_SE3:QUAT 84 5.893495 1.748018 -0.949035 -0.2634448 -0.2028576 0.5660591 0.7543359 +VERTEX_SE3:QUAT 85 6.708266 1.867317 -1.170396 -0.3397030 0.3268353 0.6077567 0.6390715 +VERTEX_SE3:QUAT 86 7.531519 1.915997 -1.317420 -0.5604674 0.3756358 -0.2774276 0.6839649 +VERTEX_SE3:QUAT 87 8.368281 2.125222 -1.559314 -0.0031736 0.1308126 0.2733909 0.9529614 +VERTEX_SE3:QUAT 88 9.321183 2.408621 -1.848830 0.4595695 0.0163438 0.0898633 0.8834327 +VERTEX_SE3:QUAT 89 10.318669 2.585762 -2.065089 0.1428704 0.4248561 0.6205578 0.6434232 +VERTEX_SE3:QUAT 90 11.240253 2.640378 -2.209619 0.3361144 0.1652169 -0.7600799 0.5310453 +VERTEX_SE3:QUAT 91 12.192929 2.761421 -2.450844 -0.2423330 0.6741297 0.6948815 0.0629576 +VERTEX_SE3:QUAT 92 12.985352 2.898456 -2.710132 0.4913153 -0.3459276 -0.7905451 0.1182450 +VERTEX_SE3:QUAT 93 13.967426 3.118593 -2.796236 0.3365947 0.0518017 0.0343959 0.9395943 +VERTEX_SE3:QUAT 94 14.988299 3.000473 -2.811562 0.4993627 -0.2292019 0.1720011 0.8176301 +VERTEX_SE3:QUAT 95 15.870802 3.192137 -3.001591 0.2344563 -0.3512442 -0.7398764 0.5236800 +VERTEX_SE3:QUAT 96 16.879458 3.475474 -3.103610 -0.0292300 0.3945027 0.6377670 0.6608831 +VERTEX_SE3:QUAT 97 17.792960 3.627633 -3.366557 0.2204502 -0.5401794 0.5065109 0.6348658 +VERTEX_SE3:QUAT 98 18.685677 3.690094 -3.204043 0.4443913 0.4482318 0.2107015 0.7464647 +VERTEX_SE3:QUAT 99 19.964003 3.959679 -3.342515 -0.1581588 -0.5952577 -0.6853172 0.3885800 +VERTEX_SE3:QUAT 100 19.875627 5.056916 -3.055943 0.0610864 0.4715085 -0.6150160 0.6290497 +VERTEX_SE3:QUAT 101 18.977121 5.393291 -2.887017 -0.0948375 -0.5352498 -0.6827316 0.4882531 +VERTEX_SE3:QUAT 102 17.929421 5.497169 -2.849873 0.3946162 -0.5486194 0.6617046 0.3247181 +VERTEX_SE3:QUAT 103 17.158268 5.533241 -2.821690 0.2180664 0.4080380 0.7013927 0.5422180 +VERTEX_SE3:QUAT 104 16.202208 5.625447 -2.875273 0.0091491 0.2279631 -0.0790994 0.9704084 +VERTEX_SE3:QUAT 105 15.310403 5.566868 -2.873163 -0.5532178 0.4709375 0.0034153 0.6871363 +VERTEX_SE3:QUAT 106 14.266753 5.464536 -2.828397 -0.1207820 -0.1083871 0.7967886 0.5820583 +VERTEX_SE3:QUAT 107 13.619287 5.485182 -2.852840 -0.3431936 0.1311685 -0.8393596 0.4006100 +VERTEX_SE3:QUAT 108 12.606411 5.381017 -2.763449 -0.3331502 -0.1406178 0.2962528 0.8840090 +VERTEX_SE3:QUAT 109 11.824950 5.345966 -2.643585 0.3235898 0.5668931 0.0043030 0.7575641 +VERTEX_SE3:QUAT 110 11.059899 5.310042 -2.408748 -0.7099156 0.2698057 -0.6229408 0.1875355 +VERTEX_SE3:QUAT 111 10.189459 5.292089 -2.291709 -0.3879471 -0.2929768 -0.2172597 0.8464395 +VERTEX_SE3:QUAT 112 8.910522 5.195000 -2.121603 -0.0500305 -0.1498343 -0.9417367 0.2969488 +VERTEX_SE3:QUAT 113 7.988733 5.203992 -1.814451 -0.1546166 0.5111550 -0.5087571 0.6752633 +VERTEX_SE3:QUAT 114 7.286301 5.204708 -1.594609 0.5036763 0.1203243 -0.7311510 0.4441288 +VERTEX_SE3:QUAT 115 6.343368 5.199478 -1.519417 0.2822118 -0.0657039 0.7324530 0.6160780 +VERTEX_SE3:QUAT 116 5.192899 5.356553 -1.239426 -0.1845165 0.3325025 0.6756395 0.6315908 +VERTEX_SE3:QUAT 117 4.238091 5.450170 -0.950660 0.6617017 0.3951525 0.4270921 0.4728611 +VERTEX_SE3:QUAT 118 3.149036 5.673540 -0.636854 -0.6165532 -0.2477158 -0.0387481 0.7463228 +VERTEX_SE3:QUAT 119 2.066874 5.934587 -0.201306 0.2189491 0.4992336 0.4965460 0.6754770 +VERTEX_SE3:QUAT 120 2.093082 7.088751 -0.469199 0.1028310 0.5731159 -0.1426113 0.8003911 +VERTEX_SE3:QUAT 121 2.930518 6.950965 -1.035306 -0.3129434 -0.2657770 0.2117535 0.8868988 +VERTEX_SE3:QUAT 122 3.854814 6.622684 -1.226963 -0.2428063 -0.3593082 0.5745217 0.6941668 +VERTEX_SE3:QUAT 123 4.778747 6.478158 -1.480449 -0.3690358 0.5915181 -0.5573009 0.4509264 +VERTEX_SE3:QUAT 124 5.586915 6.262298 -1.895246 -0.0336547 0.5545646 -0.6159333 0.5585263 +VERTEX_SE3:QUAT 125 6.455947 6.097027 -2.331240 -0.1729112 -0.5798251 0.7958505 0.0229467 +VERTEX_SE3:QUAT 126 7.210925 5.650762 -2.675318 0.5019147 0.0230395 -0.7330349 0.4584873 +VERTEX_SE3:QUAT 127 8.126049 5.384339 -3.075053 0.5825774 -0.0471874 0.1255663 0.8016296 +VERTEX_SE3:QUAT 128 8.983917 5.068989 -3.692406 -0.0644981 0.0040057 -0.7819017 0.6200433 +VERTEX_SE3:QUAT 129 9.798558 4.796508 -4.310193 0.1515276 0.3735093 -0.7959380 0.4516779 +VERTEX_SE3:QUAT 130 10.623440 4.503934 -4.792873 0.2867283 -0.0749264 -0.2610086 0.9187205 +VERTEX_SE3:QUAT 131 11.553462 4.314476 -5.438985 0.5020672 -0.4465476 0.7404283 0.0170241 +VERTEX_SE3:QUAT 132 12.409994 4.193821 -5.697552 0.3788467 0.0417907 0.7943107 0.4730742 +VERTEX_SE3:QUAT 133 13.314330 3.934317 -6.176428 -0.0332816 0.1127935 0.7601989 0.6389581 +VERTEX_SE3:QUAT 134 14.134662 3.533270 -6.636255 -0.1652718 -0.3089860 0.4028039 0.8455542 +VERTEX_SE3:QUAT 135 14.856749 3.316259 -7.161477 0.3523121 -0.0523100 -0.8043157 0.4756218 +VERTEX_SE3:QUAT 136 15.635475 2.988387 -7.807903 -0.1412221 0.2556251 0.5007176 0.8148583 +VERTEX_SE3:QUAT 137 16.357058 2.608218 -8.474676 -0.4631046 -0.0625350 -0.8554077 0.2233856 +VERTEX_SE3:QUAT 138 17.071905 2.125728 -9.264900 -0.0197122 -0.1339789 -0.6965653 0.7045976 +VERTEX_SE3:QUAT 139 17.560945 1.672520 -9.973856 -0.1215478 0.3219369 -0.7080605 0.6166305 +VERTEX_SE3:QUAT 140 18.034250 2.363374 -10.405013 -0.3137843 0.8061602 0.0318219 0.5006322 +VERTEX_SE3:QUAT 141 17.383597 2.889609 -9.809139 0.6134915 -0.2086171 0.7607724 0.0365034 +VERTEX_SE3:QUAT 142 16.897494 3.647073 -9.326345 -0.5854458 -0.1118937 -0.6491416 0.4725974 +VERTEX_SE3:QUAT 143 16.467716 4.330997 -8.628086 -0.5477540 0.3488596 -0.2021198 0.7330826 +VERTEX_SE3:QUAT 144 15.924260 4.736817 -7.857441 -0.3892822 -0.0084693 -0.6094918 0.6905848 +VERTEX_SE3:QUAT 145 15.394974 5.230977 -7.391428 -0.2162694 0.4518274 -0.5779532 0.6442435 +VERTEX_SE3:QUAT 146 14.857596 5.928749 -6.768557 -0.3803706 0.6602302 -0.3377952 0.5525475 +VERTEX_SE3:QUAT 147 14.254268 6.332020 -6.209943 -0.5264485 -0.0677296 -0.7796057 0.3323847 +VERTEX_SE3:QUAT 148 13.599909 6.803416 -5.537548 -0.7277884 0.0782763 -0.1502244 0.6645521 +VERTEX_SE3:QUAT 149 12.954869 7.193615 -4.835176 -0.2656283 0.0718732 0.6034310 0.7484296 +VERTEX_SE3:QUAT 150 12.570332 7.699674 -4.139896 -0.1391551 0.0027771 -0.1651598 0.9763966 +VERTEX_SE3:QUAT 151 12.239592 8.134718 -3.304763 -0.0201401 0.4604365 0.7790974 0.4249704 +VERTEX_SE3:QUAT 152 11.820499 8.798736 -2.585349 -0.6940745 -0.5294448 -0.4730637 0.1189933 +VERTEX_SE3:QUAT 153 11.396913 9.221127 -1.795695 0.0853143 0.1016675 -0.9848982 0.1111787 +VERTEX_SE3:QUAT 154 10.765769 9.681492 -0.988050 0.5177239 -0.6351956 0.5610338 0.1171734 +VERTEX_SE3:QUAT 155 10.289564 10.098843 -0.277729 -0.2364299 0.1278759 0.2490551 0.9304409 +VERTEX_SE3:QUAT 156 9.920867 10.500193 0.643049 0.0634798 -0.7888038 0.6071123 0.0719266 +VERTEX_SE3:QUAT 157 9.437047 10.804370 1.510795 0.2652258 0.5893472 -0.3862474 0.6581323 +VERTEX_SE3:QUAT 158 9.198585 11.132316 2.338500 -0.0589465 0.0911504 0.7465708 0.6563908 +VERTEX_SE3:QUAT 159 8.793594 11.565039 3.075386 -0.5036979 0.0396278 -0.8620337 0.0401986 +VERTEX_SE3:QUAT 160 9.346612 12.256553 2.837745 -0.1301898 0.3062092 0.4033775 0.8523926 +VERTEX_SE3:QUAT 161 9.830180 11.765430 2.061447 0.0128080 0.0245471 0.3132030 0.9492825 +VERTEX_SE3:QUAT 162 10.350947 11.212323 1.552642 -0.2551037 0.8805242 -0.2844201 0.2805432 +VERTEX_SE3:QUAT 163 10.720121 10.616745 0.700219 0.0381077 0.8125386 -0.3596520 0.4571425 +VERTEX_SE3:QUAT 164 11.126035 9.991989 -0.072394 -0.0546107 0.3641047 -0.7704785 0.5203924 +VERTEX_SE3:QUAT 165 11.539672 9.429495 -0.674078 0.0777342 0.7558629 -0.6119827 0.2193304 +VERTEX_SE3:QUAT 166 12.060497 8.909726 -1.256657 -0.0388616 0.2792964 -0.8435776 0.4570121 +VERTEX_SE3:QUAT 167 12.360307 8.426436 -1.763753 0.3009373 -0.3871308 0.2849526 0.8236313 +VERTEX_SE3:QUAT 168 12.568604 7.965454 -2.578686 0.5659699 0.0781384 0.5982534 0.5618411 +VERTEX_SE3:QUAT 169 12.898331 7.186054 -3.413287 0.2770683 0.6623229 -0.4704998 0.5130219 +VERTEX_SE3:QUAT 170 13.163055 6.538985 -4.328133 -0.7293789 0.4270579 -0.3609445 0.3941410 +VERTEX_SE3:QUAT 171 13.332705 5.936696 -5.039193 0.2467456 -0.2266448 0.8375406 0.4315953 +VERTEX_SE3:QUAT 172 13.687030 5.408227 -5.652619 0.5094460 0.7285235 0.2961405 0.3493122 +VERTEX_SE3:QUAT 173 13.826933 4.720851 -6.518254 0.5854936 0.2359859 0.7509732 0.1937711 +VERTEX_SE3:QUAT 174 13.998379 4.239101 -7.407203 -0.0231931 0.6522995 0.3826239 0.6538856 +VERTEX_SE3:QUAT 175 14.394775 3.779937 -8.234158 0.0004454 -0.5278330 0.7363272 0.4233373 +VERTEX_SE3:QUAT 176 14.597225 3.387715 -9.199057 -0.4066981 -0.3606491 -0.7657464 0.3437460 +VERTEX_SE3:QUAT 177 14.871954 3.266098 -10.115791 0.8245542 -0.1465548 0.5280157 0.1408242 +VERTEX_SE3:QUAT 178 15.057634 2.879259 -11.078628 -0.6862057 0.5972292 -0.4018662 0.1046067 +VERTEX_SE3:QUAT 179 15.019872 2.482531 -12.052087 0.3216451 0.5101539 0.4651454 0.6480178 +VERTEX_SE3:QUAT 180 15.566440 3.361681 -12.284717 -0.1986572 0.2558334 -0.0840018 0.9423525 +VERTEX_SE3:QUAT 181 15.465829 3.726775 -11.407944 0.2214950 -0.1830425 0.6332804 0.7186038 +VERTEX_SE3:QUAT 182 15.299176 4.124057 -10.517445 0.5560082 0.3502209 -0.2293771 0.7180434 +VERTEX_SE3:QUAT 183 15.328525 4.393466 -9.520564 -0.3061251 0.3982151 0.3669998 0.7829580 +VERTEX_SE3:QUAT 184 15.019132 4.675811 -8.386340 0.3959963 0.1853492 0.8700366 0.2277476 +VERTEX_SE3:QUAT 185 14.853698 4.938602 -7.486523 -0.6221182 0.5798772 -0.0135186 0.5258599 +VERTEX_SE3:QUAT 186 14.664432 5.487183 -6.622720 -0.8558610 0.0692351 -0.4463391 0.2519722 +VERTEX_SE3:QUAT 187 14.498877 5.922461 -5.612246 -0.1526782 0.7346210 0.0979964 0.6537722 +VERTEX_SE3:QUAT 188 14.094137 6.314442 -4.794014 0.7550215 0.0629203 -0.0928160 0.6460408 +VERTEX_SE3:QUAT 189 14.013628 6.688245 -3.664724 0.0009976 0.7933861 -0.5015096 0.3450008 +VERTEX_SE3:QUAT 190 13.957705 6.856948 -2.843565 -0.5238590 0.4213216 -0.7389118 0.0454890 +VERTEX_SE3:QUAT 191 13.997619 6.910702 -2.055948 -0.5001995 0.5223084 -0.6671622 0.1785750 +VERTEX_SE3:QUAT 192 14.150813 7.210825 -1.137179 0.0805505 0.4681223 -0.0805953 0.8762862 +VERTEX_SE3:QUAT 193 14.062696 7.296984 -0.387194 0.4391484 0.8944189 -0.0638761 0.0555283 +VERTEX_SE3:QUAT 194 14.000650 7.407459 0.554778 -0.3951140 0.1516372 -0.6338441 0.6474046 +VERTEX_SE3:QUAT 195 13.919877 7.487820 1.578318 -0.1435859 0.8617186 -0.4535583 0.1763776 +VERTEX_SE3:QUAT 196 13.873048 7.719950 2.600642 0.4028213 0.7691019 0.4466178 0.2162172 +VERTEX_SE3:QUAT 197 13.923630 7.956167 3.405731 -0.0047952 0.0818978 -0.4970114 0.8638573 +VERTEX_SE3:QUAT 198 13.914055 8.138810 4.547077 -0.4550918 0.1637996 0.0621236 0.8730417 +VERTEX_SE3:QUAT 199 13.645453 8.300543 5.576529 0.2039724 0.6967264 0.4465759 0.5230082 +VERTEX_SE3:QUAT 200 13.805709 9.272381 5.363966 0.7077911 0.0764068 0.2148684 0.6685995 +VERTEX_SE3:QUAT 201 13.813380 9.078562 4.449118 0.7608104 0.4433003 0.3146091 0.3545046 +VERTEX_SE3:QUAT 202 13.560748 8.847742 3.456725 0.5392387 0.1735526 0.8044989 0.1785572 +VERTEX_SE3:QUAT 203 13.609875 8.934619 2.501388 -0.1689577 0.1301197 0.1761967 0.9609770 +VERTEX_SE3:QUAT 204 13.623452 8.656898 1.558967 -0.5947921 0.6554808 0.2296450 0.4047596 +VERTEX_SE3:QUAT 205 13.881649 8.552509 0.553552 0.2803613 0.7088185 0.3909156 0.5159059 +VERTEX_SE3:QUAT 206 13.922258 8.561473 -0.471740 -0.6975613 0.0147222 -0.7155358 0.0346402 +VERTEX_SE3:QUAT 207 14.171070 8.516507 -1.396263 0.3594418 0.6796669 0.6342885 0.0808242 +VERTEX_SE3:QUAT 208 14.263295 8.498360 -2.246059 0.6379711 0.5502086 0.3403319 0.4176571 +VERTEX_SE3:QUAT 209 14.552491 8.281610 -3.142190 0.2561555 -0.0025652 0.9660225 0.0343265 +VERTEX_SE3:QUAT 210 14.650275 8.299008 -4.038077 0.3931339 -0.0638242 0.4457144 0.8016925 +VERTEX_SE3:QUAT 211 14.537107 8.206545 -5.169578 0.9028047 -0.0377831 0.4073673 0.1325445 +VERTEX_SE3:QUAT 212 14.510247 8.288358 -6.080737 0.4407289 0.6406520 -0.4321997 0.4566470 +VERTEX_SE3:QUAT 213 14.501550 7.988830 -7.205325 0.1338916 0.9503828 -0.0671777 0.2726403 +VERTEX_SE3:QUAT 214 14.685267 7.958258 -8.359144 0.5170636 0.4800705 0.7078111 0.0343646 +VERTEX_SE3:QUAT 215 14.591736 7.717034 -9.388440 0.0674057 0.2402280 -0.6293855 0.7359490 +VERTEX_SE3:QUAT 216 14.539344 7.629952 -10.289855 0.1913400 0.2455616 0.9151186 0.2562156 +VERTEX_SE3:QUAT 217 14.518660 7.357178 -11.350023 0.5457789 0.2169196 0.3868050 0.7109523 +VERTEX_SE3:QUAT 218 14.516305 7.189108 -12.271834 0.1908067 0.9061050 -0.0504485 0.3741944 +VERTEX_SE3:QUAT 219 14.409781 7.051702 -13.404546 0.7301860 0.4517247 0.4931882 0.1397806 +VERTEX_SE3:QUAT 220 14.340678 7.931494 -13.676870 -0.2077280 0.6228313 0.4553742 0.6013024 +VERTEX_SE3:QUAT 221 14.423397 8.130909 -12.676750 0.4290177 0.4351596 0.7787447 0.1419036 +VERTEX_SE3:QUAT 222 14.348275 8.459882 -11.784729 -0.4748771 0.0795737 -0.8417461 0.2441788 +VERTEX_SE3:QUAT 223 14.339246 8.648712 -10.911231 0.6134744 0.6429680 0.0386392 0.4568898 +VERTEX_SE3:QUAT 224 14.371348 8.775316 -9.835052 -0.1364764 0.7929275 0.0816757 0.5881915 +VERTEX_SE3:QUAT 225 14.369279 8.771717 -8.916805 0.4936252 0.5919132 0.6097604 0.1848382 +VERTEX_SE3:QUAT 226 14.467318 8.916835 -8.077750 -0.3910972 0.2568468 -0.6900751 0.5521495 +VERTEX_SE3:QUAT 227 14.684659 9.098430 -7.199937 0.1037988 0.4309549 0.5413459 0.7144566 +VERTEX_SE3:QUAT 228 14.704488 9.018698 -6.089782 -0.3885616 0.1775607 -0.8313524 0.3554509 +VERTEX_SE3:QUAT 229 14.622380 9.188088 -5.128644 0.7714023 -0.2357226 0.4874249 0.3343505 +VERTEX_SE3:QUAT 230 14.689364 9.318326 -4.083414 0.2787125 0.2994423 -0.4927798 0.7679985 +VERTEX_SE3:QUAT 231 14.760775 9.416714 -3.021616 0.1576737 0.5899728 -0.7755849 0.1598100 +VERTEX_SE3:QUAT 232 14.847610 9.347200 -2.018655 -0.8412963 0.0315918 -0.5376591 0.0463157 +VERTEX_SE3:QUAT 233 14.919018 9.355868 -1.055215 0.4705085 0.4013346 0.7811039 0.0861920 +VERTEX_SE3:QUAT 234 15.110388 9.269701 -0.092127 0.0399462 0.7837333 -0.1327980 0.6054181 +VERTEX_SE3:QUAT 235 15.280628 9.320008 0.906021 0.7482673 0.1701482 0.1713012 0.6179009 +VERTEX_SE3:QUAT 236 15.411532 9.319544 1.937301 -0.6173680 0.3635764 -0.0117874 0.6975170 +VERTEX_SE3:QUAT 237 15.474462 9.386962 2.993041 -0.6242646 0.4528374 -0.6083106 0.1875906 +VERTEX_SE3:QUAT 238 15.393933 9.206311 3.670974 0.3244482 0.0504096 0.2710340 0.9048385 +VERTEX_SE3:QUAT 239 15.725255 9.235096 4.618046 0.1649222 0.4867053 -0.2268272 0.8273259 +VERTEX_SE3:QUAT 240 15.748011 10.237724 4.764917 0.2162283 0.4789719 -0.2831245 0.8022915 +VERTEX_SE3:QUAT 241 15.613173 10.458556 3.790264 0.5488176 -0.1097002 0.5245981 0.6415310 +VERTEX_SE3:QUAT 242 15.541821 10.526684 2.809752 -0.3969896 -0.3225756 -0.8045579 0.3017130 +VERTEX_SE3:QUAT 243 15.380341 10.592453 1.818993 -0.4189818 0.5157941 -0.7455571 0.0505497 +VERTEX_SE3:QUAT 244 15.244731 10.753963 0.854196 0.6396998 0.2990477 0.5837185 0.4007834 +VERTEX_SE3:QUAT 245 15.114895 10.754683 -0.131990 -0.7382561 -0.1132796 -0.6488890 0.1452195 +VERTEX_SE3:QUAT 246 15.034757 10.808962 -1.180189 0.2619760 -0.0854008 0.8994241 0.3392810 +VERTEX_SE3:QUAT 247 14.821773 10.944389 -2.102962 0.2840282 0.2409622 0.8946698 0.2466397 +VERTEX_SE3:QUAT 248 14.743936 11.014340 -3.023597 0.5009109 0.5243163 0.0528121 0.6865795 +VERTEX_SE3:QUAT 249 14.891591 11.086179 -4.064054 -0.3050068 0.4056950 0.6066398 0.6118582 +VERTEX_SE3:QUAT 250 15.164376 11.267635 -5.051583 -0.4530944 0.5390284 0.1414780 0.6958001 +VERTEX_SE3:QUAT 251 15.097301 11.262452 -5.920910 0.0888941 0.5680198 0.7944827 0.1955725 +VERTEX_SE3:QUAT 252 15.434085 11.161804 -6.842836 -0.5568737 0.6088995 -0.3590676 0.4361234 +VERTEX_SE3:QUAT 253 15.771250 11.095385 -7.842685 -0.2560526 0.5222022 0.4684185 0.6650760 +VERTEX_SE3:QUAT 254 16.119051 11.201955 -8.861113 -0.0421073 0.5070966 -0.6817479 0.5256423 +VERTEX_SE3:QUAT 255 16.514902 11.177282 -9.843425 0.0885258 0.2532412 0.6260539 0.7321807 +VERTEX_SE3:QUAT 256 16.826655 11.025650 -10.635596 -0.8483115 0.4402525 -0.0106851 0.2939916 +VERTEX_SE3:QUAT 257 17.077320 10.939964 -11.655306 -0.7471885 -0.4088464 -0.3293008 0.4075720 +VERTEX_SE3:QUAT 258 17.519534 10.979231 -12.419672 0.1194676 0.7147084 0.6575055 0.2064119 +VERTEX_SE3:QUAT 259 17.986082 10.939895 -13.186058 0.4661292 -0.5154951 0.7003050 0.1629767 +VERTEX_SE3:QUAT 260 17.630098 11.802695 -13.297765 0.7253113 0.3123409 0.5993576 0.1309090 +VERTEX_SE3:QUAT 261 17.363550 11.925160 -12.255230 0.2320443 0.8054933 -0.2309736 0.4939507 +VERTEX_SE3:QUAT 262 17.088423 11.959381 -11.415003 -0.0366183 0.3411356 0.5173623 0.7839782 +VERTEX_SE3:QUAT 263 16.745089 11.866911 -10.369369 -0.2180224 -0.1349552 -0.9366443 0.2386434 +VERTEX_SE3:QUAT 264 16.557003 11.845082 -9.374316 -0.7408271 0.5499460 -0.3856586 0.0014384 +VERTEX_SE3:QUAT 265 16.275655 11.590056 -8.322242 0.1040356 0.6835504 0.6087664 0.3890231 +VERTEX_SE3:QUAT 266 16.200845 11.570211 -7.456385 -0.5898174 -0.4063525 -0.3655533 0.5944441 +VERTEX_SE3:QUAT 267 16.150976 11.543339 -6.625435 -0.3407482 0.6188704 0.6912764 0.1517467 +VERTEX_SE3:QUAT 268 15.909005 11.485447 -5.748572 -0.0213939 0.4196283 0.7332765 0.5345652 +VERTEX_SE3:QUAT 269 15.879398 11.516052 -4.702965 -0.2983744 -0.7422527 -0.5840030 0.1377471 +VERTEX_SE3:QUAT 270 15.719732 11.442326 -3.710614 -0.3752884 0.7210734 -0.1835612 0.5527360 +VERTEX_SE3:QUAT 271 15.628939 11.408751 -2.649299 0.7685492 0.2892905 0.4165113 0.3900787 +VERTEX_SE3:QUAT 272 15.450504 11.354462 -1.656456 0.1247728 -0.0192272 0.6599465 0.7406299 +VERTEX_SE3:QUAT 273 15.382120 11.527516 -0.620397 -0.1630655 0.5984234 0.1382288 0.7721346 +VERTEX_SE3:QUAT 274 15.167563 11.763836 0.312858 0.1516190 -0.1940079 0.9692049 0.0038080 +VERTEX_SE3:QUAT 275 14.855667 11.890022 1.509835 0.1103817 0.2582533 0.9594943 0.0221784 +VERTEX_SE3:QUAT 276 14.649375 11.854150 2.456094 0.9452897 0.0235898 0.3220982 0.0460841 +VERTEX_SE3:QUAT 277 14.575302 11.976527 3.596186 0.5169624 0.2944569 0.0004770 0.8037691 +VERTEX_SE3:QUAT 278 14.691446 11.959257 4.588449 -0.5626985 0.0669944 -0.4242784 0.7063073 +VERTEX_SE3:QUAT 279 14.740937 11.920768 5.484508 -0.4896218 0.2060799 -0.8327235 0.1561190 +VERTEX_SE3:QUAT 280 14.165110 12.602146 5.481467 0.1356436 0.4956639 0.1563173 0.8434945 +VERTEX_SE3:QUAT 281 14.104436 12.594711 4.543896 -0.2226458 0.2737949 0.8600895 0.3683902 +VERTEX_SE3:QUAT 282 14.102769 12.462813 3.536402 0.0003390 0.1894623 -0.7990445 0.5706416 +VERTEX_SE3:QUAT 283 14.175262 12.274981 2.406181 -0.0788939 0.2377986 -0.5464038 0.7991686 +VERTEX_SE3:QUAT 284 14.023521 12.172906 1.546459 0.0634462 0.4739774 0.8768437 0.0496505 +VERTEX_SE3:QUAT 285 13.848654 12.111989 0.652412 0.1104152 0.8859684 -0.0549690 0.4470423 +VERTEX_SE3:QUAT 286 13.721708 12.078663 -0.378496 -0.7693069 0.0570624 -0.4005052 0.4944758 +VERTEX_SE3:QUAT 287 13.797603 12.072188 -1.526499 0.0266727 0.3788175 -0.4985564 0.7792480 +VERTEX_SE3:QUAT 288 13.699361 11.980405 -2.479297 -0.3694395 -0.2515910 -0.3201220 0.8353073 +VERTEX_SE3:QUAT 289 13.699071 11.863090 -3.555347 -0.1012802 0.4184657 0.6809684 0.5923773 +VERTEX_SE3:QUAT 290 13.660728 11.686667 -4.671223 -0.4900617 0.4157107 -0.1055115 0.7588751 +VERTEX_SE3:QUAT 291 13.522961 11.563517 -5.721846 0.1247579 0.2594988 0.7803822 0.5550670 +VERTEX_SE3:QUAT 292 13.648406 11.257729 -6.783487 -0.0946383 0.8928663 0.2598643 0.3553926 +VERTEX_SE3:QUAT 293 13.434838 11.058186 -7.662748 -0.1759296 -0.6937246 -0.6720555 0.1900954 +VERTEX_SE3:QUAT 294 13.565032 11.000122 -8.562556 0.4236947 0.2514927 -0.0699341 0.8673774 +VERTEX_SE3:QUAT 295 13.505843 10.839134 -9.408303 -0.4960081 0.3323453 0.4288502 0.6779454 +VERTEX_SE3:QUAT 296 13.376928 10.442641 -10.501694 -0.3057853 -0.2650965 -0.8965089 0.1802524 +VERTEX_SE3:QUAT 297 13.369016 10.181673 -11.314040 -0.4631841 0.4360319 0.0204163 0.7713104 +VERTEX_SE3:QUAT 298 13.555025 10.195175 -12.109647 -0.8618053 -0.4228908 -0.2190573 0.1745536 +VERTEX_SE3:QUAT 299 13.442603 10.122429 -13.170448 0.8290601 -0.2809242 0.3144401 0.3672442 +VERTEX_SE3:QUAT 300 13.119376 10.952698 -13.182465 -0.6068659 0.7506400 -0.1135349 0.2352939 +VERTEX_SE3:QUAT 301 13.302822 11.095437 -12.151292 0.3303322 0.4376829 0.0941065 0.8309382 +VERTEX_SE3:QUAT 302 13.246225 11.148723 -11.196869 0.0523631 0.8948483 -0.3320533 0.2936753 +VERTEX_SE3:QUAT 303 13.349103 11.191013 -10.171254 0.2711262 0.2644900 0.7462698 0.5473728 +VERTEX_SE3:QUAT 304 13.590548 11.088395 -9.084479 0.3947430 0.5427521 0.7284475 0.1377035 +VERTEX_SE3:QUAT 305 13.846274 11.028241 -8.190879 -0.4630506 0.6673710 -0.5173585 0.2693330 +VERTEX_SE3:QUAT 306 14.108186 10.990646 -7.229298 0.5664738 0.1744109 0.7340272 0.3315001 +VERTEX_SE3:QUAT 307 14.216845 10.864368 -6.085874 0.4975897 -0.6243049 0.5863717 0.1371719 +VERTEX_SE3:QUAT 308 14.234635 10.782275 -5.154096 -0.3342818 0.7322743 -0.2307652 0.5466054 +VERTEX_SE3:QUAT 309 14.526210 10.755692 -4.314048 0.3961390 -0.0823171 0.9040387 0.1378835 +VERTEX_SE3:QUAT 310 14.518752 10.763439 -3.171086 0.2253520 0.0648925 0.6241329 0.7452943 +VERTEX_SE3:QUAT 311 14.787430 10.495049 -2.180938 0.5007730 0.2436546 0.4614203 0.6906157 +VERTEX_SE3:QUAT 312 14.871851 10.396670 -1.300904 0.6290184 -0.3154646 0.6635435 0.2540236 +VERTEX_SE3:QUAT 313 14.998339 10.499118 -0.236780 0.0314784 0.3263505 0.9285947 0.1738287 +VERTEX_SE3:QUAT 314 14.936872 10.460320 0.824425 0.4582189 0.2494161 -0.0974664 0.8475419 +VERTEX_SE3:QUAT 315 15.009533 10.067844 2.015732 -0.3837106 -0.5979405 -0.4080433 0.5733533 +VERTEX_SE3:QUAT 316 14.945211 9.817871 3.044556 -0.3882427 0.8044648 0.3125392 0.3231459 +VERTEX_SE3:QUAT 317 14.859004 9.606744 3.924005 0.4037670 0.8064174 0.4114725 0.1317331 +VERTEX_SE3:QUAT 318 15.023040 9.450547 4.958675 0.0224225 0.8254543 -0.3340699 0.4544445 +VERTEX_SE3:QUAT 319 15.093427 9.347473 5.932978 -0.3854865 0.5158436 -0.1568265 0.7488064 +VERTEX_SE3:QUAT 320 14.657860 10.438150 5.951662 -0.6114572 0.1425894 -0.6391971 0.4440894 +VERTEX_SE3:QUAT 321 14.537303 10.542047 4.786056 -0.3515980 0.4150425 -0.8128187 0.2084331 +VERTEX_SE3:QUAT 322 14.661358 10.663100 3.920137 0.7915075 -0.4872750 0.3387282 0.1460897 +VERTEX_SE3:QUAT 323 14.578459 10.717346 2.767427 -0.6138518 0.1499282 -0.3938693 0.6675137 +VERTEX_SE3:QUAT 324 14.226065 10.733200 1.891245 0.0584889 0.1669976 0.9257288 0.3342411 +VERTEX_SE3:QUAT 325 13.973392 10.749528 0.972326 -0.3154781 0.7330952 0.5651347 0.2089682 +VERTEX_SE3:QUAT 326 13.721656 11.000765 -0.059031 -0.6956064 0.5424719 0.0271676 0.4702317 +VERTEX_SE3:QUAT 327 13.611210 11.208816 -1.036524 -0.6955939 -0.0072744 -0.6999873 0.1615984 +VERTEX_SE3:QUAT 328 13.425118 11.541702 -2.099179 -0.7988094 0.4844555 -0.1832569 0.3059793 +VERTEX_SE3:QUAT 329 13.290996 11.717860 -3.100128 -0.0906601 -0.9554622 -0.2537068 0.1204396 +VERTEX_SE3:QUAT 330 13.210641 12.102793 -4.324114 -0.4875257 0.1908689 0.3784753 0.7633113 +VERTEX_SE3:QUAT 331 12.876782 12.456899 -5.202090 -0.6095231 0.4137414 0.5153966 0.4377967 +VERTEX_SE3:QUAT 332 12.643882 12.708706 -6.009153 -0.7501466 0.0273482 0.0119466 0.6605978 +VERTEX_SE3:QUAT 333 12.507506 12.954398 -6.978163 -0.1161352 0.5503485 0.7783501 0.2789269 +VERTEX_SE3:QUAT 334 12.260401 13.181411 -7.820414 -0.8706712 -0.4891983 0.0116163 0.0498169 +VERTEX_SE3:QUAT 335 12.168965 13.383238 -8.793319 0.4646527 -0.0536597 0.8824385 0.0502075 +VERTEX_SE3:QUAT 336 12.099860 13.682029 -9.602662 0.6008718 -0.2119016 0.6379486 0.4325186 +VERTEX_SE3:QUAT 337 12.150125 13.892980 -10.660238 0.1156668 0.1985916 -0.6137719 0.7552924 +VERTEX_SE3:QUAT 338 12.107548 14.188032 -11.489775 0.0377145 0.7866335 0.1963792 0.5841409 +VERTEX_SE3:QUAT 339 11.917208 14.545558 -12.595494 -0.2498848 0.6195183 -0.3404553 0.6616985 +VERTEX_SE3:QUAT 340 11.868477 15.526936 -12.423568 -0.3481805 0.6900988 0.6168818 0.1482927 +VERTEX_SE3:QUAT 341 11.983119 15.293630 -11.404805 -0.1388882 0.8058485 -0.4761928 0.3233554 +VERTEX_SE3:QUAT 342 12.153993 15.081233 -10.268602 -0.2371700 -0.9543283 -0.1810436 0.0152030 +VERTEX_SE3:QUAT 343 12.217219 14.941075 -9.297345 -0.3337608 0.7211350 0.0681834 0.6032570 +VERTEX_SE3:QUAT 344 12.368333 14.556938 -8.181894 -0.3749030 -0.3001178 -0.7216157 0.4986460 +VERTEX_SE3:QUAT 345 12.449689 14.421603 -7.187741 -0.0759231 0.5035026 -0.4580987 0.7286058 +VERTEX_SE3:QUAT 346 12.460370 14.369447 -6.069208 -0.6883082 -0.1810660 -0.2767141 0.6456596 +VERTEX_SE3:QUAT 347 12.711192 14.115084 -5.299103 0.9349822 0.1537875 0.2371987 0.2142299 +VERTEX_SE3:QUAT 348 12.984968 13.931513 -4.199425 -0.1648124 0.7985849 -0.3531495 0.4586768 +VERTEX_SE3:QUAT 349 13.220651 13.613954 -3.155675 0.8849331 -0.0949387 0.3539693 0.2873776 +VERTEX_SE3:QUAT 350 13.525527 13.483484 -2.312916 -0.2693194 0.3741488 -0.1334089 0.8773151 +VERTEX_SE3:QUAT 351 13.577335 13.247305 -1.231657 -0.6468105 0.5552529 -0.2115443 0.4780997 +VERTEX_SE3:QUAT 352 13.746776 13.046037 -0.279970 -0.8596656 0.3751900 0.2405140 0.2497211 +VERTEX_SE3:QUAT 353 13.942634 12.553665 0.692007 0.3671537 0.6030142 -0.5060090 0.4955068 +VERTEX_SE3:QUAT 354 14.032685 12.400450 1.459883 -0.4132680 0.7708118 -0.3257047 0.3591312 +VERTEX_SE3:QUAT 355 14.235454 12.339085 2.577694 0.7655930 0.5717235 -0.1142715 0.2719221 +VERTEX_SE3:QUAT 356 14.464821 12.168725 3.639050 -0.2498611 0.6411900 0.6631965 0.2943047 +VERTEX_SE3:QUAT 357 14.748173 11.982267 4.632003 -0.1725265 0.8167857 -0.2283582 0.5009473 +VERTEX_SE3:QUAT 358 15.165176 11.714667 5.543086 -0.4421700 0.2607978 -0.8338253 0.2029919 +VERTEX_SE3:QUAT 359 15.269548 11.302884 6.493801 0.3686038 -0.3521096 0.8292287 0.2291939 +VERTEX_SE3:QUAT 360 15.018963 12.305457 6.683337 0.4358319 0.4163364 0.3850744 0.6988793 +VERTEX_SE3:QUAT 361 14.597753 12.431923 5.529461 -0.6499998 -0.3978893 -0.5320192 0.3689715 +VERTEX_SE3:QUAT 362 14.287768 12.518982 4.753859 -0.6909394 0.2832410 -0.3654181 0.5557399 +VERTEX_SE3:QUAT 363 14.112617 12.598807 3.613701 -0.2645974 0.0565004 -0.2683864 0.9245348 +VERTEX_SE3:QUAT 364 13.985696 12.795762 2.726794 -0.9608127 0.0853720 -0.2419681 0.1048907 +VERTEX_SE3:QUAT 365 13.663568 12.900243 1.911724 0.4894837 0.1257681 0.7119562 0.4875515 +VERTEX_SE3:QUAT 366 13.721843 13.107196 0.964197 -0.8088516 0.4296781 -0.3853383 0.1124730 +VERTEX_SE3:QUAT 367 13.703836 13.332225 -0.063032 -0.6330171 0.5974461 -0.4897068 0.0503464 +VERTEX_SE3:QUAT 368 13.597846 13.423291 -1.127546 0.2680063 0.1525328 0.7360489 0.6026096 +VERTEX_SE3:QUAT 369 13.318593 13.547426 -1.985162 -0.8052525 0.2541890 -0.5344704 0.0360253 +VERTEX_SE3:QUAT 370 13.145660 13.718965 -2.891912 -0.0076036 0.5742558 0.4016093 0.7133600 +VERTEX_SE3:QUAT 371 12.949612 13.857784 -3.867996 -0.4423061 0.7854016 0.1122881 0.4182117 +VERTEX_SE3:QUAT 372 12.945710 14.016086 -4.909356 -0.3086885 0.0091702 -0.3701783 0.8761252 +VERTEX_SE3:QUAT 373 12.747425 13.894097 -5.765062 0.6460808 0.5113925 -0.0714640 0.5620945 +VERTEX_SE3:QUAT 374 12.553681 14.122252 -6.801400 0.1053283 0.6450531 0.4635666 0.5982628 +VERTEX_SE3:QUAT 375 12.264731 14.333833 -7.856281 -0.4327351 -0.1781808 -0.5850224 0.6623751 +VERTEX_SE3:QUAT 376 12.188131 14.368859 -8.788069 0.4499241 0.7217730 0.1462391 0.5051992 +VERTEX_SE3:QUAT 377 12.113235 14.421018 -9.771474 0.0009550 0.2579389 0.2586230 0.9309032 +VERTEX_SE3:QUAT 378 12.151101 14.584034 -10.614916 0.9494915 -0.2890577 0.1148572 0.0414658 +VERTEX_SE3:QUAT 379 12.009240 14.809586 -11.614236 -0.6473064 0.5104062 -0.2625855 0.5015265 +VERTEX_SE3:QUAT 380 11.952295 15.943427 -11.634930 -0.6200251 0.4277791 0.0694009 0.6540317 +VERTEX_SE3:QUAT 381 12.012633 16.005917 -10.576209 -0.9172591 0.3821834 -0.0186186 0.1105669 +VERTEX_SE3:QUAT 382 12.084351 16.107872 -9.556490 -0.3550642 0.1420917 0.2463323 0.8905390 +VERTEX_SE3:QUAT 383 12.076781 16.185275 -8.456850 -0.3470265 0.6148135 0.5913828 0.3896709 +VERTEX_SE3:QUAT 384 11.979736 16.350155 -7.542159 -0.2172888 -0.9022017 -0.3701282 0.0426938 +VERTEX_SE3:QUAT 385 11.881517 16.566678 -6.639406 -0.5372571 -0.8301866 -0.1453578 0.0318777 +VERTEX_SE3:QUAT 386 11.814348 16.681246 -5.567919 0.7920271 0.0828190 0.3670416 0.4807438 +VERTEX_SE3:QUAT 387 11.560201 16.771282 -4.582071 -0.7186066 0.0992625 -0.2027181 0.6577666 +VERTEX_SE3:QUAT 388 11.441987 16.954676 -3.672274 0.0001904 0.5316949 -0.6627281 0.5273443 +VERTEX_SE3:QUAT 389 11.467638 17.137316 -2.677835 -0.3882825 0.3367742 -0.2277117 0.8270231 +VERTEX_SE3:QUAT 390 11.451257 17.215784 -1.658152 0.6804249 -0.4859388 0.5484993 0.0058348 +VERTEX_SE3:QUAT 391 11.448563 17.387470 -0.721723 0.0193528 0.1883050 -0.0419562 0.9810231 +VERTEX_SE3:QUAT 392 11.272790 17.448781 0.322717 0.3534823 0.5895962 0.1587094 0.7086874 +VERTEX_SE3:QUAT 393 11.327284 17.840680 1.559606 -0.7766974 -0.0141356 -0.6260243 0.0680799 +VERTEX_SE3:QUAT 394 11.386537 18.023749 2.590684 0.2382176 0.0282924 0.7294004 0.6406458 +VERTEX_SE3:QUAT 395 11.442946 18.074605 3.423318 0.8526322 0.0624061 0.5087126 0.1016627 +VERTEX_SE3:QUAT 396 11.389719 18.143476 4.396209 0.4411782 0.5973760 0.5206932 0.4211679 +VERTEX_SE3:QUAT 397 11.488710 18.083467 5.339035 -0.1304676 0.3455920 -0.8555256 0.3627952 +VERTEX_SE3:QUAT 398 11.667951 18.262102 6.437966 -0.7166737 -0.6633597 -0.1892500 0.1025527 +VERTEX_SE3:QUAT 399 12.016782 18.300424 7.234225 0.3084038 0.1555874 0.5288864 0.7752154 +VERTEX_SE3:QUAT 400 7.977004 17.097706 -11.437016 -0.0917140 0.7841653 0.0388724 0.6125048 +VERTEX_SE3:QUAT 401 8.339058 17.226993 -10.572920 -0.8201077 -0.4204528 -0.3532423 0.1608188 +VERTEX_SE3:QUAT 402 8.511135 17.471055 -9.753138 0.2843572 0.9505369 0.1226524 0.0240195 +VERTEX_SE3:QUAT 403 8.973158 17.696121 -9.020365 0.9436709 0.0299095 0.2892985 0.1577880 +VERTEX_SE3:QUAT 404 9.265874 17.780139 -8.007169 -0.6764043 0.5921398 -0.4111156 0.1511011 +VERTEX_SE3:QUAT 405 9.634222 17.850138 -7.079728 0.2088446 0.0515437 0.9573336 0.1929753 +VERTEX_SE3:QUAT 406 9.997902 17.963038 -6.150924 -0.2650716 0.6225922 0.4167734 0.6069728 +VERTEX_SE3:QUAT 407 10.304752 18.033420 -5.138888 -0.4787497 0.6791049 -0.0982784 0.5476830 +VERTEX_SE3:QUAT 408 10.662473 18.329553 -4.238277 -0.5622701 -0.5671930 -0.4342704 0.4165976 +VERTEX_SE3:QUAT 409 10.987380 18.439445 -3.283175 0.9190064 0.3567836 -0.1213242 0.1158151 +VERTEX_SE3:QUAT 410 11.235214 18.481446 -2.254443 0.9025398 0.3146556 0.0518134 0.2893598 +VERTEX_SE3:QUAT 411 11.669757 18.572812 -1.276674 0.2178789 0.2715801 0.3869395 0.8538447 +VERTEX_SE3:QUAT 412 11.882854 18.869012 -0.343073 -0.5736590 0.3835939 0.2967474 0.6600849 +VERTEX_SE3:QUAT 413 12.212952 19.095724 0.638172 -0.5630574 0.5967250 -0.4779694 0.3137369 +VERTEX_SE3:QUAT 414 12.442225 19.015618 1.619692 -0.3208218 0.7272189 0.5570633 0.2406377 +VERTEX_SE3:QUAT 415 12.574383 19.007752 2.405836 -0.4303867 0.7332930 -0.4440221 0.2826536 +VERTEX_SE3:QUAT 416 13.069678 19.258703 3.235683 0.0510314 0.1979774 0.6396035 0.7410183 +VERTEX_SE3:QUAT 417 13.352090 19.298934 4.144055 -0.0943401 0.4653783 0.1297182 0.8704575 +VERTEX_SE3:QUAT 418 13.761282 19.534869 5.196738 -0.6488751 -0.6986178 -0.0520229 0.2969643 +VERTEX_SE3:QUAT 419 13.988333 19.571960 6.089472 -0.6732666 -0.1457424 -0.2955637 0.6619013 +VERTEX_SE3:QUAT 420 14.483882 18.685116 6.310831 -0.2679969 0.2300597 0.5024362 0.7891819 +VERTEX_SE3:QUAT 421 14.255346 18.440736 5.473870 -0.4631061 0.6855036 -0.4969677 0.2619935 +VERTEX_SE3:QUAT 422 13.968039 18.033734 4.626105 -0.3243170 0.5434844 -0.1272939 0.7637011 +VERTEX_SE3:QUAT 423 13.463988 17.680814 3.750807 0.8904174 0.0580214 0.2144200 0.3972586 +VERTEX_SE3:QUAT 424 12.980509 17.256142 2.958903 -0.7405646 0.0578366 -0.5705391 0.3502914 +VERTEX_SE3:QUAT 425 12.516992 16.963437 2.126263 -0.6023913 -0.7330002 0.0217651 0.3152168 +VERTEX_SE3:QUAT 426 12.109486 16.767024 1.390224 -0.0623024 0.9025675 0.4231295 0.0495150 +VERTEX_SE3:QUAT 427 11.767870 16.257283 0.816522 0.8297970 0.1840103 0.5259610 0.0306941 +VERTEX_SE3:QUAT 428 11.223969 15.981446 -0.102085 0.9543812 0.0974171 0.0649070 0.2746882 +VERTEX_SE3:QUAT 429 10.791818 15.824290 -1.065867 0.6503958 -0.6749992 0.2635136 0.2278638 +VERTEX_SE3:QUAT 430 10.162631 15.462637 -1.918495 0.7903631 0.5914444 0.0065927 0.1596127 +VERTEX_SE3:QUAT 431 9.874522 15.214087 -2.746576 0.9762204 0.0925220 -0.1820859 0.0726515 +VERTEX_SE3:QUAT 432 9.152163 14.859796 -3.424242 -0.6549840 -0.2649397 -0.7038836 0.0731495 +VERTEX_SE3:QUAT 433 8.475898 14.387643 -4.203242 0.2869374 0.6030219 0.3316299 0.6663731 +VERTEX_SE3:QUAT 434 8.045007 13.982533 -4.894947 0.0374247 -0.6035836 -0.7607013 0.2358385 +VERTEX_SE3:QUAT 435 7.554038 13.697982 -5.696948 -0.4065650 0.1822920 -0.2711698 0.8531948 +VERTEX_SE3:QUAT 436 6.897611 13.192862 -6.419425 0.9592189 -0.1403704 0.1018120 0.2232252 +VERTEX_SE3:QUAT 437 6.270679 12.988416 -7.013240 -0.9125829 0.0916085 0.3931073 0.0653214 +VERTEX_SE3:QUAT 438 5.588093 12.794730 -7.775654 0.0779527 0.7844916 0.5998444 0.1366859 +VERTEX_SE3:QUAT 439 5.085791 12.473519 -8.497441 -0.3631222 -0.9261725 0.0540263 0.0861853 +VERTEX_SE3:QUAT 440 5.721025 11.695768 -8.687264 0.6226533 -0.6847451 -0.3536617 0.1354638 +VERTEX_SE3:QUAT 441 6.417284 12.266712 -8.134552 -0.0921038 -0.9913341 0.0015237 0.0936546 +VERTEX_SE3:QUAT 442 7.284103 12.380405 -7.470794 -0.4860174 -0.4735628 -0.5905684 0.4367543 +VERTEX_SE3:QUAT 443 7.998017 12.677524 -6.816768 -0.2611629 0.5998216 0.3999972 0.6418803 +VERTEX_SE3:QUAT 444 8.482902 12.902061 -5.952018 0.2348499 0.9226928 0.0686315 0.2979482 +VERTEX_SE3:QUAT 445 9.126804 13.301297 -5.340059 0.9444309 -0.1678039 0.2641927 0.1004708 +VERTEX_SE3:QUAT 446 9.708828 13.883658 -4.619598 0.1449145 -0.6444672 -0.7349831 0.1531718 +VERTEX_SE3:QUAT 447 10.273284 14.355508 -3.877335 0.2266086 -0.9115990 0.3340193 0.0778910 +VERTEX_SE3:QUAT 448 10.815206 14.913410 -3.026432 -0.6270859 0.3755171 0.5554194 0.3965595 +VERTEX_SE3:QUAT 449 11.459306 15.545778 -2.227645 -0.4931648 -0.7425514 -0.0188898 0.4528234 +VERTEX_SE3:QUAT 450 11.811749 16.115322 -1.659777 0.9457743 0.1208387 -0.2586335 0.1549762 +VERTEX_SE3:QUAT 451 12.175673 16.792519 -1.030188 -0.7709002 0.5992092 -0.1320017 0.1709874 +VERTEX_SE3:QUAT 452 12.517885 17.371252 -0.279715 -0.3338736 -0.9108521 -0.2037935 0.1317007 +VERTEX_SE3:QUAT 453 13.049519 18.007608 0.462281 -0.2607113 -0.8956801 -0.2026158 0.2978817 +VERTEX_SE3:QUAT 454 13.520740 18.520845 1.283708 -0.7711969 0.3521076 -0.3605270 0.3889676 +VERTEX_SE3:QUAT 455 14.010521 19.151213 1.966899 -0.7681618 0.3443177 -0.2244530 0.4909110 +VERTEX_SE3:QUAT 456 14.508684 19.745514 2.456998 0.5886827 0.3894261 0.2518419 0.6620994 +VERTEX_SE3:QUAT 457 14.898148 20.386594 3.132259 -0.8294557 0.2048972 0.2915116 0.4301644 +VERTEX_SE3:QUAT 458 15.408890 20.944334 3.808539 0.9220945 -0.0562566 -0.0161692 0.3825120 +VERTEX_SE3:QUAT 459 15.835185 21.597376 4.329663 -0.8598161 0.4040619 -0.3061947 0.0607876 +VERTEX_SE3:QUAT 460 16.569841 21.045484 4.230354 -0.7972429 0.3204339 0.0536637 0.5087692 +VERTEX_SE3:QUAT 461 16.013213 20.440822 3.541308 -0.7519761 -0.6450609 0.1353793 0.0100356 +VERTEX_SE3:QUAT 462 15.369566 20.011749 2.936945 -0.4357442 0.2130174 -0.2451550 0.8394341 +VERTEX_SE3:QUAT 463 14.786097 19.496681 2.507538 -0.8701668 0.0102751 0.2234331 0.4390693 +VERTEX_SE3:QUAT 464 14.246730 19.102228 1.801687 -0.3532692 -0.7104453 -0.3031229 0.5278114 +VERTEX_SE3:QUAT 465 13.730022 18.667773 1.169087 0.5683157 -0.7457076 -0.1313398 0.3220052 +VERTEX_SE3:QUAT 466 13.140255 18.137139 0.406866 -0.5085280 -0.8544315 0.0916153 0.0543393 +VERTEX_SE3:QUAT 467 12.519475 17.593953 -0.360276 0.7218023 -0.2016707 0.6529893 0.1092486 +VERTEX_SE3:QUAT 468 11.825683 17.177532 -1.018733 0.8734909 -0.0553886 0.4346814 0.2121270 +VERTEX_SE3:QUAT 469 11.254960 16.916850 -1.723274 0.8009735 -0.5585145 0.1680161 0.1351799 +VERTEX_SE3:QUAT 470 10.549856 16.607515 -2.529677 0.2953915 0.4515253 0.8265568 0.1602267 +VERTEX_SE3:QUAT 471 10.054270 16.236476 -3.371035 -0.7141696 0.3587820 -0.3573622 0.4832489 +VERTEX_SE3:QUAT 472 9.647215 15.957681 -4.166752 -0.5651983 -0.0563268 -0.4134848 0.7116239 +VERTEX_SE3:QUAT 473 9.224824 15.709953 -5.150596 -0.5710173 0.0142872 -0.3652304 0.7350795 +VERTEX_SE3:QUAT 474 8.643273 15.487957 -6.074058 0.1697236 -0.8962952 -0.4084898 0.0313818 +VERTEX_SE3:QUAT 475 8.112595 15.061496 -6.763213 -0.8695143 0.3967994 -0.1552980 0.2497553 +VERTEX_SE3:QUAT 476 7.726955 14.859111 -7.766888 0.0005132 -0.9296633 0.3444052 0.1308091 +VERTEX_SE3:QUAT 477 7.054435 14.364058 -8.660837 0.9791411 0.1165426 -0.0042934 0.1663792 +VERTEX_SE3:QUAT 478 6.414702 13.977144 -9.493166 -0.7001002 -0.3143102 -0.1041513 0.6326304 +VERTEX_SE3:QUAT 479 5.993475 13.680020 -10.130338 -0.3049260 0.5604299 0.4993661 0.5861500 +VERTEX_SE3:QUAT 480 6.425485 12.883522 -10.179310 0.1607555 0.7680321 -0.5126644 0.3485105 +VERTEX_SE3:QUAT 481 6.903537 13.119233 -9.383197 -0.7007991 0.3017343 -0.6329994 0.1309537 +VERTEX_SE3:QUAT 482 7.391782 13.490072 -8.511623 -0.8091816 -0.4434853 -0.3707112 0.1054472 +VERTEX_SE3:QUAT 483 7.763048 14.003765 -7.714231 -0.5533685 0.7781326 -0.2913450 0.0584046 +VERTEX_SE3:QUAT 484 8.433199 14.456393 -6.944395 0.7858184 0.5871533 -0.1865230 0.0543112 +VERTEX_SE3:QUAT 485 8.977817 14.880657 -6.254602 -0.7240938 -0.1161284 -0.6615806 0.1565677 +VERTEX_SE3:QUAT 486 9.449149 15.143229 -5.578580 -0.8179636 -0.3828731 -0.4280389 0.0335621 +VERTEX_SE3:QUAT 487 10.130874 15.355533 -4.771271 -0.8030799 -0.3551384 -0.1115419 0.4652932 +VERTEX_SE3:QUAT 488 10.741237 15.617581 -3.949472 -0.5753447 0.3627227 0.4735518 0.5596064 +VERTEX_SE3:QUAT 489 11.143844 15.749376 -3.090847 0.6596802 0.3424245 0.4376071 0.5060311 +VERTEX_SE3:QUAT 490 11.639863 16.138449 -2.427754 0.6456591 0.5857025 0.2940810 0.3919098 +VERTEX_SE3:QUAT 491 12.116668 16.366560 -1.613564 -0.6111170 0.0118981 -0.4540724 0.6482381 +VERTEX_SE3:QUAT 492 12.591776 16.610989 -0.731459 -0.9386480 -0.1134034 -0.3256519 0.0055236 +VERTEX_SE3:QUAT 493 13.113043 16.631934 0.194436 -0.6031472 0.3858376 -0.6301102 0.3005062 +VERTEX_SE3:QUAT 494 13.757501 16.910855 1.061861 0.3354752 0.9381466 -0.0771307 0.0372597 +VERTEX_SE3:QUAT 495 14.365835 17.168954 1.888137 -0.6634723 0.4013532 -0.5838044 0.2406086 +VERTEX_SE3:QUAT 496 14.798190 17.222342 2.707724 -0.9569369 -0.0535466 0.0112877 0.2850913 +VERTEX_SE3:QUAT 497 15.240461 17.248757 3.525980 -0.5656076 0.6977814 -0.4196183 0.1308038 +VERTEX_SE3:QUAT 498 15.721691 17.177757 4.336333 -0.4235214 0.7680154 -0.0472380 0.4780697 +VERTEX_SE3:QUAT 499 16.019951 17.035777 5.324739 0.0657180 0.3535406 0.8694382 0.3387734 +VERTEX_SE3:QUAT 500 16.390421 16.245849 4.951647 -0.8425712 -0.3187891 -0.4334011 0.0247124 +VERTEX_SE3:QUAT 501 16.010472 16.358371 3.946929 -0.8698982 -0.0680618 -0.2308660 0.4305179 +VERTEX_SE3:QUAT 502 15.717095 16.505177 2.929287 0.0511444 0.7503779 -0.3138723 0.5794838 +VERTEX_SE3:QUAT 503 15.416869 16.734416 2.015800 -0.1203112 0.6998025 -0.1427793 0.6895040 +VERTEX_SE3:QUAT 504 15.176414 16.934777 1.021627 -0.6876062 0.3284295 -0.6475051 0.0083001 +VERTEX_SE3:QUAT 505 14.748077 17.046408 -0.004371 0.5435726 -0.0210570 0.8388482 0.0204732 +VERTEX_SE3:QUAT 506 14.639793 16.943478 -0.946193 -0.8507976 0.4303984 -0.0542015 0.2965854 +VERTEX_SE3:QUAT 507 14.480581 17.054137 -1.790592 -0.1006210 0.7093688 -0.2801140 0.6389112 +VERTEX_SE3:QUAT 508 14.282698 17.277990 -2.814990 -0.4820085 0.0783328 -0.8641411 0.1216225 +VERTEX_SE3:QUAT 509 14.058753 17.286883 -3.741953 -0.1923879 0.0639200 -0.4864783 0.8498471 +VERTEX_SE3:QUAT 510 13.534647 17.066124 -4.664747 0.4123310 0.4313085 0.6465475 0.4753236 +VERTEX_SE3:QUAT 511 13.247625 17.143275 -5.546563 -0.1933296 0.9369063 0.2903018 0.0235610 +VERTEX_SE3:QUAT 512 12.850750 16.923917 -6.375898 -0.8853507 0.4435691 0.0708764 0.1199043 +VERTEX_SE3:QUAT 513 12.605289 16.772372 -7.461483 -0.7559195 -0.5534497 -0.2620785 0.2315037 +VERTEX_SE3:QUAT 514 12.300129 16.814600 -8.400267 -0.6652141 -0.5450478 -0.3742345 0.3469318 +VERTEX_SE3:QUAT 515 11.682176 16.871150 -9.402874 -0.4777174 0.6226555 -0.5497729 0.2860698 +VERTEX_SE3:QUAT 516 11.043422 16.870631 -10.365419 -0.0042012 0.4467618 -0.0427762 0.8936198 +VERTEX_SE3:QUAT 517 10.652079 16.810798 -11.317247 -0.3536901 0.3195491 0.4855634 0.7328164 +VERTEX_SE3:QUAT 518 10.278511 16.800651 -12.221516 -0.8319882 0.1785162 0.2157640 0.4789296 +VERTEX_SE3:QUAT 519 9.807777 16.597063 -13.053915 -0.7436253 -0.3935418 0.1132868 0.5285001 +VERTEX_SE3:QUAT 520 10.626788 15.796709 -13.284338 -0.4068626 0.7960546 -0.1482191 0.4228369 +VERTEX_SE3:QUAT 521 11.180267 15.888050 -12.395132 0.5726644 0.6508043 -0.0289002 0.4976686 +VERTEX_SE3:QUAT 522 11.455887 15.905467 -11.690409 0.0824524 0.9701803 0.2085129 0.0920550 +VERTEX_SE3:QUAT 523 11.859292 16.081643 -10.923934 -0.3893666 0.1179100 -0.1923727 0.8930194 +VERTEX_SE3:QUAT 524 12.508915 16.192109 -10.105078 0.2402034 0.7624826 -0.0249043 0.6002519 +VERTEX_SE3:QUAT 525 12.834488 16.442442 -9.129624 -0.8460434 0.1189777 0.4611266 0.2396186 +VERTEX_SE3:QUAT 526 13.294648 16.708306 -8.299664 -0.4764919 0.2378577 0.0565182 0.8445027 +VERTEX_SE3:QUAT 527 13.630894 16.858093 -7.566609 -0.9235534 -0.3271323 -0.1423903 0.1405655 +VERTEX_SE3:QUAT 528 14.198841 17.106302 -6.906825 -0.4414742 0.2408580 0.2370549 0.8311997 +VERTEX_SE3:QUAT 529 14.838874 17.120845 -6.007545 -0.4867582 -0.2379025 -0.6116845 0.5764641 +VERTEX_SE3:QUAT 530 15.181658 17.332211 -5.145702 -0.1932643 -0.1865371 -0.9621724 0.0455749 +VERTEX_SE3:QUAT 531 15.734492 17.403476 -4.246625 -0.5270851 -0.4638827 -0.5053329 0.5016301 +VERTEX_SE3:QUAT 532 16.071670 17.536349 -3.277537 -0.6093398 -0.0921491 0.0047576 0.7875220 +VERTEX_SE3:QUAT 533 16.583069 17.462199 -2.085347 -0.6213282 0.0979225 -0.7741899 0.0706565 +VERTEX_SE3:QUAT 534 16.808483 17.446530 -1.136169 0.2343249 0.5639251 0.2676137 0.7452941 +VERTEX_SE3:QUAT 535 17.029431 17.390872 -0.106538 0.6294814 0.4637897 0.4035139 0.4752144 +VERTEX_SE3:QUAT 536 17.250998 17.461058 0.847155 0.9272171 0.1508711 0.3309014 0.0895024 +VERTEX_SE3:QUAT 537 17.442268 17.701196 1.861551 0.0183160 -0.5923102 -0.7996851 0.0966281 +VERTEX_SE3:QUAT 538 17.798332 17.763952 2.857528 0.4967008 0.4474139 0.7355396 0.1099569 +VERTEX_SE3:QUAT 539 18.022403 17.792047 3.882661 -0.9075735 -0.0141029 0.2063134 0.3654398 +VERTEX_SE3:QUAT 540 18.734171 16.949283 3.633924 -0.5391644 0.4973717 0.1637766 0.6596214 +VERTEX_SE3:QUAT 541 18.551088 16.846674 2.660716 -0.1641014 0.0823722 -0.4138051 0.8916563 +VERTEX_SE3:QUAT 542 18.395914 16.688239 1.694329 -0.7967119 -0.1221034 -0.3433279 0.4821481 +VERTEX_SE3:QUAT 543 18.282955 16.696198 0.769097 -0.1931643 0.4866228 0.3103489 0.7934541 +VERTEX_SE3:QUAT 544 18.124498 16.630309 -0.004743 -0.7922004 -0.3063204 -0.1496043 0.5061668 +VERTEX_SE3:QUAT 545 17.889862 16.599041 -0.875275 -0.6370834 -0.1930099 -0.7262203 0.1716855 +VERTEX_SE3:QUAT 546 17.708690 16.715375 -1.725474 -0.1582293 -0.9780179 -0.0585041 0.1225635 +VERTEX_SE3:QUAT 547 17.516185 16.625472 -2.625377 -0.6013562 -0.2943938 -0.2596027 0.6959235 +VERTEX_SE3:QUAT 548 17.178040 16.406145 -3.631226 -0.3936271 0.8532038 0.0859820 0.3312220 +VERTEX_SE3:QUAT 549 16.966000 16.388170 -4.517641 -0.0493173 0.3250820 0.8631300 0.3832703 +VERTEX_SE3:QUAT 550 16.784279 16.264771 -5.574670 -0.5026376 -0.4385762 -0.1910114 0.7200840 +VERTEX_SE3:QUAT 551 16.618473 16.220711 -6.559408 -0.0818458 0.4420929 0.7372525 0.5042953 +VERTEX_SE3:QUAT 552 16.623013 15.970931 -7.523616 -0.2221896 0.8549898 0.0440440 0.4665665 +VERTEX_SE3:QUAT 553 16.467083 15.435475 -8.417421 -0.4576698 0.3682380 -0.4055450 0.7003373 +VERTEX_SE3:QUAT 554 16.509708 15.336449 -9.409557 -0.9451761 -0.0584358 0.1399867 0.2891903 +VERTEX_SE3:QUAT 555 16.341389 15.141257 -10.237773 0.0578863 0.9240949 0.2420623 0.2900062 +VERTEX_SE3:QUAT 556 16.225419 14.970044 -11.074157 -0.9637137 -0.0866996 0.2067437 0.1449002 +VERTEX_SE3:QUAT 557 16.256484 14.634493 -12.021233 -0.6431481 -0.7290041 0.0411488 0.2306955 +VERTEX_SE3:QUAT 558 16.034903 14.218845 -13.194533 0.7534490 -0.3072281 0.5647809 0.1376515 +VERTEX_SE3:QUAT 559 15.917363 13.961303 -14.163226 -0.6127494 -0.5962828 -0.4240364 0.2986271 +VERTEX_SE3:QUAT 560 16.795498 13.520007 -14.367088 -0.2663949 0.4132985 0.0761579 0.8674203 +VERTEX_SE3:QUAT 561 16.994721 13.525778 -13.379284 -0.1173296 0.8148415 -0.3748917 0.4262901 +VERTEX_SE3:QUAT 562 16.892045 13.506135 -12.461739 0.6905048 0.7169091 -0.0095156 0.0956757 +VERTEX_SE3:QUAT 563 16.878261 13.387129 -11.511729 -0.7531036 -0.1137328 0.1011063 0.6400605 +VERTEX_SE3:QUAT 564 17.204304 13.183798 -10.641971 0.0391626 0.2584217 0.7999641 0.5401315 +VERTEX_SE3:QUAT 565 17.197884 13.165238 -9.705844 0.4717115 -0.6854390 -0.5468398 0.0928861 +VERTEX_SE3:QUAT 566 17.306836 13.170040 -8.522109 -0.3898209 0.7011240 0.5961815 0.0321329 +VERTEX_SE3:QUAT 567 17.620069 13.220663 -7.597591 -0.3976632 -0.1780093 -0.8999800 0.0145841 +VERTEX_SE3:QUAT 568 17.772201 13.323813 -6.419383 0.8700501 0.2179612 0.4370387 0.0671036 +VERTEX_SE3:QUAT 569 17.929719 13.476432 -5.491487 0.1922650 -0.9176201 -0.3472423 0.0207447 +VERTEX_SE3:QUAT 570 18.271097 13.525327 -4.503009 -0.5988230 0.0344922 -0.2707964 0.7529214 +VERTEX_SE3:QUAT 571 18.516656 13.432393 -3.599062 0.0681626 0.8661060 0.4708263 0.1534171 +VERTEX_SE3:QUAT 572 18.617566 13.405008 -2.760286 -0.4528614 0.1550671 -0.7102203 0.5161956 +VERTEX_SE3:QUAT 573 18.700076 13.492608 -1.621658 -0.9850339 -0.0808397 0.0389775 0.1471528 +VERTEX_SE3:QUAT 574 19.047054 13.539419 -0.596720 -0.8744171 -0.3379768 -0.2879775 0.1955386 +VERTEX_SE3:QUAT 575 19.178494 13.452468 0.273046 -0.2310506 0.5989652 0.3787146 0.6666570 +VERTEX_SE3:QUAT 576 19.480460 13.422025 1.208772 -0.0523872 0.3975008 0.3793017 0.8338939 +VERTEX_SE3:QUAT 577 19.365461 13.376841 2.183877 0.5606674 0.5158959 0.6351599 0.1267885 +VERTEX_SE3:QUAT 578 19.399871 13.179469 3.043902 -0.6253260 0.0561976 0.1684099 0.7598995 +VERTEX_SE3:QUAT 579 19.400228 13.125814 4.035754 -0.4679055 0.3590593 -0.2121295 0.7791931 +VERTEX_SE3:QUAT 580 20.289374 12.409248 3.857093 -0.4916920 -0.3422195 -0.2827395 0.7491216 +VERTEX_SE3:QUAT 581 20.016681 12.657815 2.836539 -0.6307273 -0.0856954 -0.6029979 0.4808668 +VERTEX_SE3:QUAT 582 20.096222 13.034526 1.949081 -0.5009665 0.5603764 0.1145773 0.6495251 +VERTEX_SE3:QUAT 583 19.882749 13.401384 1.140328 -0.7954457 0.4452192 -0.3904554 0.1288041 +VERTEX_SE3:QUAT 584 19.626669 13.581607 0.214308 0.7349487 0.2920605 0.4823668 0.3766609 +VERTEX_SE3:QUAT 585 19.296156 13.819892 -0.759776 0.3456725 0.5610411 0.0936605 0.7463050 +VERTEX_SE3:QUAT 586 18.949795 13.988679 -1.620846 0.9676026 0.1950037 0.1426681 0.0732427 +VERTEX_SE3:QUAT 587 18.489376 14.034949 -2.638063 -0.2770941 0.3198589 0.4750299 0.7715282 +VERTEX_SE3:QUAT 588 18.090028 14.260845 -3.582969 -0.7679726 -0.2855083 -0.1348356 0.5572455 +VERTEX_SE3:QUAT 589 17.692652 14.426956 -4.608878 -0.5325835 0.5154866 0.5390648 0.4000470 +VERTEX_SE3:QUAT 590 17.365248 14.356018 -5.491900 -0.7728146 -0.0564655 -0.4392675 0.4545474 +VERTEX_SE3:QUAT 591 17.088806 14.513603 -6.468784 -0.4948885 0.4019933 0.4063069 0.6545238 +VERTEX_SE3:QUAT 592 16.428250 14.512647 -7.421409 -0.5372587 0.2801804 0.0863413 0.7908206 +VERTEX_SE3:QUAT 593 16.080309 14.725815 -8.372265 0.0797228 0.3515951 0.1590982 0.9190826 +VERTEX_SE3:QUAT 594 15.738975 14.894381 -9.355056 -0.0643404 0.0561991 -0.2135114 0.9731983 +VERTEX_SE3:QUAT 595 15.383867 15.334446 -10.121257 -0.4572138 0.7805966 0.3925286 0.1659690 +VERTEX_SE3:QUAT 596 15.142877 15.386546 -11.224404 -0.2533130 0.7219442 0.3555100 0.5368815 +VERTEX_SE3:QUAT 597 14.836264 15.605666 -12.112777 0.4571523 0.8333312 0.0254214 0.3097170 +VERTEX_SE3:QUAT 598 14.362895 15.717890 -13.216712 -0.2198084 0.5858187 0.2686279 0.7323522 +VERTEX_SE3:QUAT 599 13.752949 15.806020 -14.069990 -0.4446717 0.6574178 -0.1154404 0.5972792 +VERTEX_SE3:QUAT 600 14.597250 15.258077 -14.643015 -0.7554623 0.5671285 -0.3278676 0.0120356 +VERTEX_SE3:QUAT 601 14.992881 15.174887 -13.916321 -0.2268161 0.4750370 0.3419578 0.7784338 +VERTEX_SE3:QUAT 602 15.526796 15.226286 -13.053011 -0.1156102 0.9184994 0.1408983 0.3509142 +VERTEX_SE3:QUAT 603 15.960153 15.191236 -12.356915 0.6567421 0.6641038 0.3458081 0.0898485 +VERTEX_SE3:QUAT 604 16.379187 15.085221 -11.584188 -0.1945995 -0.4287400 -0.8376981 0.2767220 +VERTEX_SE3:QUAT 605 17.049376 14.825444 -10.711782 0.4512323 0.6260842 0.0635065 0.6327518 +VERTEX_SE3:QUAT 606 17.427591 14.545239 -9.823992 -0.5269419 -0.3104920 -0.5454525 0.5730693 +VERTEX_SE3:QUAT 607 17.695543 14.294311 -8.990996 -0.1277473 0.0944198 -0.6345990 0.7563396 +VERTEX_SE3:QUAT 608 18.058849 14.081551 -7.996857 -0.5771027 0.3149797 -0.7064956 0.2619239 +VERTEX_SE3:QUAT 609 18.440682 14.179548 -7.356107 -0.7073494 -0.6417418 0.0170743 0.2958593 +VERTEX_SE3:QUAT 610 18.903213 14.013313 -6.295786 -0.0139510 -0.8536857 -0.5098755 0.1051334 +VERTEX_SE3:QUAT 611 19.203974 13.747288 -5.335672 -0.6200926 0.6716364 -0.2318651 0.3326082 +VERTEX_SE3:QUAT 612 19.637363 13.835515 -4.499586 0.5066730 -0.7387765 -0.4369253 0.0811671 +VERTEX_SE3:QUAT 613 20.161367 13.714491 -3.472522 0.8892701 -0.3216319 0.3242544 0.0247140 +VERTEX_SE3:QUAT 614 20.512130 13.553163 -2.568629 -0.4755187 -0.0203063 -0.8794669 0.0027409 +VERTEX_SE3:QUAT 615 20.871485 13.653829 -1.713563 -0.1573915 -0.6535458 -0.5300421 0.5168764 +VERTEX_SE3:QUAT 616 21.226433 13.657074 -0.879192 0.3397564 0.9235290 0.1767191 0.0207402 +VERTEX_SE3:QUAT 617 21.702984 13.759907 -0.037395 -0.3169266 -0.3931906 -0.2320632 0.8313275 +VERTEX_SE3:QUAT 618 22.226416 13.968584 0.717572 0.1853608 -0.8252702 -0.5060650 0.1687265 +VERTEX_SE3:QUAT 619 22.552903 14.045331 1.527860 -0.0949343 -0.6119510 -0.4742617 0.6257630 +VERTEX_SE3:QUAT 620 23.258783 13.371952 1.198577 -0.4143377 -0.7702875 -0.4611097 0.1495300 +VERTEX_SE3:QUAT 621 22.864042 13.124112 0.325362 -0.6851975 0.4321480 0.1149924 0.5749168 +VERTEX_SE3:QUAT 622 22.534506 12.985519 -0.592845 -0.5814185 0.1512479 -0.4076471 0.6876776 +VERTEX_SE3:QUAT 623 22.015660 12.754350 -1.427232 0.2664382 0.9551321 0.1043511 0.0764470 +VERTEX_SE3:QUAT 624 21.507325 12.646721 -2.342851 -0.2795709 0.1852771 0.8467280 0.4129942 +VERTEX_SE3:QUAT 625 21.067865 12.428439 -3.192323 -0.3553130 0.8081206 -0.0174829 0.4694551 +VERTEX_SE3:QUAT 626 20.626011 12.279697 -3.956242 -0.2959449 0.5097963 -0.3578346 0.7242090 +VERTEX_SE3:QUAT 627 20.251025 12.069563 -4.737430 0.1436163 0.7761412 0.2454426 0.5627940 +VERTEX_SE3:QUAT 628 19.744422 11.879737 -5.761675 -0.4372384 0.2400455 -0.1500198 0.8536362 +VERTEX_SE3:QUAT 629 19.357895 11.667513 -6.707643 -0.7292079 0.2119195 0.4250970 0.4925835 +VERTEX_SE3:QUAT 630 19.111305 11.570664 -7.577450 -0.3875029 -0.1829049 -0.6359720 0.6418153 +VERTEX_SE3:QUAT 631 18.665412 11.462915 -8.483163 -0.5609783 -0.5565334 0.2571038 0.5563017 +VERTEX_SE3:QUAT 632 18.150722 11.271873 -9.459426 -0.3104436 0.6698602 0.5024588 0.4499413 +VERTEX_SE3:QUAT 633 17.808378 11.049425 -10.380910 -0.7990613 0.4289370 -0.0055386 0.4212878 +VERTEX_SE3:QUAT 634 17.294692 10.747119 -11.424580 0.1640673 0.7675068 0.4729507 0.4004159 +VERTEX_SE3:QUAT 635 16.868444 10.534627 -12.249668 -0.4055042 -0.0434579 -0.5629789 0.7188411 +VERTEX_SE3:QUAT 636 16.424589 10.347221 -13.186353 -0.8322110 0.4798875 -0.2763295 0.0278347 +VERTEX_SE3:QUAT 637 16.110283 10.060869 -14.220857 -0.6595708 -0.5104915 -0.0187777 0.5513730 +VERTEX_SE3:QUAT 638 15.874951 9.940761 -15.177242 -0.1483951 -0.5480866 -0.8045819 0.1738618 +VERTEX_SE3:QUAT 639 15.289782 9.856950 -15.902530 -0.6897843 0.0292329 0.6539046 0.3094378 +VERTEX_SE3:QUAT 640 15.994354 9.508964 -16.153138 -0.3630682 0.2993970 0.7446352 0.4733511 +VERTEX_SE3:QUAT 641 16.423264 9.869704 -15.179932 -0.9208495 -0.2025471 0.0103273 0.3330229 +VERTEX_SE3:QUAT 642 16.678847 10.153784 -14.211262 -0.2537507 -0.2447588 -0.2300894 0.9070626 +VERTEX_SE3:QUAT 643 17.158716 10.661415 -13.335267 0.4595582 0.7478600 0.3635576 0.3119897 +VERTEX_SE3:QUAT 644 17.646448 10.994915 -12.432254 -0.8538333 0.0704316 0.3545054 0.3746118 +VERTEX_SE3:QUAT 645 18.013817 11.337945 -11.513190 0.7270006 -0.0960683 0.6735834 0.0923386 +VERTEX_SE3:QUAT 646 18.390411 11.566192 -10.583445 -0.8949314 0.3781474 0.1298925 0.1980664 +VERTEX_SE3:QUAT 647 18.561564 11.781837 -9.538836 -0.3240701 0.2656073 0.0901778 0.9034928 +VERTEX_SE3:QUAT 648 18.716563 11.967677 -8.670389 -0.2406077 0.1520599 -0.5679742 0.7722636 +VERTEX_SE3:QUAT 649 19.027477 12.158190 -7.808570 -0.2773062 -0.5855377 -0.7390916 0.1843652 +VERTEX_SE3:QUAT 650 19.458534 12.429859 -6.876314 -0.2226244 0.7742865 -0.2721098 0.5261892 +VERTEX_SE3:QUAT 651 19.693300 12.755316 -6.152236 -0.1161200 -0.1800814 -0.9251875 0.3132330 +VERTEX_SE3:QUAT 652 19.935643 13.109603 -5.208230 -0.1276456 0.9779840 -0.1649069 0.0077185 +VERTEX_SE3:QUAT 653 20.307549 13.427983 -4.254194 0.3925531 0.8438855 0.1028486 0.3509723 +VERTEX_SE3:QUAT 654 20.397803 13.757021 -3.374851 0.2633227 0.9255084 -0.0737240 0.2620308 +VERTEX_SE3:QUAT 655 20.569292 14.035747 -2.451935 0.9242411 0.2352009 0.2018120 0.2230039 +VERTEX_SE3:QUAT 656 20.706072 14.291058 -1.518850 -0.7446308 -0.5197226 -0.2553471 0.3319808 +VERTEX_SE3:QUAT 657 20.798254 14.499217 -0.613280 -0.1443081 0.4507358 0.8800066 0.0400095 +VERTEX_SE3:QUAT 658 21.137162 14.708654 0.380721 -0.8875648 -0.4004837 -0.2176138 0.0669759 +VERTEX_SE3:QUAT 659 21.447451 14.950802 1.272119 0.2010632 0.9748765 0.0433323 0.0855081 +VERTEX_SE3:QUAT 660 22.423696 14.640136 1.040335 -0.6685745 -0.0801192 0.1784082 0.7174675 +VERTEX_SE3:QUAT 661 22.004362 14.589684 0.070699 0.1239930 -0.7552209 -0.5533899 0.3286742 +VERTEX_SE3:QUAT 662 21.663543 14.610503 -0.773374 0.8541670 -0.4922610 -0.1657436 0.0246340 +VERTEX_SE3:QUAT 663 21.432211 14.653412 -1.617325 0.1629821 -0.7356305 -0.4410476 0.4876080 +VERTEX_SE3:QUAT 664 21.330261 14.789864 -2.556266 -0.3923002 0.3780757 0.8355479 0.0708446 +VERTEX_SE3:QUAT 665 21.037750 14.734432 -3.371992 -0.7441079 -0.5268861 -0.1835904 0.3674085 +VERTEX_SE3:QUAT 666 20.977985 14.728173 -4.251790 -0.1603919 0.6748764 0.0395796 0.7192008 +VERTEX_SE3:QUAT 667 20.743873 14.691598 -5.151556 -0.7893767 0.1988519 -0.4838243 0.3213355 +VERTEX_SE3:QUAT 668 20.447606 14.624771 -6.101347 0.1508737 0.4238719 0.5716247 0.6861596 +VERTEX_SE3:QUAT 669 20.186904 14.606367 -7.122210 -0.0811115 -0.5173872 -0.6124406 0.5921552 +VERTEX_SE3:QUAT 670 19.981555 14.778491 -8.165627 -0.6658329 0.6819226 0.2732128 0.1303952 +VERTEX_SE3:QUAT 671 19.409063 14.950758 -9.235183 -0.9744852 -0.2037411 -0.0731228 0.0593398 +VERTEX_SE3:QUAT 672 19.139727 15.069973 -10.253673 -0.1432700 -0.7484113 -0.6278767 0.1585089 +VERTEX_SE3:QUAT 673 18.796098 15.102559 -11.297944 0.0312164 0.5874571 -0.3330021 0.7369052 +VERTEX_SE3:QUAT 674 18.242654 15.353287 -12.201607 -0.0018000 0.6453769 0.6116694 0.4575434 +VERTEX_SE3:QUAT 675 17.734383 15.522001 -13.167161 -0.3728917 -0.3180220 -0.1236313 0.8628610 +VERTEX_SE3:QUAT 676 17.275959 15.638243 -14.089983 -0.1044371 0.4335270 0.0611681 0.8929758 +VERTEX_SE3:QUAT 677 16.721238 15.948667 -14.871291 -0.6606730 0.3785220 -0.0431158 0.6468179 +VERTEX_SE3:QUAT 678 16.377640 16.358067 -15.612742 -0.2953827 -0.3304220 -0.7184859 0.5360489 +VERTEX_SE3:QUAT 679 15.862612 16.717197 -16.414952 0.2261655 -0.0253256 0.8202289 0.5248165 +VERTEX_SE3:QUAT 680 16.416112 16.367556 -16.926216 0.3897505 0.0375217 0.9200501 0.0139434 +VERTEX_SE3:QUAT 681 16.750458 16.047175 -15.968702 0.2181711 -0.0919278 0.9584785 0.1589639 +VERTEX_SE3:QUAT 682 17.205270 15.556143 -15.304619 -0.8615454 0.4894160 0.0001321 0.1349498 +VERTEX_SE3:QUAT 683 17.470831 15.225755 -14.592375 -0.2553751 -0.0060983 0.7671371 0.5884276 +VERTEX_SE3:QUAT 684 17.804997 14.866550 -13.937051 -0.7905488 -0.4699506 -0.3920989 0.0209144 +VERTEX_SE3:QUAT 685 18.178558 14.363260 -13.069673 -0.1969244 0.5345203 -0.3224470 0.7560005 +VERTEX_SE3:QUAT 686 18.538113 13.894679 -12.175080 -0.7594740 -0.1247396 0.4193873 0.4814078 +VERTEX_SE3:QUAT 687 18.984413 13.640507 -11.435482 -0.2620938 0.5417420 0.4120420 0.6841373 +VERTEX_SE3:QUAT 688 19.518204 13.093115 -10.768696 0.1988929 0.7492242 0.6207116 0.1175661 +VERTEX_SE3:QUAT 689 19.975120 12.555985 -10.025089 0.2105353 0.7859438 0.1664295 0.5570174 +VERTEX_SE3:QUAT 690 20.627226 11.949231 -9.409246 0.6063523 0.6519891 0.3647074 0.2724623 +VERTEX_SE3:QUAT 691 21.216809 11.530078 -8.790051 -0.4806578 -0.5484901 -0.6141785 0.3015154 +VERTEX_SE3:QUAT 692 21.766155 11.299444 -8.087649 0.2070504 0.5945103 0.7358037 0.2495606 +VERTEX_SE3:QUAT 693 22.431155 10.869911 -7.390617 -0.3215386 0.1201341 0.8059566 0.4823014 +VERTEX_SE3:QUAT 694 22.970833 10.139898 -6.658100 0.5236734 0.5370568 0.1198761 0.6503583 +VERTEX_SE3:QUAT 695 23.522760 9.676511 -6.005859 -0.9322985 0.2741258 0.0902914 0.2179954 +VERTEX_SE3:QUAT 696 24.251441 8.933331 -5.217012 -0.5332440 -0.3033277 -0.5013521 0.6101551 +VERTEX_SE3:QUAT 697 24.791636 8.427054 -4.365759 -0.1739489 0.5855189 -0.3951263 0.6861374 +VERTEX_SE3:QUAT 698 25.402332 7.992018 -3.592750 0.5177676 0.8288359 0.0740328 0.1986628 +VERTEX_SE3:QUAT 699 25.944363 7.772262 -2.779973 -0.1144287 0.9396197 -0.1751449 0.2708232 +VERTEX_SE3:QUAT 700 26.644031 7.297726 -3.322820 -0.7177556 -0.0414636 -0.3071535 0.6235098 +VERTEX_SE3:QUAT 701 26.275079 7.550381 -3.925103 -0.3217474 -0.5453588 -0.7624232 0.1333163 +VERTEX_SE3:QUAT 702 25.588017 7.803565 -4.579068 -0.2169796 0.2688189 0.9128079 0.2178024 +VERTEX_SE3:QUAT 703 25.060493 8.108892 -5.241051 0.0145170 0.1328520 0.9154596 0.3795698 +VERTEX_SE3:QUAT 704 24.743758 8.456173 -6.026789 -0.5313626 0.0023393 0.2283615 0.8157814 +VERTEX_SE3:QUAT 705 24.397749 8.791982 -6.975638 -0.6443699 0.0509002 -0.6525232 0.3954872 +VERTEX_SE3:QUAT 706 24.186203 9.148826 -7.787854 -0.0563483 0.5375746 0.2340359 0.8081248 +VERTEX_SE3:QUAT 707 23.843227 9.666784 -8.794259 -0.1042694 -0.4978678 -0.7145763 0.4802460 +VERTEX_SE3:QUAT 708 23.335783 10.102493 -9.758747 0.0234508 0.3128702 -0.1560329 0.9365981 +VERTEX_SE3:QUAT 709 23.077695 10.505512 -10.724861 -0.3849036 -0.0464602 -0.1530036 0.9089997 +VERTEX_SE3:QUAT 710 22.785268 10.814557 -11.522921 -0.5780049 0.0563949 -0.4087193 0.7040444 +VERTEX_SE3:QUAT 711 22.521933 11.178690 -12.384394 -0.6077511 -0.0567176 -0.7623329 0.2151054 +VERTEX_SE3:QUAT 712 22.177567 11.568884 -13.327093 0.1424772 0.4322867 0.1211069 0.8821347 +VERTEX_SE3:QUAT 713 21.970474 12.013104 -14.339365 -0.2466932 -0.1366829 -0.7602792 0.5851801 +VERTEX_SE3:QUAT 714 21.633590 12.252890 -15.241409 -0.7715285 -0.1524827 -0.4251101 0.4480783 +VERTEX_SE3:QUAT 715 21.369522 12.602377 -16.220296 -0.8208763 -0.4634761 -0.3047574 0.1359226 +VERTEX_SE3:QUAT 716 21.262593 12.896274 -17.146331 -0.0240745 0.4404783 0.7078771 0.5516424 +VERTEX_SE3:QUAT 717 21.004125 13.225858 -18.176663 0.0542955 0.6726293 0.5555268 0.4858105 +VERTEX_SE3:QUAT 718 20.836644 13.499353 -19.154666 -0.6238834 0.3716859 -0.5634872 0.3938291 +VERTEX_SE3:QUAT 719 20.624439 13.741147 -20.183808 -0.5939876 -0.6194339 -0.4358834 0.2710832 +VERTEX_SE3:QUAT 720 21.267287 12.989306 -20.439471 0.5795356 0.1567503 0.7637106 0.2373058 +VERTEX_SE3:QUAT 721 21.529707 12.691958 -19.452744 0.8033662 -0.5382749 0.2546339 0.0049406 +VERTEX_SE3:QUAT 722 21.786894 12.560827 -18.563071 0.1504716 0.6212581 0.6961544 0.3267504 +VERTEX_SE3:QUAT 723 21.777147 12.162699 -17.711135 -0.3013326 0.4330138 -0.5659772 0.6335358 +VERTEX_SE3:QUAT 724 21.746324 11.777048 -16.863072 0.0976074 0.8685531 0.3772192 0.3062581 +VERTEX_SE3:QUAT 725 21.954225 11.450374 -15.897864 -0.5530745 -0.5197280 -0.1466544 0.6344162 +VERTEX_SE3:QUAT 726 21.940155 11.047418 -15.168621 -0.0989940 -0.5089163 -0.7927987 0.3204287 +VERTEX_SE3:QUAT 727 22.077046 10.679038 -14.125318 -0.1023590 0.1640507 -0.7141408 0.6727651 +VERTEX_SE3:QUAT 728 22.031937 10.273803 -13.220745 -0.8713292 0.1925411 -0.4512344 0.0100439 +VERTEX_SE3:QUAT 729 21.922860 9.937317 -12.310855 0.4245769 -0.2974435 0.8160765 0.2555013 +VERTEX_SE3:QUAT 730 21.914198 9.603315 -11.279645 -0.5192702 0.2204691 -0.8235214 0.0597026 +VERTEX_SE3:QUAT 731 21.841315 9.156809 -10.467888 0.0533847 -0.0565298 0.9940720 0.0759953 +VERTEX_SE3:QUAT 732 21.727135 8.754836 -9.628426 -0.5375564 0.1381226 -0.7985755 0.2328785 +VERTEX_SE3:QUAT 733 21.613410 8.454462 -8.668460 0.1337777 0.3129250 0.4378386 0.8321531 +VERTEX_SE3:QUAT 734 21.603839 8.172784 -7.791967 -0.8597197 0.1200164 -0.4763743 0.1398055 +VERTEX_SE3:QUAT 735 21.694696 7.854343 -6.945323 -0.4059007 0.5854537 -0.5882934 0.3826218 +VERTEX_SE3:QUAT 736 21.694027 7.443797 -5.960589 0.0446307 0.8360412 0.4526226 0.3068809 +VERTEX_SE3:QUAT 737 21.733641 7.067337 -4.964287 -0.0883541 -0.0277297 -0.7184745 0.6893613 +VERTEX_SE3:QUAT 738 21.699201 6.639633 -3.940956 -0.1408835 -0.3566166 -0.6781996 0.6269144 +VERTEX_SE3:QUAT 739 21.859276 6.088040 -2.821488 -0.1941927 0.8591352 0.3358315 0.3337561 +VERTEX_SE3:QUAT 740 22.183783 5.213305 -3.243476 0.3849248 0.5297342 0.2259417 0.7212246 +VERTEX_SE3:QUAT 741 22.133057 5.609713 -4.162333 -0.5895952 0.4796313 -0.6452722 0.0771699 +VERTEX_SE3:QUAT 742 22.254247 6.029650 -5.227480 0.3861530 0.3446181 0.7476965 0.4160219 +VERTEX_SE3:QUAT 743 22.099068 6.370670 -6.200738 -0.4823520 0.3726777 -0.4812783 0.6299358 +VERTEX_SE3:QUAT 744 22.150045 6.929401 -7.131692 0.6410301 0.6538812 0.0178993 0.4014964 +VERTEX_SE3:QUAT 745 21.966217 7.589796 -8.088440 -0.3207161 0.5668581 0.5965189 0.4690185 +VERTEX_SE3:QUAT 746 21.677024 8.123107 -8.979221 0.2529831 0.3373457 0.5530534 0.7185606 +VERTEX_SE3:QUAT 747 21.427514 8.637799 -9.694008 -0.1866573 0.2839311 0.7525799 0.5640618 +VERTEX_SE3:QUAT 748 21.172285 9.297191 -10.390307 -0.1368214 0.1660962 0.5718218 0.7916513 +VERTEX_SE3:QUAT 749 20.952637 9.617469 -11.336287 -0.2180236 0.6570186 0.0249373 0.7212284 +VERTEX_SE3:QUAT 750 20.547432 10.031788 -12.207187 0.2704106 0.3708238 0.8874686 0.0420380 +VERTEX_SE3:QUAT 751 20.211499 10.576559 -13.059598 -0.4077996 0.2703664 -0.8581029 0.1557593 +VERTEX_SE3:QUAT 752 19.787352 11.256172 -13.637136 0.0524551 0.3594927 -0.0108150 0.9316096 +VERTEX_SE3:QUAT 753 19.419344 11.838061 -14.352662 -0.3951205 0.8262749 0.1313769 0.3793278 +VERTEX_SE3:QUAT 754 18.973073 12.312576 -14.921157 0.3887210 0.4580214 0.2762852 0.7501859 +VERTEX_SE3:QUAT 755 18.459373 13.003437 -15.531476 -0.3167135 0.3293082 0.6143313 0.6433084 +VERTEX_SE3:QUAT 756 18.170379 13.638633 -16.177685 -0.3971644 0.7758151 -0.2494205 0.4220911 +VERTEX_SE3:QUAT 757 17.631562 14.204377 -16.784989 -0.0747773 -0.2899416 -0.7031706 0.6448980 +VERTEX_SE3:QUAT 758 17.100476 14.884005 -17.334993 -0.0786433 0.2991469 0.3439142 0.8865943 +VERTEX_SE3:QUAT 759 16.617209 15.533551 -17.900837 -0.4005882 0.3768365 -0.0893072 0.8303900 +VERTEX_SE3:QUAT 760 16.963212 14.912830 -18.778767 -0.3039860 -0.0247561 -0.3784286 0.8739402 +VERTEX_SE3:QUAT 761 17.427728 14.292920 -18.205950 0.3286623 0.4052263 -0.0789649 0.8494335 +VERTEX_SE3:QUAT 762 17.931983 13.784138 -17.567949 0.2799013 0.4797217 0.8263727 0.0928999 +VERTEX_SE3:QUAT 763 18.723127 13.260527 -16.928925 -0.4942154 0.5048881 0.7048407 0.0635502 +VERTEX_SE3:QUAT 764 19.211256 12.774326 -16.313268 -0.3569011 -0.6037852 -0.0626440 0.7100287 +VERTEX_SE3:QUAT 765 19.844087 12.403451 -15.845041 -0.4530705 0.4448728 -0.3686048 0.6789299 +VERTEX_SE3:QUAT 766 20.673355 12.039792 -15.108675 -0.4796445 0.6953465 0.5289826 0.0813128 +VERTEX_SE3:QUAT 767 21.369249 11.668437 -14.558972 -0.6886920 0.2999412 0.5683188 0.3357861 +VERTEX_SE3:QUAT 768 22.062252 11.289329 -13.820816 -0.5625690 0.1330743 0.0696218 0.8129946 +VERTEX_SE3:QUAT 769 22.585845 10.813426 -13.218339 -0.3194677 0.0618636 -0.2193524 0.9197814 +VERTEX_SE3:QUAT 770 23.173272 10.433480 -12.688457 -0.4915130 0.1063907 -0.8513588 0.1492792 +VERTEX_SE3:QUAT 771 23.849446 10.109454 -12.072984 -0.1733191 -0.3497986 -0.8699770 0.3012332 +VERTEX_SE3:QUAT 772 24.385354 9.676730 -11.505728 -0.6219055 0.7505666 -0.0190026 0.2225358 +VERTEX_SE3:QUAT 773 25.213770 9.440891 -10.812595 -0.9106875 0.0901420 -0.3776401 0.1411051 +VERTEX_SE3:QUAT 774 25.817663 8.990511 -10.117029 0.1186710 0.5287618 -0.2556540 0.8006055 +VERTEX_SE3:QUAT 775 26.521625 8.824755 -9.453795 -0.4239087 0.6521658 0.3577148 0.5167411 +VERTEX_SE3:QUAT 776 26.996918 8.417855 -8.813398 0.3265951 0.1868851 0.8327659 0.4060919 +VERTEX_SE3:QUAT 777 27.773687 8.244368 -8.351869 -0.5898815 0.5133539 0.5902649 0.2002373 +VERTEX_SE3:QUAT 778 28.562437 8.242030 -7.782872 0.0762914 0.4320920 0.6045235 0.6648515 +VERTEX_SE3:QUAT 779 29.138601 8.006534 -7.097057 0.1321418 0.9080555 0.3387566 0.2078889 +VERTEX_SE3:QUAT 780 29.826859 7.405609 -7.945040 -0.6453469 0.5629220 -0.0263676 0.5157043 +VERTEX_SE3:QUAT 781 29.238541 7.658661 -8.638078 0.3252751 0.2143132 0.9081888 0.1531638 +VERTEX_SE3:QUAT 782 28.605787 7.982773 -9.144869 -0.0744062 0.7992806 -0.0405481 0.5949538 +VERTEX_SE3:QUAT 783 28.009385 8.264640 -9.943161 -0.9332932 -0.1918796 -0.3008912 0.0401316 +VERTEX_SE3:QUAT 784 27.401591 8.601720 -10.485259 -0.0440898 0.2835856 0.5660408 0.7728086 +VERTEX_SE3:QUAT 785 26.782158 8.953987 -11.004466 -0.1794161 0.2242387 -0.6652218 0.6892074 +VERTEX_SE3:QUAT 786 26.172270 9.160231 -11.806690 -0.2468232 0.7616977 0.1596458 0.5774151 +VERTEX_SE3:QUAT 787 25.586395 9.743688 -12.328819 0.0462992 0.6110016 0.7562109 0.2295178 +VERTEX_SE3:QUAT 788 24.975598 10.055543 -13.130025 0.9559653 0.1871538 0.2087484 0.0867634 +VERTEX_SE3:QUAT 789 24.300669 10.452427 -13.920956 0.4361287 0.2488721 0.8144179 0.2908228 +VERTEX_SE3:QUAT 790 23.672022 11.007239 -14.588567 -0.4963869 0.4783988 -0.5482578 0.4734427 +VERTEX_SE3:QUAT 791 23.114184 11.435604 -15.089957 0.5598644 0.4295167 0.7016508 0.0987598 +VERTEX_SE3:QUAT 792 22.493881 11.892235 -15.688788 -0.3884037 0.3293280 0.7523237 0.4179649 +VERTEX_SE3:QUAT 793 21.929433 12.185698 -16.397155 -0.7338361 0.1387312 -0.1054600 0.6565946 +VERTEX_SE3:QUAT 794 21.280960 12.656040 -16.808813 -0.2231804 0.6913193 -0.0248842 0.6867670 +VERTEX_SE3:QUAT 795 20.556255 13.074724 -17.465895 -0.8274768 0.2137421 -0.5141068 0.0727374 +VERTEX_SE3:QUAT 796 19.986363 13.470712 -18.151849 -0.5348276 0.6784562 -0.1101270 0.4914557 +VERTEX_SE3:QUAT 797 19.402902 13.979222 -18.475625 -0.0593742 0.9229904 -0.1888837 0.3299793 +VERTEX_SE3:QUAT 798 18.967197 14.403051 -19.190474 -0.1060464 -0.1872742 -0.4016620 0.8901405 +VERTEX_SE3:QUAT 799 18.398123 14.849512 -19.855614 -0.9199055 0.2318884 -0.2991174 0.1026178 +VERTEX_SE3:QUAT 800 28.652081 7.664263 -5.380213 -0.0774702 0.7379094 0.4260222 0.5176807 +VERTEX_SE3:QUAT 801 27.964688 7.975734 -6.151648 -0.4462991 0.1553840 -0.8811078 0.0179415 +VERTEX_SE3:QUAT 802 27.321015 8.574479 -6.907683 -0.5030181 0.0231797 -0.8031519 0.3184063 +VERTEX_SE3:QUAT 803 26.776121 8.615952 -7.798955 -0.2575612 -0.8210824 -0.3478525 0.3721351 +VERTEX_SE3:QUAT 804 26.164317 8.939506 -8.622333 -0.3061437 0.0674672 -0.6607311 0.6820253 +VERTEX_SE3:QUAT 805 25.716127 9.183071 -9.494441 0.6023121 0.2351662 0.7033665 0.2952837 +VERTEX_SE3:QUAT 806 25.221471 9.540285 -10.211304 0.4075524 0.6290374 0.2250108 0.6225618 +VERTEX_SE3:QUAT 807 24.767968 9.765025 -11.081600 0.0707146 0.8718279 0.4712427 0.1133399 +VERTEX_SE3:QUAT 808 24.412232 10.020561 -11.815665 0.0420399 0.2431487 -0.2821584 0.9270911 +VERTEX_SE3:QUAT 809 23.886940 10.357227 -12.597528 -0.5952556 -0.1758721 -0.0303198 0.7834669 +VERTEX_SE3:QUAT 810 23.352770 10.550787 -13.368348 -0.1758687 0.1289142 0.0713986 0.9733209 +VERTEX_SE3:QUAT 811 22.784345 11.020842 -14.066658 -0.3053934 0.7361481 -0.2835187 0.5333273 +VERTEX_SE3:QUAT 812 22.295200 10.974018 -14.934190 -0.0142506 0.5617460 0.8152883 0.1397975 +VERTEX_SE3:QUAT 813 21.733499 11.162819 -15.793491 -0.5805672 0.4710482 -0.0881811 0.6582396 +VERTEX_SE3:QUAT 814 21.257886 11.177689 -16.757724 -0.6167791 -0.5953889 -0.4862819 0.1691910 +VERTEX_SE3:QUAT 815 20.828744 11.308266 -17.673752 0.9244407 -0.1086942 0.3379715 0.1391773 +VERTEX_SE3:QUAT 816 20.268003 11.560427 -18.699232 -0.8687281 0.0860111 -0.3505947 0.3391119 +VERTEX_SE3:QUAT 817 19.944435 11.709008 -19.475918 -0.3078341 0.7440989 0.5549911 0.2086620 +VERTEX_SE3:QUAT 818 19.397748 11.761932 -20.343657 -0.0993629 0.8307719 0.4663208 0.2872105 +VERTEX_SE3:QUAT 819 19.056795 11.909633 -21.279804 -0.9683100 -0.2207798 -0.1165070 0.0076203 +VERTEX_SE3:QUAT 820 18.205772 12.301184 -20.635123 0.0134568 -0.5949596 -0.5388940 0.5961839 +VERTEX_SE3:QUAT 821 18.845574 12.244115 -19.641491 0.4886953 0.2864739 0.7438972 0.3545793 +VERTEX_SE3:QUAT 822 19.176279 12.189817 -18.825169 -0.3752299 0.8156482 0.2861160 0.3347510 +VERTEX_SE3:QUAT 823 19.774390 11.893420 -18.157198 -0.5315023 -0.7861267 -0.0988744 0.2995563 +VERTEX_SE3:QUAT 824 20.409392 11.827568 -17.436710 -0.9076615 -0.2490481 -0.0913683 0.3252345 +VERTEX_SE3:QUAT 825 21.095992 11.711920 -16.644942 -0.0041493 -0.4044035 -0.5614347 0.7219637 +VERTEX_SE3:QUAT 826 21.608899 11.428238 -15.775474 -0.3562959 0.5055178 -0.1062122 0.7786038 +VERTEX_SE3:QUAT 827 22.077511 11.214798 -14.942043 0.2938864 0.3441657 0.7175707 0.5294082 +VERTEX_SE3:QUAT 828 22.507814 11.162330 -14.128550 0.1580245 -0.7191823 -0.6055871 0.3017769 +VERTEX_SE3:QUAT 829 23.064207 11.099193 -13.310702 0.9281598 0.2603425 0.2453750 0.1026270 +VERTEX_SE3:QUAT 830 23.682709 10.812258 -12.296864 -0.8031135 0.5368600 0.2489447 0.0694009 +VERTEX_SE3:QUAT 831 24.312391 10.331322 -11.570819 0.0642223 0.8814991 0.1520591 0.4423945 +VERTEX_SE3:QUAT 832 24.924723 10.349427 -10.640376 0.0901051 0.0473690 -0.1847248 0.9775040 +VERTEX_SE3:QUAT 833 25.474308 9.996168 -9.820244 -0.5080190 0.7018114 0.1655592 0.4711344 +VERTEX_SE3:QUAT 834 25.957788 9.531356 -9.074954 -0.3923541 0.2483987 -0.7539603 0.4646507 +VERTEX_SE3:QUAT 835 26.506160 9.124230 -8.401994 -0.3648371 0.8611058 0.3056932 0.1787243 +VERTEX_SE3:QUAT 836 27.025048 8.781903 -7.620360 -0.0328511 0.4089634 0.5658218 0.7152030 +VERTEX_SE3:QUAT 837 27.485847 8.523664 -6.977975 -0.4722470 -0.1768162 -0.6816760 0.5301289 +VERTEX_SE3:QUAT 838 28.218664 8.167528 -6.301649 -0.2612420 0.2099009 0.8992099 0.2812753 +VERTEX_SE3:QUAT 839 28.859600 8.016563 -5.641684 -0.1063805 0.7067267 -0.2556596 0.6510443 +VERTEX_SE3:QUAT 840 28.239314 8.309609 -4.891100 -0.0998548 0.6463689 0.4247743 0.6259417 +VERTEX_SE3:QUAT 841 27.802613 8.548762 -5.700860 -0.5386341 0.4261157 -0.3620343 0.6302618 +VERTEX_SE3:QUAT 842 27.211148 9.026617 -6.384832 -0.2892045 0.4058638 0.8668242 0.0158468 +VERTEX_SE3:QUAT 843 26.606137 9.274204 -6.962086 -0.0005874 -0.4996093 -0.7636731 0.4088931 +VERTEX_SE3:QUAT 844 26.076356 9.677738 -7.826817 -0.5232801 0.6610200 0.4699757 0.2614448 +VERTEX_SE3:QUAT 845 25.496011 10.034621 -8.534947 -0.0102901 0.6599774 0.6760005 0.3276389 +VERTEX_SE3:QUAT 846 24.900469 10.151938 -9.327169 -0.7336757 0.5809462 -0.1380315 0.3242976 +VERTEX_SE3:QUAT 847 24.391022 10.545213 -10.176548 0.6333925 0.2722198 0.6437648 0.3320801 +VERTEX_SE3:QUAT 848 23.895500 10.875879 -10.931013 0.4035971 0.5489158 0.1561915 0.7151259 +VERTEX_SE3:QUAT 849 23.410422 11.166622 -11.875558 -0.1845264 0.2499045 -0.1600184 0.9369588 +VERTEX_SE3:QUAT 850 22.783597 11.273829 -12.740950 -0.1380064 0.9666167 0.1973518 0.0875142 +VERTEX_SE3:QUAT 851 22.240821 11.361939 -13.755464 0.5515774 0.5375266 0.5274577 0.3586306 +VERTEX_SE3:QUAT 852 21.663415 11.541771 -14.715357 -0.6475621 0.2748193 -0.0230854 0.7103553 +VERTEX_SE3:QUAT 853 21.404447 11.757721 -15.813652 -0.7774963 -0.4728345 -0.0082987 0.4145579 +VERTEX_SE3:QUAT 854 21.109068 11.785468 -16.875990 -0.3799532 0.7108226 -0.3750893 0.4579026 +VERTEX_SE3:QUAT 855 20.720125 11.893966 -17.745165 -0.6375785 0.0902304 0.1203313 0.7555611 +VERTEX_SE3:QUAT 856 20.256839 11.789198 -18.749205 -0.9403261 0.0582393 0.1595983 0.2948276 +VERTEX_SE3:QUAT 857 19.805951 11.961986 -19.515942 -0.0377002 -0.8079009 -0.5097425 0.2933213 +VERTEX_SE3:QUAT 858 19.158531 11.892367 -20.327121 -0.4493033 0.6678090 -0.4072407 0.4316395 +VERTEX_SE3:QUAT 859 18.640285 12.170627 -21.248908 -0.2758987 -0.5244111 -0.7575249 0.2739143 +VERTEX_SE3:QUAT 860 17.968648 12.733299 -20.789841 -0.9448591 -0.0684100 0.1396100 0.2882193 +VERTEX_SE3:QUAT 861 18.302238 12.538799 -19.878605 0.5460776 0.0303833 0.8110334 0.2076079 +VERTEX_SE3:QUAT 862 18.644706 12.582560 -19.084487 -0.5084311 0.4159777 -0.5853218 0.4752460 +VERTEX_SE3:QUAT 863 18.880071 12.561479 -18.073118 -0.1429039 0.6511355 0.5294350 0.5246900 +VERTEX_SE3:QUAT 864 19.209575 12.416464 -17.173865 -0.7380123 -0.5110766 -0.1061826 0.4276258 +VERTEX_SE3:QUAT 865 19.254388 12.282910 -16.164206 -0.8415363 0.4437744 0.2951752 0.0880484 +VERTEX_SE3:QUAT 866 19.541209 12.328204 -15.211692 0.1654039 0.3091185 -0.0519283 0.9350886 +VERTEX_SE3:QUAT 867 19.506582 12.196359 -14.149574 -0.2587610 0.5086287 -0.6442993 0.5091345 +VERTEX_SE3:QUAT 868 19.753981 12.070403 -13.110018 0.8521440 -0.2181721 0.4706864 0.0685985 +VERTEX_SE3:QUAT 869 20.074993 11.978685 -12.231240 -0.2697023 -0.5352307 -0.7068436 0.3757137 +VERTEX_SE3:QUAT 870 20.343446 11.907152 -11.362628 -0.6103110 0.7170590 -0.1583684 0.2970964 +VERTEX_SE3:QUAT 871 20.570572 11.882912 -10.304063 -0.8521841 0.0978933 -0.0009469 0.5140022 +VERTEX_SE3:QUAT 872 20.772030 11.838927 -9.417145 -0.6638747 0.3989004 -0.6234020 0.1073256 +VERTEX_SE3:QUAT 873 21.069170 11.784919 -8.530895 -0.3877499 0.7753211 -0.3238479 0.3790115 +VERTEX_SE3:QUAT 874 21.227002 11.721567 -7.514114 0.9148131 0.2418654 0.3222685 0.0275896 +VERTEX_SE3:QUAT 875 21.519976 11.743095 -6.504697 -0.2449409 0.2550390 0.4975998 0.7920565 +VERTEX_SE3:QUAT 876 21.866997 11.501440 -5.547262 0.9950818 -0.0646257 -0.0675419 0.0327703 +VERTEX_SE3:QUAT 877 22.131725 11.412589 -4.483674 -0.6192870 -0.6085854 -0.4822519 0.1163632 +VERTEX_SE3:QUAT 878 22.355822 11.243125 -3.531543 0.1322014 0.9509618 -0.0186912 0.2790075 +VERTEX_SE3:QUAT 879 22.681146 11.408768 -2.501307 -0.4760666 0.3339856 0.5995031 0.5499184 +VERTEX_SE3:QUAT 880 22.072399 11.997977 -2.330592 -0.1808344 -0.9166972 -0.3485429 0.0740473 +VERTEX_SE3:QUAT 881 21.743809 11.976460 -3.253871 -0.2262532 0.7226157 -0.5278213 0.3847605 +VERTEX_SE3:QUAT 882 21.172741 12.019659 -4.076573 -0.2059273 0.6359246 0.7387929 0.0859005 +VERTEX_SE3:QUAT 883 20.637791 11.892174 -5.009767 -0.2408192 0.5654017 0.6410417 0.4597745 +VERTEX_SE3:QUAT 884 20.247739 11.943601 -6.125184 -0.4711247 -0.8358001 -0.2733413 0.0690237 +VERTEX_SE3:QUAT 885 19.702055 11.942864 -6.997598 0.8189116 0.4636875 0.2840957 0.1834867 +VERTEX_SE3:QUAT 886 19.532617 11.859703 -7.804319 -0.3023752 -0.5080454 -0.7288364 0.3453355 +VERTEX_SE3:QUAT 887 19.087945 11.668871 -8.703446 0.0009837 -0.7379414 -0.6417568 0.2087815 +VERTEX_SE3:QUAT 888 18.700225 11.736931 -9.598602 0.5910643 0.6384505 -0.0351867 0.4917172 +VERTEX_SE3:QUAT 889 18.327844 11.884847 -10.558530 0.1899161 0.3887830 0.7166715 0.5469567 +VERTEX_SE3:QUAT 890 17.963329 11.960099 -11.544508 0.1147849 0.5916199 -0.4051706 0.6874934 +VERTEX_SE3:QUAT 891 17.707018 12.091847 -12.584440 -0.2316735 0.7164092 0.5480270 0.3643510 +VERTEX_SE3:QUAT 892 17.319933 12.124983 -13.502196 -0.9800838 0.0581628 -0.1466022 0.1206673 +VERTEX_SE3:QUAT 893 16.879846 12.051761 -14.327659 -0.4802997 0.4057262 0.6827942 0.3721431 +VERTEX_SE3:QUAT 894 16.491849 12.015457 -15.180111 -0.8085151 -0.1984831 -0.1980353 0.5173875 +VERTEX_SE3:QUAT 895 16.145407 11.862889 -16.202492 -0.0059751 0.5619013 0.1538406 0.8127511 +VERTEX_SE3:QUAT 896 15.751959 11.833074 -17.094375 0.9114259 0.1161457 0.3621233 0.1570980 +VERTEX_SE3:QUAT 897 15.322480 11.914281 -18.188691 -0.8202518 0.2297512 -0.3511621 0.3886985 +VERTEX_SE3:QUAT 898 15.152206 11.927538 -19.321541 0.2141582 0.4385913 0.3259511 0.8096479 +VERTEX_SE3:QUAT 899 14.815657 11.925009 -20.183093 -0.6016149 -0.0262530 -0.3885481 0.6974243 +VERTEX_SE3:QUAT 900 14.105987 12.366662 -19.951226 0.2582537 0.3149374 0.6504476 0.6411220 +VERTEX_SE3:QUAT 901 14.340576 12.170490 -18.846048 -0.6757928 0.3728857 -0.5500457 0.3189201 +VERTEX_SE3:QUAT 902 14.528574 11.958575 -18.066871 -0.3233853 -0.9270997 -0.1296173 0.1382299 +VERTEX_SE3:QUAT 903 14.581850 11.904982 -17.191752 -0.6343437 -0.2124928 -0.7377800 0.0901974 +VERTEX_SE3:QUAT 904 14.840479 11.811967 -16.316988 -0.6982980 -0.1547528 -0.5795032 0.3906502 +VERTEX_SE3:QUAT 905 14.887862 11.483462 -15.539733 0.4331481 0.6302459 0.0019092 0.6443362 +VERTEX_SE3:QUAT 906 15.004475 11.282588 -14.686151 -0.4318909 0.7919209 -0.2537057 0.3492348 +VERTEX_SE3:QUAT 907 15.239599 11.104277 -13.732754 -0.6370812 0.1976794 0.1061956 0.7374096 +VERTEX_SE3:QUAT 908 15.255135 10.960577 -12.704887 0.6344555 -0.2554010 0.7134983 0.1521733 +VERTEX_SE3:QUAT 909 15.437920 10.691516 -11.848260 -0.4642874 -0.2386883 -0.7861312 0.3308517 +VERTEX_SE3:QUAT 910 15.373181 10.489751 -10.868738 -0.0988082 0.9750578 0.1649417 0.1108758 +VERTEX_SE3:QUAT 911 15.544410 10.485639 -9.754049 0.0268664 0.1772839 0.5598665 0.8089488 +VERTEX_SE3:QUAT 912 15.458283 10.173945 -8.967292 -0.2107178 0.2666347 -0.4182841 0.8423434 +VERTEX_SE3:QUAT 913 15.469328 10.344413 -7.949614 0.6139884 0.6049422 0.4933080 0.1170910 +VERTEX_SE3:QUAT 914 15.539455 10.094935 -6.946849 0.0784985 0.4163235 -0.3531346 0.8341514 +VERTEX_SE3:QUAT 915 15.819039 9.844393 -5.987632 0.5843487 -0.0627790 0.8070859 0.0566372 +VERTEX_SE3:QUAT 916 15.892124 9.653996 -4.865208 -0.6937524 0.6588250 -0.1991450 0.2121284 +VERTEX_SE3:QUAT 917 16.157839 9.572363 -4.070394 -0.7250759 0.3450887 -0.0933157 0.5886178 +VERTEX_SE3:QUAT 918 16.193558 9.453365 -3.139097 0.6731269 0.4950102 0.5326989 0.1345250 +VERTEX_SE3:QUAT 919 16.177601 9.163252 -2.228372 -0.1982488 0.4213530 0.3785179 0.7999271 +VERTEX_SE3:QUAT 920 15.525955 10.027760 -2.023274 -0.7635115 0.2745450 0.1036194 0.5752723 +VERTEX_SE3:QUAT 921 15.415440 10.516137 -3.020455 -0.7217827 -0.4688997 -0.3442769 0.3750150 +VERTEX_SE3:QUAT 922 15.324772 10.774877 -4.050648 0.0843877 -0.2730522 -0.9581402 0.0169901 +VERTEX_SE3:QUAT 923 15.274730 10.944643 -4.869335 -0.6295327 0.5161249 0.5516752 0.1815438 +VERTEX_SE3:QUAT 924 15.487547 11.275803 -5.749160 -0.0147396 0.7367089 -0.3491660 0.5789005 +VERTEX_SE3:QUAT 925 15.356971 11.620285 -6.647083 -0.5207705 0.1137748 0.0516643 0.8445023 +VERTEX_SE3:QUAT 926 15.397831 11.878920 -7.671677 -0.7083000 -0.3438162 -0.6146080 0.0485655 +VERTEX_SE3:QUAT 927 15.381941 12.216139 -8.723081 -0.2950779 -0.6927179 -0.3648625 0.5476736 +VERTEX_SE3:QUAT 928 15.600150 12.587029 -9.626600 0.2826198 0.1088801 0.1183836 0.9456514 +VERTEX_SE3:QUAT 929 15.615122 12.854302 -10.463675 0.0481500 -0.5905939 -0.7730239 0.2265268 +VERTEX_SE3:QUAT 930 15.880859 13.363219 -11.473769 -0.0906037 -0.6982637 -0.7038754 0.0936916 +VERTEX_SE3:QUAT 931 16.124422 13.714667 -12.454060 0.8325755 0.3658696 0.4060757 0.0897778 +VERTEX_SE3:QUAT 932 16.303224 14.169742 -13.383187 -0.7999105 -0.4542365 -0.2665104 0.2877230 +VERTEX_SE3:QUAT 933 16.379240 14.595216 -14.353377 -0.2608782 0.4712734 -0.3456305 0.7683641 +VERTEX_SE3:QUAT 934 16.628945 14.817592 -15.123851 -0.1067775 -0.1729385 -0.4939303 0.8454133 +VERTEX_SE3:QUAT 935 16.996837 15.137172 -15.951477 -0.3772455 0.5261854 0.4280138 0.6305703 +VERTEX_SE3:QUAT 936 17.357300 15.354399 -16.911115 -0.3446313 -0.5054048 -0.4848533 0.6250700 +VERTEX_SE3:QUAT 937 17.780561 15.571730 -17.846205 -0.7065011 0.2650447 -0.1630290 0.6356328 +VERTEX_SE3:QUAT 938 18.155006 15.895892 -18.913703 -0.7840609 0.3911817 -0.4743960 0.0846987 +VERTEX_SE3:QUAT 939 18.555700 16.005107 -19.854064 0.3958819 -0.2509292 0.6539752 0.5938253 +VERTEX_SE3:QUAT 940 18.109720 16.905670 -19.708378 -0.2246740 0.3114266 0.8307372 0.4030022 +VERTEX_SE3:QUAT 941 18.037017 16.556657 -18.752248 -0.0237321 0.4963122 -0.6216540 0.6055223 +VERTEX_SE3:QUAT 942 17.596285 16.208033 -17.593802 -0.0382663 -0.4206922 -0.8923932 0.1587077 +VERTEX_SE3:QUAT 943 17.509882 15.785441 -16.537753 0.0492469 0.0406265 -0.2228949 0.9727498 +VERTEX_SE3:QUAT 944 17.497093 15.418797 -15.456645 0.2876239 0.7534213 -0.1532648 0.5710856 +VERTEX_SE3:QUAT 945 17.279631 15.126308 -14.638006 0.0142778 0.7479807 0.3092227 0.5871136 +VERTEX_SE3:QUAT 946 17.140012 14.705972 -13.826517 -0.7824799 0.5131327 0.1288689 0.3283487 +VERTEX_SE3:QUAT 947 16.940090 14.180097 -12.763318 0.2041462 0.4853096 0.8375389 0.1460394 +VERTEX_SE3:QUAT 948 16.890458 13.667668 -12.015409 0.0550770 0.3192573 -0.5211453 0.7895878 +VERTEX_SE3:QUAT 949 16.701468 13.024930 -11.135545 -0.5202940 0.6917132 -0.4914232 0.0965935 +VERTEX_SE3:QUAT 950 16.489316 12.390365 -10.345412 0.2961105 -0.1810070 0.6053548 0.7163104 +VERTEX_SE3:QUAT 951 16.216524 11.877332 -9.591063 -0.6656123 0.3353453 0.1817620 0.6414564 +VERTEX_SE3:QUAT 952 15.806992 11.504029 -8.770647 -0.6090159 -0.1327634 -0.7592089 0.1872840 +VERTEX_SE3:QUAT 953 15.482733 10.855721 -7.885817 -0.8590542 0.4454492 -0.2251560 0.1136032 +VERTEX_SE3:QUAT 954 15.410768 10.193317 -7.074157 -0.3554947 0.1013095 0.1133445 0.9222326 +VERTEX_SE3:QUAT 955 15.251170 9.642013 -6.287004 -0.5458138 -0.4002788 -0.4717861 0.5650505 +VERTEX_SE3:QUAT 956 15.069132 8.964433 -5.426913 -0.6889949 0.3150022 0.0803722 0.6477654 +VERTEX_SE3:QUAT 957 15.004441 8.297521 -4.725171 0.6103334 -0.4329757 0.6003756 0.2820892 +VERTEX_SE3:QUAT 958 14.647282 7.745619 -3.987905 -0.2136288 0.3276883 -0.5771524 0.7168530 +VERTEX_SE3:QUAT 959 14.383952 7.300798 -3.263426 -0.1088973 0.3632573 -0.7343789 0.5629149 +VERTEX_SE3:QUAT 960 13.903452 8.146027 -2.907429 0.0541440 0.2671067 -0.8175559 0.5072719 +VERTEX_SE3:QUAT 961 14.135980 8.709329 -3.490319 0.1021059 -0.3028058 -0.7119261 0.6253353 +VERTEX_SE3:QUAT 962 14.587114 9.087325 -4.218595 0.0844065 0.8033666 0.2557137 0.5311196 +VERTEX_SE3:QUAT 963 14.907449 9.806585 -4.961750 -0.0538512 -0.1228620 -0.7201678 0.6807079 +VERTEX_SE3:QUAT 964 15.280488 10.358293 -6.059541 -0.1973010 0.4551438 -0.8378909 0.2277174 +VERTEX_SE3:QUAT 965 15.448172 10.901100 -6.844471 0.4468846 0.7180011 0.1717197 0.5052534 +VERTEX_SE3:QUAT 966 15.714761 11.433620 -7.498081 -0.7776646 -0.5303873 -0.2947368 0.1644912 +VERTEX_SE3:QUAT 967 15.855308 11.819939 -8.244051 -0.1485469 -0.4918734 -0.7584235 0.4009840 +VERTEX_SE3:QUAT 968 16.271976 12.293133 -9.084263 0.2513156 -0.1211064 0.9104776 0.3052936 +VERTEX_SE3:QUAT 969 16.426709 12.816641 -10.001671 0.1998978 0.0729530 0.4955962 0.8420826 +VERTEX_SE3:QUAT 970 16.822168 13.311674 -10.766350 -0.4089488 -0.2963360 -0.6018498 0.6186458 +VERTEX_SE3:QUAT 971 17.238540 13.723755 -11.719748 -0.5235180 0.0945242 -0.7884571 0.3087546 +VERTEX_SE3:QUAT 972 17.516544 14.180789 -12.402134 -0.2535317 0.4152214 -0.8700905 0.0790908 +VERTEX_SE3:QUAT 973 17.643776 14.759806 -13.291800 0.1412749 0.0748998 -0.7123017 0.6834162 +VERTEX_SE3:QUAT 974 17.806252 15.368433 -14.092042 0.0833054 0.2000186 -0.6081970 0.7636420 +VERTEX_SE3:QUAT 975 17.951477 15.610462 -14.956958 -0.5538442 0.5221359 -0.3993034 0.5110651 +VERTEX_SE3:QUAT 976 18.166826 15.989743 -15.694473 -0.5231183 0.5725019 0.0406070 0.6300316 +VERTEX_SE3:QUAT 977 18.303076 16.359566 -16.728325 -0.2709983 0.4513886 -0.7220486 0.4488364 +VERTEX_SE3:QUAT 978 18.384052 16.633410 -17.648302 0.1990755 -0.2105067 0.7933247 0.5354361 +VERTEX_SE3:QUAT 979 18.844406 17.028029 -18.614225 -0.1284581 0.3835786 -0.4006409 0.8221027 +VERTEX_SE3:QUAT 980 18.204714 18.098979 -18.505507 -0.2677470 0.2886473 -0.8623045 0.3184733 +VERTEX_SE3:QUAT 981 17.887030 17.880918 -17.497542 0.0542051 0.9249906 0.1003500 0.3624693 +VERTEX_SE3:QUAT 982 17.486355 17.772296 -16.516664 -0.2558986 -0.1112212 -0.9547159 0.1032633 +VERTEX_SE3:QUAT 983 17.231854 17.370636 -15.572387 0.6230326 0.5141517 0.4308347 0.4023181 +VERTEX_SE3:QUAT 984 17.175095 17.119111 -14.657632 0.7306481 0.4691338 0.2164664 0.4463285 +VERTEX_SE3:QUAT 985 16.997196 16.995816 -13.494763 -0.3136438 0.1062694 0.0862447 0.9396256 +VERTEX_SE3:QUAT 986 16.880456 16.942723 -12.720492 0.0944599 0.3368650 0.7830440 0.5142386 +VERTEX_SE3:QUAT 987 16.675633 16.317110 -11.807893 -0.2426781 0.8388821 -0.2302055 0.4294060 +VERTEX_SE3:QUAT 988 16.607897 16.134797 -10.951327 -0.4718605 0.1757479 -0.0782688 0.8604268 +VERTEX_SE3:QUAT 989 16.525405 15.824645 -9.985031 -0.2095636 0.6571750 -0.4413014 0.5739836 +VERTEX_SE3:QUAT 990 16.334034 15.502506 -9.060351 -0.2362524 0.8285533 0.3744467 0.3427446 +VERTEX_SE3:QUAT 991 16.193985 15.118267 -8.265807 -0.3344633 -0.0792448 -0.4868014 0.8030435 +VERTEX_SE3:QUAT 992 15.840758 14.695454 -7.260952 -0.5442352 0.4728708 -0.6612853 0.2071304 +VERTEX_SE3:QUAT 993 15.672401 14.189353 -6.434371 0.9373678 -0.1286461 0.3225689 0.0272223 +VERTEX_SE3:QUAT 994 15.382186 13.512832 -5.649388 -0.4107377 0.3342704 -0.3716876 0.7625000 +VERTEX_SE3:QUAT 995 15.084343 12.815869 -4.710637 0.1060308 -0.2659659 -0.4694367 0.8352538 +VERTEX_SE3:QUAT 996 14.916385 12.114026 -4.005034 -0.2042251 0.2131881 -0.2682745 0.9169906 +VERTEX_SE3:QUAT 997 14.800122 11.473142 -3.363332 0.0442982 0.4358240 0.7182371 0.5405836 +VERTEX_SE3:QUAT 998 14.587254 10.702286 -2.499734 -0.7416037 -0.0542453 0.0815005 0.6636558 +VERTEX_SE3:QUAT 999 14.234630 10.191202 -1.619197 0.4552393 0.5030192 0.2899330 0.6750316 +VERTEX_SE3:QUAT 1000 13.608628 11.199719 -1.292017 0.6668665 -0.0866904 0.7375377 0.0617410 +VERTEX_SE3:QUAT 1001 13.833872 11.680589 -1.916088 0.4339112 0.7659838 0.4031488 0.2499219 +VERTEX_SE3:QUAT 1002 14.063284 12.117567 -2.789581 -0.4522374 0.5771711 0.4416436 0.5170162 +VERTEX_SE3:QUAT 1003 14.377498 12.856760 -3.414229 -0.3203682 0.5249791 0.5523197 0.5627648 +VERTEX_SE3:QUAT 1004 14.745733 13.621771 -3.991794 -0.2025268 0.7638653 -0.4766472 0.3850976 +VERTEX_SE3:QUAT 1005 15.150487 14.097849 -4.701720 -0.3973971 0.4622290 -0.5869390 0.5328438 +VERTEX_SE3:QUAT 1006 15.284401 14.697600 -5.460781 -0.6480153 -0.1124616 -0.4516091 0.6028912 +VERTEX_SE3:QUAT 1007 15.440059 15.425524 -6.056721 -0.4673030 0.4705427 0.3379816 0.6678218 +VERTEX_SE3:QUAT 1008 15.518319 16.052418 -6.659442 -0.5684958 0.6341052 0.3130537 0.4203814 +VERTEX_SE3:QUAT 1009 15.828682 16.822028 -7.541261 0.7316672 0.2096042 0.2873226 0.5815281 +VERTEX_SE3:QUAT 1010 16.078494 17.572606 -8.226471 -0.4889936 0.4761588 0.1481430 0.7156897 +VERTEX_SE3:QUAT 1011 16.127708 18.111367 -9.116001 -0.5384603 0.4281711 0.2701481 0.6736096 +VERTEX_SE3:QUAT 1012 16.099936 18.811121 -9.975715 0.1919098 0.1336635 -0.1680901 0.9576275 +VERTEX_SE3:QUAT 1013 16.430827 19.303899 -10.751004 -0.5235705 0.6178861 -0.3241572 0.4888895 +VERTEX_SE3:QUAT 1014 16.634285 20.080139 -11.418049 -0.0933891 0.5556551 -0.7170414 0.4103382 +VERTEX_SE3:QUAT 1015 16.804352 20.453414 -12.352873 -0.2959342 0.2806360 0.6187162 0.6714586 +VERTEX_SE3:QUAT 1016 16.974370 21.015348 -13.093718 0.6211093 0.2809464 0.4088187 0.6067617 +VERTEX_SE3:QUAT 1017 17.005793 21.484188 -13.809243 0.7780588 0.5643145 0.2665616 0.0715439 +VERTEX_SE3:QUAT 1018 16.879961 22.323786 -14.432037 -0.3301834 -0.0919103 -0.8491905 0.4017549 +VERTEX_SE3:QUAT 1019 17.023704 23.108825 -15.174440 -0.0825427 0.4032819 0.7273304 0.5491274 +VERTEX_SE3:QUAT 1020 16.695478 23.741867 -14.573181 -0.3632629 -0.1180070 -0.4741342 0.7932914 +VERTEX_SE3:QUAT 1021 16.797662 23.196493 -13.972731 -0.8033684 0.0338721 -0.2832948 0.5226815 +VERTEX_SE3:QUAT 1022 16.698133 22.465827 -12.996713 -0.0343125 0.0986806 -0.2965587 0.9492828 +VERTEX_SE3:QUAT 1023 16.709343 21.969106 -12.199366 -0.6755113 0.6959763 0.0024893 0.2435063 +VERTEX_SE3:QUAT 1024 16.543002 21.379971 -11.492434 0.2626943 0.8632237 -0.1479739 0.4048953 +VERTEX_SE3:QUAT 1025 16.250047 20.563565 -10.745277 -0.5610781 -0.7277431 -0.3944024 0.0052988 +VERTEX_SE3:QUAT 1026 16.014761 19.901603 -10.072235 -0.5684603 0.6365924 0.4009625 0.3329145 +VERTEX_SE3:QUAT 1027 15.919411 18.993558 -9.366497 -0.2572063 -0.0312269 -0.3285400 0.9082573 +VERTEX_SE3:QUAT 1028 15.725590 18.292886 -8.752723 0.0724408 -0.2037637 -0.5501248 0.8065949 +VERTEX_SE3:QUAT 1029 15.541718 17.311787 -8.134238 -0.5721472 0.6818916 0.1897566 0.4143234 +VERTEX_SE3:QUAT 1030 15.291107 16.417673 -7.638328 0.2443835 -0.3701417 0.8856861 0.1372293 +VERTEX_SE3:QUAT 1031 15.002670 15.551503 -7.085144 -0.7953131 0.1170419 0.0254530 0.5942478 +VERTEX_SE3:QUAT 1032 14.775149 14.863206 -6.517225 -0.0302770 -0.1464965 0.4765385 0.8663332 +VERTEX_SE3:QUAT 1033 14.563355 14.116523 -5.901301 0.1484123 -0.0304702 -0.0948681 0.9838930 +VERTEX_SE3:QUAT 1034 14.086601 13.433258 -5.247279 0.2854103 0.3498369 0.8680233 0.2066172 +VERTEX_SE3:QUAT 1035 13.640782 12.940866 -4.450716 -0.2854059 0.2566263 0.7567176 0.5292116 +VERTEX_SE3:QUAT 1036 13.184881 12.433894 -3.702430 0.0697108 0.3120514 0.5543495 0.7684146 +VERTEX_SE3:QUAT 1037 12.876693 11.974532 -2.951386 -0.5222510 0.3462734 0.5620733 0.5398354 +VERTEX_SE3:QUAT 1038 12.253990 11.057949 -2.397527 -0.1448922 0.2822630 0.7530066 0.5764676 +VERTEX_SE3:QUAT 1039 11.761971 10.573943 -1.562207 -0.7300670 -0.2985132 -0.5416636 0.2906761 +VERTEX_SE3:QUAT 1040 11.323579 11.481756 -1.225163 -0.2978729 -0.3696802 -0.5779827 0.6637351 +VERTEX_SE3:QUAT 1041 11.850679 12.071555 -1.954842 0.4884224 -0.3028660 0.5492361 0.6066758 +VERTEX_SE3:QUAT 1042 12.443216 12.450404 -2.524811 -0.0022218 0.2765890 -0.9372512 0.2122587 +VERTEX_SE3:QUAT 1043 13.090803 12.890958 -3.102775 0.1984135 -0.0185882 -0.9123716 0.3575816 +VERTEX_SE3:QUAT 1044 13.764185 13.571896 -3.720847 -0.1387029 0.2036517 0.8624495 0.4421180 +VERTEX_SE3:QUAT 1045 14.405814 14.071617 -4.159384 -0.4895744 -0.4253470 -0.6995804 0.2999734 +VERTEX_SE3:QUAT 1046 14.791572 14.670350 -4.597649 -0.2638860 0.0296079 0.8561721 0.4432346 +VERTEX_SE3:QUAT 1047 15.383373 15.394379 -5.076910 0.0971801 0.0280472 0.3185587 0.9424912 +VERTEX_SE3:QUAT 1048 15.984671 15.974985 -5.666310 -0.1449255 -0.0933819 0.9379142 0.3009874 +VERTEX_SE3:QUAT 1049 16.572346 16.681937 -6.135361 -0.5847678 0.0021150 -0.0895573 0.8062392 +VERTEX_SE3:QUAT 1050 17.307253 17.408053 -6.368041 -0.5985782 0.2458505 -0.7512140 0.1301506 +VERTEX_SE3:QUAT 1051 18.067624 18.067265 -6.638962 0.0365338 0.4807504 0.4839048 0.7303290 +VERTEX_SE3:QUAT 1052 18.566530 18.724055 -6.968367 -0.0461785 -0.5751074 0.7593819 0.3007626 +VERTEX_SE3:QUAT 1053 19.335253 19.392950 -7.241513 0.3883418 -0.0822615 -0.0282817 0.9174006 +VERTEX_SE3:QUAT 1054 20.142699 19.993372 -7.481186 0.2524463 0.1601211 0.6505969 0.6981087 +VERTEX_SE3:QUAT 1055 20.773461 20.806835 -7.751131 -0.0878873 -0.4172340 -0.7957395 0.4301050 +VERTEX_SE3:QUAT 1056 21.458670 21.402191 -8.012334 -0.3332965 0.2023798 -0.8433824 0.3696781 +VERTEX_SE3:QUAT 1057 22.137565 22.129241 -8.322948 -0.5080822 0.3214407 -0.2188109 0.7685376 +VERTEX_SE3:QUAT 1058 22.666813 22.942736 -8.447071 -0.1915355 -0.4033310 0.8033512 0.3940369 +VERTEX_SE3:QUAT 1059 23.351314 23.664084 -8.784288 0.1111245 -0.2132562 0.0929042 0.9661997 +VERTEX_SE3:QUAT 1060 22.825220 24.070937 -8.205205 -0.2457980 -0.3750687 -0.8422137 0.2993039 +VERTEX_SE3:QUAT 1061 22.440706 23.332628 -8.097313 -0.1748382 0.6387099 -0.4734874 0.5807676 +VERTEX_SE3:QUAT 1062 21.876702 22.519163 -7.826750 0.0282091 0.2994424 -0.9448478 0.1296191 +VERTEX_SE3:QUAT 1063 21.505046 21.807590 -7.484716 -0.4457978 0.0021827 -0.8703867 0.2090132 +VERTEX_SE3:QUAT 1064 20.971378 20.951884 -7.216280 0.0376868 0.7533320 -0.1823929 0.6307166 +VERTEX_SE3:QUAT 1065 20.539445 20.195446 -6.945204 0.1210936 0.3748157 0.9112453 0.1203392 +VERTEX_SE3:QUAT 1066 20.122689 19.337366 -6.757754 -0.1925335 -0.3648665 -0.9012569 0.1324357 +VERTEX_SE3:QUAT 1067 19.719318 18.471941 -6.478279 0.2099174 0.5026223 -0.1596604 0.8232947 +VERTEX_SE3:QUAT 1068 19.262916 17.543459 -6.234111 0.5881801 0.6143462 -0.2760117 0.4477058 +VERTEX_SE3:QUAT 1069 18.810998 16.586236 -6.041032 -0.4427576 0.2756036 -0.2818839 0.8053259 +VERTEX_SE3:QUAT 1070 18.296964 15.909403 -5.793452 -0.2009877 0.2388119 0.5623569 0.7657203 +VERTEX_SE3:QUAT 1071 17.819207 15.154915 -5.464569 0.3845258 0.4685900 0.3988046 0.6881267 +VERTEX_SE3:QUAT 1072 17.354083 14.309967 -5.153651 0.1266810 0.1441880 -0.2737655 0.9424512 +VERTEX_SE3:QUAT 1073 16.987213 13.416020 -5.007921 -0.4502468 -0.0380829 -0.8915633 0.0306991 +VERTEX_SE3:QUAT 1074 16.655742 12.568317 -4.743049 0.4057126 0.5693493 0.6858801 0.2020076 +VERTEX_SE3:QUAT 1075 16.114096 11.719508 -4.590155 -0.2937649 0.3845761 -0.4520943 0.7492757 +VERTEX_SE3:QUAT 1076 15.729945 10.839217 -4.221311 0.0032987 0.3055736 -0.9165425 0.2579994 +VERTEX_SE3:QUAT 1077 15.255517 9.939434 -3.949816 -0.2923969 0.6838316 0.3202233 0.5868010 +VERTEX_SE3:QUAT 1078 14.838493 9.170481 -3.565312 -0.3664550 -0.0626570 0.6407771 0.6717064 +VERTEX_SE3:QUAT 1079 14.534957 8.239843 -3.119550 -0.3340531 0.4742894 0.4612186 0.6713684 +VERTEX_SE3:QUAT 1080 13.952249 8.614201 -2.545148 -0.3739890 0.8122014 0.0394560 0.4459869 +VERTEX_SE3:QUAT 1081 14.384774 9.552235 -2.959961 0.3758397 0.7890239 0.4508776 0.1813704 +VERTEX_SE3:QUAT 1082 14.607544 10.583241 -3.339056 -0.8173337 0.1926502 -0.4434976 0.3133072 +VERTEX_SE3:QUAT 1083 14.900328 11.531072 -3.733587 0.6631612 -0.6369158 0.3930358 0.0088573 +VERTEX_SE3:QUAT 1084 15.346076 12.394152 -4.037595 0.1206859 0.1581627 0.3286807 0.9232489 +VERTEX_SE3:QUAT 1085 15.653209 13.290415 -4.374768 -0.6862011 0.4279519 0.0797467 0.5827742 +VERTEX_SE3:QUAT 1086 16.350274 14.158245 -4.777575 0.4806378 0.3741194 0.6916801 0.3880729 +VERTEX_SE3:QUAT 1087 16.593874 15.068119 -5.240037 0.5661027 -0.1251563 0.4931298 0.6486036 +VERTEX_SE3:QUAT 1088 16.875117 15.868358 -5.500192 0.5821109 0.4152818 0.2249479 0.6618810 +VERTEX_SE3:QUAT 1089 17.025793 16.671088 -6.005929 -0.0749822 0.7570122 0.2993852 0.5759155 +VERTEX_SE3:QUAT 1090 17.225501 17.486164 -6.452056 0.0970014 0.3018973 0.6318491 0.7072591 +VERTEX_SE3:QUAT 1091 17.489181 18.380789 -6.884061 -0.1153081 0.4191794 0.5619907 0.7036754 +VERTEX_SE3:QUAT 1092 17.964029 19.207233 -7.043992 0.5190548 -0.2227326 0.3884739 0.7280524 +VERTEX_SE3:QUAT 1093 18.326098 19.993845 -7.129750 -0.7396775 0.2347694 -0.4086930 0.4803443 +VERTEX_SE3:QUAT 1094 18.745160 20.928390 -7.338904 0.1621251 0.2076430 -0.7661514 0.5861841 +VERTEX_SE3:QUAT 1095 19.205424 21.679703 -7.686404 0.6707089 -0.0346193 0.7231344 0.1613312 +VERTEX_SE3:QUAT 1096 19.786922 22.403517 -7.892952 0.0483754 0.3159463 0.0482257 0.9463150 +VERTEX_SE3:QUAT 1097 20.487278 23.072928 -8.048648 -0.5639447 0.2113204 -0.3360827 0.7241260 +VERTEX_SE3:QUAT 1098 20.948172 24.059239 -8.267037 0.4599857 0.5645698 0.3950761 0.5599902 +VERTEX_SE3:QUAT 1099 21.656445 24.693345 -8.507674 -0.6095264 -0.1250944 -0.5715967 0.5348889 +VERTEX_SE3:QUAT 1100 21.513410 25.170502 -7.667026 0.7908778 -0.0603013 0.4247777 0.4363944 +VERTEX_SE3:QUAT 1101 21.033681 24.271522 -7.458184 0.7909074 0.3028663 0.5117457 0.1444088 +VERTEX_SE3:QUAT 1102 20.530625 23.632032 -7.270223 0.7002842 -0.1566492 0.2628530 0.6449584 +VERTEX_SE3:QUAT 1103 19.608384 22.917393 -6.863946 0.3005119 0.3245113 -0.6886638 0.5745670 +VERTEX_SE3:QUAT 1104 18.947303 22.178642 -6.523720 -0.1042053 0.3071356 -0.9440739 0.0594422 +VERTEX_SE3:QUAT 1105 18.250884 21.506904 -6.164715 0.3265308 -0.0236171 -0.7774673 0.5369958 +VERTEX_SE3:QUAT 1106 17.731948 20.819519 -5.814923 0.7280877 0.5865217 0.1973125 0.2948700 +VERTEX_SE3:QUAT 1107 17.005428 19.884576 -5.487606 -0.2017629 0.6387947 -0.3067034 0.6761405 +VERTEX_SE3:QUAT 1108 16.460524 19.377751 -5.262787 0.7382209 0.1452615 0.2710337 0.6003913 +VERTEX_SE3:QUAT 1109 15.972466 18.550039 -5.212282 0.5582390 0.2468446 -0.6489542 0.4541975 +VERTEX_SE3:QUAT 1110 15.397637 17.830923 -4.924667 0.3175205 -0.2102245 0.1680538 0.9092548 +VERTEX_SE3:QUAT 1111 14.900861 17.206859 -4.706898 0.7627972 0.1322334 -0.2496377 0.5816664 +VERTEX_SE3:QUAT 1112 14.328257 16.537006 -4.614145 0.1591091 0.5457855 -0.5963566 0.5667109 +VERTEX_SE3:QUAT 1113 13.790058 15.752916 -4.431666 0.3597904 0.7374687 0.1438901 0.5531603 +VERTEX_SE3:QUAT 1114 13.111337 14.926009 -4.397092 0.1564714 -0.7287437 0.6478148 0.1574337 +VERTEX_SE3:QUAT 1115 12.376285 14.209527 -4.274903 0.1820599 0.8015413 -0.4991330 0.2743211 +VERTEX_SE3:QUAT 1116 11.733342 13.484703 -4.099651 0.4107027 0.3448069 -0.8404290 0.0781699 +VERTEX_SE3:QUAT 1117 11.004346 12.762721 -4.136936 0.0684072 -0.5501254 0.8264469 0.0983263 +VERTEX_SE3:QUAT 1118 10.500845 12.112083 -4.219381 -0.0949859 0.9291260 -0.2876243 0.2120726 +VERTEX_SE3:QUAT 1119 9.622619 11.491980 -4.160822 0.1552718 0.8375583 -0.5029817 0.1462742 +VERTEX_SE3:QUAT 1120 9.363340 11.993475 -3.374993 0.6454926 0.3663046 -0.4892055 0.4580809 +VERTEX_SE3:QUAT 1121 10.013777 12.780555 -3.382193 0.1666053 0.6559102 -0.0934046 0.7302740 +VERTEX_SE3:QUAT 1122 10.785384 13.619090 -3.253222 0.1520435 -0.0504043 0.0350504 0.9864652 +VERTEX_SE3:QUAT 1123 11.255043 14.313831 -3.249824 0.0265355 0.2977696 -0.7141138 0.6329855 +VERTEX_SE3:QUAT 1124 12.099677 15.024780 -3.399836 -0.1123882 0.4509809 0.3487470 0.8138554 +VERTEX_SE3:QUAT 1125 12.936162 15.617646 -3.354522 0.8904731 0.1307801 -0.0015103 0.4358348 +VERTEX_SE3:QUAT 1126 13.782849 16.281493 -3.454953 0.4083282 0.3402815 0.6870693 0.4953911 +VERTEX_SE3:QUAT 1127 14.481358 16.764788 -3.412331 0.5435322 -0.3952852 0.1786875 0.7186050 +VERTEX_SE3:QUAT 1128 15.488037 17.212821 -3.474809 0.0291957 -0.3664459 0.5676193 0.7366637 +VERTEX_SE3:QUAT 1129 16.216340 17.753678 -3.294486 -0.1725911 -0.1637220 0.9463119 0.2188634 +VERTEX_SE3:QUAT 1130 17.030418 18.339462 -3.220181 -0.2106836 -0.0721203 -0.2353511 0.9460555 +VERTEX_SE3:QUAT 1131 18.026905 18.831236 -3.220731 0.5033359 0.1650886 0.8419563 0.1025098 +VERTEX_SE3:QUAT 1132 18.835146 19.528462 -3.283931 0.7159773 -0.4701793 0.2972477 0.4218432 +VERTEX_SE3:QUAT 1133 19.722265 20.215564 -3.162678 -0.1565701 0.4421456 -0.4559356 0.7563834 +VERTEX_SE3:QUAT 1134 20.506478 20.613210 -3.000760 -0.3371698 0.5156283 -0.3713310 0.6946634 +VERTEX_SE3:QUAT 1135 21.508362 21.309062 -3.162255 -0.0280273 -0.4009298 0.4917057 0.7724606 +VERTEX_SE3:QUAT 1136 22.332403 21.931459 -3.282910 0.3940363 -0.4932759 0.3248175 0.7042073 +VERTEX_SE3:QUAT 1137 23.153428 22.481563 -3.411156 0.1126650 -0.0576194 0.9046965 0.4068302 +VERTEX_SE3:QUAT 1138 24.033010 22.859655 -3.658862 0.2240284 0.0459421 -0.9304047 0.2864396 +VERTEX_SE3:QUAT 1139 25.023254 23.425104 -3.709649 0.3190454 0.3105010 -0.5594913 0.6991199 +VERTEX_SE3:QUAT 1140 24.784099 23.986300 -3.077813 -0.3333297 0.6223165 -0.1275119 0.6966736 +VERTEX_SE3:QUAT 1141 23.944427 23.471737 -2.794497 -0.1306442 -0.0959596 0.9827268 0.0892854 +VERTEX_SE3:QUAT 1142 23.094839 23.020901 -2.550020 0.1264254 -0.1685030 0.4375786 0.8741558 +VERTEX_SE3:QUAT 1143 22.187190 22.303938 -2.202768 0.0233897 0.4070396 -0.6452259 0.6461077 +VERTEX_SE3:QUAT 1144 21.370594 21.986808 -1.772567 -0.4858002 0.7931226 -0.2510692 0.2681772 +VERTEX_SE3:QUAT 1145 20.502894 21.676604 -1.446848 0.5414705 0.1028038 0.4668984 0.6915540 +VERTEX_SE3:QUAT 1146 19.419717 21.194422 -1.167035 0.8903519 -0.0212494 0.1010252 0.4434139 +VERTEX_SE3:QUAT 1147 18.579120 20.786230 -0.907121 -0.5990646 0.3603860 -0.6621901 0.2697179 +VERTEX_SE3:QUAT 1148 17.882206 20.226860 -0.594152 0.2236932 0.6106068 -0.7593010 0.0241390 +VERTEX_SE3:QUAT 1149 16.891917 19.815727 -0.403769 -0.0555280 0.1870898 0.7665215 0.6118487 +VERTEX_SE3:QUAT 1150 16.108270 19.297736 -0.305423 0.5687425 -0.4282844 0.6048203 0.3567868 +VERTEX_SE3:QUAT 1151 15.362760 18.638338 -0.175867 -0.0101279 0.6640166 0.1809545 0.7254205 +VERTEX_SE3:QUAT 1152 14.470371 18.075406 0.032623 -0.0910156 -0.2372284 -0.9562897 0.1447374 +VERTEX_SE3:QUAT 1153 13.697829 17.415396 0.433488 0.3782287 -0.1443778 -0.3006428 0.8635462 +VERTEX_SE3:QUAT 1154 12.961339 16.682424 0.665015 0.5891104 0.2002142 -0.6034949 0.4986553 +VERTEX_SE3:QUAT 1155 12.310738 16.004892 0.840945 0.1559811 -0.0495588 -0.2473761 0.9549968 +VERTEX_SE3:QUAT 1156 11.490314 15.336681 0.878206 -0.3942577 0.4687910 -0.1755603 0.7706974 +VERTEX_SE3:QUAT 1157 10.865808 14.645152 1.184868 0.6932148 -0.2026449 -0.0023029 0.6916524 +VERTEX_SE3:QUAT 1158 10.160336 14.011772 1.454166 -0.2098318 0.2223241 -0.1210565 0.9443982 +VERTEX_SE3:QUAT 1159 9.244444 13.334214 1.584869 0.1877687 -0.8369858 0.5047548 0.0970582 +VERTEX_SE3:QUAT 1160 8.881917 13.940067 2.116705 -0.0576622 0.1418219 0.8725481 0.4639196 +VERTEX_SE3:QUAT 1161 9.806558 14.625458 1.799015 -0.0922469 0.0226779 -0.7424971 0.6630794 +VERTEX_SE3:QUAT 1162 10.593645 15.251736 1.688239 -0.5121037 -0.3613305 -0.7604705 0.1699256 +VERTEX_SE3:QUAT 1163 11.392460 15.761368 1.492451 -0.1547691 -0.6816329 0.7129578 0.0558056 +VERTEX_SE3:QUAT 1164 12.154022 16.505322 1.452942 0.4093478 0.6847425 0.0111321 0.6028583 +VERTEX_SE3:QUAT 1165 12.995290 17.096909 1.232819 -0.5414569 0.5833234 -0.5159082 0.3168547 +VERTEX_SE3:QUAT 1166 13.951437 17.499508 0.803066 0.2492904 -0.5362503 0.7760535 0.2191593 +VERTEX_SE3:QUAT 1167 14.769375 18.100153 0.560810 0.5511451 0.1050441 0.0664722 0.8250977 +VERTEX_SE3:QUAT 1168 15.588460 18.767117 0.302725 0.2089083 0.2024884 0.9287145 0.2298806 +VERTEX_SE3:QUAT 1169 16.535279 19.452210 0.251586 -0.2578410 0.0180723 0.2259850 0.9392136 +VERTEX_SE3:QUAT 1170 17.292737 20.151612 0.020271 0.1527674 0.7487239 -0.3843593 0.5180179 +VERTEX_SE3:QUAT 1171 18.113572 20.741158 -0.198414 0.2315726 0.5268493 0.8100179 0.1125836 +VERTEX_SE3:QUAT 1172 19.080468 21.425368 -0.305573 0.7525977 -0.2083067 0.5285238 0.3329679 +VERTEX_SE3:QUAT 1173 19.754422 22.109648 -0.432771 0.3917218 0.2190981 -0.6851288 0.5737147 +VERTEX_SE3:QUAT 1174 20.597151 22.861358 -0.552808 0.1368936 0.6170763 -0.4841353 0.6050537 +VERTEX_SE3:QUAT 1175 21.552901 23.535275 -0.648828 0.0480227 0.1982543 -0.9732633 0.1055823 +VERTEX_SE3:QUAT 1176 22.359735 24.172241 -0.762221 0.3279126 -0.2637335 0.2543941 0.8707477 +VERTEX_SE3:QUAT 1177 23.281497 24.681656 -0.815440 0.2088535 0.3818492 -0.8201360 0.3714141 +VERTEX_SE3:QUAT 1178 24.148695 25.127230 -1.139141 0.2267903 0.6531979 -0.3226919 0.6463502 +VERTEX_SE3:QUAT 1179 25.066297 25.697563 -1.250727 0.6135458 -0.3435976 0.5739219 0.4196615 +VERTEX_SE3:QUAT 1180 25.029230 26.312909 -0.612208 0.7840911 0.1515747 0.3308305 0.5027698 +VERTEX_SE3:QUAT 1181 24.245397 26.055059 -0.415479 0.5337857 0.0748894 0.3546102 0.7640131 +VERTEX_SE3:QUAT 1182 23.290230 25.576724 -0.254937 -0.1200568 0.3395605 -0.4628665 0.8099627 +VERTEX_SE3:QUAT 1183 22.277576 25.283605 -0.201796 -0.1870854 -0.1201851 0.4185247 0.8805632 +VERTEX_SE3:QUAT 1184 21.242315 24.756289 0.227208 0.3159708 0.3072831 0.8928699 0.0923193 +VERTEX_SE3:QUAT 1185 20.413989 24.237077 0.177428 -0.3230185 -0.2427270 -0.8888617 0.2160266 +VERTEX_SE3:QUAT 1186 19.388507 23.888677 0.449161 -0.3130484 0.0489650 0.2121456 0.9244444 +VERTEX_SE3:QUAT 1187 18.640185 23.573204 0.582890 0.0989199 0.0340738 0.4874000 0.8668882 +VERTEX_SE3:QUAT 1188 17.802474 23.349348 0.817583 0.2757924 -0.5036296 0.7792682 0.2510713 +VERTEX_SE3:QUAT 1189 17.112057 22.934500 1.163082 -0.2873620 0.5826616 -0.7336603 0.1991761 +VERTEX_SE3:QUAT 1190 16.355892 22.528774 1.215995 -0.3071802 0.1361306 0.2292024 0.9135508 +VERTEX_SE3:QUAT 1191 15.633159 22.035305 1.388180 0.2181414 0.8086747 -0.4844614 0.2525011 +VERTEX_SE3:QUAT 1192 14.788699 21.490395 1.636549 0.2427185 0.1118899 0.9411227 0.2070178 +VERTEX_SE3:QUAT 1193 13.858641 21.262519 1.792274 0.6209850 0.2227813 -0.3601603 0.6595686 +VERTEX_SE3:QUAT 1194 12.961429 20.976788 1.785016 -0.1383164 -0.0835520 0.1378301 0.9771850 +VERTEX_SE3:QUAT 1195 12.109972 20.691128 1.784438 0.5693528 0.1401208 -0.3587000 0.7263180 +VERTEX_SE3:QUAT 1196 11.274680 20.456421 1.885900 0.6634607 0.2099789 -0.5815880 0.4212887 +VERTEX_SE3:QUAT 1197 10.115782 20.225626 1.848790 0.7072947 -0.0583368 0.2909677 0.6416143 +VERTEX_SE3:QUAT 1198 8.943041 19.850321 1.793814 -0.1474999 -0.1101964 0.9479245 0.2598838 +VERTEX_SE3:QUAT 1199 7.773648 19.402677 1.643390 0.2303219 -0.7161282 0.6062800 0.2579473 +VERTEX_SE3:QUAT 1200 25.749387 25.039936 3.653708 0.3063311 0.0312887 0.1481341 0.9398077 +VERTEX_SE3:QUAT 1201 24.917704 24.648942 3.720877 0.3758992 -0.2600116 0.6915671 0.5593109 +VERTEX_SE3:QUAT 1202 23.935527 24.457165 3.590143 0.2191878 -0.0917085 0.9486255 0.2089398 +VERTEX_SE3:QUAT 1203 23.046116 24.165535 3.664916 0.7129340 -0.0472969 0.1289862 0.6876414 +VERTEX_SE3:QUAT 1204 22.169855 23.826549 3.812733 -0.4576475 0.0815185 -0.4266945 0.7757869 +VERTEX_SE3:QUAT 1205 21.298490 23.410238 3.865614 0.2134310 0.0177644 -0.1192136 0.9694946 +VERTEX_SE3:QUAT 1206 20.253934 23.025446 3.678483 -0.2696868 -0.0671809 0.8392777 0.4672993 +VERTEX_SE3:QUAT 1207 19.377648 22.884049 3.364303 0.5260386 -0.0510398 -0.8483381 0.0316360 +VERTEX_SE3:QUAT 1208 18.376339 22.704356 3.581933 0.4029333 -0.3343200 -0.8380901 0.1532318 +VERTEX_SE3:QUAT 1209 17.306058 22.501513 3.614340 0.7713601 0.1165664 0.5965498 0.1885315 +VERTEX_SE3:QUAT 1210 16.433022 22.281726 3.299962 0.3677819 -0.2233936 -0.7854508 0.4448583 +VERTEX_SE3:QUAT 1211 15.476791 22.000441 3.097152 -0.3389829 0.6992802 -0.3816802 0.5004179 +VERTEX_SE3:QUAT 1212 14.620241 21.708289 3.087086 -0.3996805 0.2828396 -0.6033365 0.6294779 +VERTEX_SE3:QUAT 1213 13.703798 21.131441 3.117477 0.6408350 0.4913730 0.0484946 0.5878192 +VERTEX_SE3:QUAT 1214 12.818066 20.696185 3.029870 0.5406149 -0.0438698 -0.1352434 0.8291684 +VERTEX_SE3:QUAT 1215 12.132693 20.253503 2.870642 0.6942566 0.3724362 -0.5818595 0.2018379 +VERTEX_SE3:QUAT 1216 11.249768 19.658080 2.670744 -0.1526461 0.5178910 -0.8416986 0.0056208 +VERTEX_SE3:QUAT 1217 10.567293 19.218952 2.469891 0.5021668 0.0768055 -0.8612233 0.0149633 +VERTEX_SE3:QUAT 1218 9.820137 18.598220 2.158901 -0.2669481 -0.3723584 0.8869098 0.0589828 +VERTEX_SE3:QUAT 1219 8.955219 17.896493 1.958578 0.6150043 -0.4376196 -0.3057260 0.5803365 +VERTEX_SE3:QUAT 1220 9.552611 17.308378 1.233265 0.6867563 0.1223526 0.0739106 0.7126941 +VERTEX_SE3:QUAT 1221 10.382034 17.936104 1.515992 0.2400896 -0.3737276 0.8959239 0.0022375 +VERTEX_SE3:QUAT 1222 11.145325 18.297482 2.079691 0.4185380 -0.6573670 0.4342690 0.4517797 +VERTEX_SE3:QUAT 1223 12.180559 18.688542 2.590168 0.5125854 -0.5700316 0.5572501 0.3190493 +VERTEX_SE3:QUAT 1224 12.870389 19.403707 3.085726 0.7899938 0.2796091 0.1980995 0.5084144 +VERTEX_SE3:QUAT 1225 13.709650 20.041283 3.444554 0.7035924 0.0336832 0.6923076 0.1566310 +VERTEX_SE3:QUAT 1226 14.568474 20.372394 3.794976 -0.0619054 -0.5097863 0.7196124 0.4673796 +VERTEX_SE3:QUAT 1227 15.339734 20.816499 4.086891 0.4487246 0.7207421 -0.5128463 0.1271443 +VERTEX_SE3:QUAT 1228 16.164086 21.317001 4.594826 -0.0876487 0.7018740 -0.3053970 0.6375134 +VERTEX_SE3:QUAT 1229 16.894792 22.026619 5.011501 -0.3097410 -0.3443736 0.5015519 0.7306935 +VERTEX_SE3:QUAT 1230 17.521189 22.418251 5.520615 -0.2228975 -0.3638166 -0.8940800 0.1362906 +VERTEX_SE3:QUAT 1231 18.235097 22.859792 5.972089 0.4384628 0.3785313 -0.7931378 0.1881406 +VERTEX_SE3:QUAT 1232 19.071597 23.280816 6.256582 -0.1225351 -0.3166346 -0.7792825 0.5267318 +VERTEX_SE3:QUAT 1233 19.836082 23.773919 6.622975 0.4385135 -0.4819936 0.1381307 0.7458606 +VERTEX_SE3:QUAT 1234 20.683660 24.267080 6.783657 0.6473124 0.0078571 0.2713269 0.7122546 +VERTEX_SE3:QUAT 1235 21.448528 24.571888 6.952554 -0.2147702 -0.0113939 -0.8505908 0.4798325 +VERTEX_SE3:QUAT 1236 22.264787 25.299387 7.029247 0.3715562 0.4141772 0.1884036 0.8092634 +VERTEX_SE3:QUAT 1237 23.174800 25.860556 7.074528 0.3288275 -0.1351259 0.0470973 0.9334855 +VERTEX_SE3:QUAT 1238 24.067754 26.453061 7.014743 0.2066103 0.3206843 -0.0155359 0.9242469 +VERTEX_SE3:QUAT 1239 24.751770 27.049848 6.862160 0.4457650 -0.2150197 0.8189250 0.2905544 +VERTEX_SE3:QUAT 1240 25.302797 26.303136 6.602416 0.1060735 -0.2881678 -0.0924613 0.9471846 +VERTEX_SE3:QUAT 1241 24.774595 25.597719 6.751470 -0.1682782 0.5169156 -0.1938078 0.8166512 +VERTEX_SE3:QUAT 1242 24.085871 24.740119 6.800114 0.6395425 0.2412863 0.5757439 0.4486483 +VERTEX_SE3:QUAT 1243 23.337502 24.022454 6.977024 -0.4621082 0.5532500 -0.1897208 0.6666157 +VERTEX_SE3:QUAT 1244 22.600953 23.528091 7.030708 0.5908947 0.0385717 0.3915790 0.7042880 +VERTEX_SE3:QUAT 1245 21.820389 23.053423 7.157942 0.6317440 0.3101856 0.6794733 0.2073655 +VERTEX_SE3:QUAT 1246 21.114754 22.522106 7.371592 0.6714007 -0.1582587 0.6454699 0.3279390 +VERTEX_SE3:QUAT 1247 20.143260 21.841189 7.537791 0.4238741 -0.0034937 -0.0084344 0.9056751 +VERTEX_SE3:QUAT 1248 19.259612 21.211967 7.790653 -0.0620948 -0.4124642 0.0980602 0.9035495 +VERTEX_SE3:QUAT 1249 18.506256 20.412783 7.651986 -0.2109193 0.0600604 -0.1301520 0.9669365 +VERTEX_SE3:QUAT 1250 17.801082 19.712807 7.686416 -0.0944697 0.5096169 0.2784465 0.8085998 +VERTEX_SE3:QUAT 1251 17.236353 18.855483 7.684409 -0.6109090 -0.0446091 -0.7893424 0.0416995 +VERTEX_SE3:QUAT 1252 16.468383 18.317656 7.755625 -0.1528546 -0.1181254 -0.7359094 0.6489370 +VERTEX_SE3:QUAT 1253 15.624588 17.679649 7.682867 0.0256977 -0.4828621 0.8467429 0.2218340 +VERTEX_SE3:QUAT 1254 14.744551 17.016807 7.493469 -0.5088127 0.4461216 -0.7334937 0.0638133 +VERTEX_SE3:QUAT 1255 14.163304 16.525991 7.336226 0.8245907 0.0732140 0.2946406 0.4773644 +VERTEX_SE3:QUAT 1256 13.168122 15.937736 7.179299 0.1665617 -0.3463594 0.1181502 0.9156052 +VERTEX_SE3:QUAT 1257 12.136775 15.313698 7.169283 0.4088765 -0.1392765 0.9016614 0.0207071 +VERTEX_SE3:QUAT 1258 11.265440 14.815095 7.170742 0.0993609 -0.6608367 0.2284444 0.7079798 +VERTEX_SE3:QUAT 1259 10.195358 14.281170 7.001720 -0.0077889 0.8248827 -0.1673317 0.5399148 +VERTEX_SE3:QUAT 1260 10.742760 13.740706 6.360910 0.2269470 -0.2426653 -0.4290497 0.8399554 +VERTEX_SE3:QUAT 1261 11.646096 14.225152 6.457252 -0.0498582 0.6832163 -0.5101335 0.5200899 +VERTEX_SE3:QUAT 1262 12.430020 14.780690 6.362110 -0.3891142 0.3621646 0.4246378 0.7328776 +VERTEX_SE3:QUAT 1263 13.077788 15.154338 6.009494 0.4755575 -0.5365691 0.5800733 0.3865923 +VERTEX_SE3:QUAT 1264 14.012257 15.776598 5.848631 0.8051242 0.2377463 0.1524763 0.5215388 +VERTEX_SE3:QUAT 1265 14.762694 16.325801 5.718688 -0.0651366 0.4765629 -0.6195290 0.6203458 +VERTEX_SE3:QUAT 1266 15.741601 16.876254 5.533438 -0.1045573 0.5514253 0.1973615 0.8037701 +VERTEX_SE3:QUAT 1267 16.866217 17.367194 5.380032 -0.2984178 -0.4198836 0.8546369 0.0651180 +VERTEX_SE3:QUAT 1268 17.861671 17.878332 5.502115 0.4637411 0.4982966 -0.2370221 0.6931559 +VERTEX_SE3:QUAT 1269 18.660834 18.330829 5.476585 0.0035803 0.7804049 -0.5435573 0.3090322 +VERTEX_SE3:QUAT 1270 19.664945 18.869980 5.332555 0.6053037 0.0709619 -0.4584180 0.6468576 +VERTEX_SE3:QUAT 1271 20.480219 19.383582 5.275920 -0.3886524 0.5599365 -0.6750644 0.2823268 +VERTEX_SE3:QUAT 1272 21.205574 20.018895 5.247793 -0.4307613 0.3358929 -0.4888070 0.6802120 +VERTEX_SE3:QUAT 1273 22.106196 20.467202 5.078988 0.4555709 0.4965738 0.0735210 0.7351627 +VERTEX_SE3:QUAT 1274 22.972386 20.863374 4.924561 0.4983275 -0.4253244 -0.3608723 0.6637319 +VERTEX_SE3:QUAT 1275 23.739437 21.313223 4.903962 0.0014441 0.6970348 -0.7006317 0.1524979 +VERTEX_SE3:QUAT 1276 24.656592 21.665399 4.788136 -0.2552311 0.6505771 -0.2348940 0.6755970 +VERTEX_SE3:QUAT 1277 25.565773 22.127593 4.780318 -0.3346581 0.5277493 -0.0830022 0.7762701 +VERTEX_SE3:QUAT 1278 26.525066 22.288370 4.755992 -0.3269534 0.0822657 -0.4193641 0.8428924 +VERTEX_SE3:QUAT 1279 27.252543 22.477355 4.787539 -0.0695344 0.6890806 -0.0274440 0.7208188 +VERTEX_SE3:QUAT 1280 27.747902 21.754308 4.078633 0.6294186 -0.0135223 -0.0735957 0.7734553 +VERTEX_SE3:QUAT 1281 26.802226 21.509384 3.998002 -0.3682422 0.7363090 -0.5303422 0.2024446 +VERTEX_SE3:QUAT 1282 25.650591 21.380287 4.041498 -0.4008614 0.4823079 -0.7534693 0.1974167 +VERTEX_SE3:QUAT 1283 24.705469 21.068120 4.077589 0.0788253 -0.6746547 0.4740882 0.5602392 +VERTEX_SE3:QUAT 1284 23.793822 20.784552 3.954724 0.2405656 -0.3530371 0.4476598 0.7855531 +VERTEX_SE3:QUAT 1285 23.035433 20.367270 4.015341 0.0688086 0.2025304 -0.5418196 0.8128212 +VERTEX_SE3:QUAT 1286 22.439556 19.757188 4.027967 0.0857485 -0.6500365 0.7187988 0.2311450 +VERTEX_SE3:QUAT 1287 21.641275 19.190747 3.951911 -0.2307107 0.1693568 -0.8913781 0.3514768 +VERTEX_SE3:QUAT 1288 20.906433 18.663532 3.761282 0.7420556 0.4527903 0.3739135 0.3233004 +VERTEX_SE3:QUAT 1289 19.956746 18.220893 3.826821 -0.1340827 0.3416943 0.1814819 0.9123219 +VERTEX_SE3:QUAT 1290 19.114706 17.799735 3.846069 0.0901052 0.6599621 -0.0021556 0.7458729 +VERTEX_SE3:QUAT 1291 18.151301 17.094319 3.994709 -0.1865410 -0.3966892 0.7602898 0.4793741 +VERTEX_SE3:QUAT 1292 17.488188 16.563439 4.100539 0.1280287 -0.2762357 0.9013082 0.3081330 +VERTEX_SE3:QUAT 1293 16.797056 15.823670 4.447214 0.0945444 0.2971874 0.7972089 0.5169129 +VERTEX_SE3:QUAT 1294 16.124338 15.109155 4.753964 -0.6885027 -0.2424196 -0.6333904 0.2569307 +VERTEX_SE3:QUAT 1295 15.476224 14.510333 4.970115 -0.4695662 0.3970286 -0.3907247 0.6849891 +VERTEX_SE3:QUAT 1296 14.681897 13.705801 5.131113 0.5830585 0.6217323 -0.2803348 0.4414795 +VERTEX_SE3:QUAT 1297 14.021989 12.926334 5.398050 0.2552797 -0.1185029 0.1076572 0.9535194 +VERTEX_SE3:QUAT 1298 13.466590 12.196096 5.638692 0.5888179 0.0364474 0.7701464 0.2425689 +VERTEX_SE3:QUAT 1299 12.804025 11.551366 5.845197 0.2392374 0.2814092 0.9039377 0.2155713 +VERTEX_SE3:QUAT 1300 12.982602 11.095162 4.955282 0.2091706 0.8953729 -0.3236811 0.2231267 +VERTEX_SE3:QUAT 1301 13.644896 11.789552 4.692028 0.5700482 -0.0279999 -0.0316526 0.8205237 +VERTEX_SE3:QUAT 1302 14.317806 12.209765 4.259178 0.6324552 0.3297882 0.6734842 0.1940599 +VERTEX_SE3:QUAT 1303 15.097865 12.837400 4.018956 -0.1737450 0.5318081 -0.5002081 0.6608969 +VERTEX_SE3:QUAT 1304 15.978991 13.506996 3.674356 0.1825581 -0.1811913 -0.0313065 0.9658479 +VERTEX_SE3:QUAT 1305 16.727434 14.237306 3.352951 0.1992826 -0.6191285 0.4980969 0.5734682 +VERTEX_SE3:QUAT 1306 17.237681 14.951878 3.162845 -0.1243937 0.7527556 0.0086192 0.6463830 +VERTEX_SE3:QUAT 1307 17.985790 15.588157 2.865191 -0.2017099 0.9257247 -0.3187125 0.0277348 +VERTEX_SE3:QUAT 1308 18.833533 16.107134 2.469114 0.5488439 -0.2784132 0.7846895 0.0742894 +VERTEX_SE3:QUAT 1309 19.542458 16.634919 2.267451 0.5088086 0.6159659 -0.1977392 0.5679780 +VERTEX_SE3:QUAT 1310 20.135210 17.279800 1.923354 0.1024613 -0.1772828 0.8277086 0.5224663 +VERTEX_SE3:QUAT 1311 20.983060 18.033159 1.587957 0.4345796 -0.1936240 0.4573891 0.7512959 +VERTEX_SE3:QUAT 1312 21.535704 18.717017 1.219342 0.4356160 0.4165470 0.4688509 0.6456826 +VERTEX_SE3:QUAT 1313 22.081264 19.589397 0.884935 -0.0428806 0.2542538 0.6058282 0.7526543 +VERTEX_SE3:QUAT 1314 22.651408 20.317812 0.560677 0.2422308 -0.2863949 0.8753141 0.3051679 +VERTEX_SE3:QUAT 1315 23.316652 21.173419 0.255261 0.6063750 0.5343081 -0.2096345 0.5503432 +VERTEX_SE3:QUAT 1316 23.817790 21.930599 -0.033855 0.6538304 0.6950526 0.2425596 0.1748500 +VERTEX_SE3:QUAT 1317 24.360420 22.850198 -0.275540 -0.0737884 0.8734007 0.2173089 0.4295386 +VERTEX_SE3:QUAT 1318 24.917689 23.336804 -0.618908 0.3796441 -0.3301267 0.4558553 0.7342225 +VERTEX_SE3:QUAT 1319 25.590012 23.896855 -0.943092 -0.1366504 0.6933857 0.3600053 0.6090477 +VERTEX_SE3:QUAT 1320 25.668976 23.621975 -1.894707 -0.2038983 0.8338841 0.2328793 0.4569791 +VERTEX_SE3:QUAT 1321 25.046363 22.721107 -1.753271 0.4110278 0.1334457 -0.1245920 0.8931546 +VERTEX_SE3:QUAT 1322 24.473806 21.920282 -1.512393 0.6387219 -0.2005538 0.7296593 0.1393189 +VERTEX_SE3:QUAT 1323 23.688992 21.077913 -1.496990 -0.4170176 0.2136023 -0.7079703 0.5284396 +VERTEX_SE3:QUAT 1324 23.045600 20.361635 -1.577391 0.5640428 0.2838748 0.5226978 0.5727633 +VERTEX_SE3:QUAT 1325 22.573513 19.725246 -1.358297 -0.1043145 0.8010793 -0.5336990 0.2501117 +VERTEX_SE3:QUAT 1326 21.789843 18.962794 -1.128087 0.4572536 0.6275440 0.2349908 0.5847110 +VERTEX_SE3:QUAT 1327 21.158693 18.130868 -1.033204 0.9381618 -0.1251090 0.3002432 0.1185504 +VERTEX_SE3:QUAT 1328 20.453593 17.526859 -0.830548 -0.0885787 0.7605660 0.0855114 0.6374802 +VERTEX_SE3:QUAT 1329 19.975190 16.816154 -0.679590 -0.7791997 0.3521557 -0.4516819 0.2545931 +VERTEX_SE3:QUAT 1330 19.210059 16.036114 -0.609016 -0.8808424 -0.3164658 -0.3385841 0.0965753 +VERTEX_SE3:QUAT 1331 18.659726 15.170314 -0.595165 0.7534331 0.3428734 0.3154216 0.4639888 +VERTEX_SE3:QUAT 1332 18.091886 14.219071 -0.634347 0.7451187 0.6367259 -0.1531045 0.1262432 +VERTEX_SE3:QUAT 1333 17.348931 13.434033 -0.464413 -0.2542141 0.6174878 -0.4080655 0.6225484 +VERTEX_SE3:QUAT 1334 16.518333 12.736470 -0.345160 -0.1244177 0.4668584 -0.2958432 0.8240390 +VERTEX_SE3:QUAT 1335 15.783056 12.054913 -0.550277 -0.0726298 0.7856587 -0.1289166 0.6007044 +VERTEX_SE3:QUAT 1336 14.860817 11.249597 -0.590300 0.5657279 -0.5956038 0.5351655 0.1969923 +VERTEX_SE3:QUAT 1337 14.202785 10.594583 -0.436710 0.4648267 0.6542065 -0.4411838 0.4016302 +VERTEX_SE3:QUAT 1338 13.403070 9.909434 -0.498016 0.6543140 -0.0959418 0.7499835 0.0138936 +VERTEX_SE3:QUAT 1339 12.721170 9.022049 -0.490389 0.3144067 0.8770645 0.0116798 0.3630012 +VERTEX_SE3:QUAT 1340 12.596483 8.965038 -1.510170 0.3710072 0.8077943 -0.4410722 0.1236013 +VERTEX_SE3:QUAT 1341 13.344106 9.725943 -1.762044 -0.8073507 -0.3313137 -0.4880059 0.0163209 +VERTEX_SE3:QUAT 1342 14.014797 10.441877 -1.849351 0.1961831 0.4268817 -0.7170428 0.5149114 +VERTEX_SE3:QUAT 1343 14.788683 11.105425 -1.912031 0.3822391 0.1835937 -0.7279642 0.5387529 +VERTEX_SE3:QUAT 1344 15.499897 11.688419 -2.161023 0.1267456 -0.7045657 0.3919789 0.5778195 +VERTEX_SE3:QUAT 1345 16.149912 12.357321 -2.031412 0.1677354 0.9812432 -0.0055834 0.0948447 +VERTEX_SE3:QUAT 1346 16.724381 12.992596 -2.309703 -0.7915328 -0.6092766 0.0176407 0.0441218 +VERTEX_SE3:QUAT 1347 17.299686 13.834582 -2.739788 0.0917376 -0.8588947 0.5021140 0.0420199 +VERTEX_SE3:QUAT 1348 18.066878 14.528737 -3.147725 0.0619703 -0.4114686 0.9088083 0.0303439 +VERTEX_SE3:QUAT 1349 18.689833 15.100311 -3.533722 -0.5684752 0.4735612 -0.4764852 0.4749080 +VERTEX_SE3:QUAT 1350 19.430740 15.946348 -3.943323 0.1809607 0.8542388 -0.4223006 0.2432930 +VERTEX_SE3:QUAT 1351 20.213260 16.636063 -4.393437 0.0523834 -0.8190594 0.1791792 0.5424872 +VERTEX_SE3:QUAT 1352 21.153997 17.213798 -4.686257 0.7214306 -0.0157436 0.6440327 0.2539919 +VERTEX_SE3:QUAT 1353 21.746862 17.850775 -5.092246 0.2129424 -0.3413046 0.8695063 0.2865756 +VERTEX_SE3:QUAT 1354 22.496734 18.322403 -5.530658 0.5159036 0.0454982 -0.6811104 0.5175538 +VERTEX_SE3:QUAT 1355 23.345473 18.809532 -5.994922 -0.1040901 0.5354755 -0.8365372 0.0513505 +VERTEX_SE3:QUAT 1356 24.081068 19.346539 -6.426986 0.4018412 0.8554401 -0.3085664 0.1073900 +VERTEX_SE3:QUAT 1357 24.715268 19.991045 -6.848575 -0.3935806 0.7858233 0.1197267 0.4617809 +VERTEX_SE3:QUAT 1358 25.413109 20.468070 -7.202058 -0.7089997 0.3954889 -0.4310170 0.3938683 +VERTEX_SE3:QUAT 1359 25.976796 20.974085 -7.586330 0.8203698 0.1625226 -0.4961312 0.2333102 +VERTEX_SE3:QUAT 1360 25.334682 21.258206 -8.284941 -0.9023866 0.2474198 -0.2171177 0.2781039 +VERTEX_SE3:QUAT 1361 24.570252 20.669315 -7.840489 -0.1075200 -0.9916803 0.0707554 0.0018437 +VERTEX_SE3:QUAT 1362 23.886172 20.139322 -7.372163 0.0837462 -0.2886351 0.9516694 0.0632593 +VERTEX_SE3:QUAT 1363 23.306823 19.643590 -6.916319 0.3493714 0.4665949 -0.5619166 0.5869230 +VERTEX_SE3:QUAT 1364 22.478984 19.046363 -6.494499 -0.4512751 -0.3222624 0.8277090 0.0859978 +VERTEX_SE3:QUAT 1365 21.670379 18.562706 -5.915559 0.5657328 0.5340113 -0.6265413 0.0471629 +VERTEX_SE3:QUAT 1366 20.940755 18.069354 -5.476964 -0.6975463 0.0703820 -0.6247898 0.3436762 +VERTEX_SE3:QUAT 1367 20.056323 17.495023 -4.910647 0.6456058 -0.2263945 0.2992104 0.6651404 +VERTEX_SE3:QUAT 1368 19.118015 17.016717 -4.610473 0.0584032 0.8536426 -0.2805019 0.4349736 +VERTEX_SE3:QUAT 1369 18.331475 16.599738 -4.306666 0.8741558 0.1815422 0.3845243 0.2345958 +VERTEX_SE3:QUAT 1370 17.596271 16.181512 -3.907352 0.2856832 0.7522691 -0.1215545 0.5811203 +VERTEX_SE3:QUAT 1371 16.922704 15.738882 -3.592231 0.8458369 -0.4530527 0.2807845 0.0215209 +VERTEX_SE3:QUAT 1372 16.173543 15.368484 -3.412841 0.2558443 -0.2439472 0.2728561 0.8947531 +VERTEX_SE3:QUAT 1373 15.282035 14.754739 -3.113457 0.1062366 0.8616858 0.0024807 0.4961906 +VERTEX_SE3:QUAT 1374 14.398575 14.318118 -2.785769 0.2409503 0.9477219 -0.1321851 0.1621520 +VERTEX_SE3:QUAT 1375 13.678392 13.839976 -2.567716 0.3383177 -0.0294466 0.0061801 0.9405508 +VERTEX_SE3:QUAT 1376 12.828768 13.203092 -2.308861 0.9519696 -0.2812612 0.0860729 0.0850732 +VERTEX_SE3:QUAT 1377 12.133908 12.784510 -2.179429 -0.5571636 -0.7370381 0.3659325 0.1115215 +VERTEX_SE3:QUAT 1378 11.354524 12.315250 -1.851304 -0.1478983 0.6917145 -0.6973569 0.1155438 +VERTEX_SE3:QUAT 1379 10.442429 11.848001 -1.626515 0.0346590 0.6723398 -0.5380850 0.5071711 +VERTEX_SE3:QUAT 1380 10.172475 12.109099 -2.444434 -0.0843886 0.5092442 -0.5361085 0.6679345 +VERTEX_SE3:QUAT 1381 11.183478 12.567979 -2.507911 0.6817040 0.5437522 0.0212359 0.4890422 +VERTEX_SE3:QUAT 1382 12.130971 13.032262 -2.929475 0.9139739 -0.2533952 -0.3083651 0.0731675 +VERTEX_SE3:QUAT 1383 13.174297 13.553351 -3.301334 0.7922112 0.0605211 -0.4184407 0.4400522 +VERTEX_SE3:QUAT 1384 14.041462 13.934019 -3.477974 0.8213242 0.1660638 -0.4498468 0.3090100 +VERTEX_SE3:QUAT 1385 14.887782 14.302577 -3.507156 0.4607196 0.6454651 0.1344456 0.5941688 +VERTEX_SE3:QUAT 1386 15.917747 14.777425 -3.728454 0.4636369 -0.7042639 0.3447659 0.4125404 +VERTEX_SE3:QUAT 1387 16.802800 15.017299 -3.906602 0.5855846 0.0651535 0.6962384 0.4099972 +VERTEX_SE3:QUAT 1388 17.747699 15.415900 -4.112960 -0.8086445 -0.3244396 0.4834635 0.0842379 +VERTEX_SE3:QUAT 1389 18.564491 15.907932 -4.256205 0.4936006 0.6117524 0.1814958 0.5909117 +VERTEX_SE3:QUAT 1390 19.477041 16.130114 -4.298919 0.2209895 -0.0881673 0.6182525 0.7491021 +VERTEX_SE3:QUAT 1391 20.339953 16.486330 -4.308443 0.0426310 -0.1855552 0.9465450 0.2603927 +VERTEX_SE3:QUAT 1392 21.054443 17.052299 -4.264825 -0.1205280 0.5400805 -0.7991943 0.2346796 +VERTEX_SE3:QUAT 1393 21.931814 17.405438 -4.400747 0.6691741 0.2238726 -0.2865062 0.6480751 +VERTEX_SE3:QUAT 1394 22.783729 17.974417 -4.495449 -0.7066438 0.4142623 -0.5728148 0.0304056 +VERTEX_SE3:QUAT 1395 23.587471 18.531937 -4.506042 0.5530284 0.0829048 -0.5019080 0.6598293 +VERTEX_SE3:QUAT 1396 24.230304 19.106489 -4.596831 0.3270697 -0.2100994 -0.0956782 0.9163675 +VERTEX_SE3:QUAT 1397 25.263029 19.686211 -4.743251 -0.6134273 0.7333627 -0.2780413 0.0926235 +VERTEX_SE3:QUAT 1398 26.086922 20.228989 -4.863232 0.8320195 -0.0748958 -0.2134560 0.5065280 +VERTEX_SE3:QUAT 1399 27.173262 20.686312 -5.274401 0.6992979 0.4947465 0.4885111 0.1660280 +VERTEX_SE3:QUAT 1400 27.173657 20.588980 -6.358150 -0.0086255 0.4530724 0.3023308 0.8385983 +VERTEX_SE3:QUAT 1401 26.360995 20.211446 -6.176013 -0.0510823 -0.9762854 0.1433301 0.1539933 +VERTEX_SE3:QUAT 1402 25.440203 19.998521 -5.957595 0.4295286 0.8913600 -0.1019047 0.1029465 +VERTEX_SE3:QUAT 1403 24.424913 19.713672 -6.035957 -0.9491906 0.2666641 -0.1389555 0.0928377 +VERTEX_SE3:QUAT 1404 23.601994 19.350001 -6.008590 0.5249109 0.2371848 -0.4474866 0.6840816 +VERTEX_SE3:QUAT 1405 22.720814 18.875353 -5.946784 0.1145730 0.7670379 0.0627376 0.6281638 +VERTEX_SE3:QUAT 1406 21.816510 18.365693 -5.795751 0.6108508 0.2604939 0.7160902 0.2149861 +VERTEX_SE3:QUAT 1407 20.815698 18.089059 -5.531043 0.4046508 -0.0810077 -0.3484002 0.8416132 +VERTEX_SE3:QUAT 1408 20.190419 17.779873 -5.432959 -0.4671927 0.8375292 -0.0988664 0.2655208 +VERTEX_SE3:QUAT 1409 19.162592 17.349809 -5.321659 0.6892565 0.4742429 0.1784926 0.5178412 +VERTEX_SE3:QUAT 1410 18.337150 17.032203 -5.113551 0.5220306 0.7846631 -0.2212540 0.2506684 +VERTEX_SE3:QUAT 1411 17.388811 16.514324 -4.898294 0.3136672 -0.8962205 0.2780830 0.1451604 +VERTEX_SE3:QUAT 1412 16.526581 16.146082 -4.609994 -0.6688697 -0.5948871 0.4151372 0.1624305 +VERTEX_SE3:QUAT 1413 15.591348 15.659461 -4.438331 0.3615758 0.2366214 -0.2229201 0.8738306 +VERTEX_SE3:QUAT 1414 14.834706 15.262840 -4.244806 0.1730973 -0.7560207 0.5222006 0.3546499 +VERTEX_SE3:QUAT 1415 13.905885 14.895311 -4.050627 0.6244345 -0.0290793 0.7642122 0.1587942 +VERTEX_SE3:QUAT 1416 12.921058 14.345932 -3.656268 0.0684279 0.3028032 -0.4186758 0.8534275 +VERTEX_SE3:QUAT 1417 11.936741 14.063908 -3.603643 -0.9703812 0.0025436 -0.2187913 0.1023924 +VERTEX_SE3:QUAT 1418 11.013351 13.716032 -3.569290 0.6749098 -0.0393517 0.6848011 0.2720213 +VERTEX_SE3:QUAT 1419 10.195362 13.423757 -3.257787 0.6415742 0.2395249 0.7013459 0.1977986 +VERTEX_SE3:QUAT 1420 10.417769 13.260771 -4.151882 -0.3449391 0.4949550 -0.3187233 0.7310623 +VERTEX_SE3:QUAT 1421 11.375662 13.539798 -4.152894 0.8203689 0.1218522 0.3338773 0.4479653 +VERTEX_SE3:QUAT 1422 12.303605 14.073498 -4.137507 0.7782856 -0.4497386 0.1672922 0.4049940 +VERTEX_SE3:QUAT 1423 13.042485 14.366518 -4.311185 0.0670014 -0.0375626 0.9962164 0.0406530 +VERTEX_SE3:QUAT 1424 13.895827 14.723392 -4.490456 0.0865245 -0.6426942 0.6590854 0.3808728 +VERTEX_SE3:QUAT 1425 14.898302 15.081651 -4.661762 0.2648308 0.6261907 -0.6416808 0.3549587 +VERTEX_SE3:QUAT 1426 16.039463 15.522764 -4.701148 0.2683401 0.2865512 -0.3682814 0.8427638 +VERTEX_SE3:QUAT 1427 16.759641 16.068103 -4.819229 0.9753324 -0.1412749 0.1570768 0.0639923 +VERTEX_SE3:QUAT 1428 17.580802 16.719427 -4.763627 0.1809388 -0.2429735 0.9171017 0.2591321 +VERTEX_SE3:QUAT 1429 18.261024 17.355973 -4.662319 0.4128052 0.2605642 0.8655147 0.1121714 +VERTEX_SE3:QUAT 1430 19.014589 17.742844 -4.747469 0.4866104 0.6585178 -0.5663926 0.0936165 +VERTEX_SE3:QUAT 1431 19.746021 18.326300 -4.731422 0.7247026 0.6616129 -0.0806760 0.1748310 +VERTEX_SE3:QUAT 1432 20.389381 18.883129 -4.646027 0.2654220 0.8169476 -0.4265660 0.2831770 +VERTEX_SE3:QUAT 1433 21.257692 19.552544 -4.752434 0.1274937 0.6873903 -0.6569327 0.2822752 +VERTEX_SE3:QUAT 1434 21.852832 20.063082 -4.801179 0.3446316 0.3771567 0.5948743 0.6205694 +VERTEX_SE3:QUAT 1435 22.694658 20.804077 -4.465166 -0.0527697 0.0773708 0.7653496 0.6367646 +VERTEX_SE3:QUAT 1436 23.390912 21.591713 -4.329609 -0.1136340 0.4246896 -0.8976279 0.0314677 +VERTEX_SE3:QUAT 1437 23.843251 22.399233 -4.245629 0.4536934 0.4815141 -0.2742828 0.6979079 +VERTEX_SE3:QUAT 1438 24.624795 22.969424 -3.806775 -0.5534567 0.7506650 -0.3597007 0.0283398 +VERTEX_SE3:QUAT 1439 25.167781 23.684175 -3.387601 0.5154878 0.5824451 0.2329325 0.5837572 +VERTEX_SE3:QUAT 1440 25.491967 23.665713 -4.306323 0.1993721 0.9188866 -0.0060398 0.3403846 +VERTEX_SE3:QUAT 1441 24.875205 23.029936 -4.675884 0.8542766 0.0624334 0.4872824 0.1699098 +VERTEX_SE3:QUAT 1442 24.269176 22.272479 -4.835382 0.7462230 0.4595090 0.4673381 0.1166096 +VERTEX_SE3:QUAT 1443 23.692485 21.594856 -4.911911 -0.0158864 0.4730735 0.0159733 0.8807349 +VERTEX_SE3:QUAT 1444 22.907426 20.806642 -5.071314 0.3762390 0.0474630 0.5971172 0.7068539 +VERTEX_SE3:QUAT 1445 22.285123 20.171247 -5.197580 0.8788780 0.1134653 0.3778286 0.2682251 +VERTEX_SE3:QUAT 1446 21.665288 19.417022 -5.374162 -0.1204713 0.4835597 -0.6783554 0.5398987 +VERTEX_SE3:QUAT 1447 20.933027 18.625256 -5.497406 -0.2109993 0.3822736 -0.8550994 0.2795554 +VERTEX_SE3:QUAT 1448 20.358052 17.862481 -5.782017 0.3901312 0.5476872 0.1256389 0.7294184 +VERTEX_SE3:QUAT 1449 19.785771 17.208824 -5.823300 -0.0175823 0.9825551 -0.0636450 0.1738551 +VERTEX_SE3:QUAT 1450 19.252122 16.457435 -6.022813 0.2237257 0.4687565 0.3805029 0.7651351 +VERTEX_SE3:QUAT 1451 18.448712 15.881366 -6.348945 0.4933169 -0.7065591 0.5033688 0.0635024 +VERTEX_SE3:QUAT 1452 17.705311 15.260036 -6.448423 0.9542179 0.1098756 0.0573824 0.2722183 +VERTEX_SE3:QUAT 1453 16.996314 14.642067 -6.476537 0.1333350 -0.4645717 0.8666497 0.1237467 +VERTEX_SE3:QUAT 1454 16.379271 13.916183 -6.674086 0.6402125 -0.1713105 0.7139306 0.2260171 +VERTEX_SE3:QUAT 1455 15.683357 13.293380 -6.850260 0.9349383 -0.1111194 -0.0969174 0.3227226 +VERTEX_SE3:QUAT 1456 14.830659 12.654802 -6.844891 0.2583212 -0.0362300 0.0186372 0.9651996 +VERTEX_SE3:QUAT 1457 14.195095 12.129115 -6.902261 -0.0072892 0.4102756 -0.9116262 0.0236307 +VERTEX_SE3:QUAT 1458 13.435050 11.631118 -6.987440 -0.6842056 0.4221783 -0.5847049 0.1083902 +VERTEX_SE3:QUAT 1459 12.414002 11.167907 -7.114250 0.2366405 -0.4471892 0.7895568 0.3473084 +VERTEX_SE3:QUAT 1460 12.339849 11.107094 -8.113968 0.6586771 0.1996529 -0.0088031 0.7254003 +VERTEX_SE3:QUAT 1461 13.132112 11.797203 -8.176374 0.7794415 -0.5441734 0.0429139 0.3074162 +VERTEX_SE3:QUAT 1462 13.988617 12.418020 -8.050806 0.3347695 0.5858376 -0.6617493 0.3268204 +VERTEX_SE3:QUAT 1463 14.675583 13.164040 -8.155409 0.2430231 -0.2855835 0.1812796 0.9091312 +VERTEX_SE3:QUAT 1464 15.295960 13.747997 -8.177146 -0.0636197 -0.9274091 0.3639234 0.0585210 +VERTEX_SE3:QUAT 1465 15.755427 14.541555 -8.025686 0.6824805 0.7299338 -0.0036736 0.0374633 +VERTEX_SE3:QUAT 1466 16.653739 15.314938 -8.029831 0.0156939 -0.9687425 0.1760724 0.1740410 +VERTEX_SE3:QUAT 1467 17.435845 15.954822 -8.084360 0.0514519 0.7617199 0.3613595 0.5353082 +VERTEX_SE3:QUAT 1468 18.265392 16.426038 -8.155317 0.4029274 0.4467278 -0.4889811 0.6316497 +VERTEX_SE3:QUAT 1469 19.152659 17.016642 -8.238460 0.4413934 0.0361259 0.7723896 0.4552814 +VERTEX_SE3:QUAT 1470 19.889673 17.615917 -8.120359 0.0523599 0.3099066 -0.6584449 0.6838616 +VERTEX_SE3:QUAT 1471 20.680628 18.226722 -8.233719 0.0082102 0.8816099 -0.4434268 0.1614601 +VERTEX_SE3:QUAT 1472 21.363022 19.098625 -8.323929 -0.2336560 -0.6770817 0.6895994 0.1068551 +VERTEX_SE3:QUAT 1473 21.824742 19.859539 -8.464153 0.5620950 0.0224353 0.7070112 0.4285803 +VERTEX_SE3:QUAT 1474 22.265498 20.551509 -8.435533 0.6698421 0.5670700 -0.4707600 0.0901567 +VERTEX_SE3:QUAT 1475 22.763380 21.216158 -8.672092 0.9064753 0.3190331 0.0650862 0.2688573 +VERTEX_SE3:QUAT 1476 23.382214 21.958230 -8.666082 0.4731141 -0.0847972 0.8734769 0.0775284 +VERTEX_SE3:QUAT 1477 23.989366 22.788130 -8.744956 0.1690180 0.3058264 0.3025177 0.8867842 +VERTEX_SE3:QUAT 1478 24.476643 23.663460 -8.702090 0.4247264 0.6175308 -0.6173499 0.2390445 +VERTEX_SE3:QUAT 1479 25.259884 24.309363 -8.765654 -0.4024603 0.8151946 0.2657550 0.3207145 +VERTEX_SE3:QUAT 1480 24.749043 24.493505 -9.530708 0.4235593 -0.3251150 0.7828346 0.3194804 +VERTEX_SE3:QUAT 1481 24.125802 23.782310 -9.506341 0.7017735 0.4764266 0.2755614 0.4523247 +VERTEX_SE3:QUAT 1482 23.411820 23.113466 -9.337119 0.3348730 0.0934245 0.3537187 0.8683404 +VERTEX_SE3:QUAT 1483 22.559678 22.602942 -9.319302 -0.0851917 -0.9625560 0.1316001 0.2211557 +VERTEX_SE3:QUAT 1484 21.861171 21.916899 -9.309867 -0.1213124 0.2025075 -0.9603777 0.1481506 +VERTEX_SE3:QUAT 1485 21.042935 21.368449 -9.216338 -0.0281501 -0.6642407 0.7408833 0.0953096 +VERTEX_SE3:QUAT 1486 20.465922 20.687111 -9.068499 0.1257075 0.9166862 0.3065357 0.2234274 +VERTEX_SE3:QUAT 1487 19.878524 19.973661 -8.708166 0.8593018 0.2194956 -0.3458347 0.3063011 +VERTEX_SE3:QUAT 1488 19.297544 19.195720 -8.584667 0.2110061 -0.9774308 -0.0060313 0.0083115 +VERTEX_SE3:QUAT 1489 18.692276 18.484943 -8.316902 0.6029029 0.4786210 -0.2159661 0.6006569 +VERTEX_SE3:QUAT 1490 18.062375 17.849691 -7.928028 -0.1132505 0.7216481 -0.1014219 0.6753606 +VERTEX_SE3:QUAT 1491 17.349920 17.140502 -7.716778 0.2337818 -0.6454874 0.6838116 0.2471715 +VERTEX_SE3:QUAT 1492 16.627461 16.310807 -7.280126 -0.0663553 0.7157703 -0.1282245 0.6832484 +VERTEX_SE3:QUAT 1493 15.980423 15.620622 -6.843340 -0.5822718 0.8052963 0.0199663 0.1098124 +VERTEX_SE3:QUAT 1494 15.352729 15.017733 -6.482828 0.0187690 0.2258782 -0.9154816 0.3324457 +VERTEX_SE3:QUAT 1495 14.552036 14.306338 -6.266060 0.9608088 0.1737777 -0.1471649 0.1580831 +VERTEX_SE3:QUAT 1496 13.905061 13.713730 -6.050229 -0.0799325 0.5526707 -0.2403291 0.7939823 +VERTEX_SE3:QUAT 1497 12.975143 13.178339 -5.456024 0.2868799 -0.2461496 0.6258161 0.6822496 +VERTEX_SE3:QUAT 1498 12.030357 12.625962 -5.104523 0.3787746 -0.4487539 0.8084932 0.0385797 +VERTEX_SE3:QUAT 1499 11.484103 12.075933 -4.611138 0.6863459 0.1443619 -0.6294349 0.3345154 +VERTEX_SE3:QUAT 1500 10.830459 12.235140 -5.479704 0.7072244 -0.4008919 0.5101607 0.2808120 +VERTEX_SE3:QUAT 1501 11.370802 12.735769 -5.777122 0.9013339 -0.0204981 -0.2687577 0.3390374 +VERTEX_SE3:QUAT 1502 12.079686 13.275862 -6.132278 0.5723794 -0.0083192 -0.0847193 0.8155582 +VERTEX_SE3:QUAT 1503 12.843717 13.822294 -6.498164 0.6317935 -0.0561129 -0.2575013 0.7289592 +VERTEX_SE3:QUAT 1504 13.556608 14.286682 -6.978933 0.1394495 -0.9590296 -0.0336917 0.2442967 +VERTEX_SE3:QUAT 1505 14.175097 14.902332 -7.439655 0.4240342 -0.1163736 0.2195754 0.8708839 +VERTEX_SE3:QUAT 1506 14.735257 15.609005 -8.055299 -0.8825689 -0.2429796 -0.3519668 0.1953267 +VERTEX_SE3:QUAT 1507 15.305073 16.139036 -8.537354 0.8446575 0.0592153 -0.4699137 0.2494559 +VERTEX_SE3:QUAT 1508 15.741537 16.715448 -9.220667 0.3436210 0.5106804 -0.7471453 0.2508067 +VERTEX_SE3:QUAT 1509 16.119995 17.361381 -9.940990 0.8820488 -0.0966595 -0.4085606 0.2138341 +VERTEX_SE3:QUAT 1510 16.632891 18.002339 -10.339854 0.8283484 0.2841315 -0.3322738 0.3502889 +VERTEX_SE3:QUAT 1511 17.095713 18.691417 -10.862072 0.4565013 0.7734551 0.3836880 0.2148423 +VERTEX_SE3:QUAT 1512 17.904353 19.202708 -11.404888 -0.9465672 0.0516433 -0.2679067 0.1719578 +VERTEX_SE3:QUAT 1513 18.480301 19.784485 -11.969656 0.5667589 0.3204625 0.5001481 0.5709116 +VERTEX_SE3:QUAT 1514 19.183204 20.383977 -12.698131 0.0096323 0.8477974 -0.5215925 0.0953311 +VERTEX_SE3:QUAT 1515 19.624818 21.183142 -13.405896 0.1078849 0.8035042 0.1936392 0.5524905 +VERTEX_SE3:QUAT 1516 20.036623 21.651334 -14.042042 -0.2093057 0.5563909 -0.7120153 0.3737038 +VERTEX_SE3:QUAT 1517 20.522828 21.936826 -14.921273 0.8734419 -0.1551786 -0.3629459 0.2851125 +VERTEX_SE3:QUAT 1518 21.121321 22.210454 -15.783494 0.0257885 0.2681401 -0.8365291 0.4771320 +VERTEX_SE3:QUAT 1519 21.524049 22.344609 -16.591235 0.4132125 0.7797823 0.1436055 0.4478531 +VERTEX_SE3:QUAT 1520 20.622114 22.438786 -17.159779 0.5834990 -0.4616577 0.3983110 0.5364228 +VERTEX_SE3:QUAT 1521 20.284132 22.041640 -16.224511 0.3130879 -0.3245611 0.5396972 0.7108888 +VERTEX_SE3:QUAT 1522 19.925289 21.496483 -15.360343 0.4140653 0.3266730 -0.3430003 0.7772937 +VERTEX_SE3:QUAT 1523 19.378182 21.233179 -14.468677 0.4642831 0.3633227 0.3147632 0.7438831 +VERTEX_SE3:QUAT 1524 19.036694 20.870415 -13.697078 -0.4282003 0.2577966 -0.7962016 0.3409523 +VERTEX_SE3:QUAT 1525 18.614834 20.649230 -12.748088 -0.2597852 -0.9033043 0.2364501 0.2462607 +VERTEX_SE3:QUAT 1526 18.079657 20.318301 -11.928502 0.0399310 0.4446567 -0.7749288 0.4474050 +VERTEX_SE3:QUAT 1527 17.880140 20.165263 -11.025111 0.3551736 -0.3747356 -0.1501074 0.8431445 +VERTEX_SE3:QUAT 1528 17.406305 19.926033 -10.236688 0.4855029 -0.6863395 0.1617113 0.5167924 +VERTEX_SE3:QUAT 1529 17.154409 19.754207 -9.331454 0.4916120 0.8557170 -0.1276922 0.0987963 +VERTEX_SE3:QUAT 1530 16.829954 19.428640 -8.452839 0.3210476 0.0980071 0.2343853 0.9123522 +VERTEX_SE3:QUAT 1531 16.455962 19.175556 -7.511580 0.9296967 0.1521436 0.1781530 0.2842144 +VERTEX_SE3:QUAT 1532 16.438174 19.057545 -6.470612 0.2608930 -0.9341207 0.1932817 0.1483091 +VERTEX_SE3:QUAT 1533 16.394855 18.939923 -5.456100 0.8261836 -0.2232919 0.5172111 0.0073530 +VERTEX_SE3:QUAT 1534 16.262368 18.748976 -4.354314 -0.2849213 -0.6888848 0.6397441 0.1870430 +VERTEX_SE3:QUAT 1535 15.964106 18.626332 -3.332118 0.7683494 -0.2304878 -0.4960039 0.3324076 +VERTEX_SE3:QUAT 1536 15.827195 18.550028 -2.414314 0.7460181 -0.2249017 -0.3418184 0.5253917 +VERTEX_SE3:QUAT 1537 15.688136 18.315297 -1.441143 -0.5732384 -0.5071240 0.6397914 0.0699284 +VERTEX_SE3:QUAT 1538 15.345501 18.368537 -0.503342 -0.2079466 0.5902996 -0.5744980 0.5275004 +VERTEX_SE3:QUAT 1539 15.156185 18.033330 0.328688 0.6121592 -0.1542221 0.4003584 0.6642212 +VERTEX_SE3:QUAT 1540 14.264015 17.988847 -0.115119 0.8116948 -0.4001626 0.1920380 0.3796615 +VERTEX_SE3:QUAT 1541 14.487333 17.862892 -0.910876 0.5505594 -0.2755557 0.7394769 0.2722634 +VERTEX_SE3:QUAT 1542 14.548444 17.847159 -1.886512 -0.6606067 -0.3776309 0.6091220 0.2235263 +VERTEX_SE3:QUAT 1543 14.882698 17.971994 -2.720129 0.8470723 -0.4212590 -0.0236294 0.3231889 +VERTEX_SE3:QUAT 1544 15.372696 18.037778 -3.544667 0.6197887 0.2827339 -0.7308612 0.0420178 +VERTEX_SE3:QUAT 1545 15.658566 18.295406 -4.536858 0.3522112 0.0824302 -0.7509564 0.5524645 +VERTEX_SE3:QUAT 1546 15.990890 18.264652 -5.323215 0.4444972 0.2707127 -0.2156139 0.8262249 +VERTEX_SE3:QUAT 1547 16.657053 18.331307 -6.023202 0.5966644 0.2159005 0.6683346 0.3882107 +VERTEX_SE3:QUAT 1548 17.309664 18.536334 -6.868771 -0.3287508 -0.5541743 0.7329085 0.2183090 +VERTEX_SE3:QUAT 1549 17.892745 18.615553 -7.599910 0.3121807 -0.6271812 0.6262852 0.3419851 +VERTEX_SE3:QUAT 1550 18.486287 18.713762 -8.533766 -0.1397260 -0.7530740 0.5222420 0.3749926 +VERTEX_SE3:QUAT 1551 18.936554 18.686507 -9.420154 -0.2811582 0.4241247 -0.7525693 0.4179806 +VERTEX_SE3:QUAT 1552 19.532034 18.618481 -10.295671 0.4028324 -0.7532579 -0.0314491 0.5189793 +VERTEX_SE3:QUAT 1553 20.004949 18.620069 -11.203080 0.7919358 0.0882846 -0.3625316 0.4833367 +VERTEX_SE3:QUAT 1554 20.459501 18.623046 -12.049569 0.5906242 0.3647412 0.2966011 0.6558618 +VERTEX_SE3:QUAT 1555 20.994849 18.771584 -13.005696 0.4162051 -0.0122657 0.0140912 0.9090788 +VERTEX_SE3:QUAT 1556 21.393377 18.862297 -13.942958 0.5853473 0.2150579 0.6507775 0.4331366 +VERTEX_SE3:QUAT 1557 21.842018 18.774983 -14.766724 0.9456397 0.0488952 0.0057919 0.3214673 +VERTEX_SE3:QUAT 1558 22.166268 18.888050 -15.718919 0.5392315 -0.5591823 0.5404571 0.3231884 +VERTEX_SE3:QUAT 1559 22.399923 18.681998 -16.730177 -0.2591488 -0.9013907 0.2314261 0.2584157 +VERTEX_SE3:QUAT 1560 21.548007 18.387064 -17.245904 0.6234771 -0.6295239 0.4156933 0.2053657 +VERTEX_SE3:QUAT 1561 21.242434 18.337884 -16.364740 0.8981680 -0.0475965 0.4257967 0.0986204 +VERTEX_SE3:QUAT 1562 21.025935 18.428536 -15.333257 0.7191652 0.5571056 -0.4103514 0.0636126 +VERTEX_SE3:QUAT 1563 20.487485 18.560095 -14.299397 -0.3935114 0.6094637 -0.6655320 0.1754136 +VERTEX_SE3:QUAT 1564 20.188797 18.643779 -13.424974 -0.1191201 -0.4808696 0.7959878 0.3478193 +VERTEX_SE3:QUAT 1565 19.977508 18.613921 -12.551356 -0.3554375 0.8388170 -0.2220824 0.3474616 +VERTEX_SE3:QUAT 1566 19.695455 18.790973 -11.487366 0.0929704 -0.4536492 0.8860233 0.0228389 +VERTEX_SE3:QUAT 1567 19.337114 18.907654 -10.334481 0.5326388 -0.7362403 0.4079166 0.0886012 +VERTEX_SE3:QUAT 1568 19.105121 19.292004 -9.270276 -0.0131542 -0.4305839 0.7258041 0.5363142 +VERTEX_SE3:QUAT 1569 18.947489 19.321723 -8.250971 0.0998960 0.3399652 -0.9213363 0.1599494 +VERTEX_SE3:QUAT 1570 19.034442 19.372174 -7.172302 0.5939921 -0.2920874 0.1783385 0.7280479 +VERTEX_SE3:QUAT 1571 18.963680 19.504922 -6.038121 0.1288179 -0.1730860 0.2764803 0.9364859 +VERTEX_SE3:QUAT 1572 18.949520 19.581741 -5.049395 0.1930243 -0.5922062 0.7733114 0.1184184 +VERTEX_SE3:QUAT 1573 18.929377 19.688300 -4.047386 0.9086693 -0.3811548 0.1170157 0.1238891 +VERTEX_SE3:QUAT 1574 18.897785 19.851675 -2.945736 0.3204180 0.2977986 -0.8627289 0.2536676 +VERTEX_SE3:QUAT 1575 18.783318 19.856217 -1.944921 0.1332880 -0.1728474 -0.2165541 0.9515579 +VERTEX_SE3:QUAT 1576 18.827846 19.990398 -0.921275 0.2714320 -0.7490683 0.2127917 0.5656332 +VERTEX_SE3:QUAT 1577 18.869502 19.949258 0.194581 -0.1584084 0.5430876 -0.7795771 0.2687419 +VERTEX_SE3:QUAT 1578 18.889254 19.884327 1.158030 0.0358604 0.4180358 -0.6548021 0.6286448 +VERTEX_SE3:QUAT 1579 18.801068 19.816067 2.073380 -0.1213551 -0.3278155 0.8887225 0.2966180 +VERTEX_SE3:QUAT 1580 17.705427 19.597759 1.737863 0.4809790 0.6056376 -0.6333208 0.0276960 +VERTEX_SE3:QUAT 1581 17.898019 19.890671 0.713530 -0.0407581 -0.6221979 0.5104333 0.5921709 +VERTEX_SE3:QUAT 1582 17.857181 20.223892 -0.098189 0.2040352 0.3553034 -0.8955948 0.1733180 +VERTEX_SE3:QUAT 1583 17.928590 20.470424 -0.900825 0.4531965 0.6004488 -0.1741510 0.6354098 +VERTEX_SE3:QUAT 1584 17.982832 20.799894 -1.851505 0.2531733 0.7006663 0.4371011 0.5038974 +VERTEX_SE3:QUAT 1585 18.243379 20.961617 -2.760827 0.2936401 0.3079408 -0.8776707 0.2205495 +VERTEX_SE3:QUAT 1586 18.568293 21.074527 -3.685501 0.7362256 0.5135396 0.2797995 0.3405307 +VERTEX_SE3:QUAT 1587 18.888829 21.352994 -4.473050 0.7194244 -0.6520090 0.0541277 0.2332016 +VERTEX_SE3:QUAT 1588 19.231745 21.462588 -5.333262 -0.5731466 -0.0228818 -0.8160877 0.0705709 +VERTEX_SE3:QUAT 1589 19.544191 21.585732 -6.254249 0.3694980 0.6100400 -0.6846013 0.1504775 +VERTEX_SE3:QUAT 1590 19.640847 21.793014 -7.270914 0.8413635 -0.0994127 0.5311424 0.0106036 +VERTEX_SE3:QUAT 1591 19.896794 21.907275 -8.132283 0.5621533 -0.4930948 0.3730307 0.5492625 +VERTEX_SE3:QUAT 1592 20.084823 22.029024 -9.164654 0.8204789 0.0964425 0.5163857 0.2255196 +VERTEX_SE3:QUAT 1593 20.349658 22.056929 -10.031316 0.7825625 0.5413475 -0.3071322 0.0144468 +VERTEX_SE3:QUAT 1594 20.600204 21.977796 -11.085370 0.8885810 0.1601575 0.4022420 0.1515740 +VERTEX_SE3:QUAT 1595 20.940760 21.950979 -12.067196 0.2197530 -0.2356837 0.1946104 0.9264387 +VERTEX_SE3:QUAT 1596 21.128329 22.051872 -13.086455 0.4199792 0.3093099 0.8327209 0.1857978 +VERTEX_SE3:QUAT 1597 21.561602 22.211270 -13.966187 0.6454091 0.3712295 0.4608045 0.4830061 +VERTEX_SE3:QUAT 1598 22.090628 22.313287 -14.890905 0.9084709 -0.0038961 -0.2808835 0.3094671 +VERTEX_SE3:QUAT 1599 22.344304 22.465501 -15.729977 0.2715575 -0.5213872 0.2775218 0.7598642 +VERTEX_SE3:QUAT 1600 15.510743 18.922483 1.791225 0.5023852 0.4841868 -0.2829423 0.6581155 +VERTEX_SE3:QUAT 1601 15.825764 18.868395 0.854120 0.1354075 0.3488764 -0.9239644 0.0789929 +VERTEX_SE3:QUAT 1602 16.155172 18.994513 -0.013991 0.2536475 -0.5660391 0.6817341 0.3879450 +VERTEX_SE3:QUAT 1603 16.730597 19.235982 -0.830003 0.3244677 0.8219122 -0.3269381 0.3351008 +VERTEX_SE3:QUAT 1604 17.083623 19.614103 -1.669699 0.4602631 0.0582741 -0.4017089 0.7895518 +VERTEX_SE3:QUAT 1605 17.189304 19.876890 -2.633255 0.6049744 0.7519126 -0.1850518 0.1854434 +VERTEX_SE3:QUAT 1606 17.338692 19.902428 -3.435039 0.0680731 0.9594844 -0.2421541 0.1269532 +VERTEX_SE3:QUAT 1607 17.480787 20.002802 -4.478215 -0.0446069 0.5453494 -0.7522615 0.3670244 +VERTEX_SE3:QUAT 1608 17.840290 20.083569 -5.561515 0.1717671 -0.9678601 0.0591851 0.1738967 +VERTEX_SE3:QUAT 1609 18.101306 20.214978 -6.607250 -0.4514646 0.5868590 -0.5985920 0.3057185 +VERTEX_SE3:QUAT 1610 18.142739 20.263766 -7.390389 0.7651075 -0.2595098 0.5811368 0.0976995 +VERTEX_SE3:QUAT 1611 18.747714 20.513046 -8.164264 0.6327451 0.7264483 -0.1635955 0.2124689 +VERTEX_SE3:QUAT 1612 19.125234 20.662889 -9.072169 -0.3997574 0.0788672 -0.8518850 0.3290380 +VERTEX_SE3:QUAT 1613 19.434919 20.748175 -9.967177 0.4898084 -0.2037761 -0.0135431 0.8475728 +VERTEX_SE3:QUAT 1614 19.851506 20.803678 -10.948300 0.6873730 -0.4213451 0.5878047 0.0668755 +VERTEX_SE3:QUAT 1615 20.204042 20.754961 -11.990314 0.7489299 0.0745969 0.1388228 0.6436361 +VERTEX_SE3:QUAT 1616 20.779895 20.902858 -12.706338 0.8898474 0.0559006 0.4513510 0.0364547 +VERTEX_SE3:QUAT 1617 21.349374 20.933667 -13.620043 0.4756615 0.8199141 -0.3024253 0.1001296 +VERTEX_SE3:QUAT 1618 21.611583 20.967230 -14.550471 0.4995445 0.5115790 -0.6134540 0.3352856 +VERTEX_SE3:QUAT 1619 21.903255 21.013319 -15.404470 0.4036285 -0.3529326 0.7982743 0.2743733 +VERTEX_SE3:QUAT 1620 22.904097 21.094269 -15.034588 0.6470806 -0.0889652 0.2166849 0.7255478 +VERTEX_SE3:QUAT 1621 22.410244 21.128907 -14.057431 -0.0975652 0.3455977 -0.4335022 0.8265102 +VERTEX_SE3:QUAT 1622 22.095229 21.076317 -13.271098 -0.3004697 -0.2632757 0.8535899 0.3343475 +VERTEX_SE3:QUAT 1623 21.496171 20.950671 -12.468569 -0.4711893 0.7896817 -0.3462078 0.1858051 +VERTEX_SE3:QUAT 1624 21.139181 20.973616 -11.571356 -0.1492535 -0.3634648 0.4232152 0.8163979 +VERTEX_SE3:QUAT 1625 20.824116 21.224186 -10.569956 0.0585886 0.2593068 -0.2908242 0.9191021 +VERTEX_SE3:QUAT 1626 20.695489 21.337544 -9.546610 -0.6339251 -0.3587991 0.6729964 0.1283667 +VERTEX_SE3:QUAT 1627 20.362413 21.314601 -8.541488 -0.1106983 -0.3998054 0.8849789 0.2114563 +VERTEX_SE3:QUAT 1628 20.013990 21.485576 -7.608739 0.9279380 -0.0187780 -0.3493987 0.1284484 +VERTEX_SE3:QUAT 1629 19.881574 21.603043 -6.720111 0.4658994 0.7811189 -0.2514175 0.3310291 +VERTEX_SE3:QUAT 1630 19.480267 21.526987 -5.693813 0.1893372 -0.0460996 0.1457148 0.9699451 +VERTEX_SE3:QUAT 1631 19.221599 21.551757 -4.677392 0.2414857 -0.5181836 0.0904892 0.8154643 +VERTEX_SE3:QUAT 1632 18.809830 21.540269 -3.795011 0.1262733 -0.1311366 0.5509447 0.8144435 +VERTEX_SE3:QUAT 1633 18.423389 21.587962 -2.948096 0.7385384 0.2628387 -0.4365241 0.4415016 +VERTEX_SE3:QUAT 1634 18.054608 21.645174 -2.206928 0.1437375 -0.2123322 0.9664675 0.0139688 +VERTEX_SE3:QUAT 1635 17.604260 21.818837 -1.371081 0.7319094 0.3176156 0.4870047 0.3553244 +VERTEX_SE3:QUAT 1636 17.231333 21.702676 -0.514884 0.5550368 0.4502651 0.2513218 0.6527119 +VERTEX_SE3:QUAT 1637 17.030331 21.703972 0.265166 0.1138446 -0.4191575 0.8136227 0.3864770 +VERTEX_SE3:QUAT 1638 16.995550 21.672216 1.281277 0.6993948 -0.4545957 0.5325023 0.1436350 +VERTEX_SE3:QUAT 1639 16.856725 21.725931 2.382237 0.7040261 0.5423784 -0.4176071 0.1891487 +VERTEX_SE3:QUAT 1640 17.805613 22.043611 2.688468 0.2900954 0.5398317 -0.1805140 0.7693121 +VERTEX_SE3:QUAT 1641 17.909791 22.061330 1.669394 0.4484744 -0.0878726 0.8589206 0.2310942 +VERTEX_SE3:QUAT 1642 18.108328 22.038184 0.613807 0.5045795 0.7408143 -0.0802688 0.4360627 +VERTEX_SE3:QUAT 1643 18.169166 21.833552 -0.342107 0.4365816 -0.8721891 0.1679245 0.1431222 +VERTEX_SE3:QUAT 1644 18.530995 21.669440 -1.454135 0.2336483 0.4077994 -0.0200651 0.8824429 +VERTEX_SE3:QUAT 1645 18.519942 21.607736 -2.484302 0.6659805 0.6153283 0.1661121 0.3876182 +VERTEX_SE3:QUAT 1646 18.646796 21.399822 -3.335803 0.7997011 0.3562555 -0.1467535 0.4604603 +VERTEX_SE3:QUAT 1647 18.896481 21.293438 -4.159505 0.1790042 -0.0923815 0.7894746 0.5797870 +VERTEX_SE3:QUAT 1648 18.909524 21.299983 -5.004669 0.8580921 -0.0642789 -0.3256819 0.3917619 +VERTEX_SE3:QUAT 1649 19.038674 21.261813 -5.937667 0.5372906 -0.6133849 0.3662613 0.4482526 +VERTEX_SE3:QUAT 1650 19.362688 21.265871 -6.724479 0.0785903 0.0792832 -0.9423903 0.3153385 +VERTEX_SE3:QUAT 1651 19.629490 21.172566 -7.783993 0.7163155 -0.3100995 -0.3699800 0.5038305 +VERTEX_SE3:QUAT 1652 19.958384 21.056951 -8.791837 0.5642190 -0.2029447 -0.6254090 0.4993335 +VERTEX_SE3:QUAT 1653 20.321564 20.907668 -9.743452 -0.6376772 0.1878355 -0.7117690 0.2268711 +VERTEX_SE3:QUAT 1654 20.734018 20.694654 -10.755664 0.1024279 0.6902236 0.0936858 0.7101570 +VERTEX_SE3:QUAT 1655 20.984708 20.500292 -11.673714 0.0771776 0.8162589 -0.0781584 0.5671475 +VERTEX_SE3:QUAT 1656 21.499643 20.132360 -12.627955 0.4910073 -0.1302201 0.8026475 0.3125886 +VERTEX_SE3:QUAT 1657 21.736168 19.843901 -13.484476 -0.1740577 -0.9283340 0.3105702 0.1069860 +VERTEX_SE3:QUAT 1658 22.041049 19.666893 -14.367967 -0.0070561 0.0329263 0.0988586 0.9945316 +VERTEX_SE3:QUAT 1659 22.281670 19.689588 -15.424467 0.9394644 -0.3219147 0.0869169 0.0788859 +VERTEX_SE3:QUAT 1660 23.218948 19.926193 -15.195832 0.3807667 -0.3201514 0.6443297 0.5808262 +VERTEX_SE3:QUAT 1661 22.893211 20.029056 -14.245103 0.3306501 -0.5629071 0.3095554 0.6913621 +VERTEX_SE3:QUAT 1662 22.885277 20.203456 -13.320612 0.1691448 -0.5998788 -0.1857171 0.7596346 +VERTEX_SE3:QUAT 1663 22.651081 20.311041 -12.244883 0.4994535 0.5883341 -0.0455715 0.6342968 +VERTEX_SE3:QUAT 1664 22.288101 20.401409 -11.227295 0.2150084 0.9413297 -0.1745605 0.1928692 +VERTEX_SE3:QUAT 1665 21.932184 20.617432 -10.414829 0.2131279 0.2405542 -0.7694937 0.5518964 +VERTEX_SE3:QUAT 1666 21.568308 20.743245 -9.536144 0.2875725 -0.1542771 -0.3236237 0.8881263 +VERTEX_SE3:QUAT 1667 21.276453 20.710398 -8.561511 0.0105328 -0.5237852 0.7999139 0.2927045 +VERTEX_SE3:QUAT 1668 20.951520 20.751605 -7.741634 0.8624183 -0.4358338 -0.1693236 0.1939406 +VERTEX_SE3:QUAT 1669 20.608974 20.613509 -6.902172 0.4900193 -0.0676899 0.7960166 0.3487933 +VERTEX_SE3:QUAT 1670 20.182430 20.585470 -5.988831 0.4873553 0.6274884 -0.2205370 0.5657797 +VERTEX_SE3:QUAT 1671 19.752225 20.571352 -5.080176 0.2237840 -0.8397497 0.4768151 0.1318654 +VERTEX_SE3:QUAT 1672 19.306742 20.362005 -4.327090 0.4474693 0.8152075 0.1173086 0.3484921 +VERTEX_SE3:QUAT 1673 18.902699 20.020049 -3.463598 0.7521049 -0.2156684 -0.0396560 0.6214924 +VERTEX_SE3:QUAT 1674 18.508986 19.835695 -2.617342 0.2345875 -0.1243045 0.2701855 0.9254820 +VERTEX_SE3:QUAT 1675 18.024106 19.765598 -1.777486 -0.5655628 0.3989370 -0.6893058 0.2141158 +VERTEX_SE3:QUAT 1676 17.825052 19.850601 -0.838768 0.4529375 -0.6718725 -0.2472741 0.5313102 +VERTEX_SE3:QUAT 1677 17.367796 19.867289 0.026492 0.7441986 -0.5364107 -0.2566357 0.3042534 +VERTEX_SE3:QUAT 1678 16.985611 19.940876 0.890905 0.7719337 0.0127984 0.3787471 0.5103971 +VERTEX_SE3:QUAT 1679 16.658510 19.960791 1.638148 0.6251832 -0.5337860 0.3651157 0.4369313 +VERTEX_SE3:QUAT 1680 17.498529 19.588069 2.168586 0.3324186 -0.4885844 0.8046002 0.0583245 +VERTEX_SE3:QUAT 1681 18.137110 19.429067 1.259204 0.7361775 -0.6225927 0.2636263 0.0303686 +VERTEX_SE3:QUAT 1682 18.640662 19.228443 0.123134 0.1434664 -0.8894664 -0.2748875 0.3357137 +VERTEX_SE3:QUAT 1683 19.173030 19.055603 -0.928044 0.8271145 0.3713756 0.0124818 0.4216704 +VERTEX_SE3:QUAT 1684 19.718957 19.188579 -1.782759 -0.7193078 -0.1342704 0.6034799 0.3168278 +VERTEX_SE3:QUAT 1685 20.241870 19.120884 -2.800653 0.0666405 -0.6572603 0.4155955 0.6251786 +VERTEX_SE3:QUAT 1686 20.818393 19.070900 -3.698932 0.3890957 -0.8675409 0.1766335 0.2545149 +VERTEX_SE3:QUAT 1687 21.392838 18.957275 -4.492343 0.6572122 -0.0168831 -0.7368853 0.1574391 +VERTEX_SE3:QUAT 1688 22.060621 18.988661 -5.311870 0.4063978 -0.7243124 -0.0931245 0.5491267 +VERTEX_SE3:QUAT 1689 22.317814 18.845055 -6.192461 0.3168920 0.1157800 0.1303409 0.9323013 +VERTEX_SE3:QUAT 1690 22.875360 18.741344 -7.072633 0.2811592 -0.2163999 -0.5365933 0.7656293 +VERTEX_SE3:QUAT 1691 23.495903 18.747502 -8.045414 0.2134074 0.0621306 -0.9748261 0.0176399 +VERTEX_SE3:QUAT 1692 24.165601 18.750903 -8.826031 0.7077582 -0.0826260 -0.6339398 0.3006188 +VERTEX_SE3:QUAT 1693 24.846994 18.656966 -9.449022 -0.0860808 -0.7872191 0.5269692 0.3085120 +VERTEX_SE3:QUAT 1694 25.461935 18.633664 -10.226344 -0.5011654 -0.0901116 0.8554544 0.0943978 +VERTEX_SE3:QUAT 1695 26.091783 18.645135 -10.932961 -0.5921912 -0.6556010 0.4611990 0.0824159 +VERTEX_SE3:QUAT 1696 26.750113 18.545353 -11.649386 0.2234665 -0.1440317 0.8545858 0.4460949 +VERTEX_SE3:QUAT 1697 27.597308 18.461835 -12.242332 0.0804862 -0.4853515 -0.0784696 0.8670631 +VERTEX_SE3:QUAT 1698 28.306766 18.368142 -12.869888 -0.2443690 -0.7069855 0.6066351 0.2691639 +VERTEX_SE3:QUAT 1699 29.059992 18.249153 -13.712821 0.2020665 0.4877168 -0.5069736 0.6813803 +VERTEX_SE3:QUAT 1700 29.844781 18.098364 -13.274927 -0.5849865 -0.8093898 0.0413336 0.0311530 +VERTEX_SE3:QUAT 1701 29.190667 18.254513 -12.597579 0.9224778 0.1111720 -0.2921993 0.2264840 +VERTEX_SE3:QUAT 1702 28.310334 18.476137 -11.838922 0.1686896 -0.6804262 0.1682594 0.6930028 +VERTEX_SE3:QUAT 1703 27.500224 18.670372 -11.253051 -0.0781098 -0.3314932 0.8160739 0.4669417 +VERTEX_SE3:QUAT 1704 26.545887 19.000712 -10.770534 0.7573457 -0.4404354 -0.4542014 0.1616948 +VERTEX_SE3:QUAT 1705 25.766570 19.092449 -10.206490 0.3215749 -0.1827619 0.4684172 0.8023547 +VERTEX_SE3:QUAT 1706 24.976618 19.405200 -9.506455 0.2388016 0.1423130 0.0646703 0.9584042 +VERTEX_SE3:QUAT 1707 24.301824 19.548340 -9.000141 0.6010286 -0.4119900 0.5892755 0.3489747 +VERTEX_SE3:QUAT 1708 23.548609 20.025295 -8.345146 0.1330125 -0.4820593 0.5865715 0.6370717 +VERTEX_SE3:QUAT 1709 22.768013 20.400753 -7.916192 0.5159081 0.8218899 -0.1119520 0.2140154 +VERTEX_SE3:QUAT 1710 21.901049 20.763928 -7.574873 0.7284974 0.1099911 -0.2772045 0.6167261 +VERTEX_SE3:QUAT 1711 20.984501 21.084442 -7.118559 0.6151947 0.3519834 -0.3681121 0.6017779 +VERTEX_SE3:QUAT 1712 20.206985 21.435273 -6.825802 0.4225167 0.1035450 -0.0365721 0.8996780 +VERTEX_SE3:QUAT 1713 19.508485 21.788952 -6.441785 0.4800875 -0.6043572 -0.0555420 0.6333904 +VERTEX_SE3:QUAT 1714 18.572382 22.329362 -6.271425 -0.7433528 -0.3164249 0.4397489 0.3923299 +VERTEX_SE3:QUAT 1715 17.696365 22.739855 -5.914343 0.0767794 -0.1355584 -0.6382276 0.7539193 +VERTEX_SE3:QUAT 1716 17.007965 23.264997 -5.554972 -0.6963387 -0.1675036 0.6337571 0.2922445 +VERTEX_SE3:QUAT 1717 16.161289 23.696624 -5.389117 0.8866356 -0.2871754 -0.0008812 0.3625009 +VERTEX_SE3:QUAT 1718 15.428306 24.074686 -5.165219 0.9094607 -0.3885822 0.1359932 0.0582320 +VERTEX_SE3:QUAT 1719 14.808157 24.428489 -4.785473 -0.6671771 -0.6439863 0.3739321 0.0181986 +VERTEX_SE3:QUAT 1720 15.040019 24.291634 -3.883992 0.5492618 0.5155828 -0.5836542 0.3030407 +VERTEX_SE3:QUAT 1721 15.891428 23.835458 -4.171189 0.0461797 0.9014051 -0.4166957 0.1081714 +VERTEX_SE3:QUAT 1722 16.628648 23.469772 -4.590785 -0.4944566 -0.8541918 -0.0359761 0.1567634 +VERTEX_SE3:QUAT 1723 17.626298 23.265837 -5.193786 -0.2245227 -0.1793853 0.9362149 0.2022674 +VERTEX_SE3:QUAT 1724 18.474926 22.932057 -5.720000 0.6714395 -0.1272702 -0.5289693 0.5031529 +VERTEX_SE3:QUAT 1725 19.314350 22.661912 -6.221724 0.6926989 0.0150770 0.3940141 0.6038988 +VERTEX_SE3:QUAT 1726 20.144985 22.430417 -6.647990 -0.0766644 0.4803192 -0.4840995 0.7273676 +VERTEX_SE3:QUAT 1727 21.170561 22.439162 -6.938131 -0.5305851 -0.3829269 0.6275801 0.4218882 +VERTEX_SE3:QUAT 1728 22.084102 22.079392 -7.384104 0.8319119 0.0147758 -0.4955659 0.2492363 +VERTEX_SE3:QUAT 1729 23.176368 21.874577 -7.452957 -0.4518578 0.4598691 -0.7535495 0.1284841 +VERTEX_SE3:QUAT 1730 23.946004 21.568226 -7.864624 0.7331156 0.2747010 0.4545451 0.4248171 +VERTEX_SE3:QUAT 1731 24.941018 21.395065 -8.210449 0.4109965 -0.1855897 0.7392324 0.5001738 +VERTEX_SE3:QUAT 1732 25.910306 21.105211 -8.502374 0.2477421 0.1564753 -0.1912709 0.9367789 +VERTEX_SE3:QUAT 1733 26.918102 20.796168 -8.831877 -0.1338878 -0.5732955 0.4754348 0.6537339 +VERTEX_SE3:QUAT 1734 27.927784 20.309564 -9.093100 0.1838440 0.5199085 0.0596610 0.8320680 +VERTEX_SE3:QUAT 1735 28.911918 19.825789 -9.295253 0.7989489 -0.1264070 0.4873995 0.3288520 +VERTEX_SE3:QUAT 1736 29.843851 19.397014 -9.552099 0.4486370 0.0753636 -0.8878829 0.0686236 +VERTEX_SE3:QUAT 1737 30.800551 18.928471 -9.896257 0.5624238 -0.1737292 -0.6524948 0.4772297 +VERTEX_SE3:QUAT 1738 31.664429 18.513715 -10.210407 0.6196845 -0.3074815 0.7175771 0.0808038 +VERTEX_SE3:QUAT 1739 32.632171 17.988634 -10.440630 -0.5143970 -0.2320279 0.8045191 0.1852237 +VERTEX_SE3:QUAT 1740 33.075709 18.121571 -9.662527 0.8445099 -0.2287707 0.0953528 0.4747366 +VERTEX_SE3:QUAT 1741 32.202508 18.495029 -9.325452 0.1155271 0.2175235 -0.8811834 0.4035503 +VERTEX_SE3:QUAT 1742 31.192289 18.945897 -8.864428 -0.4365618 -0.2688949 0.7528490 0.4127078 +VERTEX_SE3:QUAT 1743 30.205482 19.447241 -8.518988 -0.1434177 0.6907177 -0.5971665 0.3817493 +VERTEX_SE3:QUAT 1744 29.298192 19.812418 -8.261691 0.0837019 0.2954546 -0.2322375 0.9229119 +VERTEX_SE3:QUAT 1745 28.439391 20.218300 -8.118684 -0.3925711 -0.3663103 0.2645203 0.8010829 +VERTEX_SE3:QUAT 1746 27.493128 20.521654 -8.060426 -0.2991001 -0.4274767 0.3591639 0.7738244 +VERTEX_SE3:QUAT 1747 26.424508 20.882885 -7.837154 -0.0121282 -0.0653890 0.9033824 0.4236477 +VERTEX_SE3:QUAT 1748 25.532556 21.119128 -7.581349 0.2299438 -0.0370434 -0.5471307 0.8039911 +VERTEX_SE3:QUAT 1749 24.563013 21.473670 -7.531408 0.0256663 -0.8793956 0.0416899 0.4735679 +VERTEX_SE3:QUAT 1750 23.622269 21.864405 -7.401462 0.3436576 0.5057249 -0.6134646 0.4998029 +VERTEX_SE3:QUAT 1751 22.695707 22.023509 -7.330903 0.3997323 -0.3781547 -0.1247261 0.8256249 +VERTEX_SE3:QUAT 1752 21.985521 22.325727 -7.143227 0.1642923 0.0085066 0.8461049 0.5069933 +VERTEX_SE3:QUAT 1753 20.983442 22.569583 -7.000478 0.6809417 0.4923511 -0.0970165 0.5333822 +VERTEX_SE3:QUAT 1754 20.260510 22.875516 -6.719202 0.1678316 0.1169809 0.2042334 0.9573070 +VERTEX_SE3:QUAT 1755 19.493013 23.219350 -6.711790 -0.1991145 -0.2465814 0.0726246 0.9456620 +VERTEX_SE3:QUAT 1756 18.545272 23.408009 -6.515347 -0.1655694 0.7165220 -0.6597651 0.1545735 +VERTEX_SE3:QUAT 1757 17.613793 23.907845 -6.223186 -0.1623893 -0.9551044 0.1998816 0.1464675 +VERTEX_SE3:QUAT 1758 16.675349 24.268748 -5.989649 0.5976226 -0.2673181 -0.4473841 0.6092912 +VERTEX_SE3:QUAT 1759 15.657718 24.579427 -5.636780 0.5284088 0.7672060 -0.3566684 0.0704752 +VERTEX_SE3:QUAT 1760 16.014354 24.794696 -4.695938 0.0648375 0.1007529 -0.5731372 0.8106533 +VERTEX_SE3:QUAT 1761 16.885684 24.301681 -5.055594 0.5213886 0.2723107 0.4216120 0.6901044 +VERTEX_SE3:QUAT 1762 17.763118 23.756293 -5.346966 -0.6893824 -0.0741733 0.7203683 0.0178813 +VERTEX_SE3:QUAT 1763 18.594989 23.029701 -5.567845 0.4121723 -0.4767935 -0.6826434 0.3698376 +VERTEX_SE3:QUAT 1764 19.526856 22.590496 -5.508626 0.4297544 -0.4086493 0.7842348 0.1824628 +VERTEX_SE3:QUAT 1765 20.502284 22.163263 -5.765648 0.5700503 -0.6610769 0.3234340 0.3652538 +VERTEX_SE3:QUAT 1766 21.364448 21.499151 -5.846102 0.2241652 -0.7654795 0.6000533 0.0610512 +VERTEX_SE3:QUAT 1767 22.077329 21.063139 -6.017200 -0.2096076 -0.5552231 0.7919819 0.1433757 +VERTEX_SE3:QUAT 1768 22.961118 20.423477 -6.153683 0.3411415 0.1364987 -0.3014034 0.8798560 +VERTEX_SE3:QUAT 1769 23.772602 19.856271 -6.403145 0.1777323 -0.6332733 0.7410107 0.1352009 +VERTEX_SE3:QUAT 1770 24.595222 19.299549 -6.551147 0.5616001 -0.1423154 -0.1243213 0.8055407 +VERTEX_SE3:QUAT 1771 25.402752 18.687519 -6.927177 0.2285215 -0.1393366 -0.8681968 0.4178487 +VERTEX_SE3:QUAT 1772 26.208318 18.151494 -7.021182 0.6485441 -0.6313766 0.3570051 0.2308713 +VERTEX_SE3:QUAT 1773 26.921400 17.765059 -7.221158 0.6766440 -0.0601329 -0.5520518 0.4835036 +VERTEX_SE3:QUAT 1774 27.511333 17.204497 -7.506598 0.1803157 0.4371519 -0.6989160 0.5365640 +VERTEX_SE3:QUAT 1775 28.199797 16.507361 -7.783821 0.4061647 0.6659228 -0.5150754 0.3553511 +VERTEX_SE3:QUAT 1776 28.918696 15.943260 -7.999873 0.6466028 -0.3130138 0.4082846 0.5632326 +VERTEX_SE3:QUAT 1777 29.743457 15.364935 -8.418852 0.6754390 -0.5387565 -0.0205305 0.5030926 +VERTEX_SE3:QUAT 1778 30.524527 14.843802 -8.710088 -0.3975499 -0.2158148 0.3568800 0.8173217 +VERTEX_SE3:QUAT 1779 31.464388 14.250585 -8.829845 0.3035141 0.0880416 0.1509734 0.9366616 +VERTEX_SE3:QUAT 1780 31.794197 14.557619 -7.740072 0.4729921 -0.0904234 0.8731994 0.0749995 +VERTEX_SE3:QUAT 1781 30.889621 15.004467 -7.659385 0.3064312 -0.7952680 0.4220841 0.3090207 +VERTEX_SE3:QUAT 1782 30.035864 15.456128 -7.279808 0.8857354 0.1702871 -0.0289228 0.4308580 +VERTEX_SE3:QUAT 1783 29.192903 16.113613 -7.011877 -0.1356286 0.5506345 -0.7000617 0.4339587 +VERTEX_SE3:QUAT 1784 28.336315 16.603213 -6.772963 -0.4574860 -0.1159419 0.8567234 0.2080600 +VERTEX_SE3:QUAT 1785 27.621456 17.191425 -6.515244 0.5894602 0.2526919 -0.3572806 0.6789949 +VERTEX_SE3:QUAT 1786 26.797011 17.871682 -6.527254 0.0715057 0.5106646 -0.8536121 0.0738583 +VERTEX_SE3:QUAT 1787 26.074594 18.539704 -6.263485 -0.1098447 -0.7765190 0.4444488 0.4329177 +VERTEX_SE3:QUAT 1788 25.482851 19.137664 -6.212874 0.2105018 0.2835859 0.5273656 0.7727571 +VERTEX_SE3:QUAT 1789 24.839339 19.984353 -6.265588 0.1050659 -0.1196658 0.4831769 0.8609189 +VERTEX_SE3:QUAT 1790 24.050089 20.482581 -6.234747 -0.2857127 -0.4497893 0.4757943 0.6997697 +VERTEX_SE3:QUAT 1791 23.163437 21.213737 -6.370607 -0.4435385 -0.5771576 0.3479593 0.5908359 +VERTEX_SE3:QUAT 1792 22.299989 22.007727 -6.217933 0.3790528 0.4826347 -0.6211773 0.4873618 +VERTEX_SE3:QUAT 1793 21.468140 22.741886 -6.205852 -0.2103585 -0.0714860 -0.9623567 0.1565522 +VERTEX_SE3:QUAT 1794 20.621378 23.340508 -6.005639 -0.4026564 -0.6833786 0.3721139 0.4820714 +VERTEX_SE3:QUAT 1795 19.776540 23.955569 -5.898440 -0.0882674 -0.4741678 0.8339787 0.2680546 +VERTEX_SE3:QUAT 1796 19.031130 24.544001 -5.921549 0.1358326 -0.8593266 0.4553861 0.1890260 +VERTEX_SE3:QUAT 1797 18.132167 25.009788 -5.769956 0.6177456 -0.5724173 -0.0065069 0.5391535 +VERTEX_SE3:QUAT 1798 17.374391 25.561380 -5.663930 0.5783696 -0.1195554 -0.0972005 0.8010913 +VERTEX_SE3:QUAT 1799 16.606728 26.261035 -5.496413 0.0231131 0.3965732 -0.6605568 0.6370716 +VERTEX_SE3:QUAT 1800 16.991693 26.647632 -4.792697 -0.1814674 0.2167497 -0.6465996 0.7085182 +VERTEX_SE3:QUAT 1801 17.663286 26.314213 -5.076691 0.3074135 -0.8079154 0.2812775 0.4167165 +VERTEX_SE3:QUAT 1802 18.265175 25.559645 -5.216539 0.5984402 -0.0750351 -0.6663442 0.4384341 +VERTEX_SE3:QUAT 1803 19.120714 24.873242 -5.491249 0.0248085 -0.8070906 0.5770440 0.1225130 +VERTEX_SE3:QUAT 1804 19.844539 24.324819 -5.663833 -0.6731601 -0.2940779 0.6678861 0.1195900 +VERTEX_SE3:QUAT 1805 20.565531 23.737695 -5.858660 -0.0754892 0.1841459 0.8070661 0.5559100 +VERTEX_SE3:QUAT 1806 21.295576 22.914562 -6.146499 0.3658768 0.2784059 -0.7876035 0.4102499 +VERTEX_SE3:QUAT 1807 22.132976 22.328205 -6.369142 -0.1765267 0.5280933 -0.8080125 0.1925399 +VERTEX_SE3:QUAT 1808 22.851652 21.934529 -6.760966 0.0855855 0.2552456 0.6956382 0.6660422 +VERTEX_SE3:QUAT 1809 23.740466 21.476816 -6.536172 0.4797515 -0.0903640 0.6641074 0.5662457 +VERTEX_SE3:QUAT 1810 24.603059 21.008397 -6.603208 0.4518414 -0.3725620 -0.5940772 0.5514609 +VERTEX_SE3:QUAT 1811 25.700838 20.226960 -6.844929 -0.0058041 -0.1655238 0.9839373 0.0665999 +VERTEX_SE3:QUAT 1812 26.546086 19.706453 -6.655215 0.1347439 0.7874707 -0.5607912 0.2173643 +VERTEX_SE3:QUAT 1813 27.393216 19.451027 -6.384842 0.4163344 0.4217679 -0.3349655 0.7325132 +VERTEX_SE3:QUAT 1814 28.380873 19.154558 -6.375797 -0.3105877 -0.6123756 0.4495622 0.5713363 +VERTEX_SE3:QUAT 1815 29.403064 18.911626 -6.313697 0.6942658 -0.4942911 0.2821942 0.4404971 +VERTEX_SE3:QUAT 1816 30.286429 18.536647 -6.267433 -0.2712588 -0.7030125 0.5210835 0.4008292 +VERTEX_SE3:QUAT 1817 31.249735 18.330596 -6.239497 -0.1616898 0.1370498 -0.8192417 0.5328384 +VERTEX_SE3:QUAT 1818 32.137484 18.000783 -6.238437 0.3765845 -0.0652071 -0.7685570 0.5130811 +VERTEX_SE3:QUAT 1819 33.122881 17.749556 -6.224771 0.2654912 -0.5947030 -0.1865073 0.7355663 +VERTEX_SE3:QUAT 1820 33.350608 18.598744 -5.706963 0.3747491 -0.5928214 0.5054109 0.5026786 +VERTEX_SE3:QUAT 1821 32.437785 18.901890 -5.685822 -0.0068813 -0.0223015 0.7323491 0.6805292 +VERTEX_SE3:QUAT 1822 31.534165 19.267407 -5.598608 0.8398670 -0.1212022 -0.3381770 0.4069028 +VERTEX_SE3:QUAT 1823 30.581543 19.619857 -5.787719 0.9131434 -0.1208846 -0.1779138 0.3462697 +VERTEX_SE3:QUAT 1824 29.848121 20.033604 -5.897754 -0.1828651 0.3936162 -0.6395614 0.6344981 +VERTEX_SE3:QUAT 1825 28.865898 20.385372 -6.249932 -0.0907069 0.4713815 -0.3993491 0.7810839 +VERTEX_SE3:QUAT 1826 27.913710 20.706497 -6.486454 0.1336361 0.6208583 -0.7282142 0.2576439 +VERTEX_SE3:QUAT 1827 27.024010 21.132318 -6.785703 0.2290086 -0.4784208 0.5836745 0.6148111 +VERTEX_SE3:QUAT 1828 26.148254 21.484417 -7.238895 0.2677838 -0.6485905 0.5850147 0.4066694 +VERTEX_SE3:QUAT 1829 25.537132 21.927581 -7.440315 0.6740618 -0.1667299 -0.2504960 0.6746062 +VERTEX_SE3:QUAT 1830 24.607060 22.323329 -7.772965 0.5387015 0.3661570 -0.5958964 0.4697203 +VERTEX_SE3:QUAT 1831 23.693352 22.888652 -8.009382 0.1864962 -0.0467181 0.9813285 0.0055741 +VERTEX_SE3:QUAT 1832 23.019646 23.669673 -8.203254 -0.2201001 -0.1356690 0.6406817 0.7229639 +VERTEX_SE3:QUAT 1833 22.241346 24.155442 -8.493816 -0.4357579 -0.3621392 0.8059845 0.1713454 +VERTEX_SE3:QUAT 1834 21.559157 24.695273 -8.548834 -0.5464730 -0.1368614 0.7357207 0.3759671 +VERTEX_SE3:QUAT 1835 20.624943 25.310105 -8.647336 0.7896037 -0.2106198 -0.5579276 0.1445059 +VERTEX_SE3:QUAT 1836 19.747676 25.714033 -8.695486 0.2612997 0.2574109 -0.2575377 0.8939443 +VERTEX_SE3:QUAT 1837 18.893650 26.236578 -8.703177 -0.5907010 -0.4285194 0.5844900 0.3547039 +VERTEX_SE3:QUAT 1838 18.019460 26.651239 -8.777813 0.8783740 0.2915765 -0.2515344 0.2831479 +VERTEX_SE3:QUAT 1839 17.099764 27.299248 -8.768431 0.0268170 -0.2350422 0.9577933 0.1633033 +VERTEX_SE3:QUAT 1840 17.484417 27.700836 -7.702610 0.5273885 -0.3836880 0.1296860 0.7468778 +VERTEX_SE3:QUAT 1841 18.226771 27.147632 -7.844809 0.3669330 -0.6832432 0.0424299 0.6298719 +VERTEX_SE3:QUAT 1842 19.277402 26.692960 -7.922953 0.5453270 0.2853604 -0.6954127 0.3709300 +VERTEX_SE3:QUAT 1843 20.284300 26.415885 -8.050431 0.1811113 -0.0381948 -0.6250105 0.7583546 +VERTEX_SE3:QUAT 1844 21.225877 26.198749 -8.042076 -0.3232396 0.7549792 -0.5114850 0.2527955 +VERTEX_SE3:QUAT 1845 22.138116 25.888205 -8.138026 -0.4560918 -0.7489907 0.4741859 0.0783640 +VERTEX_SE3:QUAT 1846 23.102615 25.460944 -7.922650 0.7853134 -0.1423139 0.3021022 0.5213097 +VERTEX_SE3:QUAT 1847 24.005378 25.129392 -7.777874 0.2773658 0.2216910 -0.7052578 0.6136226 +VERTEX_SE3:QUAT 1848 24.960412 24.776198 -7.746122 0.8355664 0.0207784 -0.5282203 0.1496006 +VERTEX_SE3:QUAT 1849 25.832087 24.458503 -7.716282 0.0337230 0.1787038 0.7260396 0.6631698 +VERTEX_SE3:QUAT 1850 26.653233 24.096866 -7.883832 0.0291792 0.7943764 -0.3541937 0.4926068 +VERTEX_SE3:QUAT 1851 27.683442 23.648959 -8.148108 0.2142012 0.2534119 0.0213834 0.9431029 +VERTEX_SE3:QUAT 1852 28.747234 23.262872 -8.305589 0.2750065 0.3887693 -0.4799213 0.7368211 +VERTEX_SE3:QUAT 1853 29.550564 22.972234 -8.589061 0.1407721 0.7109512 -0.3662217 0.5836208 +VERTEX_SE3:QUAT 1854 30.239795 22.528071 -8.966931 -0.2322389 -0.0595218 0.7193206 0.6519970 +VERTEX_SE3:QUAT 1855 31.151145 22.053310 -9.460515 0.7557522 -0.3295161 0.4296812 0.3682822 +VERTEX_SE3:QUAT 1856 32.143165 21.391689 -9.843508 -0.2181258 0.1918087 -0.6019283 0.7438501 +VERTEX_SE3:QUAT 1857 33.031683 20.829517 -10.150022 0.1572990 -0.8844946 0.3940816 0.1939744 +VERTEX_SE3:QUAT 1858 33.899776 20.370446 -10.426866 0.0423996 -0.5508207 0.5673043 0.6107083 +VERTEX_SE3:QUAT 1859 34.705991 20.009475 -10.550628 0.0504763 0.5452608 -0.8100289 0.2097523 +VERTEX_SE3:QUAT 1860 35.280419 20.517138 -9.785332 0.2257264 0.5198653 -0.2573935 0.7826470 +VERTEX_SE3:QUAT 1861 34.403745 20.993866 -9.430793 -0.0975156 0.1493124 0.1454382 0.9731620 +VERTEX_SE3:QUAT 1862 33.589395 21.558749 -9.181151 -0.0731949 -0.5399929 0.7053305 0.4533862 +VERTEX_SE3:QUAT 1863 32.785529 22.149796 -8.952369 0.1898615 -0.2103863 -0.0309996 0.9585036 +VERTEX_SE3:QUAT 1864 32.098005 22.733741 -8.743947 0.5462128 -0.3562722 0.6767186 0.3417216 +VERTEX_SE3:QUAT 1865 31.407933 23.646203 -8.694156 0.4798229 0.2992202 0.4321400 0.7024900 +VERTEX_SE3:QUAT 1866 30.573593 24.377085 -8.449720 -0.0268921 -0.5714604 0.8187744 0.0481487 +VERTEX_SE3:QUAT 1867 30.079218 25.002366 -8.023721 0.4704018 0.2483214 -0.1217656 0.8379927 +VERTEX_SE3:QUAT 1868 29.508030 25.940528 -7.730287 0.1547539 0.1442258 0.5743741 0.7907873 +VERTEX_SE3:QUAT 1869 28.882065 26.827883 -7.632686 0.4595817 0.0048999 0.4404767 0.7711945 +VERTEX_SE3:QUAT 1870 28.272222 27.581094 -7.513050 0.7090996 0.0222911 0.0238496 0.7043522 +VERTEX_SE3:QUAT 1871 27.704149 28.479010 -7.224103 0.0248480 0.1959625 -0.6868111 0.6994797 +VERTEX_SE3:QUAT 1872 27.142551 29.486696 -7.038517 -0.1448530 0.1056423 0.7507906 0.6357443 +VERTEX_SE3:QUAT 1873 26.462948 30.298236 -6.813228 0.3054005 0.2284484 0.4274163 0.8196689 +VERTEX_SE3:QUAT 1874 25.991445 31.146378 -6.459036 -0.4156283 0.0410532 0.1776317 0.8910751 +VERTEX_SE3:QUAT 1875 25.334099 31.975360 -6.369592 0.3376484 0.3892460 -0.4889055 0.7038839 +VERTEX_SE3:QUAT 1876 24.853630 32.747873 -6.062130 0.5556944 0.2316163 0.4929051 0.6281737 +VERTEX_SE3:QUAT 1877 24.298910 33.428485 -5.908051 -0.0485627 -0.4146412 0.9067423 0.0594368 +VERTEX_SE3:QUAT 1878 23.391164 34.078075 -5.784782 -0.0092631 -0.8051354 0.5534121 0.2130875 +VERTEX_SE3:QUAT 1879 22.592130 34.677802 -5.613540 0.8730766 -0.0775477 0.0397310 0.4797343 +VERTEX_SE3:QUAT 1880 23.111264 35.332221 -4.969935 -0.2029203 -0.0154155 0.8209536 0.5334987 +VERTEX_SE3:QUAT 1881 23.913425 34.573412 -5.189871 0.1436998 0.0620642 -0.3715033 0.9151413 +VERTEX_SE3:QUAT 1882 24.488050 33.883159 -5.557075 -0.1647380 0.3747541 -0.9000344 0.1495289 +VERTEX_SE3:QUAT 1883 25.263071 32.964987 -5.976073 0.1131223 0.1583095 -0.7296613 0.6555424 +VERTEX_SE3:QUAT 1884 25.793884 32.208878 -6.010885 -0.2403270 0.0006732 0.4047066 0.8823010 +VERTEX_SE3:QUAT 1885 26.637285 31.409902 -6.196805 -0.4473085 -0.7026270 0.5324627 0.1507111 +VERTEX_SE3:QUAT 1886 27.281748 30.981680 -6.289729 0.0993804 -0.3879255 0.7269267 0.5578663 +VERTEX_SE3:QUAT 1887 27.995989 30.150843 -6.545147 -0.0186326 0.2532253 0.0399567 0.9664022 +VERTEX_SE3:QUAT 1888 28.666060 29.494068 -6.778372 -0.1850441 0.4146567 -0.8706320 0.1892577 +VERTEX_SE3:QUAT 1889 29.328920 28.718386 -6.909037 0.4757939 -0.1224895 0.1018403 0.8650116 +VERTEX_SE3:QUAT 1890 29.804653 28.080179 -7.069320 0.6085578 -0.1459735 -0.7680032 0.1360886 +VERTEX_SE3:QUAT 1891 30.195481 27.300792 -7.311136 -0.0360310 0.3870691 -0.1394065 0.9107388 +VERTEX_SE3:QUAT 1892 30.831311 26.371164 -7.535046 0.0724033 0.5390257 -0.1740904 0.8209151 +VERTEX_SE3:QUAT 1893 31.227543 25.421124 -7.709986 0.4168907 0.1183284 0.3422499 0.8337060 +VERTEX_SE3:QUAT 1894 31.682313 24.582149 -8.081664 -0.0167798 -0.1723275 -0.5543221 0.8140938 +VERTEX_SE3:QUAT 1895 32.131163 23.720761 -8.322064 -0.0681286 0.3470780 0.0169156 0.9352054 +VERTEX_SE3:QUAT 1896 32.524150 22.862545 -8.893621 -0.4269867 0.3704553 0.8248437 0.0088346 +VERTEX_SE3:QUAT 1897 32.972295 22.174843 -9.336278 -0.3018869 -0.6822965 -0.0833936 0.6605916 +VERTEX_SE3:QUAT 1898 33.348709 21.275270 -9.653626 0.1452399 0.3702101 -0.2967453 0.8682120 +VERTEX_SE3:QUAT 1899 33.837379 20.423841 -9.849281 0.4901032 -0.4686607 0.1860377 0.7110175 +VERTEX_SE3:QUAT 1900 34.533478 20.486026 -9.187184 0.1917038 0.1852672 -0.7909611 0.5507325 +VERTEX_SE3:QUAT 1901 34.151134 21.427930 -8.918041 -0.1763472 0.4670135 -0.8615221 0.0926270 +VERTEX_SE3:QUAT 1902 33.837584 22.133496 -8.558210 -0.2014794 -0.1438660 0.9139866 0.3214609 +VERTEX_SE3:QUAT 1903 33.317800 22.864158 -8.320780 0.1320083 -0.2039195 -0.2977980 0.9232047 +VERTEX_SE3:QUAT 1904 33.042309 23.655446 -7.997551 0.1337391 -0.2353035 -0.4025739 0.8744600 +VERTEX_SE3:QUAT 1905 32.633489 24.330964 -7.571114 0.3137986 0.3132296 0.4728625 0.7614583 +VERTEX_SE3:QUAT 1906 32.141529 24.914773 -7.216621 -0.0811238 0.3197714 -0.9063346 0.2640508 +VERTEX_SE3:QUAT 1907 31.734788 25.736527 -6.765023 0.6616524 -0.4150531 0.2646753 0.5655917 +VERTEX_SE3:QUAT 1908 31.088451 26.325107 -6.423931 -0.3584271 -0.6873054 0.5673218 0.2780060 +VERTEX_SE3:QUAT 1909 30.610030 27.114327 -6.265754 0.6219613 -0.6564621 0.2012946 0.3764336 +VERTEX_SE3:QUAT 1910 30.160758 27.946369 -5.998587 0.1867257 0.0945351 0.6949780 0.6878970 +VERTEX_SE3:QUAT 1911 29.665917 28.553377 -5.648184 0.2045961 0.1023457 0.3366170 0.9134302 +VERTEX_SE3:QUAT 1912 29.174517 29.247321 -5.300752 -0.1441341 -0.2490992 0.2580595 0.9222691 +VERTEX_SE3:QUAT 1913 28.680724 30.066922 -4.881231 0.1054292 -0.8370937 0.2831866 0.4560308 +VERTEX_SE3:QUAT 1914 28.280604 30.944752 -4.501303 -0.1386066 -0.5697449 0.4731499 0.6575015 +VERTEX_SE3:QUAT 1915 27.724230 31.616900 -3.966091 -0.4969789 -0.2650521 0.4710269 0.6788911 +VERTEX_SE3:QUAT 1916 27.352190 32.485175 -3.413727 0.5846171 0.6859269 -0.2428602 0.3588120 +VERTEX_SE3:QUAT 1917 26.985967 33.181608 -2.902258 0.5367945 0.5336215 -0.4674979 0.4566677 +VERTEX_SE3:QUAT 1918 26.592684 33.807357 -2.349935 0.3878469 -0.4126024 -0.6067709 0.5578200 +VERTEX_SE3:QUAT 1919 26.348121 34.437239 -1.852864 0.3328489 0.1982727 -0.8979757 0.2086605 +VERTEX_SE3:QUAT 1920 27.226374 34.285041 -1.539756 0.1693157 -0.3761068 0.1070038 0.9046690 +VERTEX_SE3:QUAT 1921 27.529988 33.495957 -2.213639 -0.3754166 0.1991761 0.7202194 0.5483386 +VERTEX_SE3:QUAT 1922 27.752839 32.753527 -2.887737 -0.8627602 -0.0508818 0.5022934 0.0275176 +VERTEX_SE3:QUAT 1923 28.156552 32.402352 -3.540905 0.0233396 -0.2247903 -0.9731936 0.0426484 +VERTEX_SE3:QUAT 1924 28.506405 31.575913 -4.300368 -0.3308531 0.1660130 0.7416545 0.5593966 +VERTEX_SE3:QUAT 1925 28.980091 30.988613 -5.131875 0.1384467 0.2380868 -0.7831181 0.5575601 +VERTEX_SE3:QUAT 1926 29.499681 30.289303 -5.759095 0.6425249 0.0776749 -0.6258333 0.4352714 +VERTEX_SE3:QUAT 1927 29.608461 29.644376 -6.371756 0.3391273 0.5282009 -0.7406597 0.2396239 +VERTEX_SE3:QUAT 1928 29.694470 28.919697 -7.143878 0.3858608 0.7595662 -0.4782891 0.2130967 +VERTEX_SE3:QUAT 1929 29.984732 28.419483 -7.790608 0.1997492 -0.0912592 -0.4564244 0.8622348 +VERTEX_SE3:QUAT 1930 30.244059 27.796815 -8.254938 -0.2102291 0.1099038 -0.9657140 0.1054580 +VERTEX_SE3:QUAT 1931 30.275848 26.975919 -9.020094 0.0688327 -0.2379305 -0.3051148 0.9195412 +VERTEX_SE3:QUAT 1932 30.585453 26.248294 -9.731388 0.0174952 -0.5408016 0.3396843 0.7693128 +VERTEX_SE3:QUAT 1933 30.641014 25.429636 -10.369284 0.2645972 -0.5561544 0.0404093 0.7867958 +VERTEX_SE3:QUAT 1934 31.101860 24.670208 -11.145025 0.0421536 0.6175106 -0.7468354 0.2431885 +VERTEX_SE3:QUAT 1935 31.350910 24.078114 -11.789634 0.2094183 0.4943025 -0.7609508 0.3643664 +VERTEX_SE3:QUAT 1936 31.622738 23.632456 -12.630193 -0.3931683 0.0249304 0.9186429 0.0298731 +VERTEX_SE3:QUAT 1937 31.554199 23.211027 -13.263479 0.6709694 -0.3105874 0.1308655 0.6604618 +VERTEX_SE3:QUAT 1938 31.364168 22.466835 -13.819080 0.6663160 0.1387925 -0.4616872 0.5688625 +VERTEX_SE3:QUAT 1939 31.239321 21.709214 -14.708611 0.3238598 -0.0720726 0.3885338 0.8596289 +VERTEX_SE3:QUAT 1940 32.117360 21.604292 -14.342014 0.3985016 0.0152147 -0.0854439 0.9130522 +VERTEX_SE3:QUAT 1941 32.332892 22.226676 -13.449896 0.0203666 -0.3615990 0.5286508 0.7676977 +VERTEX_SE3:QUAT 1942 32.346489 22.708060 -12.755799 0.6972159 -0.6088214 0.0596169 0.3737276 +VERTEX_SE3:QUAT 1943 32.393737 23.398304 -12.008392 0.2252306 -0.1047918 0.4401657 0.8628696 +VERTEX_SE3:QUAT 1944 32.628290 23.930072 -11.301397 0.7451554 -0.0448702 0.5936373 0.3005409 +VERTEX_SE3:QUAT 1945 32.600976 24.394876 -10.585041 0.4475931 0.4765091 -0.6979893 0.2922508 +VERTEX_SE3:QUAT 1946 32.649287 25.007115 -9.882404 -0.2283986 -0.0384332 0.7112348 0.6637033 +VERTEX_SE3:QUAT 1947 32.939843 25.723572 -9.111070 0.1595624 0.6044318 -0.0802494 0.7763775 +VERTEX_SE3:QUAT 1948 33.151661 26.318214 -8.278687 0.3590438 0.1246474 -0.5708513 0.7277907 +VERTEX_SE3:QUAT 1949 33.378302 26.926411 -7.345735 0.3305123 -0.1069534 -0.3338908 0.8762645 +VERTEX_SE3:QUAT 1950 33.626130 27.460889 -6.651026 -0.1908134 -0.2196497 -0.3932063 0.8722001 +VERTEX_SE3:QUAT 1951 33.877347 28.129180 -6.071027 -0.0742677 -0.5027686 -0.8237996 0.2511219 +VERTEX_SE3:QUAT 1952 34.285351 29.021966 -5.605284 0.5238448 -0.5158038 0.1548388 0.6599682 +VERTEX_SE3:QUAT 1953 34.711264 29.719663 -4.845027 -0.1158192 0.1919398 -0.8969468 0.3810924 +VERTEX_SE3:QUAT 1954 34.954998 30.516683 -4.476032 0.7914608 -0.0660372 -0.2026718 0.5728465 +VERTEX_SE3:QUAT 1955 35.078146 31.333368 -4.047211 -0.5639814 -0.4103874 0.6952918 0.1734260 +VERTEX_SE3:QUAT 1956 35.192067 32.339712 -3.612082 0.0747619 0.6274745 -0.6331297 0.4470271 +VERTEX_SE3:QUAT 1957 35.253247 33.273408 -3.158220 0.1907154 0.3411391 -0.8933509 0.2217564 +VERTEX_SE3:QUAT 1958 35.270213 34.105155 -2.465380 0.6289155 0.0220567 0.7717978 0.0911425 +VERTEX_SE3:QUAT 1959 35.447837 34.989602 -2.037033 -0.1932526 -0.5177371 -0.0064197 0.8334030 +VERTEX_SE3:QUAT 1960 36.353190 34.808546 -2.026748 0.0994866 -0.7232395 0.1926209 0.6556861 +VERTEX_SE3:QUAT 1961 36.207377 33.897059 -2.635448 -0.1460687 0.1608393 0.9366549 0.2747223 +VERTEX_SE3:QUAT 1962 36.263969 33.232802 -3.141733 0.7392241 -0.3078845 0.5391345 0.2609383 +VERTEX_SE3:QUAT 1963 36.196637 32.245067 -3.651152 0.5063948 -0.1802988 -0.4145630 0.7342985 +VERTEX_SE3:QUAT 1964 36.215913 31.395705 -4.326328 -0.1522877 -0.4147510 -0.0711453 0.8942754 +VERTEX_SE3:QUAT 1965 35.993194 30.499583 -5.022598 -0.3064029 0.2481794 -0.6660020 0.6332185 +VERTEX_SE3:QUAT 1966 36.090434 29.680508 -5.704347 -0.1819163 0.2262371 0.1315868 0.9478440 +VERTEX_SE3:QUAT 1967 36.091627 29.057099 -6.246483 0.0352039 0.5221779 -0.5765661 0.6274253 +VERTEX_SE3:QUAT 1968 36.062296 28.393696 -6.729518 0.0012020 0.2785945 0.9270569 0.2508968 +VERTEX_SE3:QUAT 1969 36.085443 27.514117 -7.329090 0.6392342 0.2018111 -0.6717227 0.3153418 +VERTEX_SE3:QUAT 1970 36.014567 26.605790 -7.921575 -0.0483796 -0.0365216 -0.5861717 0.8079161 +VERTEX_SE3:QUAT 1971 35.902402 25.696493 -8.504541 0.5496697 -0.0316132 -0.8091243 0.2053819 +VERTEX_SE3:QUAT 1972 35.875977 24.823424 -9.059341 -0.2175693 0.5743765 -0.7720216 0.1635172 +VERTEX_SE3:QUAT 1973 35.966156 23.825957 -9.430485 0.7735380 -0.0678537 0.5224660 0.3522274 +VERTEX_SE3:QUAT 1974 35.946114 22.923025 -9.844730 -0.3292991 -0.2400389 -0.3351780 0.8494699 +VERTEX_SE3:QUAT 1975 36.008364 21.850600 -10.323107 -0.4637370 0.2337524 -0.5662118 0.6400875 +VERTEX_SE3:QUAT 1976 36.105734 21.010307 -10.690642 0.6870169 -0.0934250 0.6581774 0.2933974 +VERTEX_SE3:QUAT 1977 35.896064 20.017371 -11.087912 -0.3999288 0.5729280 -0.6069604 0.3786944 +VERTEX_SE3:QUAT 1978 35.886442 18.913763 -11.349658 0.3632946 0.2020851 0.2683916 0.8689905 +VERTEX_SE3:QUAT 1979 35.800312 18.132672 -11.747817 -0.5599104 -0.2751627 -0.7524566 0.2111750 +VERTEX_SE3:QUAT 1980 36.728066 18.207836 -11.871853 -0.0500911 -0.4284281 0.8005015 0.4160981 +VERTEX_SE3:QUAT 1981 36.761910 19.089332 -11.367996 -0.0009351 -0.2975488 -0.2784030 0.9132117 +VERTEX_SE3:QUAT 1982 36.745555 19.838854 -10.854970 0.3457938 -0.6222122 0.3462502 0.6110560 +VERTEX_SE3:QUAT 1983 36.755886 20.818710 -10.302975 -0.1191565 -0.6655473 0.2306519 0.6997487 +VERTEX_SE3:QUAT 1984 36.706484 21.566488 -9.819196 0.3640208 -0.3104277 0.1658851 0.8623257 +VERTEX_SE3:QUAT 1985 36.882232 22.292371 -9.358759 0.1823392 0.4824948 -0.6695720 0.5344385 +VERTEX_SE3:QUAT 1986 36.920890 23.252810 -8.834564 -0.3941632 0.2369735 -0.8411766 0.2844308 +VERTEX_SE3:QUAT 1987 37.162902 24.020817 -8.209102 0.7737311 -0.1291224 0.1403406 0.6041292 +VERTEX_SE3:QUAT 1988 37.218504 24.767009 -7.583740 0.1180519 -0.3742651 0.6339282 0.6664266 +VERTEX_SE3:QUAT 1989 37.468537 25.475606 -7.116545 0.2022901 0.6700067 -0.2868829 0.6541161 +VERTEX_SE3:QUAT 1990 37.767902 26.097821 -6.556187 0.8137557 0.0074670 0.0603471 0.5780174 +VERTEX_SE3:QUAT 1991 37.904016 26.802091 -5.911245 -0.1157585 0.4107810 -0.8578563 0.2862543 +VERTEX_SE3:QUAT 1992 37.992824 27.625813 -5.324200 0.4352462 -0.5086052 0.6164976 0.4145024 +VERTEX_SE3:QUAT 1993 38.146548 28.519264 -4.752867 -0.3180334 0.0305518 -0.6388786 0.6998253 +VERTEX_SE3:QUAT 1994 38.201295 29.407998 -4.145115 0.4620182 -0.2009747 -0.1851812 0.8437157 +VERTEX_SE3:QUAT 1995 38.222213 30.200370 -3.639990 -0.3453301 0.1362269 0.0988579 0.9232640 +VERTEX_SE3:QUAT 1996 38.372553 30.907278 -3.006033 -0.0679932 -0.2774926 0.7222052 0.6299162 +VERTEX_SE3:QUAT 1997 38.485704 31.738645 -2.505709 0.5770240 0.2283079 0.7639674 0.1768406 +VERTEX_SE3:QUAT 1998 38.787600 32.553194 -1.894053 0.2035844 0.5571634 -0.5044554 0.6274130 +VERTEX_SE3:QUAT 1999 38.836981 33.380789 -1.361571 -0.4063110 -0.6761003 0.5281998 0.3143321 +VERTEX_SE3:QUAT 2000 35.474382 17.663425 -11.729953 0.2204481 0.1721718 -0.7314942 0.6218325 +VERTEX_SE3:QUAT 2001 35.774822 18.452902 -11.404374 0.5042054 0.6558969 -0.5292208 0.1884186 +VERTEX_SE3:QUAT 2002 35.960068 19.161642 -10.863088 0.6765921 -0.1879734 -0.6707103 0.2388238 +VERTEX_SE3:QUAT 2003 36.269463 19.812786 -10.122460 -0.1270188 0.0868233 -0.8705108 0.4674813 +VERTEX_SE3:QUAT 2004 36.456280 20.539609 -9.550864 0.2650122 0.4154476 -0.4988180 0.7129884 +VERTEX_SE3:QUAT 2005 36.649074 21.320966 -8.734144 -0.2963123 -0.4899017 0.6664208 0.4775758 +VERTEX_SE3:QUAT 2006 36.801668 22.134585 -8.120469 0.5653044 -0.4654587 -0.5369979 0.4188227 +VERTEX_SE3:QUAT 2007 37.189461 22.808296 -7.465115 0.7840709 0.2259332 -0.3607768 0.4516936 +VERTEX_SE3:QUAT 2008 37.499156 23.562315 -6.804328 0.7173804 0.0093311 -0.6191263 0.3193131 +VERTEX_SE3:QUAT 2009 37.708699 24.233671 -6.238820 -0.2136825 -0.2120853 -0.9281472 0.2188660 +VERTEX_SE3:QUAT 2010 38.000880 24.863693 -5.874079 -0.3768783 -0.2344139 0.5093787 0.7372559 +VERTEX_SE3:QUAT 2011 38.239534 25.752190 -5.366492 0.1465768 -0.4643747 -0.1078227 0.8667443 +VERTEX_SE3:QUAT 2012 38.359981 26.724461 -4.693729 0.2738159 0.0816437 0.0200789 0.9581002 +VERTEX_SE3:QUAT 2013 38.525748 27.418444 -4.109904 0.2644528 -0.1400163 0.8620779 0.4090011 +VERTEX_SE3:QUAT 2014 38.709290 28.353438 -3.404019 0.4199124 0.4712536 -0.7706879 0.0873713 +VERTEX_SE3:QUAT 2015 38.727585 29.120921 -2.890183 -0.3974768 -0.1457026 0.7072795 0.5661613 +VERTEX_SE3:QUAT 2016 38.894076 30.185822 -2.301214 0.4260530 -0.2372880 -0.2775675 0.8277255 +VERTEX_SE3:QUAT 2017 38.992036 31.070899 -1.780786 0.3776850 -0.4602917 -0.3734892 0.7113307 +VERTEX_SE3:QUAT 2018 39.058428 31.910531 -1.109597 0.5991987 0.0660061 0.3778458 0.7027352 +VERTEX_SE3:QUAT 2019 39.173074 32.666477 -0.675515 -0.5555481 0.4424953 -0.6146422 0.3431897 +VERTEX_SE3:QUAT 2020 38.113157 32.759938 -0.449813 0.2119254 0.3448605 -0.0309951 0.9138918 +VERTEX_SE3:QUAT 2021 38.137261 32.099794 -0.860054 0.1266890 -0.5819553 0.6244926 0.5052592 +VERTEX_SE3:QUAT 2022 38.035523 31.297831 -1.466566 0.5175812 0.2742287 -0.5942760 0.5511300 +VERTEX_SE3:QUAT 2023 37.992979 30.398147 -2.025289 -0.4132445 0.2610266 -0.8583786 0.1558209 +VERTEX_SE3:QUAT 2024 37.859813 29.593050 -2.677594 0.0543649 -0.2032913 -0.5376185 0.8165068 +VERTEX_SE3:QUAT 2025 37.795764 28.626141 -3.440775 -0.0098715 0.8342811 -0.2504555 0.4910699 +VERTEX_SE3:QUAT 2026 37.955594 28.059532 -4.216384 0.2610677 -0.2339615 0.8339469 0.4261904 +VERTEX_SE3:QUAT 2027 38.207211 27.465049 -4.885995 0.5139669 -0.0423045 0.8269288 0.2241364 +VERTEX_SE3:QUAT 2028 38.354837 26.801964 -5.499922 0.6131625 -0.0855064 0.5473211 0.5631696 +VERTEX_SE3:QUAT 2029 38.201850 26.094750 -6.307919 -0.1544112 0.3899976 -0.8712291 0.2549882 +VERTEX_SE3:QUAT 2030 38.149399 25.456351 -7.088732 0.4120705 -0.0681393 -0.8320050 0.3651337 +VERTEX_SE3:QUAT 2031 37.885120 24.722499 -7.648331 -0.1169233 -0.6311884 0.2048966 0.7388827 +VERTEX_SE3:QUAT 2032 37.959582 24.040819 -8.124279 -0.3708732 0.2365971 0.2833587 0.8521636 +VERTEX_SE3:QUAT 2033 37.844697 23.125071 -8.821570 0.6807853 -0.1530154 -0.4798624 0.5318362 +VERTEX_SE3:QUAT 2034 37.711628 22.302576 -9.394293 0.2685966 -0.1456534 -0.1895930 0.9331106 +VERTEX_SE3:QUAT 2035 37.667535 21.631484 -9.964006 0.7043447 -0.3606966 -0.2589594 0.5538380 +VERTEX_SE3:QUAT 2036 37.893579 20.857597 -10.561022 -0.2225582 -0.3537111 0.8475123 0.3272296 +VERTEX_SE3:QUAT 2037 37.552586 20.166216 -11.545671 0.7924931 0.2743334 -0.4823923 0.2529693 +VERTEX_SE3:QUAT 2038 37.544771 19.337578 -12.273304 -0.2060122 -0.8306335 0.4055598 0.3211359 +VERTEX_SE3:QUAT 2039 37.424191 18.795017 -12.984504 0.5641708 -0.3001616 0.4219164 0.6431181 +VERTEX_SE3:QUAT 2040 36.483076 18.977383 -13.042157 -0.1090062 -0.2233348 0.2465495 0.9367244 +VERTEX_SE3:QUAT 2041 36.703188 19.508052 -12.258675 -0.1398052 -0.4426454 0.8391018 0.2835979 +VERTEX_SE3:QUAT 2042 36.707369 20.088756 -11.315775 0.0380871 0.5640115 -0.2121358 0.7971441 +VERTEX_SE3:QUAT 2043 36.842090 20.691113 -10.605667 -0.3155473 0.1674660 -0.7106362 0.6061199 +VERTEX_SE3:QUAT 2044 36.759813 21.624615 -9.814171 -0.1907783 -0.0459090 -0.9622142 0.1887853 +VERTEX_SE3:QUAT 2045 36.894878 22.145088 -8.941222 0.5272361 -0.2801264 0.4639844 0.6544232 +VERTEX_SE3:QUAT 2046 37.100414 22.790655 -8.238987 -0.1793432 -0.4875038 0.7598311 0.3909383 +VERTEX_SE3:QUAT 2047 37.161815 23.594891 -7.421062 0.4435565 -0.1123700 -0.5919332 0.6635101 +VERTEX_SE3:QUAT 2048 37.492265 24.207347 -6.593863 0.7090952 0.2773044 -0.3607167 0.5386740 +VERTEX_SE3:QUAT 2049 37.780402 24.794455 -5.900413 0.3530243 0.5312354 -0.7290754 0.2482173 +VERTEX_SE3:QUAT 2050 37.929593 25.339051 -5.006931 0.7852670 -0.4404947 0.3750484 0.2205875 +VERTEX_SE3:QUAT 2051 37.909837 26.025079 -4.212325 0.5180554 0.4399054 -0.0889494 0.7281414 +VERTEX_SE3:QUAT 2052 38.103080 26.882872 -3.396624 -0.3608530 0.5346586 -0.6812073 0.3462397 +VERTEX_SE3:QUAT 2053 38.105394 27.544574 -2.733286 -0.1805200 0.3830986 -0.2463204 0.8717650 +VERTEX_SE3:QUAT 2054 37.869434 28.095597 -1.928218 0.1154297 0.7046145 -0.5431133 0.4418397 +VERTEX_SE3:QUAT 2055 37.680840 28.650056 -1.175286 0.7961041 -0.0962747 0.3326114 0.4963055 +VERTEX_SE3:QUAT 2056 37.434428 29.289738 -0.369146 0.2309181 -0.6018719 -0.0570044 0.7623501 +VERTEX_SE3:QUAT 2057 37.376925 30.109153 0.281007 0.1695182 0.1588730 0.5316817 0.8144554 +VERTEX_SE3:QUAT 2058 37.307716 30.756727 0.949225 -0.0725616 0.0764102 0.3044631 0.9466776 +VERTEX_SE3:QUAT 2059 37.202016 31.435252 1.754138 0.2236630 -0.6482990 0.2088186 0.6971930 +VERTEX_SE3:QUAT 2060 36.132959 31.412716 1.483918 -0.2865076 -0.2083962 0.7894376 0.5012710 +VERTEX_SE3:QUAT 2061 36.255703 30.691747 0.611054 -0.1057298 -0.1430373 0.7718229 0.6104515 +VERTEX_SE3:QUAT 2062 36.596182 29.989144 -0.341819 -0.5714992 -0.5065830 0.5526634 0.3336547 +VERTEX_SE3:QUAT 2063 36.642815 29.536580 -0.943693 -0.0373535 0.0813487 0.7873570 0.6099640 +VERTEX_SE3:QUAT 2064 36.878898 28.851113 -1.662645 -0.1372298 -0.0682063 0.1531473 0.9762488 +VERTEX_SE3:QUAT 2065 37.275388 28.212483 -2.392589 0.4192246 0.1137273 -0.7394433 0.5143350 +VERTEX_SE3:QUAT 2066 37.556137 27.612154 -3.118034 0.4933161 -0.5064813 -0.2603042 0.6575391 +VERTEX_SE3:QUAT 2067 37.738129 27.271234 -3.880655 -0.5062983 -0.0209571 0.8583123 0.0807642 +VERTEX_SE3:QUAT 2068 37.917578 26.845868 -4.577690 0.1830149 -0.5474128 -0.1067228 0.8096017 +VERTEX_SE3:QUAT 2069 38.240968 26.159856 -5.488697 0.0736692 -0.7355578 0.6596800 0.1354614 +VERTEX_SE3:QUAT 2070 38.535827 25.705284 -6.240170 0.2584907 -0.2937946 0.4828593 0.7833991 +VERTEX_SE3:QUAT 2071 38.457369 25.246384 -7.045253 0.0862609 -0.7808387 0.5138140 0.3447393 +VERTEX_SE3:QUAT 2072 38.632698 24.591216 -7.836290 0.1570286 -0.9112745 0.0883065 0.3703009 +VERTEX_SE3:QUAT 2073 38.843761 23.927274 -8.697805 -0.1124670 0.1049384 -0.7914392 0.5915768 +VERTEX_SE3:QUAT 2074 38.942288 23.389408 -9.423917 0.3296912 0.1506796 0.6251107 0.6912568 +VERTEX_SE3:QUAT 2075 39.135082 22.765740 -10.072106 -0.3011485 -0.1560445 -0.5089234 0.7911742 +VERTEX_SE3:QUAT 2076 39.398162 22.075761 -10.720542 -0.0434306 -0.8009632 0.1322901 0.5822981 +VERTEX_SE3:QUAT 2077 39.540341 21.459526 -11.459017 0.4538947 -0.1713812 -0.7983010 0.3568245 +VERTEX_SE3:QUAT 2078 39.703038 20.747703 -12.184162 0.5954705 0.2693528 0.1167804 0.7478143 +VERTEX_SE3:QUAT 2079 39.979977 20.089837 -12.908143 -0.0869705 -0.3966639 -0.4462266 0.7974809 +VERTEX_SE3:QUAT 2080 39.102985 20.093017 -13.061659 -0.0952368 -0.2870786 0.9286531 0.2147540 +VERTEX_SE3:QUAT 2081 38.647750 20.559698 -12.537805 0.4809399 0.0565669 0.5342361 0.6928844 +VERTEX_SE3:QUAT 2082 38.504761 21.229492 -11.884262 0.5838169 0.3422501 -0.2462064 0.6938336 +VERTEX_SE3:QUAT 2083 38.322508 21.879892 -11.098065 0.4162963 -0.5973809 -0.2065249 0.6535908 +VERTEX_SE3:QUAT 2084 37.993559 22.279980 -10.407550 0.5045790 0.0343729 0.8013296 0.3195143 +VERTEX_SE3:QUAT 2085 37.767688 22.988240 -9.860533 0.6865750 -0.2709174 0.3099751 0.5992779 +VERTEX_SE3:QUAT 2086 37.661524 23.921849 -9.329684 0.6662105 0.0518241 0.5930663 0.4491660 +VERTEX_SE3:QUAT 2087 37.378370 24.669665 -8.696248 -0.3654710 -0.8378099 0.2326205 0.3322548 +VERTEX_SE3:QUAT 2088 36.967374 25.228055 -7.960271 -0.1003020 -0.6025206 0.2904772 0.7365673 +VERTEX_SE3:QUAT 2089 36.823281 26.017527 -7.528992 0.7598126 -0.0007912 0.2368362 0.6054690 +VERTEX_SE3:QUAT 2090 36.685225 26.806383 -6.877024 -0.1174242 -0.6368163 0.4292790 0.6296000 +VERTEX_SE3:QUAT 2091 36.309868 27.508007 -6.331382 0.5018001 -0.2715816 -0.6519144 0.4994474 +VERTEX_SE3:QUAT 2092 36.112061 28.266013 -5.735491 -0.0870291 -0.0368451 0.4254599 0.9000290 +VERTEX_SE3:QUAT 2093 35.820697 29.163095 -4.991005 0.5292884 0.5179977 -0.4942763 0.4552178 +VERTEX_SE3:QUAT 2094 35.565462 29.771884 -4.352558 0.7360659 0.0501652 -0.5612556 0.3750767 +VERTEX_SE3:QUAT 2095 35.319941 30.469585 -3.613517 0.2336010 -0.6419743 -0.1394836 0.7168291 +VERTEX_SE3:QUAT 2096 35.301126 31.088258 -2.900762 0.4703870 -0.6331900 -0.2830621 0.5456027 +VERTEX_SE3:QUAT 2097 35.019061 31.875561 -2.031942 0.3991010 -0.4943981 -0.7532160 0.1701601 +VERTEX_SE3:QUAT 2098 34.879385 32.705037 -1.555437 -0.4475882 -0.1094156 0.8654971 0.1964888 +VERTEX_SE3:QUAT 2099 34.778726 33.439811 -0.923254 0.2504205 -0.0669124 -0.3031477 0.9170135 +VERTEX_SE3:QUAT 2100 33.846364 33.714807 -1.579466 0.2411619 -0.5803513 0.5060389 0.5907266 +VERTEX_SE3:QUAT 2101 33.863792 33.048247 -2.362899 0.1944613 -0.1578247 0.6009986 0.7589972 +VERTEX_SE3:QUAT 2102 33.909315 32.182924 -3.006374 0.3375295 -0.3240634 0.0809546 0.8800586 +VERTEX_SE3:QUAT 2103 33.954047 31.446974 -3.458258 0.8348233 -0.2018995 -0.2110813 0.4666384 +VERTEX_SE3:QUAT 2104 34.162136 30.645821 -4.143567 0.1607890 0.3044741 -0.5019586 0.7933977 +VERTEX_SE3:QUAT 2105 34.369443 29.919544 -4.626348 -0.1202348 0.1857324 0.5847950 0.7804242 +VERTEX_SE3:QUAT 2106 34.352545 29.220373 -4.995563 -0.3375342 0.0809102 0.8905074 0.2941440 +VERTEX_SE3:QUAT 2107 34.472264 28.464461 -5.621923 -0.1038091 -0.0947050 -0.5652046 0.8128950 +VERTEX_SE3:QUAT 2108 34.448887 27.627581 -6.162434 0.3826014 -0.5594819 -0.7301968 0.0860747 +VERTEX_SE3:QUAT 2109 34.583525 26.766110 -6.708842 0.0071572 -0.7328465 0.5920292 0.3352405 +VERTEX_SE3:QUAT 2110 34.828639 25.980249 -7.470234 0.0789488 0.2910418 0.6793106 0.6690283 +VERTEX_SE3:QUAT 2111 34.861567 25.123715 -8.005733 -0.0629438 0.2976214 -0.2349515 0.9231778 +VERTEX_SE3:QUAT 2112 34.570427 24.249498 -8.488070 -0.5376334 0.0843274 0.7089016 0.4486622 +VERTEX_SE3:QUAT 2113 34.584748 23.535303 -9.097238 0.4020200 0.3335719 -0.7869163 0.3284393 +VERTEX_SE3:QUAT 2114 34.478400 22.821418 -9.778024 0.4507447 -0.6260617 -0.0695480 0.6324864 +VERTEX_SE3:QUAT 2115 34.243881 21.928029 -10.477724 0.3654428 -0.6201933 0.3825659 0.5791849 +VERTEX_SE3:QUAT 2116 34.038518 21.184835 -11.232416 0.6682269 0.5216684 -0.5301345 0.0170966 +VERTEX_SE3:QUAT 2117 33.809608 20.428731 -11.859285 0.2590035 -0.3465362 -0.8613998 0.2661209 +VERTEX_SE3:QUAT 2118 33.617322 19.686905 -12.525045 0.4053524 -0.1850401 -0.4400256 0.7796326 +VERTEX_SE3:QUAT 2119 33.690999 19.079154 -13.191470 -0.3846923 -0.2671035 -0.6777734 0.5668252 +VERTEX_SE3:QUAT 2120 32.788800 19.571298 -13.662121 0.5011780 -0.2145832 0.0448328 0.8371169 +VERTEX_SE3:QUAT 2121 32.993997 20.286328 -13.070473 -0.1931885 0.2990347 -0.5656754 0.7438198 +VERTEX_SE3:QUAT 2122 33.145561 21.091208 -12.528030 0.6599995 0.1106166 -0.7212809 0.1786576 +VERTEX_SE3:QUAT 2123 33.272107 21.736121 -12.073806 -0.5298057 0.0131013 0.7634663 0.3691253 +VERTEX_SE3:QUAT 2124 33.260757 22.524362 -11.475044 0.3396398 0.0969528 -0.7190658 0.5984892 +VERTEX_SE3:QUAT 2125 33.409787 23.151529 -10.766849 0.4418778 -0.6665465 -0.5120532 0.3134666 +VERTEX_SE3:QUAT 2126 33.575243 23.922118 -9.954646 0.0709258 0.2275091 -0.4581063 0.8563573 +VERTEX_SE3:QUAT 2127 33.785517 24.687430 -9.430425 -0.3195912 -0.0281570 -0.4907785 0.8100649 +VERTEX_SE3:QUAT 2128 34.064027 25.515543 -8.754082 -0.4464872 -0.0968588 -0.1429465 0.8779715 +VERTEX_SE3:QUAT 2129 34.115873 26.258357 -8.044973 0.7071119 0.1434623 0.4965409 0.4825541 +VERTEX_SE3:QUAT 2130 34.380285 27.124555 -7.517986 0.5309271 0.1325118 -0.0414257 0.8359671 +VERTEX_SE3:QUAT 2131 34.618676 27.944819 -6.801418 -0.2220783 0.5145666 -0.8148612 0.1479991 +VERTEX_SE3:QUAT 2132 34.410426 28.711893 -6.109299 0.1357900 0.3594100 -0.3743862 0.8439316 +VERTEX_SE3:QUAT 2133 34.485273 29.472326 -5.561865 0.6276920 -0.2173238 0.3721394 0.6482942 +VERTEX_SE3:QUAT 2134 34.491548 30.330879 -5.000705 0.1773803 -0.3205558 0.1721877 0.9144023 +VERTEX_SE3:QUAT 2135 34.572769 31.247545 -4.408714 -0.0926424 -0.4392197 -0.0826264 0.8897620 +VERTEX_SE3:QUAT 2136 34.670195 32.000410 -3.956283 0.6506495 0.4301933 -0.6223572 0.0652727 +VERTEX_SE3:QUAT 2137 34.601491 32.902110 -3.571068 0.3286331 0.2903603 0.4716791 0.7649902 +VERTEX_SE3:QUAT 2138 34.551552 33.548316 -3.271324 -0.5145967 -0.4573215 0.2540325 0.6793488 +VERTEX_SE3:QUAT 2139 34.520483 34.414148 -2.721659 -0.4193548 -0.1145235 0.3607540 0.8251560 +VERTEX_SE3:QUAT 2140 33.625934 34.862727 -3.134946 0.6344081 -0.3584867 -0.2574210 0.6346244 +VERTEX_SE3:QUAT 2141 33.517354 33.964963 -3.333543 -0.3726491 0.0491314 0.0819120 0.9230434 +VERTEX_SE3:QUAT 2142 33.580819 33.106061 -3.793130 0.1629960 0.6698123 -0.6810541 0.2468787 +VERTEX_SE3:QUAT 2143 33.612699 32.350649 -4.200764 0.4818356 -0.2435376 -0.7766618 0.3245308 +VERTEX_SE3:QUAT 2144 33.386042 31.506049 -4.871627 0.5779373 0.5149918 -0.5958766 0.2137827 +VERTEX_SE3:QUAT 2145 33.449029 30.710372 -5.439709 0.3375853 -0.2115669 0.1924353 0.8967967 +VERTEX_SE3:QUAT 2146 33.286279 29.951434 -5.887507 -0.3393660 -0.5128672 0.5867616 0.5267910 +VERTEX_SE3:QUAT 2147 33.219689 29.182312 -6.238416 -0.0463796 -0.8388670 0.1532031 0.5202690 +VERTEX_SE3:QUAT 2148 33.265629 28.368849 -6.688410 0.2800614 -0.6533258 0.4080065 0.5729413 +VERTEX_SE3:QUAT 2149 33.294698 27.645913 -6.989610 -0.4481096 -0.4304627 -0.2452324 0.7441510 +VERTEX_SE3:QUAT 2150 33.124241 26.810973 -7.444991 0.1715227 -0.3613101 -0.5101367 0.7614431 +VERTEX_SE3:QUAT 2151 33.092895 25.893098 -8.167177 0.8115389 0.0249370 -0.1417581 0.5662927 +VERTEX_SE3:QUAT 2152 32.970138 25.139809 -8.619998 0.0011933 -0.0856873 0.3506817 0.9325656 +VERTEX_SE3:QUAT 2153 32.954624 24.334992 -9.156821 0.0520318 -0.3722238 -0.8791259 0.2930526 +VERTEX_SE3:QUAT 2154 32.908138 23.297163 -9.754960 0.1326511 0.6231456 -0.4882711 0.5963930 +VERTEX_SE3:QUAT 2155 32.753206 22.339860 -10.231396 0.3336085 -0.6405102 -0.5489794 0.4208012 +VERTEX_SE3:QUAT 2156 32.790816 21.489688 -10.513770 -0.1199886 -0.5765733 0.8081862 0.0009774 +VERTEX_SE3:QUAT 2157 32.783449 20.734855 -10.922483 0.0381031 0.0803023 -0.5849600 0.8061771 +VERTEX_SE3:QUAT 2158 32.705227 19.795495 -11.465969 0.6154661 -0.6523811 0.2824133 0.3403574 +VERTEX_SE3:QUAT 2159 32.444461 18.925751 -11.887904 -0.6878474 -0.0767659 0.6736723 0.2591111 +VERTEX_SE3:QUAT 2160 31.739140 19.263008 -12.375322 0.6173933 0.4410520 -0.5725015 0.3107100 +VERTEX_SE3:QUAT 2161 31.630996 20.003303 -11.681774 0.6732626 0.6584236 -0.2949059 0.1619455 +VERTEX_SE3:QUAT 2162 31.638845 20.933331 -11.124155 0.0225144 -0.3573699 0.5485040 0.7555946 +VERTEX_SE3:QUAT 2163 31.473192 21.677633 -10.222522 0.6259497 0.1027785 -0.5951799 0.4933400 +VERTEX_SE3:QUAT 2164 31.514011 22.479635 -9.537843 0.7267402 -0.4297771 -0.3871716 0.3704571 +VERTEX_SE3:QUAT 2165 31.408100 23.149313 -8.767192 0.7333799 -0.3865967 -0.5170900 0.2128728 +VERTEX_SE3:QUAT 2166 31.203430 23.921354 -7.938636 0.2294089 0.1054236 0.7037585 0.6640643 +VERTEX_SE3:QUAT 2167 30.886307 24.746317 -7.331915 0.2232467 -0.1151831 -0.9450108 0.2094001 +VERTEX_SE3:QUAT 2168 30.725036 25.590561 -6.511615 0.6259725 -0.4339942 0.4765795 0.4389527 +VERTEX_SE3:QUAT 2169 30.643535 26.307770 -5.684751 0.3393920 -0.1274506 -0.6897137 0.6267890 +VERTEX_SE3:QUAT 2170 30.586142 27.026742 -4.807113 -0.3309845 -0.8124896 0.4122880 0.2456186 +VERTEX_SE3:QUAT 2171 30.424743 27.669556 -4.063935 0.1669865 -0.8574446 0.1266149 0.4699711 +VERTEX_SE3:QUAT 2172 30.236917 28.171309 -3.181659 -0.0953540 0.5231529 -0.6565527 0.5349367 +VERTEX_SE3:QUAT 2173 30.104176 28.669846 -2.264353 0.4290513 -0.0312232 0.0130567 0.9026459 +VERTEX_SE3:QUAT 2174 30.005172 29.168248 -1.488026 0.0681532 -0.2844465 0.6950507 0.6567723 +VERTEX_SE3:QUAT 2175 29.874448 29.674258 -0.693439 0.1216809 -0.1029540 -0.0060305 0.9871970 +VERTEX_SE3:QUAT 2176 29.731280 30.237162 -0.075617 -0.2304837 -0.0534169 0.8142017 0.5301881 +VERTEX_SE3:QUAT 2177 29.490660 31.013231 0.593520 -0.3247145 -0.7684921 0.1292217 0.5359870 +VERTEX_SE3:QUAT 2178 29.471035 31.680171 1.478536 0.6001171 -0.6450265 -0.3710888 0.2934167 +VERTEX_SE3:QUAT 2179 29.527858 32.372823 2.106533 0.1587566 0.1506025 -0.0172744 0.9756110 +VERTEX_SE3:QUAT 2180 28.816373 32.929173 1.636672 0.7115732 -0.4880609 0.4033422 0.3045904 +VERTEX_SE3:QUAT 2181 28.581564 32.294358 0.800028 -0.0570173 -0.8906828 0.1898601 0.4091288 +VERTEX_SE3:QUAT 2182 28.679222 31.638331 0.172143 0.1961826 -0.6286535 0.0925996 0.7468149 +VERTEX_SE3:QUAT 2183 28.568360 31.077464 -0.508893 0.3800140 0.0105950 0.7199751 0.5806143 +VERTEX_SE3:QUAT 2184 28.563043 30.377306 -1.146734 0.4002689 -0.6402387 -0.4959352 0.4288677 +VERTEX_SE3:QUAT 2185 28.695264 29.792566 -2.021614 0.3368178 0.0104208 0.5937441 0.7306936 +VERTEX_SE3:QUAT 2186 28.731007 29.044013 -2.703065 0.5033165 -0.4012295 -0.5060014 0.5741515 +VERTEX_SE3:QUAT 2187 28.627557 28.328473 -3.497976 0.1749458 -0.4140296 -0.4665220 0.7617944 +VERTEX_SE3:QUAT 2188 28.654950 27.881001 -4.299171 0.2824078 -0.4187878 0.8630418 0.0046280 +VERTEX_SE3:QUAT 2189 28.548654 27.371965 -5.131957 0.4067104 -0.2937575 0.7193086 0.4805083 +VERTEX_SE3:QUAT 2190 28.363414 26.843100 -6.009788 0.8399216 0.1935632 0.0837834 0.5000453 +VERTEX_SE3:QUAT 2191 28.207091 26.195053 -6.728356 -0.1214783 0.0847208 -0.9862626 0.0731542 +VERTEX_SE3:QUAT 2192 28.063309 25.468128 -7.314011 -0.1661665 0.1964651 -0.3673765 0.8937699 +VERTEX_SE3:QUAT 2193 27.786869 24.732070 -7.960767 0.4757152 0.3844647 -0.6682782 0.4234220 +VERTEX_SE3:QUAT 2194 27.771558 23.931388 -8.747402 0.4394217 -0.4723418 0.0214200 0.7637689 +VERTEX_SE3:QUAT 2195 27.999038 23.101439 -9.329852 -0.1383075 0.1668020 0.7299268 0.6482707 +VERTEX_SE3:QUAT 2196 27.897261 22.249328 -9.845359 0.6357873 -0.0772229 0.5312551 0.5545982 +VERTEX_SE3:QUAT 2197 27.790663 21.348347 -10.374930 0.6785415 0.2428609 -0.6448708 0.2544438 +VERTEX_SE3:QUAT 2198 27.822495 20.474379 -10.761694 0.4806977 -0.3304855 0.2756898 0.7640053 +VERTEX_SE3:QUAT 2199 27.710598 19.680408 -11.148037 -0.3338008 -0.1085604 0.9312466 0.0978336 +VERTEX_SE3:QUAT 2200 26.984308 19.687271 -11.522542 0.7096754 -0.0716763 0.1840454 0.6762770 +VERTEX_SE3:QUAT 2201 26.964807 20.528041 -11.155582 0.1810722 0.0828126 -0.1732688 0.9645376 +VERTEX_SE3:QUAT 2202 26.918876 21.311158 -10.636219 0.0974779 -0.3474144 0.5966970 0.7167663 +VERTEX_SE3:QUAT 2203 26.630791 22.236785 -10.145194 0.5333649 -0.1375216 0.3710206 0.7476319 +VERTEX_SE3:QUAT 2204 26.475858 23.154403 -9.547034 0.4470392 0.1668379 0.2667950 0.8373419 +VERTEX_SE3:QUAT 2205 26.262831 24.031198 -8.973647 0.1262966 -0.4508010 0.8714695 0.1461797 +VERTEX_SE3:QUAT 2206 26.122014 25.044930 -8.550003 0.4230467 0.3388359 0.5688161 0.6186032 +VERTEX_SE3:QUAT 2207 26.115574 26.155539 -8.169253 -0.3378060 0.1258047 -0.7529855 0.5505207 +VERTEX_SE3:QUAT 2208 26.268195 27.107623 -7.756525 -0.1194175 0.4633086 0.8103537 0.3382476 +VERTEX_SE3:QUAT 2209 26.189851 27.955745 -7.261664 0.6228750 0.2489019 0.0698408 0.7383744 +VERTEX_SE3:QUAT 2210 26.228845 28.918509 -6.999686 0.7556606 -0.0806312 -0.4428653 0.4757583 +VERTEX_SE3:QUAT 2211 26.209326 29.787201 -6.492593 0.2420818 0.1021977 -0.2534683 0.9309704 +VERTEX_SE3:QUAT 2212 26.172132 30.683855 -6.068384 -0.4318810 0.3781580 0.6633814 0.4800005 +VERTEX_SE3:QUAT 2213 26.283505 31.491343 -5.733965 0.1965319 0.5777891 -0.7683952 0.1926234 +VERTEX_SE3:QUAT 2214 26.264139 32.253416 -5.403020 -0.2566123 -0.0191726 0.0619334 0.9643375 +VERTEX_SE3:QUAT 2215 26.113645 33.200614 -5.096726 0.6144104 -0.3152374 -0.2015081 0.6946364 +VERTEX_SE3:QUAT 2216 26.051820 34.220552 -4.699679 -0.2964389 -0.7788103 0.4139105 0.3664104 +VERTEX_SE3:QUAT 2217 26.348883 35.197184 -4.235347 -0.6355881 -0.3636776 0.3226145 0.5997385 +VERTEX_SE3:QUAT 2218 26.301717 36.123588 -3.919087 -0.1310412 -0.7998869 0.5253338 0.2589082 +VERTEX_SE3:QUAT 2219 26.338825 37.090716 -3.549512 0.1436747 0.1182439 0.4442323 0.8763753 +VERTEX_SE3:QUAT 2220 25.557807 37.326567 -3.904330 -0.6118046 -0.1876898 0.1554196 0.7525373 +VERTEX_SE3:QUAT 2221 25.565183 36.140541 -4.420084 -0.1933293 -0.2396270 -0.0418083 0.9505024 +VERTEX_SE3:QUAT 2222 25.827135 35.340558 -4.901392 -0.3866982 -0.7469661 0.5406908 0.0126360 +VERTEX_SE3:QUAT 2223 25.942810 34.379822 -5.394401 0.8243915 0.0750698 -0.4192961 0.3727384 +VERTEX_SE3:QUAT 2224 25.963912 33.593198 -5.691270 0.0451290 0.4748149 -0.5662196 0.6722422 +VERTEX_SE3:QUAT 2225 25.907783 32.434397 -6.240197 0.2324695 -0.2021706 -0.0996372 0.9461276 +VERTEX_SE3:QUAT 2226 25.688747 31.561257 -6.846388 0.1688521 -0.5307134 -0.4965649 0.6657744 +VERTEX_SE3:QUAT 2227 25.591939 30.735659 -7.410834 0.3969672 0.0625353 -0.8630055 0.3061501 +VERTEX_SE3:QUAT 2228 25.445239 29.984332 -8.072855 0.6373261 0.3949982 -0.5039538 0.4287451 +VERTEX_SE3:QUAT 2229 25.226426 29.095476 -8.788913 -0.6051884 -0.0159331 0.6335060 0.4818333 +VERTEX_SE3:QUAT 2230 24.942689 28.449211 -9.392349 0.5544719 -0.2049457 0.2436724 0.7688835 +VERTEX_SE3:QUAT 2231 24.414741 27.750026 -10.057758 -0.3691609 0.1674978 0.5876018 0.7002777 +VERTEX_SE3:QUAT 2232 24.437662 27.077710 -10.763245 0.1498812 0.0572643 0.3891891 0.9070768 +VERTEX_SE3:QUAT 2233 24.127389 26.416202 -11.238612 -0.2339712 0.2863416 0.6673848 0.6464236 +VERTEX_SE3:QUAT 2234 23.845944 25.627516 -11.717811 0.3218481 -0.2813385 0.5312365 0.7314712 +VERTEX_SE3:QUAT 2235 23.864433 24.755380 -12.277537 -0.0060113 0.0804692 0.9762692 0.2009654 +VERTEX_SE3:QUAT 2236 23.823942 23.914580 -12.978399 -0.2278131 -0.3084491 0.5357597 0.7522778 +VERTEX_SE3:QUAT 2237 23.792268 23.123233 -13.615900 -0.1004706 -0.4148668 0.3642516 0.8277149 +VERTEX_SE3:QUAT 2238 23.727506 22.332495 -14.456099 0.1895743 -0.4840842 -0.8034862 0.2900585 +VERTEX_SE3:QUAT 2239 23.665988 21.606678 -15.132388 0.5625270 -0.1316404 0.5972770 0.5563222 +VERTEX_SE3:QUAT 2240 23.085772 22.100350 -15.767269 0.3817428 -0.5416517 -0.7408025 0.1099886 +VERTEX_SE3:QUAT 2241 23.286111 22.843842 -15.065139 0.5226568 -0.4849563 0.4833239 0.5079815 +VERTEX_SE3:QUAT 2242 23.426532 23.511043 -14.412662 -0.9446689 0.1812539 0.2729896 0.0149787 +VERTEX_SE3:QUAT 2243 23.550629 24.044550 -13.712556 0.1501414 0.1334431 -0.7861433 0.5844906 +VERTEX_SE3:QUAT 2244 23.687774 24.859363 -12.921112 0.1958415 0.0420826 0.2614193 0.9442114 +VERTEX_SE3:QUAT 2245 23.945850 25.751270 -12.042614 -0.0221087 -0.5362134 0.8292676 0.1558899 +VERTEX_SE3:QUAT 2246 23.981818 26.415865 -11.134281 0.3529057 -0.6068165 -0.2289717 0.6743910 +VERTEX_SE3:QUAT 2247 24.098737 27.020251 -10.315856 -0.5808814 0.1658554 0.6046830 0.5190639 +VERTEX_SE3:QUAT 2248 24.254038 27.550633 -9.504185 -0.2094892 -0.7952654 0.4775379 0.3092327 +VERTEX_SE3:QUAT 2249 24.497848 27.928605 -8.783000 -0.1601626 0.0869254 -0.8184797 0.5448696 +VERTEX_SE3:QUAT 2250 24.649057 28.744076 -7.769648 -0.5054729 -0.4183054 0.7401900 0.1470932 +VERTEX_SE3:QUAT 2251 24.697440 29.274040 -6.959412 0.7401139 -0.5375280 -0.0896450 0.3940290 +VERTEX_SE3:QUAT 2252 24.762319 29.820368 -6.252041 0.8645412 -0.3248266 -0.2560855 0.2854407 +VERTEX_SE3:QUAT 2253 24.794021 30.403657 -5.421361 0.0646204 -0.0354748 -0.8466194 0.5270686 +VERTEX_SE3:QUAT 2254 25.020343 31.097033 -4.647542 0.3706748 0.0219477 -0.1187243 0.9208816 +VERTEX_SE3:QUAT 2255 25.203386 31.689130 -3.986548 0.6195452 -0.6757223 -0.3332337 0.2202689 +VERTEX_SE3:QUAT 2256 25.444581 32.114776 -3.110348 0.2174505 -0.4940538 -0.3690162 0.7566064 +VERTEX_SE3:QUAT 2257 25.633822 32.614020 -2.154004 0.2602087 0.0721415 -0.5361410 0.7997749 +VERTEX_SE3:QUAT 2258 25.886178 33.111588 -1.201548 0.8762146 -0.3101041 -0.0659623 0.3629497 +VERTEX_SE3:QUAT 2259 26.171230 33.619933 -0.339261 -0.6725670 -0.1298284 0.7224251 0.0943408 +VERTEX_SE3:QUAT 2260 25.566216 34.440906 -0.571133 0.1846178 0.5659386 -0.7441779 0.3030330 +VERTEX_SE3:QUAT 2261 25.597486 34.032180 -1.361355 0.7488499 -0.1158552 -0.2454765 0.6046013 +VERTEX_SE3:QUAT 2262 25.426368 33.542635 -2.377762 -0.1145345 0.0806555 0.5069522 0.8505151 +VERTEX_SE3:QUAT 2263 25.205811 33.136723 -3.370729 0.2774990 -0.1447471 0.3683961 0.8754010 +VERTEX_SE3:QUAT 2264 24.865289 32.681900 -4.054665 0.1787370 -0.0332929 -0.8198219 0.5429888 +VERTEX_SE3:QUAT 2265 24.614036 32.282577 -5.054976 0.9020307 -0.2225742 -0.1506229 0.3378078 +VERTEX_SE3:QUAT 2266 24.437693 32.048970 -5.956348 -0.4468263 -0.1677586 0.6093541 0.6331595 +VERTEX_SE3:QUAT 2267 24.153501 31.597584 -6.759136 0.3383471 0.8044634 -0.4567104 0.1725557 +VERTEX_SE3:QUAT 2268 23.813169 31.002141 -7.630478 -0.4422138 -0.2046339 -0.0454373 0.8720707 +VERTEX_SE3:QUAT 2269 23.503256 30.553493 -8.443212 -0.4389087 -0.4326088 0.5353468 0.5775920 +VERTEX_SE3:QUAT 2270 22.937352 30.002509 -9.209815 0.0471526 0.2215548 0.7510391 0.6201858 +VERTEX_SE3:QUAT 2271 22.712612 29.399344 -10.005229 -0.4951784 -0.4903656 0.4293930 0.5744229 +VERTEX_SE3:QUAT 2272 22.351240 28.794505 -10.679904 -0.6097030 0.0462991 0.7347893 0.2936040 +VERTEX_SE3:QUAT 2273 21.913751 28.287431 -11.299461 -0.1399138 -0.2732135 0.6775414 0.6683683 +VERTEX_SE3:QUAT 2274 21.567794 27.753541 -12.213204 0.0464776 -0.1004427 0.1885112 0.9758149 +VERTEX_SE3:QUAT 2275 21.257709 27.166078 -13.187986 0.1195601 -0.8093440 0.0704786 0.5707016 +VERTEX_SE3:QUAT 2276 20.924777 26.805317 -14.057238 -0.3800302 -0.6921241 0.0446584 0.6120024 +VERTEX_SE3:QUAT 2277 20.694857 26.401393 -14.865171 -0.0321897 0.4023292 -0.5156186 0.7557992 +VERTEX_SE3:QUAT 2278 20.504403 25.820993 -15.586290 0.3997833 -0.3665707 0.8152813 0.2027701 +VERTEX_SE3:QUAT 2279 20.224589 25.428546 -16.302709 0.5507735 -0.5782714 0.1336332 0.5868500 +VERTEX_SE3:QUAT 2280 19.352810 26.164859 -16.353853 0.1935722 -0.4344576 0.7210109 0.5039044 +VERTEX_SE3:QUAT 2281 19.738003 26.843635 -15.679565 -0.0658301 0.1055249 -0.9461148 0.2989944 +VERTEX_SE3:QUAT 2282 19.979613 27.269254 -15.093811 0.7118802 0.5450425 -0.4381298 0.0647887 +VERTEX_SE3:QUAT 2283 20.336997 27.813573 -14.335084 -0.1813469 0.1642682 0.6442241 0.7246410 +VERTEX_SE3:QUAT 2284 20.737808 28.258278 -13.704801 -0.2450356 -0.7239021 0.5853839 0.2706457 +VERTEX_SE3:QUAT 2285 21.295145 28.932309 -12.963162 0.0160497 0.0132650 0.9632369 0.2678454 +VERTEX_SE3:QUAT 2286 21.603414 29.548054 -12.383010 0.5251188 -0.4061249 0.4474144 0.5992773 +VERTEX_SE3:QUAT 2287 21.843004 29.960045 -11.627174 -0.1193860 -0.8985082 0.1954656 0.3744639 +VERTEX_SE3:QUAT 2288 22.246777 30.335512 -10.747923 0.0377132 -0.0352324 -0.9337791 0.3541088 +VERTEX_SE3:QUAT 2289 22.513050 30.852072 -9.761754 -0.1148273 -0.4604232 -0.4097544 0.7790548 +VERTEX_SE3:QUAT 2290 22.861594 31.142507 -8.938721 0.3725544 -0.5992533 -0.6354349 0.3135622 +VERTEX_SE3:QUAT 2291 23.262666 31.667288 -8.158598 -0.3262469 0.3570526 0.8611170 0.1566968 +VERTEX_SE3:QUAT 2292 23.535301 32.334420 -7.414272 0.7644912 -0.1956128 -0.6076174 0.0899443 +VERTEX_SE3:QUAT 2293 23.891497 32.990364 -6.731487 0.2347886 0.3010644 0.9195765 0.0928098 +VERTEX_SE3:QUAT 2294 24.357982 33.769462 -6.146503 -0.0431204 -0.6877210 0.6281716 0.3613597 +VERTEX_SE3:QUAT 2295 24.724371 34.393457 -5.596603 0.2139175 0.1286865 0.9531084 0.1710656 +VERTEX_SE3:QUAT 2296 24.881459 34.997716 -5.026930 0.5079693 0.0120023 0.3593064 0.7827657 +VERTEX_SE3:QUAT 2297 25.282107 35.609411 -4.313560 -0.4448358 0.4945622 0.6209560 0.4146601 +VERTEX_SE3:QUAT 2298 25.596554 36.272897 -3.582785 0.1857040 -0.5581079 -0.2459261 0.7704219 +VERTEX_SE3:QUAT 2299 25.904048 36.907726 -2.997756 -0.4981809 0.0225294 -0.0188513 0.8665754 +VERTEX_SE3:QUAT 2300 25.193315 37.441294 -3.475448 0.5199830 -0.1597611 -0.0934282 0.8338856 +VERTEX_SE3:QUAT 2301 24.832729 36.797906 -4.123272 0.4206786 0.0543932 -0.3231266 0.8459670 +VERTEX_SE3:QUAT 2302 24.457144 35.936990 -4.731521 0.2246642 0.1269805 -0.1064952 0.9602399 +VERTEX_SE3:QUAT 2303 24.178474 35.186655 -5.282031 0.1237795 -0.3554965 0.8705904 0.3168173 +VERTEX_SE3:QUAT 2304 23.646583 34.240722 -5.892926 0.0615161 0.1481450 0.6364006 0.7544952 +VERTEX_SE3:QUAT 2305 23.269262 33.474032 -6.353885 0.1607384 -0.1723740 -0.5386817 0.8088711 +VERTEX_SE3:QUAT 2306 22.969032 32.586279 -6.680848 0.1261669 0.0257675 -0.7996759 0.5864610 +VERTEX_SE3:QUAT 2307 22.417561 31.884879 -7.048497 0.1269347 0.2892446 0.9462622 0.0693755 +VERTEX_SE3:QUAT 2308 22.038241 31.036296 -7.419058 -0.3873368 -0.2953170 -0.2919758 0.8231089 +VERTEX_SE3:QUAT 2309 21.590654 30.342422 -8.000994 0.3332240 0.0859911 0.1607190 0.9250604 +VERTEX_SE3:QUAT 2310 21.188105 29.564504 -8.521267 -0.1986326 -0.0242797 0.9386435 0.2808984 +VERTEX_SE3:QUAT 2311 20.686873 28.701541 -9.086426 -0.4743662 -0.1599171 0.8302882 0.2449994 +VERTEX_SE3:QUAT 2312 20.287633 27.984085 -9.546500 -0.6091545 0.0075812 0.1014388 0.7865008 +VERTEX_SE3:QUAT 2313 19.814590 27.165112 -10.008752 -0.0192039 -0.4062332 -0.6111831 0.6790147 +VERTEX_SE3:QUAT 2314 19.425233 26.359029 -10.427900 0.0556691 0.0102418 0.3138279 0.9477912 +VERTEX_SE3:QUAT 2315 18.906601 25.398663 -11.068825 -0.2814891 -0.0989615 0.0153496 0.9543243 +VERTEX_SE3:QUAT 2316 18.309386 24.735508 -11.478757 0.2226182 -0.4078121 0.0203779 0.8852769 +VERTEX_SE3:QUAT 2317 17.848729 24.023053 -12.080122 -0.1530423 0.1898207 -0.0713096 0.9671924 +VERTEX_SE3:QUAT 2318 17.607136 23.298961 -12.207144 -0.3333100 -0.5777132 0.2152033 0.7133299 +VERTEX_SE3:QUAT 2319 17.015956 22.557787 -12.542487 0.1923491 -0.1122714 0.8138478 0.5367016 +VERTEX_SE3:QUAT 2320 16.275861 23.227953 -12.979715 0.6734592 -0.1085747 -0.1918198 0.7055987 +VERTEX_SE3:QUAT 2321 17.049956 23.768763 -12.721141 -0.6700356 -0.0008362 -0.0134589 0.7422065 +VERTEX_SE3:QUAT 2322 17.805213 24.396351 -12.227136 -0.0237677 -0.7691776 -0.5890942 0.2465135 +VERTEX_SE3:QUAT 2323 18.432102 25.006630 -11.956012 -0.0926757 0.2208165 0.9646490 0.1100166 +VERTEX_SE3:QUAT 2324 19.084601 25.556918 -11.698443 -0.3189740 -0.5581296 0.7659515 0.0080773 +VERTEX_SE3:QUAT 2325 19.877059 26.302530 -11.600876 -0.7613477 -0.1206447 0.4771137 0.4220865 +VERTEX_SE3:QUAT 2326 20.519315 27.153906 -11.416659 -0.1840733 -0.3964031 -0.8713430 0.2230316 +VERTEX_SE3:QUAT 2327 21.333253 27.976622 -11.251015 0.0880829 -0.0505563 -0.4315901 0.8963344 +VERTEX_SE3:QUAT 2328 21.877065 28.657484 -11.176372 -0.4037124 0.0763009 -0.3139370 0.8559427 +VERTEX_SE3:QUAT 2329 22.678706 29.317825 -11.108989 -0.7950203 -0.2799294 0.3970886 0.3631845 +VERTEX_SE3:QUAT 2330 23.367559 29.808059 -10.571820 -0.2233600 -0.2164674 -0.6686490 0.6753967 +VERTEX_SE3:QUAT 2331 24.206627 30.424056 -10.165418 -0.2656794 -0.5417370 -0.7792442 0.1694517 +VERTEX_SE3:QUAT 2332 24.988267 30.781180 -9.780119 -0.1017486 0.4349912 0.8438540 0.2972210 +VERTEX_SE3:QUAT 2333 25.849663 31.266432 -9.559165 0.0980415 -0.3548725 -0.0307134 0.9292524 +VERTEX_SE3:QUAT 2334 26.815301 31.712172 -9.326314 0.1936279 -0.6192505 0.7305890 0.2127833 +VERTEX_SE3:QUAT 2335 27.600358 32.229062 -9.099518 -0.4812907 0.0837790 0.3831794 0.7839094 +VERTEX_SE3:QUAT 2336 28.337246 32.701983 -8.884101 -0.0312424 -0.3508727 -0.4031538 0.8446179 +VERTEX_SE3:QUAT 2337 29.116329 33.145628 -8.657532 -0.4616972 -0.5635227 0.6745689 0.1193087 +VERTEX_SE3:QUAT 2338 30.088444 33.525568 -8.520372 -0.0781258 -0.2316752 -0.9656010 0.0885305 +VERTEX_SE3:QUAT 2339 31.119156 33.983928 -8.277830 0.5323341 -0.5573593 0.0025848 0.6371534 +VERTEX_SE3:QUAT 2340 30.669078 34.872004 -8.397480 -0.6789410 -0.1156807 0.6720090 0.2721415 +VERTEX_SE3:QUAT 2341 29.833755 34.426687 -8.721758 0.2157777 0.1238140 -0.0603827 0.9666768 +VERTEX_SE3:QUAT 2342 29.017599 33.910310 -8.988482 -0.1875115 -0.2380833 -0.7098927 0.6357736 +VERTEX_SE3:QUAT 2343 28.046076 33.552476 -9.177090 0.2281539 0.1580086 -0.1113713 0.9542408 +VERTEX_SE3:QUAT 2344 27.294716 33.009134 -9.344442 0.4590418 -0.4415902 -0.3492749 0.6872305 +VERTEX_SE3:QUAT 2345 26.501810 32.543006 -9.686073 0.2111853 -0.2463759 -0.0419466 0.9449551 +VERTEX_SE3:QUAT 2346 25.664137 32.063394 -10.099031 0.4020686 0.0516798 -0.8165817 0.4109311 +VERTEX_SE3:QUAT 2347 24.897790 31.572376 -10.593114 -0.4463056 0.5553604 0.6886316 0.1348057 +VERTEX_SE3:QUAT 2348 24.219397 31.108481 -11.020111 -0.1188653 -0.6182320 -0.7259496 0.2768708 +VERTEX_SE3:QUAT 2349 23.217908 30.681095 -11.380573 -0.0075468 -0.5317391 -0.4171323 0.7370192 +VERTEX_SE3:QUAT 2350 22.666691 30.114576 -11.663805 0.1601317 -0.7110429 -0.3843893 0.5665869 +VERTEX_SE3:QUAT 2351 21.747955 29.682371 -12.048933 -0.4453836 -0.1440638 -0.3021116 0.8304262 +VERTEX_SE3:QUAT 2352 20.896537 29.140975 -12.246850 -0.3701842 0.6100383 0.6966818 0.0738332 +VERTEX_SE3:QUAT 2353 20.115034 28.473708 -12.548386 0.1554224 -0.0651537 0.9717193 0.1654103 +VERTEX_SE3:QUAT 2354 19.361444 27.838196 -12.838977 0.3305933 0.3446430 0.8783612 0.0202716 +VERTEX_SE3:QUAT 2355 18.357222 27.533205 -13.153536 -0.4378277 0.5245979 0.7299103 0.0182986 +VERTEX_SE3:QUAT 2356 17.454853 26.891748 -13.426636 -0.2168872 -0.6313224 0.4098463 0.6216253 +VERTEX_SE3:QUAT 2357 16.545873 26.376249 -13.780716 -0.2323808 -0.6879916 0.6543968 0.2107878 +VERTEX_SE3:QUAT 2358 15.687700 26.003523 -14.065552 -0.2965561 0.2488519 -0.6085048 0.6927114 +VERTEX_SE3:QUAT 2359 14.942699 25.355972 -14.318366 0.3525290 -0.0935369 -0.3381304 0.8675494 +VERTEX_SE3:QUAT 2360 14.419888 26.288728 -14.303465 -0.1983612 0.6139453 -0.6360537 0.4232726 +VERTEX_SE3:QUAT 2361 15.232688 26.559247 -14.095240 -0.0120595 -0.1339761 0.2750944 0.9519601 +VERTEX_SE3:QUAT 2362 16.098722 27.056683 -13.817488 -0.4323426 0.3820752 -0.2466892 0.7786160 +VERTEX_SE3:QUAT 2363 16.978546 27.643054 -13.525694 0.0027311 0.0735877 0.5192516 0.8514430 +VERTEX_SE3:QUAT 2364 17.876455 28.089422 -13.370355 -0.5138957 0.0012540 0.8343775 0.1993086 +VERTEX_SE3:QUAT 2365 18.757607 28.494117 -13.242266 -0.2226734 0.4996294 -0.2489341 0.7992615 +VERTEX_SE3:QUAT 2366 19.651556 28.814720 -13.160919 0.4966065 0.0515385 0.3341080 0.7994358 +VERTEX_SE3:QUAT 2367 20.582174 29.395942 -12.895642 -0.0298981 0.1828783 -0.3096602 0.9326158 +VERTEX_SE3:QUAT 2368 21.468123 29.824496 -12.808995 0.2791111 0.5744018 0.7517657 0.1643410 +VERTEX_SE3:QUAT 2369 22.524314 30.171166 -12.703625 0.0551920 0.4215308 0.1670620 0.8895819 +VERTEX_SE3:QUAT 2370 23.246423 30.487434 -12.392384 0.0582864 -0.4969612 0.4876491 0.7154234 +VERTEX_SE3:QUAT 2371 24.183383 30.843823 -12.254346 0.3048242 -0.1839280 -0.8437412 0.4016882 +VERTEX_SE3:QUAT 2372 25.359998 31.181945 -12.000590 -0.1915060 0.4819391 0.8235511 0.2298341 +VERTEX_SE3:QUAT 2373 26.326154 31.486294 -11.932929 -0.2726730 -0.2847659 -0.4666561 0.7917006 +VERTEX_SE3:QUAT 2374 27.336079 31.719132 -11.759984 -0.4243191 0.1971535 -0.1901431 0.8630929 +VERTEX_SE3:QUAT 2375 28.260977 32.067294 -11.466260 0.2910414 0.0931437 -0.3298880 0.8931926 +VERTEX_SE3:QUAT 2376 29.085215 32.224864 -11.214979 0.2264631 0.4421437 0.7733840 0.3938281 +VERTEX_SE3:QUAT 2377 29.904838 32.607833 -10.838544 0.4576721 0.2763123 0.8000380 0.2722628 +VERTEX_SE3:QUAT 2378 30.900927 32.851714 -10.364202 -0.4645753 -0.6034381 -0.1152203 0.6377747 +VERTEX_SE3:QUAT 2379 31.737616 33.264381 -9.976425 -0.3256125 0.3786036 -0.3487817 0.7930871 +VERTEX_SE3:QUAT 2380 31.593185 34.180341 -10.227544 -0.3299358 -0.4784936 0.1747004 0.7947742 +VERTEX_SE3:QUAT 2381 30.909307 33.907228 -10.448036 -0.0616751 0.0696481 0.8828728 0.4603052 +VERTEX_SE3:QUAT 2382 30.125961 33.315086 -10.688670 0.6081820 -0.3520763 -0.6623941 0.2595976 +VERTEX_SE3:QUAT 2383 29.141154 32.797420 -10.960853 0.4253665 0.3987203 0.8095646 0.0684879 +VERTEX_SE3:QUAT 2384 28.090257 32.354879 -11.260917 0.5164684 -0.4693111 0.2307072 0.6780720 +VERTEX_SE3:QUAT 2385 27.351824 31.817553 -11.532730 0.3088966 -0.1628239 0.1735573 0.9208415 +VERTEX_SE3:QUAT 2386 26.455074 31.315351 -11.845543 -0.4628266 -0.4173608 0.7192968 0.3069425 +VERTEX_SE3:QUAT 2387 25.713462 30.601698 -12.174571 -0.0346704 -0.5541243 -0.5748238 0.6011006 +VERTEX_SE3:QUAT 2388 24.959991 29.756831 -12.147226 0.0158903 0.2987219 -0.2850860 0.9106254 +VERTEX_SE3:QUAT 2389 24.136705 29.160204 -12.361682 0.3154852 -0.1326872 -0.4311025 0.8348735 +VERTEX_SE3:QUAT 2390 23.533856 28.610873 -12.534726 -0.1631079 -0.4000315 0.4845166 0.7606670 +VERTEX_SE3:QUAT 2391 22.589203 28.030211 -12.763175 0.0901836 0.3585416 -0.6906099 0.6215890 +VERTEX_SE3:QUAT 2392 21.708146 27.551085 -12.950654 0.4351557 0.0068305 -0.4207244 0.7959798 +VERTEX_SE3:QUAT 2393 20.805653 27.050733 -12.919683 -0.1468914 0.3946341 0.8495125 0.3178291 +VERTEX_SE3:QUAT 2394 19.857125 26.592913 -12.804160 -0.3554187 0.4741573 -0.2843137 0.7536698 +VERTEX_SE3:QUAT 2395 18.911826 25.981231 -12.504035 -0.1774645 -0.5996844 0.3362134 0.7041630 +VERTEX_SE3:QUAT 2396 18.137469 25.520628 -12.338101 -0.3693359 -0.1368778 -0.0612795 0.9171152 +VERTEX_SE3:QUAT 2397 17.394012 24.896023 -12.388525 -0.2291548 0.2142360 0.9426051 0.1143964 +VERTEX_SE3:QUAT 2398 16.471395 24.163976 -12.301798 0.2272765 -0.6638206 -0.7040910 0.1092865 +VERTEX_SE3:QUAT 2399 15.635761 23.689809 -12.319964 -0.2794117 0.3017710 -0.7287389 0.5475426 +VERTEX_SE3:QUAT 2400 30.868249 35.057460 -10.637513 0.0143777 -0.0660270 -0.9465638 0.3153579 +VERTEX_SE3:QUAT 2401 30.189549 34.444326 -10.714414 0.2322087 0.0796241 0.7904633 0.5611657 +VERTEX_SE3:QUAT 2402 29.243296 33.967706 -10.590245 -0.6183682 0.1392490 0.1768904 0.7529543 +VERTEX_SE3:QUAT 2403 28.503734 33.406567 -10.458148 0.1361646 0.3598136 0.3430415 0.8569223 +VERTEX_SE3:QUAT 2404 27.613468 32.974387 -10.509443 -0.2470049 0.3749082 -0.3379771 0.8271662 +VERTEX_SE3:QUAT 2405 26.681572 32.575864 -10.653972 -0.0705314 0.6424519 0.6359985 0.4216477 +VERTEX_SE3:QUAT 2406 25.729645 32.120639 -10.638369 0.0418940 -0.4548452 -0.2946238 0.8393793 +VERTEX_SE3:QUAT 2407 24.669180 31.691086 -10.700114 0.4870289 -0.1260501 0.8612905 0.0713642 +VERTEX_SE3:QUAT 2408 23.838135 31.247043 -10.616414 0.0835381 0.0042149 0.8829523 0.4619511 +VERTEX_SE3:QUAT 2409 23.077640 30.599933 -10.482528 0.1284722 0.1001269 0.1058857 0.9809474 +VERTEX_SE3:QUAT 2410 22.197680 29.956329 -10.389775 -0.2715700 -0.0067655 0.5389170 0.7973534 +VERTEX_SE3:QUAT 2411 21.461083 29.329237 -10.348287 -0.3420897 0.0485646 0.7325237 0.5865366 +VERTEX_SE3:QUAT 2412 20.568964 28.849272 -10.339639 0.2910330 -0.3919548 -0.1860429 0.8526777 +VERTEX_SE3:QUAT 2413 19.706760 28.219468 -10.127383 0.0445102 0.2127501 -0.1747005 0.9603312 +VERTEX_SE3:QUAT 2414 18.790746 27.803985 -9.963073 -0.2668592 0.4759283 0.1604141 0.8225240 +VERTEX_SE3:QUAT 2415 17.816892 27.266437 -9.891947 0.4856613 -0.4613743 -0.1880905 0.7182540 +VERTEX_SE3:QUAT 2416 17.107178 26.809348 -9.818219 0.5352940 -0.4215072 -0.6149319 0.3970526 +VERTEX_SE3:QUAT 2417 16.479093 26.133943 -10.028401 0.2786199 -0.4786804 0.7103696 0.4342936 +VERTEX_SE3:QUAT 2418 15.777167 25.416994 -10.240451 -0.3147467 -0.0120245 0.5570667 0.7684182 +VERTEX_SE3:QUAT 2419 15.112504 24.595518 -10.436799 -0.0190070 -0.1344008 0.9451900 0.2969698 +VERTEX_SE3:QUAT 2420 15.888882 23.919803 -10.161135 -0.3881400 -0.3189400 0.8265866 0.2537305 +VERTEX_SE3:QUAT 2421 16.778587 24.814976 -10.143214 0.4341112 -0.3382256 -0.7609416 0.3436840 +VERTEX_SE3:QUAT 2422 17.375824 25.629420 -10.156241 0.1614968 0.2926684 -0.6576062 0.6751430 +VERTEX_SE3:QUAT 2423 18.046485 26.287371 -10.151449 -0.0694054 0.4558270 0.4978717 0.7345260 +VERTEX_SE3:QUAT 2424 18.830972 26.850137 -10.288785 0.3645017 -0.0180209 -0.9165493 0.1635576 +VERTEX_SE3:QUAT 2425 19.527968 27.484456 -10.525650 0.2292430 -0.2556954 0.9390947 0.0129869 +VERTEX_SE3:QUAT 2426 20.136095 28.161760 -10.449203 0.3914594 -0.1247233 0.9018282 0.1338262 +VERTEX_SE3:QUAT 2427 20.723852 28.845278 -10.703489 -0.1739597 -0.0333711 0.8846758 0.4312460 +VERTEX_SE3:QUAT 2428 21.476705 29.480442 -10.764153 0.2175427 -0.2140927 0.3365343 0.8908334 +VERTEX_SE3:QUAT 2429 21.981222 30.056573 -10.811757 0.1315650 -0.0251665 -0.8032191 0.5804277 +VERTEX_SE3:QUAT 2430 22.673453 30.924722 -10.660307 0.2921211 -0.3947742 -0.1299794 0.8613501 +VERTEX_SE3:QUAT 2431 23.345784 31.542012 -10.612874 0.3309443 -0.2475798 0.3209570 0.8521542 +VERTEX_SE3:QUAT 2432 24.146476 32.273989 -10.711356 0.1436692 -0.2806629 -0.5558905 0.7691380 +VERTEX_SE3:QUAT 2433 24.885804 32.919721 -10.980881 -0.3841378 0.1961899 -0.8937592 0.1230536 +VERTEX_SE3:QUAT 2434 25.446180 33.768770 -10.982170 -0.1101586 0.2561332 -0.7454844 0.6054040 +VERTEX_SE3:QUAT 2435 26.093697 34.237456 -11.219161 0.1007120 -0.0420060 -0.2296460 0.9671377 +VERTEX_SE3:QUAT 2436 26.805454 34.992818 -11.175153 0.4407656 0.0209773 -0.8353992 0.3277100 +VERTEX_SE3:QUAT 2437 27.649232 35.587345 -11.145915 -0.3660335 -0.1148871 -0.8365970 0.3910574 +VERTEX_SE3:QUAT 2438 28.476493 36.168354 -11.245536 -0.0356086 -0.3581410 0.3402965 0.8687148 +VERTEX_SE3:QUAT 2439 29.328837 36.888774 -11.255908 -0.0636956 -0.2328051 0.7460186 0.6206456 +VERTEX_SE3:QUAT 2440 30.123900 36.128843 -11.395287 -0.0210854 0.6652701 -0.6827235 0.3014295 +VERTEX_SE3:QUAT 2441 29.457046 35.475463 -11.543529 0.1468072 -0.3944850 0.5260546 0.7389829 +VERTEX_SE3:QUAT 2442 28.727082 34.899570 -11.660678 0.5327221 -0.2323021 -0.0939453 0.8083422 +VERTEX_SE3:QUAT 2443 28.010035 34.209266 -11.873724 0.1285154 0.3269985 -0.3578367 0.8651640 +VERTEX_SE3:QUAT 2444 27.160359 33.352760 -11.975490 -0.4757396 -0.2399323 0.8244059 0.1909433 +VERTEX_SE3:QUAT 2445 26.275403 32.657185 -12.000677 0.4917604 0.2227425 0.5101069 0.6695882 +VERTEX_SE3:QUAT 2446 25.622125 31.916851 -12.110358 -0.2765394 -0.6718772 0.5773676 0.3724966 +VERTEX_SE3:QUAT 2447 24.717873 31.337043 -12.287664 -0.4278955 0.1523952 0.8024181 0.3870482 +VERTEX_SE3:QUAT 2448 24.056544 30.878972 -12.334879 0.0277363 -0.4021051 0.9138612 0.0489890 +VERTEX_SE3:QUAT 2449 23.327866 30.249586 -12.413865 -0.4305888 0.2654014 -0.2187621 0.8344450 +VERTEX_SE3:QUAT 2450 22.602914 29.640712 -12.518016 0.0236296 0.0970941 -0.9737312 0.2046020 +VERTEX_SE3:QUAT 2451 21.763041 28.976429 -12.552302 0.2782703 -0.4540915 0.3644522 0.7638987 +VERTEX_SE3:QUAT 2452 21.034055 28.412381 -12.790569 0.3931063 0.4626826 -0.0453593 0.7933062 +VERTEX_SE3:QUAT 2453 20.251602 27.710820 -12.740584 -0.2263807 0.5723908 0.7281213 0.3015954 +VERTEX_SE3:QUAT 2454 19.431953 26.999399 -12.719789 -0.2846830 0.2377370 0.8633383 0.3421749 +VERTEX_SE3:QUAT 2455 18.592360 26.460089 -12.792277 -0.0469720 0.4977660 -0.1520587 0.8525848 +VERTEX_SE3:QUAT 2456 17.830514 25.952751 -12.911110 -0.3829648 -0.4613223 -0.0113849 0.8002438 +VERTEX_SE3:QUAT 2457 17.044440 25.433431 -12.996217 0.0008352 -0.6678703 0.5695928 0.4790748 +VERTEX_SE3:QUAT 2458 16.109091 25.051782 -13.055246 0.6047719 0.2004310 0.3967504 0.6608082 +VERTEX_SE3:QUAT 2459 15.371761 24.642550 -12.938344 0.0383510 0.6799468 0.3995948 0.6136168 +VERTEX_SE3:QUAT 2460 15.807166 23.898538 -12.954952 0.3522800 -0.2359194 -0.8642102 0.2708902 +VERTEX_SE3:QUAT 2461 16.589015 24.386382 -13.051515 0.0229139 0.2050040 0.5376385 0.8175532 +VERTEX_SE3:QUAT 2462 17.370090 25.031569 -13.196506 -0.2674226 -0.2231873 0.5829475 0.7340605 +VERTEX_SE3:QUAT 2463 18.177388 25.419922 -13.226467 -0.2005078 0.6109061 -0.4873843 0.5908020 +VERTEX_SE3:QUAT 2464 19.137119 25.792281 -13.315123 -0.0223601 -0.0930244 -0.2319802 0.9680040 +VERTEX_SE3:QUAT 2465 20.097740 26.209814 -13.505738 -0.1321723 -0.1991340 -0.8302977 0.5034698 +VERTEX_SE3:QUAT 2466 21.055940 26.389691 -13.426432 0.2668604 -0.1198810 0.6854274 0.6667859 +VERTEX_SE3:QUAT 2467 22.020287 26.720723 -13.433087 0.4724353 -0.0211177 0.8770896 0.0840993 +VERTEX_SE3:QUAT 2468 22.858688 27.115138 -13.421389 -0.2917542 0.2342900 0.5725310 0.7295176 +VERTEX_SE3:QUAT 2469 23.844976 27.532707 -13.538782 -0.1157044 -0.1990854 -0.9678386 0.1013213 +VERTEX_SE3:QUAT 2470 24.738307 27.855986 -13.640658 -0.1464669 0.3224641 -0.3097974 0.8823774 +VERTEX_SE3:QUAT 2471 25.530246 28.379528 -13.721780 -0.0210128 -0.5536773 0.4700813 0.6870396 +VERTEX_SE3:QUAT 2472 26.594593 28.738061 -13.785162 0.3815134 -0.2600966 0.3404389 0.8190840 +VERTEX_SE3:QUAT 2473 27.442081 29.278260 -13.898373 -0.5408593 0.3596245 -0.4809748 0.5889013 +VERTEX_SE3:QUAT 2474 28.332455 29.820116 -14.006361 -0.2859565 0.1254218 0.0036831 0.9499919 +VERTEX_SE3:QUAT 2475 29.322386 30.396201 -14.192302 -0.5218170 -0.1854447 -0.7921512 0.2565420 +VERTEX_SE3:QUAT 2476 30.067901 30.807020 -14.192606 -0.6380227 0.2520847 0.2571561 0.6806255 +VERTEX_SE3:QUAT 2477 30.913019 31.544070 -14.338029 0.6536135 0.1868151 -0.3535973 0.6425406 +VERTEX_SE3:QUAT 2478 31.841418 32.152934 -14.408901 -0.1554606 0.3008440 0.6144975 0.7125431 +VERTEX_SE3:QUAT 2479 32.655057 32.835068 -14.535399 0.2372322 0.1908110 -0.5351755 0.7879716 +VERTEX_SE3:QUAT 2480 33.161385 31.936354 -14.674171 -0.1463178 -0.5216253 0.7276659 0.4207143 +VERTEX_SE3:QUAT 2481 32.359151 31.357788 -14.729008 -0.4716308 0.3470738 -0.6244937 0.5168287 +VERTEX_SE3:QUAT 2482 31.741502 30.915644 -14.835626 -0.0044545 0.5926106 -0.4396014 0.6749396 +VERTEX_SE3:QUAT 2483 30.980151 30.514944 -14.853246 0.1386984 -0.3134818 -0.9128244 0.2219089 +VERTEX_SE3:QUAT 2484 29.992767 30.105310 -15.016740 0.2321620 0.1549553 -0.1047872 0.9545204 +VERTEX_SE3:QUAT 2485 29.255452 29.595196 -15.204558 0.2290672 -0.3236614 -0.7490662 0.5307272 +VERTEX_SE3:QUAT 2486 28.433002 29.048638 -15.608543 -0.4887866 0.2709845 0.8236376 0.0963128 +VERTEX_SE3:QUAT 2487 27.764623 28.542385 -15.831310 -0.6886869 -0.1351475 0.5361633 0.4690143 +VERTEX_SE3:QUAT 2488 27.013579 27.781055 -16.139423 0.4702829 -0.4137386 0.3752447 0.6832612 +VERTEX_SE3:QUAT 2489 26.099669 27.391661 -16.448317 -0.3823437 -0.4060343 0.2968545 0.7751302 +VERTEX_SE3:QUAT 2490 25.277870 26.878624 -16.767094 0.1772320 0.3184992 0.1455915 0.9197555 +VERTEX_SE3:QUAT 2491 24.511594 26.567214 -17.157309 -0.1451236 0.2988070 -0.9396980 0.0813708 +VERTEX_SE3:QUAT 2492 23.513537 26.215298 -17.651946 -0.0404094 0.2316825 0.4989196 0.8341280 +VERTEX_SE3:QUAT 2493 22.716072 26.009232 -18.022851 0.1812781 -0.4737537 0.8606801 0.0438797 +VERTEX_SE3:QUAT 2494 21.959581 25.557462 -18.408052 0.6370329 -0.0318159 -0.7599453 0.1251398 +VERTEX_SE3:QUAT 2495 20.954246 25.210592 -18.840829 -0.0153177 -0.5776641 0.2049072 0.7899890 +VERTEX_SE3:QUAT 2496 19.958473 24.988395 -19.154264 -0.4266420 0.1261205 0.4203762 0.7907933 +VERTEX_SE3:QUAT 2497 19.146033 24.858252 -19.495410 -0.1505193 -0.0936703 0.9817213 0.0692318 +VERTEX_SE3:QUAT 2498 18.077194 24.725983 -19.844810 -0.1696352 0.2841479 0.4879340 0.8077155 +VERTEX_SE3:QUAT 2499 17.115483 24.441108 -20.037304 0.5558019 0.0836508 -0.6399911 0.5239258 +VERTEX_SE3:QUAT 2500 17.542456 23.357194 -20.274082 0.1697298 0.3943220 0.4278255 0.7954038 +VERTEX_SE3:QUAT 2501 18.401353 23.478055 -20.166089 0.1568142 -0.0833977 0.8866658 0.4269402 +VERTEX_SE3:QUAT 2502 19.349831 23.627239 -19.918856 -0.2105088 -0.4169292 0.2806863 0.8384934 +VERTEX_SE3:QUAT 2503 20.317883 23.680222 -19.742814 0.4407943 -0.5569537 0.1208841 0.6934623 +VERTEX_SE3:QUAT 2504 21.309156 23.906763 -19.467279 -0.0426022 0.2765871 -0.9587022 0.0507417 +VERTEX_SE3:QUAT 2505 22.222573 24.112726 -19.278987 0.2946298 0.1511433 0.9307315 0.1552028 +VERTEX_SE3:QUAT 2506 23.128727 24.240460 -18.821088 0.2749934 -0.4323170 -0.5461114 0.6627540 +VERTEX_SE3:QUAT 2507 23.965261 24.385097 -18.474060 0.0751866 -0.0215085 0.8534928 0.5152033 +VERTEX_SE3:QUAT 2508 24.881574 24.411317 -18.096975 0.1987362 0.3905171 0.3673234 0.8204107 +VERTEX_SE3:QUAT 2509 25.764575 24.770996 -17.593679 -0.0324826 0.5942967 -0.2806201 0.7529998 +VERTEX_SE3:QUAT 2510 26.576091 25.043488 -17.099427 0.5334518 0.0690597 -0.4091310 0.7370697 +VERTEX_SE3:QUAT 2511 27.426753 25.375055 -16.784164 0.4010360 -0.1649276 -0.1369548 0.8906247 +VERTEX_SE3:QUAT 2512 28.043013 25.701270 -16.404323 0.2886398 -0.2312982 0.0549596 0.9274523 +VERTEX_SE3:QUAT 2513 29.027440 26.083903 -16.181153 -0.3315799 0.1357717 0.9335727 0.0079220 +VERTEX_SE3:QUAT 2514 29.847657 26.733855 -15.909302 -0.2884074 0.2031109 -0.6496177 0.6734716 +VERTEX_SE3:QUAT 2515 30.624858 27.192608 -15.764812 0.7298140 0.1355715 -0.3476574 0.5728231 +VERTEX_SE3:QUAT 2516 31.450485 27.722829 -15.366376 0.0890083 -0.0857735 -0.9432636 0.3081789 +VERTEX_SE3:QUAT 2517 32.357158 28.244679 -15.068063 -0.2080847 -0.5856461 0.6234033 0.4744341 +VERTEX_SE3:QUAT 2518 33.227198 28.811234 -14.820155 -0.4894625 -0.3691578 0.4324516 0.6611615 +VERTEX_SE3:QUAT 2519 34.181044 29.520986 -14.659016 0.0208882 0.2648055 0.4226134 0.8665100 +VERTEX_SE3:QUAT 2520 34.595622 28.667621 -14.896108 -0.1196324 -0.1137050 -0.1356915 0.9769069 +VERTEX_SE3:QUAT 2521 33.945157 28.211608 -15.281436 -0.0010299 0.3620815 0.7437389 0.5619150 +VERTEX_SE3:QUAT 2522 33.272395 27.847673 -15.541584 0.2332111 -0.2095524 0.1097393 0.9432167 +VERTEX_SE3:QUAT 2523 32.289988 27.539821 -16.069848 0.5931977 -0.4443606 0.2541142 0.6213583 +VERTEX_SE3:QUAT 2524 31.387464 27.052385 -16.280048 0.3100203 0.1727071 -0.4494001 0.8198166 +VERTEX_SE3:QUAT 2525 30.630858 26.566678 -16.614593 -0.3019326 0.0858045 0.2702753 0.9101789 +VERTEX_SE3:QUAT 2526 29.669973 26.196503 -16.861205 0.3790593 -0.3542593 -0.8019465 0.2961354 +VERTEX_SE3:QUAT 2527 28.796036 25.774206 -17.150676 0.4137530 0.1855041 0.4981280 0.7390975 +VERTEX_SE3:QUAT 2528 27.963437 25.382699 -17.415071 0.7851003 0.0822586 0.0997226 0.6057281 +VERTEX_SE3:QUAT 2529 27.058295 24.760418 -17.698205 0.3815466 0.2527202 0.8766263 0.1485970 +VERTEX_SE3:QUAT 2530 26.409833 24.152019 -18.228698 -0.3375673 -0.2480622 -0.8790539 0.2275471 +VERTEX_SE3:QUAT 2531 25.668995 23.693892 -18.618384 -0.1818388 -0.0215815 -0.9802866 0.0742093 +VERTEX_SE3:QUAT 2532 24.773083 23.216332 -19.107179 0.5101683 -0.1250477 0.3815235 0.7606124 +VERTEX_SE3:QUAT 2533 24.106275 22.712600 -19.519334 0.6994767 -0.1796243 0.5036272 0.4741594 +VERTEX_SE3:QUAT 2534 23.401250 21.904758 -19.822564 0.0037560 -0.1224234 0.9027509 0.4123581 +VERTEX_SE3:QUAT 2535 22.677414 21.143635 -20.417276 0.7670138 -0.1779109 0.5124873 0.3426286 +VERTEX_SE3:QUAT 2536 21.947046 20.667217 -20.740231 -0.3441145 -0.2370693 0.8370337 0.3532110 +VERTEX_SE3:QUAT 2537 21.147795 20.143030 -21.028964 -0.3097922 0.2468402 -0.3451831 0.8508510 +VERTEX_SE3:QUAT 2538 20.281842 19.748772 -21.304660 0.4831115 -0.3170660 0.2543032 0.7755013 +VERTEX_SE3:QUAT 2539 19.343013 19.379636 -21.846877 -0.1058272 0.0671226 -0.9786970 0.1626262 +VERTEX_SE3:QUAT 2540 19.945755 18.826780 -22.415699 -0.4049578 -0.1566078 -0.8653995 0.2501338 +VERTEX_SE3:QUAT 2541 20.717123 19.244695 -22.092421 -0.0790029 -0.3417845 0.1849632 0.9180036 +VERTEX_SE3:QUAT 2542 21.636031 19.753120 -21.633901 0.2273129 0.1941543 -0.7082971 0.6394906 +VERTEX_SE3:QUAT 2543 22.568788 20.159681 -21.354413 0.4673720 -0.6522289 0.5957841 0.0346732 +VERTEX_SE3:QUAT 2544 23.298845 20.670724 -20.911564 -0.3576000 0.6706154 -0.6495543 0.0218287 +VERTEX_SE3:QUAT 2545 24.198356 20.955761 -20.393750 0.1667777 -0.3154322 0.1958115 0.9134252 +VERTEX_SE3:QUAT 2546 24.930162 21.349966 -20.279605 0.3903714 0.3043499 0.8684795 0.0269194 +VERTEX_SE3:QUAT 2547 25.784844 21.675932 -19.874039 0.2312734 0.0113845 0.6433545 0.7297109 +VERTEX_SE3:QUAT 2548 26.565068 22.149680 -19.631899 0.0581136 -0.6818631 0.3502492 0.6395397 +VERTEX_SE3:QUAT 2549 27.410158 22.306598 -19.072524 0.4043631 -0.7172588 0.5633308 0.0684746 +VERTEX_SE3:QUAT 2550 28.280543 22.640675 -18.557910 0.5091757 0.5336497 -0.3651421 0.5680047 +VERTEX_SE3:QUAT 2551 29.246211 23.140227 -17.928191 0.3531500 0.4825659 -0.5012851 0.6254027 +VERTEX_SE3:QUAT 2552 30.037167 23.324311 -17.480888 0.6899847 -0.1434624 0.6911801 0.1600304 +VERTEX_SE3:QUAT 2553 30.856145 23.666731 -17.077393 0.4115242 0.4414410 -0.7128434 0.3572561 +VERTEX_SE3:QUAT 2554 31.861061 23.855060 -16.690462 0.2931618 -0.4446488 0.1752240 0.8280339 +VERTEX_SE3:QUAT 2555 32.618101 24.390060 -16.354827 0.6316741 0.1019985 0.5399231 0.5468703 +VERTEX_SE3:QUAT 2556 33.518822 24.669663 -15.917370 -0.0009394 -0.7513641 0.5406882 0.3782954 +VERTEX_SE3:QUAT 2557 34.399659 25.036306 -15.748989 0.4058341 0.5846644 -0.6250204 0.3206490 +VERTEX_SE3:QUAT 2558 35.256218 25.470177 -15.667747 0.4534928 -0.5020567 0.1403007 0.7229102 +VERTEX_SE3:QUAT 2559 36.199650 25.852047 -15.482387 0.0930629 -0.2520007 0.9282663 0.2572094 +VERTEX_SE3:QUAT 2560 36.599449 25.167994 -16.039969 -0.2278520 0.5995033 -0.6748489 0.3650455 +VERTEX_SE3:QUAT 2561 35.870301 24.739623 -16.251837 -0.3919692 0.7755129 -0.4919890 0.0537278 +VERTEX_SE3:QUAT 2562 34.952669 24.567399 -16.327727 -0.1882614 0.0546838 0.5278316 0.8264146 +VERTEX_SE3:QUAT 2563 34.019967 24.305089 -16.466584 0.3112509 -0.1373844 -0.8574729 0.3859905 +VERTEX_SE3:QUAT 2564 33.026169 24.265993 -16.540368 -0.1441795 0.1333469 -0.9772240 0.0803998 +VERTEX_SE3:QUAT 2565 32.233605 24.187856 -16.584922 -0.3640490 0.0163986 -0.0559515 0.9295530 +VERTEX_SE3:QUAT 2566 31.207580 23.659916 -16.558572 0.0108957 0.7009608 -0.0076452 0.7130756 +VERTEX_SE3:QUAT 2567 30.118723 23.306138 -16.711395 0.4048572 -0.1111328 0.9074940 0.0139544 +VERTEX_SE3:QUAT 2568 29.088203 23.203593 -16.823034 0.2713744 0.5958768 -0.4808925 0.5831202 +VERTEX_SE3:QUAT 2569 28.045548 22.985086 -17.044323 -0.0039288 -0.3831937 0.8878081 0.2548409 +VERTEX_SE3:QUAT 2570 27.189904 22.602719 -17.181554 0.4712568 0.5573155 -0.5021732 0.4638303 +VERTEX_SE3:QUAT 2571 26.245693 22.344345 -17.506573 0.4964849 -0.4513894 0.1144216 0.7325695 +VERTEX_SE3:QUAT 2572 25.371816 21.921355 -17.761350 0.1210517 -0.2320277 -0.0708415 0.9625441 +VERTEX_SE3:QUAT 2573 24.482226 21.632200 -17.868586 0.0786054 -0.3158091 0.3998431 0.8568613 +VERTEX_SE3:QUAT 2574 23.507818 21.635121 -18.208036 -0.0312363 -0.7864666 0.2364006 0.5697450 +VERTEX_SE3:QUAT 2575 22.645653 21.498673 -18.445329 -0.2779358 0.7092049 -0.5468166 0.3475221 +VERTEX_SE3:QUAT 2576 21.541236 21.407056 -18.480143 0.4808886 0.0540373 0.8671634 0.1177018 +VERTEX_SE3:QUAT 2577 20.405760 20.897385 -18.617746 0.6976573 0.4538916 -0.1919165 0.5200238 +VERTEX_SE3:QUAT 2578 19.432052 20.506471 -18.625352 -0.2436174 0.1676114 -0.9551564 0.0152735 +VERTEX_SE3:QUAT 2579 18.583649 20.159675 -18.986507 -0.0519667 -0.5616488 0.3696464 0.7383844 +VERTEX_SE3:QUAT 2580 18.939377 19.505190 -19.639246 0.3820946 0.6488260 -0.6048222 0.2592656 +VERTEX_SE3:QUAT 2581 19.915324 19.825709 -19.521475 0.1776340 0.3668604 -0.5211313 0.7498545 +VERTEX_SE3:QUAT 2582 20.759149 20.264370 -19.235509 -0.2267528 -0.0255457 -0.5162411 0.8254851 +VERTEX_SE3:QUAT 2583 21.501570 20.697211 -18.937213 0.1827175 -0.3149187 0.4683927 0.8050148 +VERTEX_SE3:QUAT 2584 22.372467 21.220125 -18.615762 -0.2338705 0.0530027 -0.6534389 0.7179923 +VERTEX_SE3:QUAT 2585 23.349346 21.734404 -18.262989 -0.1790837 0.7362259 -0.4034495 0.5129609 +VERTEX_SE3:QUAT 2586 24.104072 22.208213 -17.972155 -0.2238569 0.0059331 -0.6635679 0.7138141 +VERTEX_SE3:QUAT 2587 24.965954 22.772997 -17.629597 0.5991070 0.4328184 0.3424288 0.5800703 +VERTEX_SE3:QUAT 2588 25.797498 23.246521 -17.125244 0.0531582 -0.4558242 0.1461140 0.8763841 +VERTEX_SE3:QUAT 2589 26.441685 23.710058 -16.820070 0.1254447 -0.0295600 0.9012477 0.4136937 +VERTEX_SE3:QUAT 2590 27.131914 24.381090 -16.612323 -0.2173710 0.0325986 0.6787187 0.7007339 +VERTEX_SE3:QUAT 2591 27.893381 24.969434 -16.348769 0.4573613 -0.6253210 0.6320598 0.0171637 +VERTEX_SE3:QUAT 2592 28.603381 25.381682 -15.930451 -0.0374947 0.4366707 -0.8408637 0.3175865 +VERTEX_SE3:QUAT 2593 29.506173 25.798785 -15.728203 0.1327963 -0.4385929 0.7323391 0.5036674 +VERTEX_SE3:QUAT 2594 29.956941 26.345487 -15.333143 -0.2803959 0.1515899 0.3351805 0.8865961 +VERTEX_SE3:QUAT 2595 30.548838 26.777549 -14.891772 0.7749519 0.2519294 -0.2142912 0.5385726 +VERTEX_SE3:QUAT 2596 31.266772 27.265930 -14.481585 0.5866137 0.2859049 0.6229819 0.4313192 +VERTEX_SE3:QUAT 2597 31.972967 27.710511 -13.830724 0.1142739 -0.4100045 -0.2363036 0.8734978 +VERTEX_SE3:QUAT 2598 32.719493 27.943491 -13.285692 0.3145355 -0.7592591 0.3510415 0.4487347 +VERTEX_SE3:QUAT 2599 33.409789 28.411416 -12.825007 0.5458330 0.4005471 -0.3240720 0.6607615 +VERTEX_SE3:QUAT 2600 34.035505 27.869157 -13.095586 -0.0254830 0.3624524 -0.4674362 0.8059046 +VERTEX_SE3:QUAT 2601 33.327432 27.402990 -13.698136 0.0317148 0.3129086 -0.0020770 0.9492513 +VERTEX_SE3:QUAT 2602 32.720427 26.880218 -14.157768 -0.3859131 -0.3094415 0.4776710 0.7260492 +VERTEX_SE3:QUAT 2603 31.946657 26.283659 -14.531258 0.3685767 -0.3924129 -0.5291836 0.6558415 +VERTEX_SE3:QUAT 2604 31.358341 25.839741 -15.144036 -0.2209990 -0.0546978 0.9628065 0.1455032 +VERTEX_SE3:QUAT 2605 30.627190 25.443375 -15.381536 0.4287618 -0.2820639 0.8015687 0.3067425 +VERTEX_SE3:QUAT 2606 29.839812 25.074249 -15.664367 -0.0075772 -0.8202513 0.4808216 0.3097435 +VERTEX_SE3:QUAT 2607 29.111025 24.672077 -15.980335 -0.2389223 0.3165306 0.0656579 0.9156492 +VERTEX_SE3:QUAT 2608 28.375594 24.355103 -16.459419 0.6177491 0.0726780 -0.7814264 0.0497668 +VERTEX_SE3:QUAT 2609 27.542886 24.031336 -16.882865 0.3231818 0.0592780 -0.9145017 0.2360642 +VERTEX_SE3:QUAT 2610 26.770877 23.730816 -17.305772 0.0958303 -0.5821297 0.6945716 0.4117183 +VERTEX_SE3:QUAT 2611 25.948420 23.477634 -17.731358 -0.3285566 0.5646168 -0.7567170 0.0252565 +VERTEX_SE3:QUAT 2612 25.096541 23.075362 -17.898072 0.1330088 -0.4090743 -0.1919053 0.8821220 +VERTEX_SE3:QUAT 2613 24.219225 22.912586 -18.338228 0.7355476 -0.0857541 -0.6658677 0.0907534 +VERTEX_SE3:QUAT 2614 23.390676 22.538269 -18.518802 0.2366240 -0.1129359 -0.1650719 0.9507922 +VERTEX_SE3:QUAT 2615 22.604717 22.168700 -18.927058 -0.2346405 0.4488157 -0.8373739 0.2057020 +VERTEX_SE3:QUAT 2616 21.903918 21.810274 -19.333522 0.6354057 0.1123944 0.6841015 0.3400473 +VERTEX_SE3:QUAT 2617 21.030543 21.596843 -19.382886 -0.2070304 0.4295162 -0.8790070 0.0009960 +VERTEX_SE3:QUAT 2618 20.079445 21.132087 -19.451414 -0.0757456 -0.8248021 0.5272610 0.1896308 +VERTEX_SE3:QUAT 2619 19.065568 20.982786 -19.539790 0.4828728 -0.3266710 -0.3021853 0.7541909 +VERTEX_SE3:QUAT 2620 19.484651 20.148414 -19.839078 -0.0203126 0.1918730 -0.9795788 0.0565466 +VERTEX_SE3:QUAT 2621 20.330644 20.495202 -19.574580 0.3211252 0.3848979 0.6801916 0.5348566 +VERTEX_SE3:QUAT 2622 21.332255 20.818481 -19.077392 0.2941543 -0.5262649 0.7928426 0.0889896 +VERTEX_SE3:QUAT 2623 22.364880 21.235473 -18.955464 -0.2009155 -0.3977125 0.8163539 0.3674562 +VERTEX_SE3:QUAT 2624 23.230734 21.587377 -18.736170 -0.0026069 -0.4195623 0.3707236 0.8285679 +VERTEX_SE3:QUAT 2625 24.068801 21.955922 -18.535209 -0.2933627 0.0631515 0.6668643 0.6820866 +VERTEX_SE3:QUAT 2626 25.198465 22.417328 -18.391605 0.6994257 -0.3138309 0.3981544 0.5037727 +VERTEX_SE3:QUAT 2627 26.162042 22.826305 -18.179278 -0.3060192 0.1426085 0.8867795 0.3156537 +VERTEX_SE3:QUAT 2628 27.003947 23.217569 -17.856818 0.5144320 -0.1525967 0.8350122 0.1217724 +VERTEX_SE3:QUAT 2629 27.828463 23.624747 -17.686954 -0.2577993 0.4148955 -0.1086402 0.8657936 +VERTEX_SE3:QUAT 2630 28.823891 24.193644 -17.664099 0.7186377 0.4467363 -0.2796363 0.4536410 +VERTEX_SE3:QUAT 2631 29.902814 24.824330 -17.579167 -0.0320727 0.1816562 0.3839172 0.9047541 +VERTEX_SE3:QUAT 2632 30.782623 25.321979 -17.427615 -0.4756219 0.0920803 -0.8131375 0.3226647 +VERTEX_SE3:QUAT 2633 31.648399 26.024702 -17.235314 -0.3044945 -0.3206866 0.7421416 0.5036557 +VERTEX_SE3:QUAT 2634 32.392737 26.556898 -17.009249 -0.0089451 0.5435785 -0.5301217 0.6507022 +VERTEX_SE3:QUAT 2635 33.283288 27.389485 -16.793554 -0.1160777 0.2287146 0.9364524 0.2393167 +VERTEX_SE3:QUAT 2636 34.135529 28.013963 -16.714236 -0.5336808 0.5485871 -0.4593695 0.4507956 +VERTEX_SE3:QUAT 2637 34.764412 28.722564 -16.759506 -0.1485148 -0.1241585 0.9339700 0.3003799 +VERTEX_SE3:QUAT 2638 35.270118 29.337081 -16.556289 -0.2042837 -0.1494852 -0.9209507 0.2962637 +VERTEX_SE3:QUAT 2639 36.006419 29.986168 -16.440679 0.6123739 0.2411344 -0.5121212 0.5518915 +VERTEX_SE3:QUAT 2640 36.382532 29.329771 -16.892070 -0.2799243 -0.0079985 -0.8098765 0.5154400 +VERTEX_SE3:QUAT 2641 35.598679 28.776023 -16.825180 0.0286031 0.3375806 0.0447391 0.9397976 +VERTEX_SE3:QUAT 2642 34.590200 28.262941 -16.777496 0.5616718 -0.2743585 -0.2824064 0.7276667 +VERTEX_SE3:QUAT 2643 33.738733 27.788766 -16.763378 0.6841015 0.1977971 -0.2015393 0.6725053 +VERTEX_SE3:QUAT 2644 32.784379 27.114239 -16.629254 -0.2492729 -0.1372238 0.5891828 0.7562382 +VERTEX_SE3:QUAT 2645 31.979147 26.436406 -16.527457 -0.2333139 0.4775311 -0.6134931 0.5840846 +VERTEX_SE3:QUAT 2646 31.056459 26.032782 -16.660374 -0.6258173 0.0924776 -0.4816101 0.6065083 +VERTEX_SE3:QUAT 2647 30.265477 25.680984 -16.672304 0.1101766 0.0059436 0.7370165 0.6668077 +VERTEX_SE3:QUAT 2648 29.470412 25.006916 -16.575232 0.2785405 0.2430447 -0.1799038 0.9115805 +VERTEX_SE3:QUAT 2649 28.740439 24.232798 -16.425212 0.3792630 0.1407778 -0.9087114 0.1028821 +VERTEX_SE3:QUAT 2650 27.954028 23.616845 -16.446167 -0.0570376 0.4962650 -0.2332507 0.8343033 +VERTEX_SE3:QUAT 2651 27.210645 22.853098 -16.393219 0.3483500 -0.1115248 0.3055923 0.8791063 +VERTEX_SE3:QUAT 2652 26.337835 22.078760 -16.401455 -0.4339481 -0.4979156 -0.6648224 0.3489702 +VERTEX_SE3:QUAT 2653 25.613784 21.304991 -16.009325 0.3860459 -0.1839970 0.1446842 0.8922893 +VERTEX_SE3:QUAT 2654 24.861533 20.678598 -16.059633 -0.0558354 0.0348158 0.5664305 0.8214784 +VERTEX_SE3:QUAT 2655 24.295644 20.100920 -15.932867 0.2704622 -0.0286758 0.2321547 0.9338801 +VERTEX_SE3:QUAT 2656 23.365297 19.351003 -15.679891 0.3479395 -0.2094922 0.3291351 0.8524794 +VERTEX_SE3:QUAT 2657 22.697603 18.581299 -15.455191 0.3797493 0.4154656 -0.2485930 0.7882768 +VERTEX_SE3:QUAT 2658 21.970508 17.821969 -15.272456 0.3471919 0.1218544 -0.2878548 0.8841657 +VERTEX_SE3:QUAT 2659 21.314623 17.003745 -15.137132 -0.5275089 0.0329155 0.1232972 0.8399099 +VERTEX_SE3:QUAT 2660 22.108411 16.360852 -15.252012 0.4826010 -0.0339288 0.8041476 0.3453864 +VERTEX_SE3:QUAT 2661 22.689549 17.286533 -15.216107 -0.2733820 -0.3866810 -0.8457479 0.2458669 +VERTEX_SE3:QUAT 2662 23.429236 18.108809 -15.185462 -0.0815643 0.3090015 0.9465310 0.0440962 +VERTEX_SE3:QUAT 2663 24.116136 18.751328 -15.354537 -0.2106406 -0.2762179 -0.4466547 0.8245203 +VERTEX_SE3:QUAT 2664 24.881195 19.404698 -15.423907 0.1345013 0.5726681 -0.6981052 0.4081786 +VERTEX_SE3:QUAT 2665 25.493304 20.129671 -15.534129 -0.3283536 0.4770993 0.6093007 0.5415836 +VERTEX_SE3:QUAT 2666 26.143901 20.757079 -15.842556 0.6164986 0.1892505 0.6683006 0.3707938 +VERTEX_SE3:QUAT 2667 26.739666 21.741428 -15.774324 0.2262753 0.4786976 0.7181270 0.4515991 +VERTEX_SE3:QUAT 2668 27.306277 22.621663 -16.160745 -0.5470338 -0.0650018 0.7316941 0.4014381 +VERTEX_SE3:QUAT 2669 27.795507 23.460439 -16.376713 0.0316339 -0.4100101 0.7819123 0.4685128 +VERTEX_SE3:QUAT 2670 28.316839 24.256130 -16.610781 -0.2755181 -0.5153810 -0.6591413 0.4732916 +VERTEX_SE3:QUAT 2671 28.817779 25.317849 -17.132809 -0.2030811 0.4112542 -0.5607388 0.6893475 +VERTEX_SE3:QUAT 2672 29.297056 26.374279 -17.245024 -0.5730683 0.1530516 0.3834015 0.7079345 +VERTEX_SE3:QUAT 2673 29.707433 27.140805 -17.737088 0.1292641 0.5104480 -0.7058873 0.4737687 +VERTEX_SE3:QUAT 2674 30.188797 27.943536 -18.163867 0.2362786 0.5831300 0.1074862 0.7697913 +VERTEX_SE3:QUAT 2675 30.626596 29.005241 -18.394483 0.2055291 0.2616654 -0.8861293 0.3225893 +VERTEX_SE3:QUAT 2676 31.140904 29.861807 -18.726928 -0.0311775 0.0722558 0.9341817 0.3480110 +VERTEX_SE3:QUAT 2677 31.940861 30.596103 -18.882450 -0.2396497 -0.1971357 0.5558057 0.7712234 +VERTEX_SE3:QUAT 2678 32.507900 31.235337 -19.019646 0.5722828 -0.1802589 -0.4634206 0.6521047 +VERTEX_SE3:QUAT 2679 33.098737 32.061472 -19.276543 -0.5939279 0.2219412 0.6066308 0.4795736 +VERTEX_SE3:QUAT 2680 33.905314 31.394377 -19.201403 -0.5662301 0.2427830 0.5050235 0.6044759 +VERTEX_SE3:QUAT 2681 33.498251 30.656848 -19.159786 0.1647403 -0.4278514 -0.2757379 0.8448506 +VERTEX_SE3:QUAT 2682 33.014236 29.922162 -19.054348 0.4622016 -0.4405325 0.0971937 0.7634489 +VERTEX_SE3:QUAT 2683 32.571827 29.198816 -18.760840 -0.2365353 -0.2158983 0.5304555 0.7848923 +VERTEX_SE3:QUAT 2684 32.141685 28.336744 -18.623174 0.0162812 -0.4084632 -0.2228343 0.8850071 +VERTEX_SE3:QUAT 2685 31.654354 27.668926 -18.515610 -0.4339923 -0.0557736 0.8959192 0.0766087 +VERTEX_SE3:QUAT 2686 31.045651 26.714303 -18.301099 -0.2878216 -0.3718452 0.8367665 0.2805561 +VERTEX_SE3:QUAT 2687 30.519023 25.953937 -18.004698 0.3372135 -0.3714685 -0.3711625 0.7813684 +VERTEX_SE3:QUAT 2688 29.997344 25.208955 -17.746851 -0.6279940 0.1052700 0.4512649 0.6252214 +VERTEX_SE3:QUAT 2689 29.543278 24.214260 -17.378700 -0.6466758 -0.2620396 0.0190499 0.7160885 +VERTEX_SE3:QUAT 2690 29.028664 23.542557 -16.921733 -0.2489307 -0.4541285 -0.3650769 0.7736405 +VERTEX_SE3:QUAT 2691 28.462425 22.795804 -16.534931 0.2106293 -0.2534289 0.7831484 0.5273402 +VERTEX_SE3:QUAT 2692 27.926460 22.040131 -16.333469 -0.5167159 -0.4290677 0.2052532 0.7118825 +VERTEX_SE3:QUAT 2693 27.349076 21.216033 -15.917081 -0.4462744 0.0785659 -0.1440575 0.8797238 +VERTEX_SE3:QUAT 2694 26.854384 20.421957 -15.545249 0.5073161 -0.2762893 -0.6813697 0.4494773 +VERTEX_SE3:QUAT 2695 26.607190 19.664770 -15.464226 -0.1148654 -0.3908763 0.8074382 0.4266910 +VERTEX_SE3:QUAT 2696 26.111259 18.852581 -15.282606 0.1941008 0.0338005 0.9803056 0.0135429 +VERTEX_SE3:QUAT 2697 25.649234 17.926294 -15.205602 -0.3532920 0.5924693 0.1445107 0.7094234 +VERTEX_SE3:QUAT 2698 25.295982 17.075061 -14.710249 -0.1352985 0.0538734 0.1901995 0.9708842 +VERTEX_SE3:QUAT 2699 24.851594 16.258662 -14.479489 0.5119243 -0.0855510 0.8515457 0.0740574 +VERTEX_SE3:QUAT 2700 25.822785 15.913238 -14.800309 -0.1436723 0.5621584 0.6455699 0.4965639 +VERTEX_SE3:QUAT 2701 26.269330 16.895321 -14.863125 -0.0437582 -0.3390260 -0.9391646 0.0334131 +VERTEX_SE3:QUAT 2702 26.516072 17.729925 -15.035148 -0.2901426 -0.0221559 0.2721634 0.9171987 +VERTEX_SE3:QUAT 2703 26.862574 18.416306 -15.318795 0.0773669 -0.1396300 0.9863791 0.0396748 +VERTEX_SE3:QUAT 2704 27.290796 19.078620 -15.616617 0.1050602 -0.2143225 0.6113104 0.7545381 +VERTEX_SE3:QUAT 2705 27.698292 20.126726 -15.940596 0.5761965 0.0213155 0.5715661 0.5838283 +VERTEX_SE3:QUAT 2706 27.924029 21.025503 -16.332237 -0.1775746 0.4513554 -0.8534040 0.1909115 +VERTEX_SE3:QUAT 2707 28.140191 21.869678 -16.742170 0.6982061 -0.2509348 0.6704162 0.0090590 +VERTEX_SE3:QUAT 2708 28.547865 22.575603 -16.955594 -0.2017961 -0.3655360 -0.4790193 0.7721414 +VERTEX_SE3:QUAT 2709 28.687877 23.562883 -17.153820 -0.0575856 0.6872397 0.6064566 0.3957220 +VERTEX_SE3:QUAT 2710 28.878185 24.501614 -17.701545 0.5053717 0.1038927 0.7453933 0.4221310 +VERTEX_SE3:QUAT 2711 29.253035 25.545560 -18.140905 -0.2467401 0.4832904 -0.3513572 0.7629534 +VERTEX_SE3:QUAT 2712 29.658131 26.241917 -18.677095 0.5201977 -0.3227964 0.7014161 0.3649826 +VERTEX_SE3:QUAT 2713 30.078013 26.999352 -18.982047 -0.2716588 0.2750705 -0.5165238 0.7640294 +VERTEX_SE3:QUAT 2714 30.440931 27.775314 -19.477012 0.1940964 0.5913001 0.4084935 0.6677003 +VERTEX_SE3:QUAT 2715 30.746751 28.471207 -20.261721 0.6432332 0.2039385 0.3607395 0.6438378 +VERTEX_SE3:QUAT 2716 31.144190 29.263018 -20.691845 0.0594445 0.0026227 -0.6347807 0.7703979 +VERTEX_SE3:QUAT 2717 31.653484 30.094644 -21.034535 -0.5737152 -0.1929714 -0.7885947 0.1083110 +VERTEX_SE3:QUAT 2718 32.142981 30.937643 -21.359203 0.5368153 -0.0234938 0.8308138 0.1450028 +VERTEX_SE3:QUAT 2719 32.671755 31.848040 -21.596219 0.0737967 -0.0532420 0.1416833 0.9857206 +VERTEX_SE3:QUAT 2720 33.563644 31.356617 -21.543975 -0.5989436 -0.0728309 0.7771083 0.1790665 +VERTEX_SE3:QUAT 2721 32.952393 30.665350 -21.210179 0.0010246 0.2141854 0.1975488 0.9566076 +VERTEX_SE3:QUAT 2722 32.419265 29.718918 -20.708570 0.4862390 -0.0760265 -0.7386479 0.4606418 +VERTEX_SE3:QUAT 2723 31.862806 28.885501 -20.439635 -0.2164187 -0.5276713 0.5121886 0.6421751 +VERTEX_SE3:QUAT 2724 31.295663 28.039026 -20.316903 0.1284363 -0.3251682 -0.1950119 0.9163733 +VERTEX_SE3:QUAT 2725 30.786777 27.177811 -20.095001 -0.6514601 -0.1995382 -0.0776359 0.7278441 +VERTEX_SE3:QUAT 2726 30.315147 26.452479 -19.783956 -0.5495989 0.0244410 0.3586756 0.7541190 +VERTEX_SE3:QUAT 2727 29.729391 25.417638 -19.602997 0.5604599 0.2364709 0.7875173 0.0989078 +VERTEX_SE3:QUAT 2728 29.157521 24.639778 -19.438064 0.3691000 -0.1902540 -0.8532416 0.3155113 +VERTEX_SE3:QUAT 2729 29.070534 23.598636 -19.211500 0.3298391 0.5966866 0.6753653 0.2811638 +VERTEX_SE3:QUAT 2730 28.872014 23.008887 -18.711240 0.4375589 0.3385963 0.1994588 0.8087713 +VERTEX_SE3:QUAT 2731 28.405146 22.051851 -18.378305 -0.3329843 0.4286317 -0.2592026 0.7988807 +VERTEX_SE3:QUAT 2732 28.123936 21.201023 -18.009264 -0.5044424 -0.1725254 0.4977526 0.6841163 +VERTEX_SE3:QUAT 2733 28.091657 20.256466 -17.826922 0.4012947 0.2416081 0.8812132 0.0636503 +VERTEX_SE3:QUAT 2734 27.695952 19.271326 -17.646397 0.0201622 0.5500314 -0.2225717 0.8046868 +VERTEX_SE3:QUAT 2735 27.114871 18.369970 -17.265337 -0.5939042 -0.0559200 -0.0843827 0.7981418 +VERTEX_SE3:QUAT 2736 26.581086 17.392768 -16.930503 -0.0650175 -0.3098017 -0.1252205 0.9402741 +VERTEX_SE3:QUAT 2737 26.216255 16.411601 -16.656966 -0.2417898 0.3179482 0.8751546 0.2730403 +VERTEX_SE3:QUAT 2738 25.948569 15.476976 -16.226892 -0.7610812 0.1078201 -0.2000128 0.6075566 +VERTEX_SE3:QUAT 2739 25.545967 14.653201 -15.665865 0.0382719 -0.0813481 -0.9936258 0.0680109 +VERTEX_SE3:QUAT 2740 26.412690 14.222927 -16.096273 -0.3510945 0.2891620 -0.8833888 0.1128815 +VERTEX_SE3:QUAT 2741 26.779645 15.010204 -16.657937 0.2403895 0.0263407 0.4627126 0.8528869 +VERTEX_SE3:QUAT 2742 27.348641 15.942822 -17.227972 -0.1190546 0.2062393 0.9639388 0.1187994 +VERTEX_SE3:QUAT 2743 27.937562 16.876573 -17.389085 -0.0262843 -0.2129278 0.0404234 0.9758775 +VERTEX_SE3:QUAT 2744 28.486608 17.724625 -17.655928 -0.2011911 -0.0299652 0.9581233 0.2015538 +VERTEX_SE3:QUAT 2745 28.818331 18.724811 -17.881070 -0.1129248 0.0543695 -0.9879281 0.0910493 +VERTEX_SE3:QUAT 2746 29.150966 19.662110 -18.125049 -0.6368854 0.5662631 -0.4328479 0.2938805 +VERTEX_SE3:QUAT 2747 29.316821 20.491829 -18.520303 0.4073612 0.8192546 0.3438363 0.2113181 +VERTEX_SE3:QUAT 2748 29.495045 21.378261 -18.846881 -0.1917060 0.4548942 0.1510468 0.8564490 +VERTEX_SE3:QUAT 2749 29.910453 22.162812 -19.138989 0.1213114 0.7733678 0.1449233 0.6051306 +VERTEX_SE3:QUAT 2750 30.006033 23.155830 -19.441026 -0.0400340 0.4587239 -0.6722036 0.5797517 +VERTEX_SE3:QUAT 2751 30.072114 24.182395 -19.822172 0.4947209 0.6490220 0.4254607 0.3911583 +VERTEX_SE3:QUAT 2752 30.108891 25.133166 -20.012482 -0.1236157 0.6249369 -0.3674778 0.6775936 +VERTEX_SE3:QUAT 2753 30.232769 26.030704 -20.368090 0.7703616 0.0881746 0.2731007 0.5693718 +VERTEX_SE3:QUAT 2754 30.385486 26.985182 -20.452232 0.2349451 0.5342097 0.6432105 0.4956825 +VERTEX_SE3:QUAT 2755 30.736830 27.820529 -20.626910 -0.0967361 0.0594857 0.1149055 0.9868639 +VERTEX_SE3:QUAT 2756 31.009404 28.795948 -20.725218 0.5993672 -0.0000320 0.7978368 0.0649260 +VERTEX_SE3:QUAT 2757 31.193920 29.888417 -20.822370 -0.2576809 0.0327778 0.0942328 0.9610652 +VERTEX_SE3:QUAT 2758 31.526302 30.711759 -20.904675 -0.0712081 0.3960158 0.1827572 0.8970511 +VERTEX_SE3:QUAT 2759 31.698638 31.543976 -20.909059 0.8857341 0.3813106 0.2315334 0.1283337 +VERTEX_SE3:QUAT 2760 32.044769 31.356914 -21.857109 0.0431803 0.2997124 0.3543176 0.8847412 +VERTEX_SE3:QUAT 2761 31.674169 30.444213 -21.857800 0.0953884 -0.1232342 0.6790937 0.7173188 +VERTEX_SE3:QUAT 2762 31.571908 29.547206 -21.684273 0.0519343 0.5712867 -0.2971598 0.7633023 +VERTEX_SE3:QUAT 2763 31.082478 28.849523 -21.679776 -0.1680540 0.6398407 0.0946139 0.7439153 +VERTEX_SE3:QUAT 2764 30.667740 28.092266 -21.744607 0.8126906 -0.1312393 0.5451934 0.1583490 +VERTEX_SE3:QUAT 2765 30.242509 27.075718 -21.644095 0.6141236 0.1896205 0.5475390 0.5358146 +VERTEX_SE3:QUAT 2766 29.629212 26.152630 -21.673036 0.0306254 0.4700039 -0.4526562 0.7571399 +VERTEX_SE3:QUAT 2767 29.282573 25.254175 -21.763449 0.0150245 0.3125133 -0.4922354 0.8122894 +VERTEX_SE3:QUAT 2768 28.778055 24.386568 -21.949272 -0.2534490 -0.3926493 -0.8566304 0.2185735 +VERTEX_SE3:QUAT 2769 28.491213 23.561150 -21.828535 0.3510801 0.3127632 -0.2150628 0.8559614 +VERTEX_SE3:QUAT 2770 28.235420 22.597484 -21.705614 -0.6473558 0.0728843 -0.6913929 0.3124007 +VERTEX_SE3:QUAT 2771 27.744235 21.816174 -21.656945 0.5504369 0.3029348 0.5165156 0.5817743 +VERTEX_SE3:QUAT 2772 27.213323 21.014683 -21.567801 -0.4693389 -0.0042344 -0.7099161 0.5250926 +VERTEX_SE3:QUAT 2773 26.745096 20.161653 -21.368339 0.5319981 0.6906941 0.4310627 0.2326040 +VERTEX_SE3:QUAT 2774 26.206867 19.371861 -21.433322 0.1596703 0.6730844 -0.0978799 0.7154595 +VERTEX_SE3:QUAT 2775 25.637772 18.386239 -21.248812 0.2418987 0.4834208 0.5585377 0.6291462 +VERTEX_SE3:QUAT 2776 25.039417 17.460426 -21.063091 0.3930569 0.7473718 -0.1795745 0.5046729 +VERTEX_SE3:QUAT 2777 24.669104 16.582124 -20.789689 -0.1468747 0.0935639 -0.0527884 0.9833041 +VERTEX_SE3:QUAT 2778 24.096864 15.710842 -20.644542 0.4622502 0.3100181 0.5040273 0.6604317 +VERTEX_SE3:QUAT 2779 23.660955 14.874180 -20.429020 0.7052999 0.4449696 -0.0313240 0.5509745 +VERTEX_SE3:QUAT 2780 24.119646 14.352713 -21.168080 0.6618253 0.5579432 0.3787915 0.3274197 +VERTEX_SE3:QUAT 2781 24.295415 15.265186 -21.521354 0.0228924 0.6631305 -0.2370408 0.7096094 +VERTEX_SE3:QUAT 2782 24.531107 16.245494 -22.077502 0.5390691 0.0093184 0.7293722 0.4211102 +VERTEX_SE3:QUAT 2783 25.111013 17.148101 -22.463899 -0.2904981 0.2807832 0.7303519 0.5507793 +VERTEX_SE3:QUAT 2784 25.770657 17.965732 -22.670474 0.5008182 0.7652751 0.2624321 0.3076760 +VERTEX_SE3:QUAT 2785 26.159202 18.741304 -22.925813 -0.2518266 0.4312275 -0.8614400 0.0924518 +VERTEX_SE3:QUAT 2786 26.625410 19.674373 -23.251741 -0.3207182 0.4094169 -0.8541076 0.0042287 +VERTEX_SE3:QUAT 2787 27.132407 20.472511 -23.532352 0.0776630 -0.1427146 -0.1708451 0.9718091 +VERTEX_SE3:QUAT 2788 27.647138 21.328979 -23.743429 -0.4502871 0.3716823 -0.5606315 0.5871849 +VERTEX_SE3:QUAT 2789 28.248597 22.097346 -23.996677 -0.6050359 0.6697138 -0.2473203 0.3524878 +VERTEX_SE3:QUAT 2790 28.843162 22.847289 -24.426725 0.3311629 0.5820603 -0.1923361 0.7173171 +VERTEX_SE3:QUAT 2791 29.256437 23.633463 -24.555262 0.6283620 0.7080755 0.1534750 0.2832591 +VERTEX_SE3:QUAT 2792 29.812899 24.547984 -24.939582 -0.3562701 -0.0128092 -0.9024500 0.2418501 +VERTEX_SE3:QUAT 2793 30.397217 25.258376 -25.353885 0.4248235 -0.4345519 0.4331145 0.6656587 +VERTEX_SE3:QUAT 2794 30.899706 26.102959 -25.636516 0.1229350 0.4844576 -0.0064246 0.8661100 +VERTEX_SE3:QUAT 2795 31.424174 26.969702 -25.846019 -0.0021093 -0.2834704 0.2452669 0.9270837 +VERTEX_SE3:QUAT 2796 31.651439 27.813579 -26.092750 -0.4935015 0.0115966 -0.6097523 0.6200999 +VERTEX_SE3:QUAT 2797 31.942318 28.729206 -26.342618 -0.4669466 0.7857448 -0.2860586 0.2876393 +VERTEX_SE3:QUAT 2798 32.404133 29.561524 -26.651781 0.1978356 0.1828969 -0.2799045 0.9214463 +VERTEX_SE3:QUAT 2799 32.625511 30.423943 -27.000301 0.1031044 -0.4364652 0.6945058 0.5626094 +VERTEX_SE3:QUAT 2800 25.324657 14.577972 -19.287650 -0.3323828 0.2623053 -0.8254808 0.3732278 +VERTEX_SE3:QUAT 2801 25.878082 15.375131 -19.619114 0.4840874 0.2260829 -0.2037078 0.8203957 +VERTEX_SE3:QUAT 2802 26.256182 16.131804 -19.973067 -0.6417015 0.6427171 -0.4017365 0.1172249 +VERTEX_SE3:QUAT 2803 26.709700 16.824739 -20.341300 -0.0130155 0.7805631 -0.0951746 0.6176517 +VERTEX_SE3:QUAT 2804 27.166583 17.498526 -20.878675 0.0339391 -0.3996953 0.7073023 0.5820783 +VERTEX_SE3:QUAT 2805 27.628884 18.336339 -21.352312 0.1742255 -0.4882161 0.7111724 0.4748939 +VERTEX_SE3:QUAT 2806 27.988489 19.166813 -21.796679 0.6817679 0.0939265 0.7232549 0.0572069 +VERTEX_SE3:QUAT 2807 28.474435 19.766612 -22.289491 0.3976310 0.5545036 0.0371940 0.7300903 +VERTEX_SE3:QUAT 2808 28.945203 20.607878 -22.930078 -0.2883558 0.1221593 -0.3606325 0.8785626 +VERTEX_SE3:QUAT 2809 29.393769 21.247129 -23.573013 -0.4346107 0.2416290 0.0268834 0.8671830 +VERTEX_SE3:QUAT 2810 29.817406 22.186135 -24.301168 0.6135370 0.3993672 0.6810859 0.0141484 +VERTEX_SE3:QUAT 2811 30.011829 23.047124 -24.725200 0.1889823 0.9255156 -0.0461590 0.3249245 +VERTEX_SE3:QUAT 2812 30.159022 23.829700 -25.405932 -0.1689596 -0.5289955 -0.7442907 0.3710091 +VERTEX_SE3:QUAT 2813 30.431024 24.657227 -26.005354 0.5863897 0.3657558 0.2042801 0.6932817 +VERTEX_SE3:QUAT 2814 30.642285 25.589945 -26.431183 0.1367283 0.5824327 0.4439367 0.6670815 +VERTEX_SE3:QUAT 2815 30.694181 26.402268 -27.026587 -0.4491578 0.6502985 -0.0146992 0.6124974 +VERTEX_SE3:QUAT 2816 30.601327 27.269494 -27.699331 0.1680317 0.6527030 -0.6330423 0.3807907 +VERTEX_SE3:QUAT 2817 30.733134 28.105804 -28.298465 -0.2748450 0.9076898 -0.2096290 0.2379393 +VERTEX_SE3:QUAT 2818 30.906615 29.044543 -28.976179 -0.3917040 0.2583469 -0.8418561 0.2666519 +VERTEX_SE3:QUAT 2819 31.109770 29.649823 -29.577380 -0.4870016 0.4061960 -0.7214600 0.2780822 +VERTEX_SE3:QUAT 2820 30.753184 30.338780 -28.919913 -0.2295190 0.1742662 -0.0307601 0.9570821 +VERTEX_SE3:QUAT 2821 30.848186 29.579528 -28.276848 -0.0906607 0.0291307 -0.6256809 0.7742451 +VERTEX_SE3:QUAT 2822 31.103320 28.688896 -27.573180 -0.3907380 0.2603122 -0.8799428 0.0725402 +VERTEX_SE3:QUAT 2823 31.363780 27.974100 -26.747504 -0.6209630 -0.0847766 -0.4956941 0.6012531 +VERTEX_SE3:QUAT 2824 31.531837 27.366776 -26.100094 -0.1761679 -0.8338820 -0.5097240 0.1174186 +VERTEX_SE3:QUAT 2825 31.759717 26.841287 -25.328496 -0.6753310 0.6339851 0.2153826 0.3091946 +VERTEX_SE3:QUAT 2826 32.028726 26.253080 -24.591528 -0.2561519 0.4347839 -0.6727178 0.5411099 +VERTEX_SE3:QUAT 2827 32.193979 25.299035 -23.938113 -0.4671144 -0.2233351 -0.1115245 0.8482263 +VERTEX_SE3:QUAT 2828 32.641842 24.769071 -23.130720 0.5592892 -0.0676644 0.6763394 0.4745337 +VERTEX_SE3:QUAT 2829 33.027103 24.166969 -22.335175 -0.6632716 0.5564888 0.0834528 0.4933829 +VERTEX_SE3:QUAT 2830 33.344056 23.541551 -21.611171 -0.4777020 0.3442211 -0.2600060 0.7653166 +VERTEX_SE3:QUAT 2831 33.754030 22.889311 -21.030924 -0.8668137 -0.0531142 -0.3188099 0.3797013 +VERTEX_SE3:QUAT 2832 34.164357 22.394779 -20.368870 -0.2157461 -0.7729387 -0.5842366 0.1211900 +VERTEX_SE3:QUAT 2833 34.467799 21.850607 -19.853363 -0.6112768 -0.5537003 -0.5461551 0.1465311 +VERTEX_SE3:QUAT 2834 34.979184 21.312053 -19.196226 0.4557758 0.0910308 0.7101543 0.5288314 +VERTEX_SE3:QUAT 2835 35.517357 20.697289 -18.470421 -0.7754087 0.0349942 -0.3686449 0.5114858 +VERTEX_SE3:QUAT 2836 35.864586 20.167979 -17.772061 -0.5430485 0.3274235 -0.0457480 0.7718804 +VERTEX_SE3:QUAT 2837 36.366131 19.917251 -17.018046 -0.4066794 0.3353568 -0.1541880 0.8356876 +VERTEX_SE3:QUAT 2838 36.906442 19.287007 -16.328861 -0.0784017 0.7232046 0.6162259 0.3018176 +VERTEX_SE3:QUAT 2839 37.235201 18.721806 -15.640486 -0.6126057 0.4359241 0.1462236 0.6428865 +VERTEX_SE3:QUAT 2840 36.945598 19.296458 -14.993756 -0.1687328 0.7613287 0.6082744 0.1480209 +VERTEX_SE3:QUAT 2841 36.524910 19.804420 -15.648102 -0.6429189 0.2510170 0.4203105 0.5890541 +VERTEX_SE3:QUAT 2842 35.969818 20.366523 -16.409321 0.3055974 0.9199512 -0.1125299 0.2182594 +VERTEX_SE3:QUAT 2843 35.329367 20.876776 -17.082564 -0.5575470 0.2840931 0.3714352 0.6859069 +VERTEX_SE3:QUAT 2844 34.713773 21.396913 -17.929759 -0.6144045 -0.7700181 0.0184671 0.1709916 +VERTEX_SE3:QUAT 2845 34.270570 21.824837 -18.686314 0.4472924 0.2981444 0.5213593 0.6627397 +VERTEX_SE3:QUAT 2846 33.879360 22.198229 -19.388813 -0.0674967 -0.9532896 -0.2821895 0.0839778 +VERTEX_SE3:QUAT 2847 33.232494 22.725048 -20.263384 -0.8962520 0.0385086 0.3139935 0.3108980 +VERTEX_SE3:QUAT 2848 32.789133 23.068293 -20.812035 0.0755500 0.6925671 -0.3387275 0.6323817 +VERTEX_SE3:QUAT 2849 32.394621 23.331459 -21.674106 0.0192966 0.4419348 0.8565056 0.2659312 +VERTEX_SE3:QUAT 2850 31.729059 23.799290 -22.426491 0.5065335 -0.4263499 0.7378318 0.1313540 +VERTEX_SE3:QUAT 2851 31.337531 24.182601 -23.126543 -0.1546120 0.7444349 0.6491295 0.0232960 +VERTEX_SE3:QUAT 2852 30.850696 24.688610 -23.982080 -0.6789432 -0.6747525 -0.2648275 0.1166690 +VERTEX_SE3:QUAT 2853 30.547971 25.087116 -24.706713 -0.2741886 -0.8648906 -0.3173420 0.2758239 +VERTEX_SE3:QUAT 2854 30.026591 25.813085 -25.382708 -0.1753512 0.4041078 -0.1806542 0.8793821 +VERTEX_SE3:QUAT 2855 29.520364 26.336484 -26.129567 -0.5049636 0.1983688 -0.7098475 0.4491971 +VERTEX_SE3:QUAT 2856 29.050991 26.947877 -26.836286 -0.1115420 0.5543218 0.7485448 0.3463618 +VERTEX_SE3:QUAT 2857 28.548084 27.533693 -27.596694 0.4024019 0.4733928 0.4738625 0.6240403 +VERTEX_SE3:QUAT 2858 27.919704 28.134523 -28.144312 -0.8170925 0.1783372 -0.5456421 0.0532013 +VERTEX_SE3:QUAT 2859 27.413021 28.844696 -28.708242 -0.6822790 -0.3193144 -0.6576608 0.0039915 +VERTEX_SE3:QUAT 2860 27.343956 29.672300 -28.038927 0.0205992 0.2924431 0.9109788 0.2901212 +VERTEX_SE3:QUAT 2861 27.934291 28.919415 -27.643438 -0.7795822 -0.3607998 -0.4961719 0.1260501 +VERTEX_SE3:QUAT 2862 28.539318 28.386632 -27.118686 -0.4041452 -0.8292431 -0.1637119 0.3496011 +VERTEX_SE3:QUAT 2863 29.325723 27.755993 -26.652940 0.8295539 -0.1278164 0.2799727 0.4659598 +VERTEX_SE3:QUAT 2864 30.181524 27.107665 -26.228919 -0.8370835 -0.3627531 -0.3937742 0.1124426 +VERTEX_SE3:QUAT 2865 30.635466 26.597255 -25.742637 0.5858346 0.8034632 -0.1048216 0.0160364 +VERTEX_SE3:QUAT 2866 31.072268 26.002955 -25.216019 -0.1450151 0.8627686 0.4822561 0.0450549 +VERTEX_SE3:QUAT 2867 31.674517 25.316573 -24.684374 -0.0994663 0.5594916 0.3613747 0.7392455 +VERTEX_SE3:QUAT 2868 32.388782 24.653346 -24.328492 0.2698994 0.6715841 -0.0477324 0.6883682 +VERTEX_SE3:QUAT 2869 32.885681 24.073548 -23.816061 -0.3723012 0.7409884 0.5464025 0.1173556 +VERTEX_SE3:QUAT 2870 33.487079 23.424030 -23.115332 -0.6484069 0.4605439 0.1401853 0.5897592 +VERTEX_SE3:QUAT 2871 33.975661 22.778699 -22.285932 0.1010436 0.7481682 0.5326593 0.3825031 +VERTEX_SE3:QUAT 2872 34.535119 21.991779 -21.741881 0.2009734 0.3727494 -0.1062336 0.8996566 +VERTEX_SE3:QUAT 2873 35.056165 21.199501 -21.031549 -0.5105940 0.7186733 -0.4545483 0.1272333 +VERTEX_SE3:QUAT 2874 35.539765 20.440055 -20.633832 0.1142357 0.7987387 0.5872921 0.0636765 +VERTEX_SE3:QUAT 2875 35.968729 19.737210 -20.162487 0.5722388 -0.3050409 0.6568583 0.3847466 +VERTEX_SE3:QUAT 2876 36.532702 19.036075 -19.423753 -0.7684651 0.0565871 -0.6209030 0.1440094 +VERTEX_SE3:QUAT 2877 37.006506 18.418666 -18.921234 0.5862973 0.7361755 0.3380419 0.0053578 +VERTEX_SE3:QUAT 2878 37.483431 17.782204 -18.397357 -0.6215870 0.4870694 0.0218148 0.6131208 +VERTEX_SE3:QUAT 2879 38.005576 17.219791 -17.734449 -0.2841439 0.1232748 -0.0768960 0.9477091 +VERTEX_SE3:QUAT 2880 37.988561 17.954215 -17.037927 -0.7218851 -0.6384149 -0.2667943 0.0113632 +VERTEX_SE3:QUAT 2881 37.557122 18.475012 -17.863781 0.2691960 0.6735414 -0.3175204 0.6107833 +VERTEX_SE3:QUAT 2882 36.903110 19.061358 -18.541796 -0.8461059 -0.2610315 -0.2666275 0.3806272 +VERTEX_SE3:QUAT 2883 36.233135 19.482344 -19.259118 -0.6413303 -0.6505608 -0.1998336 0.3543058 +VERTEX_SE3:QUAT 2884 35.465319 19.917927 -19.943439 -0.5474862 0.5609088 0.5270435 0.3284286 +VERTEX_SE3:QUAT 2885 34.627508 20.329462 -20.542654 0.3358542 0.4167053 0.5498443 0.6412721 +VERTEX_SE3:QUAT 2886 34.026019 20.683486 -21.242922 -0.5656898 -0.3204457 0.0291262 0.7592504 +VERTEX_SE3:QUAT 2887 33.317562 21.331261 -21.692355 -0.0998210 0.3534461 0.8716536 0.3245484 +VERTEX_SE3:QUAT 2888 32.354824 21.786579 -22.275152 -0.3635951 -0.6481380 -0.6018793 0.2923304 +VERTEX_SE3:QUAT 2889 31.742918 22.427978 -22.641769 -0.4365691 0.6133189 0.6534102 0.0793875 +VERTEX_SE3:QUAT 2890 30.875410 22.602351 -23.156919 -0.7990506 -0.5608621 0.0788705 0.2018198 +VERTEX_SE3:QUAT 2891 30.210656 23.237475 -23.695861 -0.2467702 -0.5872811 -0.7350961 0.2320326 +VERTEX_SE3:QUAT 2892 29.658042 23.690540 -24.237036 -0.8968835 0.1971736 0.1474792 0.3673859 +VERTEX_SE3:QUAT 2893 28.929596 24.229460 -24.787548 -0.2175512 0.4275503 0.4723046 0.7394596 +VERTEX_SE3:QUAT 2894 28.260551 24.730252 -25.339219 -0.0886745 0.5015448 -0.0985400 0.8549149 +VERTEX_SE3:QUAT 2895 27.248339 24.905339 -25.842561 -0.6616405 0.1210483 0.1537936 0.7238278 +VERTEX_SE3:QUAT 2896 26.562989 25.175200 -26.509836 -0.7228134 0.4496941 -0.2113664 0.4802503 +VERTEX_SE3:QUAT 2897 26.015115 25.513001 -27.245984 0.9151128 -0.3439825 0.1849987 0.1001002 +VERTEX_SE3:QUAT 2898 25.355577 25.924374 -27.777237 -0.2016962 -0.6606877 -0.3834978 0.6129762 +VERTEX_SE3:QUAT 2899 24.769468 26.079423 -28.612063 -0.6088839 -0.2915486 0.0273872 0.7372311 +VERTEX_SE3:QUAT 2900 24.608195 26.587338 -27.660885 -0.6474350 -0.4153528 -0.2300913 0.5961275 +VERTEX_SE3:QUAT 2901 25.390463 26.194088 -27.202801 -0.3440034 -0.8897512 -0.2634894 0.1434498 +VERTEX_SE3:QUAT 2902 26.221674 25.941916 -26.832644 -0.6383394 0.3463585 -0.6387048 0.2541943 +VERTEX_SE3:QUAT 2903 27.064189 25.873867 -26.191668 -0.1274347 0.7292861 0.6264296 0.2439018 +VERTEX_SE3:QUAT 2904 28.007883 25.705225 -25.574643 -0.4564218 0.8657726 0.1444230 0.1458046 +VERTEX_SE3:QUAT 2905 28.780500 25.382304 -25.022073 -0.5859936 -0.1708728 -0.7894132 0.0651207 +VERTEX_SE3:QUAT 2906 29.697408 25.311182 -24.322720 -0.7601222 -0.2402291 0.1390925 0.5875010 +VERTEX_SE3:QUAT 2907 30.671214 24.991520 -23.598908 -0.4601778 -0.2689197 -0.4736601 0.7011168 +VERTEX_SE3:QUAT 2908 31.431127 24.856400 -22.989472 -0.3830225 -0.8922819 -0.2353897 0.0414536 +VERTEX_SE3:QUAT 2909 32.172186 24.790045 -22.202313 -0.6889129 0.4412186 0.0540624 0.5725403 +VERTEX_SE3:QUAT 2910 33.016350 24.586629 -21.534208 0.0875188 0.9637359 0.0291216 0.2504107 +VERTEX_SE3:QUAT 2911 33.813642 24.485354 -20.886411 -0.1049494 0.9414212 -0.1731521 0.2696851 +VERTEX_SE3:QUAT 2912 34.529216 24.516790 -20.347518 0.0387758 0.8074236 0.0285486 0.5880039 +VERTEX_SE3:QUAT 2913 35.205266 24.434391 -19.671116 -0.0597887 0.9762929 0.0640248 0.1979350 +VERTEX_SE3:QUAT 2914 35.898928 24.360849 -18.985673 0.1913455 0.6602145 -0.3128315 0.6554694 +VERTEX_SE3:QUAT 2915 36.495606 24.269875 -18.087971 -0.4701254 0.6014159 -0.2017898 0.6136464 +VERTEX_SE3:QUAT 2916 37.224566 24.187031 -17.416201 -0.6599179 -0.2983263 -0.3807485 0.5749264 +VERTEX_SE3:QUAT 2917 37.809280 23.923144 -16.706726 0.2365708 0.5363286 0.4891270 0.6458643 +VERTEX_SE3:QUAT 2918 38.468107 23.846281 -16.062751 -0.0283548 -0.9479002 -0.2240751 0.2246589 +VERTEX_SE3:QUAT 2919 39.058572 23.899176 -15.423433 0.6172656 -0.7540150 -0.0919802 0.2049004 +VERTEX_SE3:QUAT 2920 38.673782 24.787227 -15.062787 -0.3496911 -0.1149061 -0.6707304 0.6439204 +VERTEX_SE3:QUAT 2921 37.871947 25.010035 -15.680512 0.6485673 -0.6246130 -0.4184605 0.1187852 +VERTEX_SE3:QUAT 2922 37.273697 25.064271 -16.290503 -0.5708403 -0.0270006 -0.6714570 0.4717603 +VERTEX_SE3:QUAT 2923 36.653624 25.201172 -16.812434 -0.8217647 0.4470261 -0.3336212 0.1164791 +VERTEX_SE3:QUAT 2924 35.745401 25.406973 -17.352858 -0.5882476 0.3796626 -0.5814172 0.4144576 +VERTEX_SE3:QUAT 2925 35.025733 25.680560 -18.114393 -0.8410970 -0.2106643 -0.4312053 0.2494761 +VERTEX_SE3:QUAT 2926 34.333455 25.914863 -18.842331 0.2692395 -0.7728806 -0.5567576 0.1420799 +VERTEX_SE3:QUAT 2927 33.659489 26.124527 -19.573893 0.8422715 -0.3645044 0.2593575 0.3007471 +VERTEX_SE3:QUAT 2928 32.728540 26.553516 -19.898102 0.0280027 0.9354829 0.3513369 0.0254959 +VERTEX_SE3:QUAT 2929 31.886373 26.802486 -20.228303 -0.9399252 -0.1809464 -0.2015421 0.2077973 +VERTEX_SE3:QUAT 2930 31.066255 27.164743 -20.748799 0.0087640 0.9602389 0.2102212 0.1834982 +VERTEX_SE3:QUAT 2931 30.225538 27.430726 -21.391050 -0.6590470 -0.1348697 -0.6547827 0.3445675 +VERTEX_SE3:QUAT 2932 29.410556 27.716298 -22.048069 -0.7692541 0.3838233 0.0495518 0.5084019 +VERTEX_SE3:QUAT 2933 28.540742 27.782783 -22.500751 -0.1987212 -0.7255626 -0.2992012 0.5869816 +VERTEX_SE3:QUAT 2934 27.728127 28.013528 -22.932695 -0.4711110 0.0175849 -0.6093000 0.6375725 +VERTEX_SE3:QUAT 2935 26.899980 28.093639 -23.445447 0.1236327 0.8653008 -0.2026183 0.4414922 +VERTEX_SE3:QUAT 2936 26.015687 28.121778 -23.826841 0.3710152 0.4855196 0.4309667 0.6639925 +VERTEX_SE3:QUAT 2937 25.098602 27.983756 -24.163049 0.9229254 0.3835967 0.0102345 0.0309444 +VERTEX_SE3:QUAT 2938 24.261656 27.947142 -24.696881 0.8424122 -0.1874941 0.1798591 0.4720577 +VERTEX_SE3:QUAT 2939 23.497234 27.940312 -25.075721 -0.6298568 0.5194244 -0.5408441 0.2024013 +VERTEX_SE3:QUAT 2940 23.393591 28.849778 -24.659834 0.8017041 0.2072175 0.1123756 0.5492751 +VERTEX_SE3:QUAT 2941 24.266923 28.593856 -24.243870 -0.9772841 0.1649607 0.0830011 0.1039927 +VERTEX_SE3:QUAT 2942 25.109813 28.512839 -23.754240 -0.7964155 0.0495488 0.2302514 0.5570023 +VERTEX_SE3:QUAT 2943 25.947839 28.356034 -23.353208 0.4863614 0.3938465 0.6260074 0.4652444 +VERTEX_SE3:QUAT 2944 26.922765 28.377302 -23.181037 -0.3547161 0.7023717 0.6081684 0.1047934 +VERTEX_SE3:QUAT 2945 27.982317 28.098151 -23.143104 -0.1487781 0.8905918 0.4008506 0.1550167 +VERTEX_SE3:QUAT 2946 28.932380 27.781147 -23.006437 -0.9704461 0.0896608 -0.2038635 0.0929249 +VERTEX_SE3:QUAT 2947 29.974394 27.470973 -23.004005 0.7789573 -0.2924649 -0.5359344 0.1430527 +VERTEX_SE3:QUAT 2948 30.957086 26.921324 -23.034847 -0.2915237 -0.6743757 0.1390441 0.6640016 +VERTEX_SE3:QUAT 2949 31.682980 26.707180 -23.014812 -0.6186839 -0.2854069 -0.3892058 0.6199129 +VERTEX_SE3:QUAT 2950 32.618084 26.474958 -23.138831 -0.5521701 0.8292006 -0.0689045 0.0527893 +VERTEX_SE3:QUAT 2951 33.642591 26.326667 -23.314552 0.7895412 -0.1424618 -0.5342807 0.2662207 +VERTEX_SE3:QUAT 2952 34.566058 26.165223 -23.363277 -0.6315373 -0.1741856 0.3154418 0.6865249 +VERTEX_SE3:QUAT 2953 35.470949 25.919851 -23.643971 -0.4985968 0.6939157 0.3586314 0.3758533 +VERTEX_SE3:QUAT 2954 36.441805 25.939507 -23.771282 0.4600973 0.6477279 0.2636184 0.5470506 +VERTEX_SE3:QUAT 2955 37.528246 25.642328 -23.899267 -0.2550162 -0.7837204 0.3222424 0.4657348 +VERTEX_SE3:QUAT 2956 38.564199 25.645760 -24.046184 -0.8852303 -0.1065350 -0.2593142 0.3711788 +VERTEX_SE3:QUAT 2957 39.360417 25.473997 -24.092054 0.7828877 -0.3831920 0.2064788 0.4445417 +VERTEX_SE3:QUAT 2958 40.268314 25.254877 -24.214192 -0.7857246 0.1861756 0.4303462 0.4034571 +VERTEX_SE3:QUAT 2959 41.180473 24.994341 -24.269066 -0.5670689 -0.3552156 -0.2784450 0.6890015 +VERTEX_SE3:QUAT 2960 41.347457 25.984851 -24.153644 0.0300169 -0.8099952 0.4792031 0.3367063 +VERTEX_SE3:QUAT 2961 40.309762 26.289481 -24.088649 0.1568718 -0.8331714 -0.5185693 0.1109172 +VERTEX_SE3:QUAT 2962 39.329223 26.491136 -23.847774 -0.9328401 0.2501975 0.1226776 0.2283872 +VERTEX_SE3:QUAT 2963 38.461026 26.543430 -23.618922 0.4967022 0.6282453 0.5783931 0.1551004 +VERTEX_SE3:QUAT 2964 37.512816 27.050297 -23.498914 -0.6951666 0.5857874 -0.3900909 0.1463745 +VERTEX_SE3:QUAT 2965 36.488001 27.288331 -23.312863 0.7091417 0.6803413 0.1393090 0.1218474 +VERTEX_SE3:QUAT 2966 35.678935 27.570371 -23.193478 -0.7906309 0.4469965 -0.3505065 0.2285654 +VERTEX_SE3:QUAT 2967 34.664705 27.913485 -23.013005 0.7660866 -0.3994324 0.2433960 0.4408213 +VERTEX_SE3:QUAT 2968 33.558381 28.125711 -22.889129 -0.0004267 0.8151211 -0.2760064 0.5093112 +VERTEX_SE3:QUAT 2969 32.468059 28.413405 -22.688894 -0.9552030 -0.2019420 0.1964332 0.0906683 +VERTEX_SE3:QUAT 2970 31.423184 28.535074 -22.507237 -0.8586538 0.2224675 -0.4404561 0.1386370 +VERTEX_SE3:QUAT 2971 30.441400 28.626953 -22.249760 0.3062198 0.9227952 0.1688330 0.1617834 +VERTEX_SE3:QUAT 2972 29.452211 29.048706 -22.044022 -0.2803803 -0.6479582 0.0202650 0.7079028 +VERTEX_SE3:QUAT 2973 28.515380 29.278918 -21.638574 -0.0534161 -0.6426975 -0.7641787 0.0108443 +VERTEX_SE3:QUAT 2974 27.612477 29.577593 -21.423015 0.6503255 0.7559670 0.0447587 0.0598941 +VERTEX_SE3:QUAT 2975 26.787592 29.917673 -21.307137 -0.2977970 -0.6547220 0.3085019 0.6224810 +VERTEX_SE3:QUAT 2976 25.926308 30.401215 -21.152627 -0.7180414 -0.3652972 0.4183415 0.4194817 +VERTEX_SE3:QUAT 2977 25.089952 30.975278 -20.770971 -0.4895080 -0.4591264 -0.6860829 0.2808472 +VERTEX_SE3:QUAT 2978 24.160765 31.243323 -20.592031 -0.6471985 0.3099872 0.1103589 0.6876503 +VERTEX_SE3:QUAT 2979 23.255368 31.856797 -20.467836 0.5221383 -0.7558813 0.3861329 0.0831658 +VERTEX_SE3:QUAT 2980 23.872767 32.540006 -20.145985 0.8567249 -0.2192136 -0.3682258 0.2870149 +VERTEX_SE3:QUAT 2981 24.673150 31.907766 -20.443019 -0.6828636 -0.3150320 -0.6572689 0.0494949 +VERTEX_SE3:QUAT 2982 25.681779 31.310434 -20.724307 -0.1080813 0.7870777 -0.2885730 0.5343714 +VERTEX_SE3:QUAT 2983 26.426004 30.712635 -21.143411 0.8553869 -0.4905999 0.0123378 0.1657487 +VERTEX_SE3:QUAT 2984 27.134179 30.240775 -21.363528 -0.8811901 -0.2121517 -0.1124088 0.4072590 +VERTEX_SE3:QUAT 2985 27.933020 29.648634 -21.631211 -0.6463025 0.6042408 -0.4558881 0.0967070 +VERTEX_SE3:QUAT 2986 28.537276 29.137697 -22.053859 0.3476588 -0.7009021 -0.6030915 0.1554033 +VERTEX_SE3:QUAT 2987 29.219215 28.466132 -22.235311 -0.4586518 0.6038957 -0.3535014 0.5477092 +VERTEX_SE3:QUAT 2988 30.081959 27.958420 -22.419069 0.7826019 -0.4710543 0.2159452 0.3449780 +VERTEX_SE3:QUAT 2989 30.869371 27.270381 -22.688076 0.4965516 -0.6911923 -0.5132315 0.1108292 +VERTEX_SE3:QUAT 2990 31.423648 26.613350 -23.121777 -0.1309546 -0.7346573 0.0958267 0.6587464 +VERTEX_SE3:QUAT 2991 32.083969 25.974696 -23.372147 -0.4301209 -0.8654601 -0.1439207 0.2127479 +VERTEX_SE3:QUAT 2992 32.801972 25.357868 -23.657296 0.5162480 -0.5535887 -0.2148976 0.6171278 +VERTEX_SE3:QUAT 2993 33.529515 24.795942 -23.921565 0.9244023 0.3785710 0.0152493 0.0439526 +VERTEX_SE3:QUAT 2994 34.300829 24.192320 -24.111696 0.8044884 -0.2193594 0.1811114 0.5214197 +VERTEX_SE3:QUAT 2995 35.219755 23.577048 -24.285582 -0.1411426 0.8724805 0.4652999 0.0485041 +VERTEX_SE3:QUAT 2996 36.056284 22.907986 -24.339914 -0.3964338 -0.7260090 0.5596206 0.0507530 +VERTEX_SE3:QUAT 2997 36.852388 22.378004 -24.512244 -0.4637426 0.5283418 -0.4840139 0.5210838 +VERTEX_SE3:QUAT 2998 37.671843 21.822630 -24.585236 0.9265314 -0.0784529 -0.2922051 0.2236089 +VERTEX_SE3:QUAT 2999 38.405433 21.291557 -24.572949 0.6970268 0.7143967 -0.0551888 0.0272983 +VERTEX_SE3:QUAT 3000 38.875206 21.966131 -24.233978 0.4871862 0.4909454 0.7219973 0.0184996 +VERTEX_SE3:QUAT 3001 38.182597 22.466294 -24.195160 0.4568147 0.7822055 -0.3425692 0.2492415 +VERTEX_SE3:QUAT 3002 37.352321 23.050952 -24.118758 -0.1698283 -0.8880145 -0.1749293 0.3898568 +VERTEX_SE3:QUAT 3003 36.403744 23.502658 -24.105352 -0.6257235 -0.3764051 -0.2273732 0.6442753 +VERTEX_SE3:QUAT 3004 35.701405 24.204859 -23.734878 0.5613978 -0.5806972 -0.5742939 0.1334534 +VERTEX_SE3:QUAT 3005 35.145832 24.942475 -23.613959 -0.6825620 0.3483541 -0.1426623 0.6264232 +VERTEX_SE3:QUAT 3006 34.519087 25.483368 -23.367336 -0.9131547 0.0464621 0.3952672 0.0880548 +VERTEX_SE3:QUAT 3007 33.815598 26.011387 -23.173263 -0.9308575 0.1667160 -0.0841635 0.3140488 +VERTEX_SE3:QUAT 3008 32.975182 26.554993 -23.153144 0.1617358 -0.8044586 -0.5190886 0.2392382 +VERTEX_SE3:QUAT 3009 32.138285 27.176444 -23.216543 -0.5913956 -0.4697539 -0.0503859 0.6534859 +VERTEX_SE3:QUAT 3010 31.370366 27.807845 -23.249408 0.3971173 -0.6586021 -0.3837851 0.5111263 +VERTEX_SE3:QUAT 3011 30.635096 28.448100 -23.138521 -0.8290634 0.4432813 0.0404190 0.3384107 +VERTEX_SE3:QUAT 3012 29.871136 29.131290 -23.209988 0.0479248 0.7018928 0.6673318 0.2443725 +VERTEX_SE3:QUAT 3013 29.176822 29.812800 -23.310473 0.9551265 0.2713044 0.0611430 0.1019257 +VERTEX_SE3:QUAT 3014 28.393308 30.457983 -23.348163 0.8101526 0.3095482 0.4710516 0.1610686 +VERTEX_SE3:QUAT 3015 27.804763 31.135159 -23.417783 0.7410242 0.0773118 0.0912408 0.6607429 +VERTEX_SE3:QUAT 3016 27.360206 32.036896 -23.472397 -0.3916988 -0.8598454 0.0290252 0.3261832 +VERTEX_SE3:QUAT 3017 26.666231 32.670344 -23.635676 0.7212880 0.6820162 0.1120606 0.0451659 +VERTEX_SE3:QUAT 3018 25.863138 33.288677 -23.643135 0.7052255 0.2533944 -0.2085554 0.6284528 +VERTEX_SE3:QUAT 3019 25.090787 33.972795 -23.509529 -0.7250433 0.4615413 -0.0798223 0.5048962 +VERTEX_SE3:QUAT 3020 25.839995 34.804959 -23.425552 -0.8608141 -0.0207161 0.4746245 0.1824873 +VERTEX_SE3:QUAT 3021 26.646588 34.207307 -23.544149 -0.4773221 0.6284954 0.6042913 0.1094952 +VERTEX_SE3:QUAT 3022 27.341156 33.591426 -23.763161 -0.9129158 -0.2633839 -0.3083077 0.0464769 +VERTEX_SE3:QUAT 3023 28.081851 32.877618 -23.886946 0.0121492 -0.7522487 0.5791573 0.3139284 +VERTEX_SE3:QUAT 3024 28.776135 32.223935 -24.008512 0.6414693 0.7053898 -0.0802649 0.2906887 +VERTEX_SE3:QUAT 3025 29.515210 31.616245 -24.197567 -0.3279377 -0.8324849 -0.2342147 0.3802226 +VERTEX_SE3:QUAT 3026 30.089138 30.997974 -24.243041 -0.6627871 -0.6643436 0.3277835 0.1091732 +VERTEX_SE3:QUAT 3027 30.948540 30.323252 -24.573631 0.8642077 0.0860249 0.3608543 0.3398956 +VERTEX_SE3:QUAT 3028 31.799819 29.731500 -25.040663 0.9845045 0.0943925 -0.0704721 0.1299026 +VERTEX_SE3:QUAT 3029 32.535268 28.993165 -25.224046 0.7903659 0.2550036 -0.5086236 0.2271495 +VERTEX_SE3:QUAT 3030 33.270485 28.521300 -25.720143 -0.4894432 -0.8419214 0.2072524 0.0930599 +VERTEX_SE3:QUAT 3031 33.942272 28.090032 -25.968273 -0.6674864 -0.6407538 -0.0221357 0.3786905 +VERTEX_SE3:QUAT 3032 34.810745 27.726069 -26.242306 0.4465306 -0.5746116 -0.6516133 0.2140843 +VERTEX_SE3:QUAT 3033 35.714198 27.188904 -26.687342 -0.2182251 -0.6703889 -0.7089517 0.0185490 +VERTEX_SE3:QUAT 3034 36.564342 26.630958 -26.811039 -0.7443336 -0.2456965 -0.2567362 0.5654089 +VERTEX_SE3:QUAT 3035 37.328753 26.317682 -26.947499 0.3873708 -0.6306487 -0.0911540 0.6662710 +VERTEX_SE3:QUAT 3036 37.996924 25.982942 -27.307191 0.5241751 -0.7748997 -0.2606104 0.2384390 +VERTEX_SE3:QUAT 3037 38.762213 25.603093 -27.694751 -0.1781529 -0.8213060 -0.4276728 0.3328873 +VERTEX_SE3:QUAT 3038 39.494214 24.987380 -27.969537 0.0795033 -0.8057160 -0.2816598 0.5149453 +VERTEX_SE3:QUAT 3039 40.402080 24.459474 -28.204869 -0.7232431 -0.1400856 0.5897117 0.3309615 +VERTEX_SE3:QUAT 3040 41.042950 25.412013 -28.184431 0.0827499 -0.8377752 -0.1426023 0.5205283 +VERTEX_SE3:QUAT 3041 40.240455 25.798403 -27.867596 0.7322028 0.6738939 0.0935652 0.0314898 +VERTEX_SE3:QUAT 3042 39.411764 26.014170 -27.375050 -0.7554483 -0.5790780 0.3020460 0.0522942 +VERTEX_SE3:QUAT 3043 38.770224 26.464847 -26.969817 -0.7946646 0.1600062 -0.2465668 0.5311413 +VERTEX_SE3:QUAT 3044 37.919848 26.951059 -26.691812 0.6563334 0.6841219 0.1574386 0.2764359 +VERTEX_SE3:QUAT 3045 37.012686 27.672664 -26.447601 -0.7059553 0.3375089 0.4592203 0.4205136 +VERTEX_SE3:QUAT 3046 36.273707 28.178589 -26.119728 0.8001120 0.4823621 -0.0895071 0.3451609 +VERTEX_SE3:QUAT 3047 35.437412 28.710272 -25.850643 -0.2121735 -0.7786806 -0.4773581 0.3475173 +VERTEX_SE3:QUAT 3048 34.501969 29.285054 -25.674013 0.8893557 0.0396261 -0.3117925 0.3320567 +VERTEX_SE3:QUAT 3049 33.618740 29.716753 -25.448164 0.7289695 0.0716318 -0.6365409 0.2414292 +VERTEX_SE3:QUAT 3050 32.556693 30.144101 -25.126260 0.1511682 0.8688067 0.3022106 0.3619278 +VERTEX_SE3:QUAT 3051 31.607230 30.598210 -24.985458 0.7494569 0.3927830 0.1781674 0.5022870 +VERTEX_SE3:QUAT 3052 30.792424 31.007582 -24.727279 -0.3366261 -0.7993293 -0.4622107 0.1847074 +VERTEX_SE3:QUAT 3053 29.981148 31.544886 -24.553980 0.7959536 0.1498091 -0.4671918 0.3546082 +VERTEX_SE3:QUAT 3054 29.078408 31.979016 -24.144121 -0.0322626 -0.7845522 0.1841538 0.5912059 +VERTEX_SE3:QUAT 3055 28.139730 32.293762 -23.722679 -0.5622114 -0.5763177 -0.5914424 0.0444082 +VERTEX_SE3:QUAT 3056 27.314182 32.510501 -23.480812 0.7419849 0.6393712 0.1975093 0.0406564 +VERTEX_SE3:QUAT 3057 26.476882 32.960478 -23.291850 -0.6536415 -0.4873484 0.5622849 0.1381299 +VERTEX_SE3:QUAT 3058 25.830778 33.476751 -23.082939 -0.3992573 -0.6810273 0.1390297 0.5978847 +VERTEX_SE3:QUAT 3059 24.991513 33.906165 -22.955317 0.0292801 -0.9794336 0.1995792 0.0045463 +VERTEX_SE3:QUAT 3060 25.245785 34.910023 -23.205468 0.2869833 -0.8737225 -0.1895427 0.3439815 +VERTEX_SE3:QUAT 3061 26.146447 34.552493 -23.539395 0.0569238 -0.8278520 0.0813735 0.5520861 +VERTEX_SE3:QUAT 3062 26.993520 34.142444 -23.759526 -0.9610963 -0.2176513 -0.1555990 0.0686341 +VERTEX_SE3:QUAT 3063 27.781503 33.554964 -23.884837 0.9152931 -0.1595817 0.0951604 0.3573748 +VERTEX_SE3:QUAT 3064 28.552641 33.037143 -23.953695 -0.6035955 -0.3206232 0.2837378 0.6725817 +VERTEX_SE3:QUAT 3065 29.598594 32.658290 -24.253022 -0.1058198 -0.8242751 0.3068675 0.4639020 +VERTEX_SE3:QUAT 3066 30.465712 32.191614 -24.485796 0.7816863 0.4573666 0.2169120 0.3643233 +VERTEX_SE3:QUAT 3067 31.351124 31.876929 -24.754593 -0.3112875 -0.4437492 0.8373208 0.0712788 +VERTEX_SE3:QUAT 3068 32.199999 31.571466 -25.232100 0.8314587 0.3426267 0.3822470 0.2125339 +VERTEX_SE3:QUAT 3069 33.067045 31.160330 -25.586627 -0.4605347 0.7848687 -0.0085846 0.4145061 +VERTEX_SE3:QUAT 3070 33.806161 30.664453 -25.866418 -0.8524458 -0.4617141 -0.1659571 0.1805949 +VERTEX_SE3:QUAT 3071 34.648228 30.438968 -26.267223 0.7052509 0.5573467 -0.3182786 0.3011388 +VERTEX_SE3:QUAT 3072 35.333931 30.007589 -26.621507 -0.8404137 -0.3948276 0.0313309 0.3699112 +VERTEX_SE3:QUAT 3073 36.238843 29.414609 -27.188866 -0.9286529 0.0351180 -0.2760809 0.2452544 +VERTEX_SE3:QUAT 3074 36.958015 28.938511 -27.604777 -0.5566441 -0.2280680 0.6479506 0.4672177 +VERTEX_SE3:QUAT 3075 37.815616 28.497644 -27.991947 -0.2419064 -0.7114771 0.4977252 0.4330719 +VERTEX_SE3:QUAT 3076 38.577706 27.948933 -28.601363 0.7153457 -0.6297836 0.3023103 0.0161734 +VERTEX_SE3:QUAT 3077 39.127767 27.382863 -29.082726 -0.8901975 -0.4027114 -0.1817161 0.1111358 +VERTEX_SE3:QUAT 3078 39.836763 26.871001 -29.498477 -0.4679709 -0.7919435 -0.2450541 0.3062305 +VERTEX_SE3:QUAT 3079 40.509904 26.486384 -29.873462 -0.7691328 0.6091153 0.0603338 0.1837746 +VERTEX_SE3:QUAT 3080 40.909844 27.348871 -30.109836 -0.6066845 0.2116015 0.7164994 0.2716382 +VERTEX_SE3:QUAT 3081 40.039136 27.726575 -29.666505 0.6563754 0.5450530 -0.0101811 0.5215217 +VERTEX_SE3:QUAT 3082 39.268847 28.236626 -29.284397 0.5650448 -0.2011016 0.2283065 0.7669150 +VERTEX_SE3:QUAT 3083 38.387237 28.730060 -29.026007 0.7871010 -0.0195527 -0.0156181 0.6163163 +VERTEX_SE3:QUAT 3084 37.417119 29.143353 -28.871036 0.0848496 -0.6746873 -0.5541272 0.4801465 +VERTEX_SE3:QUAT 3085 36.384888 29.664002 -28.601196 0.8327092 0.2114096 0.3548537 0.3687548 +VERTEX_SE3:QUAT 3086 35.399892 29.941686 -28.260039 0.1830701 0.8179860 -0.5283529 0.1350095 +VERTEX_SE3:QUAT 3087 34.411927 30.279487 -27.913061 -0.7312490 0.3141944 0.5499797 0.2531385 +VERTEX_SE3:QUAT 3088 33.444827 30.448546 -27.757341 -0.7557185 -0.3623006 0.1222921 0.5316696 +VERTEX_SE3:QUAT 3089 32.585009 30.721619 -27.442702 -0.0963004 -0.9053145 -0.0555594 0.4099329 +VERTEX_SE3:QUAT 3090 31.493558 30.830672 -27.109509 -0.6071504 -0.2819432 0.6216546 0.4067209 +VERTEX_SE3:QUAT 3091 30.670927 31.035408 -26.961305 0.3356288 0.7721193 -0.4971884 0.2097353 +VERTEX_SE3:QUAT 3092 29.895580 31.420611 -26.711771 0.5990620 -0.5592190 0.5418428 0.1865617 +VERTEX_SE3:QUAT 3093 28.893684 31.860788 -26.520053 -0.6059348 -0.7191331 -0.0882701 0.3284799 +VERTEX_SE3:QUAT 3094 28.014050 32.261884 -26.076201 0.1044081 -0.9372439 -0.0225803 0.3319079 +VERTEX_SE3:QUAT 3095 27.204183 32.624408 -25.815521 0.6494479 0.4527502 0.0725317 0.6066084 +VERTEX_SE3:QUAT 3096 26.376722 32.838973 -25.367239 0.0343225 -0.7878140 -0.2531126 0.5604508 +VERTEX_SE3:QUAT 3097 25.497427 33.222369 -25.105207 -0.0727264 0.8906281 0.4298392 0.1293475 +VERTEX_SE3:QUAT 3098 24.508180 33.579189 -24.723292 -0.6580760 -0.5574604 0.4995702 0.0812619 +VERTEX_SE3:QUAT 3099 23.760297 33.753755 -24.589725 -0.8273496 0.0197103 0.5481854 0.1208178 +VERTEX_SE3:QUAT 3100 23.988577 34.615524 -25.221627 0.2604064 -0.8238898 -0.3806280 0.3294183 +VERTEX_SE3:QUAT 3101 25.140261 34.395607 -25.281089 0.7262426 0.6224411 0.2884830 0.0437756 +VERTEX_SE3:QUAT 3102 26.175299 34.005688 -25.549259 0.9550721 0.1147927 -0.2577765 0.0906152 +VERTEX_SE3:QUAT 3103 27.120891 33.630642 -25.668367 0.8504139 0.4601338 0.1384146 0.2142766 +VERTEX_SE3:QUAT 3104 27.876970 33.058341 -25.681149 0.7639654 0.0642812 -0.1332590 0.6280659 +VERTEX_SE3:QUAT 3105 28.708246 32.539111 -25.749948 0.2276252 -0.6979321 0.3331656 0.5916741 +VERTEX_SE3:QUAT 3106 29.731345 32.065793 -25.832599 0.5522027 0.3825943 -0.7013697 0.2382737 +VERTEX_SE3:QUAT 3107 30.621704 31.653220 -25.996843 0.7017976 0.5015173 -0.3162165 0.3949274 +VERTEX_SE3:QUAT 3108 31.605109 31.214979 -26.245119 -0.9327794 0.2019475 0.1336951 0.2669559 +VERTEX_SE3:QUAT 3109 32.661909 30.807094 -26.577611 0.7642260 -0.5645166 -0.2518316 0.1840123 +VERTEX_SE3:QUAT 3110 33.506875 30.497148 -26.984469 0.6871256 0.6125306 0.3827898 0.0783367 +VERTEX_SE3:QUAT 3111 34.541227 30.299250 -27.184849 -0.3464991 -0.8357526 0.4008976 0.1440039 +VERTEX_SE3:QUAT 3112 35.490525 30.044171 -27.419528 0.7814487 -0.1002099 -0.2056456 0.5805220 +VERTEX_SE3:QUAT 3113 36.548209 29.863727 -27.562317 -0.5984114 0.6981656 0.0079551 0.3929444 +VERTEX_SE3:QUAT 3114 37.539691 29.607542 -27.630848 0.5498672 0.7781907 -0.0773673 0.2933933 +VERTEX_SE3:QUAT 3115 38.479199 29.474337 -27.686417 0.6372264 -0.5098808 0.1966771 0.5433987 +VERTEX_SE3:QUAT 3116 39.501819 29.228549 -27.766243 0.7051460 -0.5062199 0.3588607 0.3431173 +VERTEX_SE3:QUAT 3117 40.438822 29.010623 -27.758669 -0.0893401 0.8791540 0.4410525 0.1567779 +VERTEX_SE3:QUAT 3118 41.412574 28.676566 -27.831161 0.7854106 -0.3537461 -0.1612683 0.4816496 +VERTEX_SE3:QUAT 3119 42.463660 28.573802 -28.035666 0.7250068 0.4086953 0.4809918 0.2756449 +VERTEX_SE3:QUAT 3120 42.580007 29.476885 -28.564871 0.8237161 -0.3229334 -0.2067567 0.4176811 +VERTEX_SE3:QUAT 3121 41.675584 29.898888 -28.512630 0.9531868 -0.0300205 0.2948997 0.0597310 +VERTEX_SE3:QUAT 3122 40.796870 30.178623 -28.265286 0.7067055 0.6482411 0.2777386 0.0566758 +VERTEX_SE3:QUAT 3123 39.705566 30.406955 -27.902105 -0.4936652 -0.8061632 -0.1775890 0.2736013 +VERTEX_SE3:QUAT 3124 38.774247 30.583808 -27.724364 0.4823158 0.2211910 -0.2779165 0.8007549 +VERTEX_SE3:QUAT 3125 37.852758 30.717204 -27.316278 0.6991138 0.1984999 -0.4081948 0.5524624 +VERTEX_SE3:QUAT 3126 36.871706 30.968370 -26.953518 0.4888431 0.0090540 -0.0894575 0.8677257 +VERTEX_SE3:QUAT 3127 35.997335 31.207116 -26.824330 0.5246928 0.4113899 -0.6616415 0.3430544 +VERTEX_SE3:QUAT 3128 34.951352 31.494467 -26.749850 0.9350498 -0.0645269 0.3038790 0.1708088 +VERTEX_SE3:QUAT 3129 33.952956 31.707168 -26.784377 0.8249056 0.0323493 -0.5186777 0.2223908 +VERTEX_SE3:QUAT 3130 33.039368 32.031423 -26.803547 -0.1655961 -0.9321099 0.2624807 0.1866896 +VERTEX_SE3:QUAT 3131 31.908596 32.199954 -26.894066 0.4679195 -0.6120143 0.3007586 0.5621691 +VERTEX_SE3:QUAT 3132 31.122844 32.498125 -26.899146 0.4425334 0.5925827 0.1999095 0.6426867 +VERTEX_SE3:QUAT 3133 29.950894 32.834093 -26.950984 -0.6399025 -0.7529319 0.0043287 0.1536218 +VERTEX_SE3:QUAT 3134 28.901286 33.162472 -27.053799 0.6478003 0.6001827 -0.4295219 0.1888026 +VERTEX_SE3:QUAT 3135 28.028725 33.845361 -26.982540 0.3446066 -0.9377329 0.0266464 0.0345448 +VERTEX_SE3:QUAT 3136 27.199272 34.415342 -26.875557 -0.1844452 0.9576467 0.0479132 0.2158636 +VERTEX_SE3:QUAT 3137 26.377658 34.824633 -26.865013 0.8057202 -0.5123629 0.1841671 0.2331987 +VERTEX_SE3:QUAT 3138 25.554638 35.264011 -26.953467 0.3851934 0.5851361 -0.6398959 0.3158717 +VERTEX_SE3:QUAT 3139 24.716514 35.836426 -26.849740 -0.3025181 -0.8984529 -0.0123083 0.3179838 +VERTEX_SE3:QUAT 3140 25.177517 36.686286 -27.453011 -0.7702445 -0.4367725 0.1961853 0.4212654 +VERTEX_SE3:QUAT 3141 26.185195 36.174246 -27.338302 -0.6363883 -0.3995487 0.3045734 0.5853253 +VERTEX_SE3:QUAT 3142 27.014848 35.609104 -27.065214 -0.1253510 0.8712027 0.4722934 0.0472442 +VERTEX_SE3:QUAT 3143 27.783744 35.028659 -26.959886 -0.0829673 0.8967275 0.1880214 0.3919748 +VERTEX_SE3:QUAT 3144 28.715781 34.289702 -26.945789 0.2535285 0.5138327 -0.7815644 0.2466907 +VERTEX_SE3:QUAT 3145 29.360012 33.663874 -26.673819 -0.8456224 -0.3475376 0.0766065 0.3978339 +VERTEX_SE3:QUAT 3146 30.069522 33.075619 -26.457427 -0.7036424 -0.6709636 -0.2266210 0.0577760 +VERTEX_SE3:QUAT 3147 30.792996 32.279785 -26.476233 0.6076648 0.3627282 -0.7002705 0.0937703 +VERTEX_SE3:QUAT 3148 31.439586 31.550579 -26.404442 -0.8452422 0.2964799 0.3971157 0.1999110 +VERTEX_SE3:QUAT 3149 32.050340 30.813755 -26.106116 0.1925188 0.7993206 -0.3171853 0.4726696 +VERTEX_SE3:QUAT 3150 32.883080 30.279502 -25.822167 -0.0975726 0.9711548 0.0350608 0.2147295 +VERTEX_SE3:QUAT 3151 33.505818 29.641196 -25.757900 -0.3300319 -0.6835278 0.5886928 0.2780459 +VERTEX_SE3:QUAT 3152 34.146822 28.988905 -25.418914 -0.8648374 0.1248609 -0.2228941 0.4321855 +VERTEX_SE3:QUAT 3153 34.926499 28.418312 -25.195362 0.8238130 0.4695579 -0.3136393 0.0497782 +VERTEX_SE3:QUAT 3154 35.756206 27.727533 -24.927907 0.8162978 -0.0999921 -0.1894884 0.5364267 +VERTEX_SE3:QUAT 3155 36.620280 27.074106 -24.418721 0.5271259 0.7011016 -0.1203583 0.4648748 +VERTEX_SE3:QUAT 3156 37.471743 26.356916 -24.199154 -0.8638182 0.1092400 -0.4453665 0.2086467 +VERTEX_SE3:QUAT 3157 38.068828 25.757810 -23.984799 0.6401572 -0.5091431 0.2807138 0.5021671 +VERTEX_SE3:QUAT 3158 38.757497 25.017332 -23.628242 0.3526997 -0.8193589 0.0213371 0.4514406 +VERTEX_SE3:QUAT 3159 39.377043 24.392748 -23.407788 0.5663724 0.7426589 -0.1934748 0.3004122 +VERTEX_SE3:QUAT 3160 40.031874 24.840261 -24.035322 -0.6651846 -0.6671237 -0.2889343 0.1702717 +VERTEX_SE3:QUAT 3161 39.626240 25.491525 -24.099599 0.6441141 0.1788088 -0.4932444 0.5566457 +VERTEX_SE3:QUAT 3162 38.988071 26.333276 -24.011846 -0.0837070 -0.9776360 -0.1688933 0.0932526 +VERTEX_SE3:QUAT 3163 38.544676 26.968628 -23.861301 -0.9149149 0.3106252 -0.2019970 0.1601248 +VERTEX_SE3:QUAT 3164 37.840835 27.603187 -24.107391 -0.9222158 0.1839293 -0.2553733 0.2246608 +VERTEX_SE3:QUAT 3165 37.344590 28.392920 -24.154613 0.7388218 0.5890594 0.2322298 0.2306961 +VERTEX_SE3:QUAT 3166 36.757968 29.253755 -24.178764 -0.0653026 -0.8559815 0.1048588 0.5020318 +VERTEX_SE3:QUAT 3167 36.276609 29.971867 -24.257995 0.3020755 0.6452528 -0.3427412 0.6123134 +VERTEX_SE3:QUAT 3168 35.945236 30.773605 -24.539138 0.6585051 0.7174885 0.2248525 0.0319797 +VERTEX_SE3:QUAT 3169 35.359348 31.510559 -24.712469 -0.6429508 -0.4529055 0.5354709 0.3078340 +VERTEX_SE3:QUAT 3170 34.857185 32.298420 -24.828919 0.8255539 0.3493064 0.0118990 0.4430623 +VERTEX_SE3:QUAT 3171 34.422809 33.021566 -24.944187 0.4678378 0.5797270 0.0468137 0.6654719 +VERTEX_SE3:QUAT 3172 33.727126 33.764682 -24.934905 0.4708384 -0.5597081 -0.0493094 0.6801520 +VERTEX_SE3:QUAT 3173 33.027458 34.690023 -24.990734 0.1249802 0.9613381 -0.0745834 0.2337655 +VERTEX_SE3:QUAT 3174 32.411397 35.541930 -25.126981 -0.5388960 0.6482261 -0.5359132 0.0468083 +VERTEX_SE3:QUAT 3175 31.888534 36.379500 -25.308374 -0.0553209 -0.6485603 -0.0000584 0.7591503 +VERTEX_SE3:QUAT 3176 31.252368 37.048037 -25.563191 0.7997586 -0.4130210 0.3508946 0.2582108 +VERTEX_SE3:QUAT 3177 30.848561 37.845414 -25.830040 -0.0439000 -0.7412748 0.6254052 0.2396933 +VERTEX_SE3:QUAT 3178 30.235489 38.535107 -26.176192 -0.8117191 -0.4739379 0.2194158 0.2614415 +VERTEX_SE3:QUAT 3179 29.806770 39.496160 -26.438209 0.4709446 0.2879704 -0.8189832 0.1566867 +VERTEX_SE3:QUAT 3180 30.646454 39.547632 -27.181497 0.3789803 0.4903163 0.0386261 0.7838826 +VERTEX_SE3:QUAT 3181 31.221100 38.835895 -26.969187 -0.6205092 -0.7595427 -0.0206737 0.1939993 +VERTEX_SE3:QUAT 3182 31.564397 38.243302 -26.492713 -0.9526396 -0.2220475 0.0965679 0.1839762 +VERTEX_SE3:QUAT 3183 32.108118 37.569541 -25.870202 0.1634878 -0.4814603 0.8139901 0.2808698 +VERTEX_SE3:QUAT 3184 32.597526 36.885639 -25.181043 -0.2212890 0.7723722 -0.5475354 0.2338316 +VERTEX_SE3:QUAT 3185 33.059786 36.395224 -24.674268 0.6403834 -0.5685019 -0.3756615 0.3543911 +VERTEX_SE3:QUAT 3186 33.617541 35.837351 -24.294866 -0.9862602 -0.0851117 0.0728013 0.1214367 +VERTEX_SE3:QUAT 3187 34.130625 35.090941 -23.788633 0.8827845 -0.0899685 -0.0468303 0.4586983 +VERTEX_SE3:QUAT 3188 34.734766 34.243027 -23.306593 -0.1602206 0.9201483 -0.2104346 0.2887452 +VERTEX_SE3:QUAT 3189 35.074594 33.467910 -22.872946 0.6470652 -0.2303041 0.2720549 0.6739828 +VERTEX_SE3:QUAT 3190 35.315112 32.743478 -22.533041 0.3087939 0.6429757 -0.6992626 0.0475434 +VERTEX_SE3:QUAT 3191 35.689942 31.891732 -21.820436 0.1122221 -0.8386772 0.5329091 0.0058921 +VERTEX_SE3:QUAT 3192 36.084349 31.154999 -21.185381 0.4478801 -0.6162467 0.2978444 0.5752670 +VERTEX_SE3:QUAT 3193 36.554148 30.541165 -20.791411 0.7536053 -0.1455790 -0.2590877 0.5863099 +VERTEX_SE3:QUAT 3194 37.099711 30.008282 -20.128600 -0.3838010 0.8444741 -0.3735333 0.0057614 +VERTEX_SE3:QUAT 3195 37.528155 29.428042 -19.685900 -0.5038334 -0.6957376 0.4723570 0.1974334 +VERTEX_SE3:QUAT 3196 37.919921 28.674243 -19.141969 0.2568969 -0.8226558 0.4279851 0.2721585 +VERTEX_SE3:QUAT 3197 38.501730 28.064882 -18.648190 0.1538810 -0.8509349 0.3557744 0.3544783 +VERTEX_SE3:QUAT 3198 38.898848 27.535116 -18.227057 0.1894638 -0.6362933 0.7463003 0.0476462 +VERTEX_SE3:QUAT 3199 39.493954 26.756959 -17.758704 0.8528152 -0.0771382 -0.1090720 0.5048358 +VERTEX_SE3:QUAT 3200 30.000686 39.028267 -28.830615 0.7854686 -0.4829532 0.1185852 0.3684194 +VERTEX_SE3:QUAT 3201 30.591833 38.373249 -28.186598 0.3517921 -0.4553444 0.7588285 0.3050953 +VERTEX_SE3:QUAT 3202 31.069517 37.799676 -27.529068 0.1208936 0.6611245 -0.2219073 0.7064391 +VERTEX_SE3:QUAT 3203 31.499877 36.945086 -26.877478 0.5995978 0.3899488 0.2442992 0.6547826 +VERTEX_SE3:QUAT 3204 31.821003 36.234456 -26.163501 -0.2163467 -0.9390175 0.2666285 0.0186944 +VERTEX_SE3:QUAT 3205 32.154729 35.618915 -25.484664 -0.7855360 0.5654635 -0.1193915 0.2212010 +VERTEX_SE3:QUAT 3206 32.750868 34.912416 -24.764022 -0.6347117 0.7655572 -0.0449075 0.0951131 +VERTEX_SE3:QUAT 3207 33.207461 34.169790 -24.131957 0.5109928 -0.6429311 -0.2280668 0.5229832 +VERTEX_SE3:QUAT 3208 33.403668 33.534488 -23.279904 0.3767320 -0.3000005 0.7494938 0.4542375 +VERTEX_SE3:QUAT 3209 33.682982 32.749644 -22.580339 0.8377916 0.1887737 0.0705681 0.5074346 +VERTEX_SE3:QUAT 3210 34.026494 32.108489 -21.985279 0.5748719 -0.7867591 -0.1437945 0.1727877 +VERTEX_SE3:QUAT 3211 34.445642 31.500094 -21.383739 0.3400345 -0.3424522 0.8419775 0.2411990 +VERTEX_SE3:QUAT 3212 34.780316 30.692744 -20.850020 0.7173416 -0.3320182 -0.0299233 0.6117921 +VERTEX_SE3:QUAT 3213 35.141498 30.039968 -20.219346 0.5223820 0.1083519 0.1101370 0.8385981 +VERTEX_SE3:QUAT 3214 35.483422 29.442316 -19.508293 0.9816883 0.0492561 -0.1781197 0.0462101 +VERTEX_SE3:QUAT 3215 35.959435 29.002281 -18.793291 0.7430643 -0.2638616 -0.6141091 0.0332041 +VERTEX_SE3:QUAT 3216 36.299249 28.191362 -18.257733 -0.4378137 -0.3893079 0.5742015 0.5718839 +VERTEX_SE3:QUAT 3217 36.778454 27.580438 -17.640289 0.0359598 -0.5840001 0.7124918 0.3873064 +VERTEX_SE3:QUAT 3218 37.211191 27.006167 -16.870288 0.1146632 -0.9442088 -0.2949485 0.0912554 +VERTEX_SE3:QUAT 3219 37.754026 26.212778 -16.479290 -0.5537624 -0.4886314 0.4059277 0.5383394 +VERTEX_SE3:QUAT 3220 37.171581 26.041510 -15.930410 -0.0549205 -0.8174647 -0.2180692 0.5302650 +VERTEX_SE3:QUAT 3221 36.821027 26.942251 -16.421065 -0.4342743 -0.8680951 -0.2332688 0.0583301 +VERTEX_SE3:QUAT 3222 36.337243 27.816918 -16.957491 -0.9132390 0.0338730 -0.3884296 0.1181930 +VERTEX_SE3:QUAT 3223 36.023967 28.685374 -17.245563 -0.3250553 -0.9164875 0.0982160 0.2115260 +VERTEX_SE3:QUAT 3224 35.782143 29.457756 -17.576158 -0.7916717 -0.5603560 -0.0517125 0.2378716 +VERTEX_SE3:QUAT 3225 35.363602 30.407082 -17.983402 -0.9072728 -0.0667415 -0.1962213 0.3659220 +VERTEX_SE3:QUAT 3226 35.034006 31.165448 -18.426733 -0.9518946 -0.1916078 -0.2244459 0.0825057 +VERTEX_SE3:QUAT 3227 34.549369 32.078363 -19.026499 0.7930625 0.3792297 0.3317403 0.3423230 +VERTEX_SE3:QUAT 3228 34.048115 32.857568 -19.667119 0.5314813 0.6976070 -0.0963277 0.4707367 +VERTEX_SE3:QUAT 3229 33.734281 33.484335 -20.175149 -0.7904752 0.5889573 -0.1680395 0.0063986 +VERTEX_SE3:QUAT 3230 33.126562 34.245820 -20.603266 -0.0607364 -0.9331131 0.1161694 0.3348368 +VERTEX_SE3:QUAT 3231 32.693500 34.918116 -20.858491 0.8953448 0.1058643 0.3460163 0.2596596 +VERTEX_SE3:QUAT 3232 32.257935 35.898546 -21.544438 0.3109700 0.8041994 -0.3132287 0.3980562 +VERTEX_SE3:QUAT 3233 32.068789 36.807637 -21.964861 0.7117209 0.4421550 0.1631483 0.5208982 +VERTEX_SE3:QUAT 3234 31.729127 37.619547 -22.585907 0.7216685 0.3770215 0.3421941 0.4689909 +VERTEX_SE3:QUAT 3235 31.358819 38.412187 -23.294490 0.5856283 -0.6679511 0.2082728 0.4092716 +VERTEX_SE3:QUAT 3236 30.855494 38.922035 -23.677410 0.3346731 0.7655579 0.2976991 0.4618335 +VERTEX_SE3:QUAT 3237 30.354706 39.688016 -24.081036 0.7465733 -0.1641232 -0.0468762 0.6430355 +VERTEX_SE3:QUAT 3238 29.949591 40.386177 -24.621442 0.9127453 -0.0722169 -0.3576712 0.1837173 +VERTEX_SE3:QUAT 3239 29.610600 41.210850 -25.204701 0.5886234 -0.7191266 0.0721833 0.3621726 +VERTEX_SE3:QUAT 3240 28.863895 41.086644 -24.685374 -0.8764831 -0.4240473 0.1131458 0.1978872 +VERTEX_SE3:QUAT 3241 29.293430 40.385482 -24.238265 -0.4925750 0.6351907 -0.5859693 0.1026775 +VERTEX_SE3:QUAT 3242 29.652151 39.640269 -23.686619 -0.6443559 0.6713293 -0.1442558 0.3366196 +VERTEX_SE3:QUAT 3243 29.895050 38.904631 -23.046094 0.6264716 0.7007070 0.3342766 0.0692977 +VERTEX_SE3:QUAT 3244 30.329331 37.917007 -22.391821 -0.3542925 0.9210256 0.0154894 0.1610859 +VERTEX_SE3:QUAT 3245 30.587255 37.269788 -21.657974 0.4619256 -0.6954300 -0.1760397 0.5215476 +VERTEX_SE3:QUAT 3246 30.903388 36.623040 -21.007180 -0.9426843 0.1054820 0.2781424 0.1511842 +VERTEX_SE3:QUAT 3247 31.038091 35.778862 -20.390182 -0.8235277 -0.5140183 0.1973453 0.1365363 +VERTEX_SE3:QUAT 3248 31.070070 34.936286 -19.856340 0.2549099 -0.5979314 0.5991062 0.4675156 +VERTEX_SE3:QUAT 3249 31.204945 34.118375 -19.081747 0.5679867 -0.4666625 0.3687052 0.5689233 +VERTEX_SE3:QUAT 3250 31.331127 33.349048 -18.367877 0.0754620 -0.6340410 0.1167650 0.7606993 +VERTEX_SE3:QUAT 3251 31.451288 32.665770 -17.771721 0.2471850 0.6771388 -0.4097175 0.5590296 +VERTEX_SE3:QUAT 3252 31.891018 31.876855 -17.109918 0.3681975 -0.6331911 0.0338324 0.6799669 +VERTEX_SE3:QUAT 3253 32.059024 30.946789 -16.486153 -0.5373089 -0.3001074 0.6692438 0.4163502 +VERTEX_SE3:QUAT 3254 32.344030 30.268066 -15.842816 -0.9179075 -0.0837518 -0.3073077 0.2366294 +VERTEX_SE3:QUAT 3255 32.659620 29.491200 -15.203582 0.8522333 0.4588773 -0.2238822 0.1140474 +VERTEX_SE3:QUAT 3256 33.070155 28.851553 -14.706999 -0.7413417 -0.5578562 0.1379142 0.3466822 +VERTEX_SE3:QUAT 3257 33.329227 27.999695 -13.993853 0.6260826 -0.4376995 -0.0512981 0.6432793 +VERTEX_SE3:QUAT 3258 33.457486 27.489248 -13.568261 0.3997412 0.7292413 0.1869918 0.5229227 +VERTEX_SE3:QUAT 3259 33.672976 26.767141 -13.016160 0.4724474 -0.2837933 0.0866168 0.8299110 +VERTEX_SE3:QUAT 3260 32.858635 26.754452 -12.702443 -0.2523192 0.9265356 0.1868307 0.2072708 +VERTEX_SE3:QUAT 3261 32.562216 27.547883 -13.285618 0.8431052 0.0634077 -0.2327457 0.4806064 +VERTEX_SE3:QUAT 3262 32.221635 28.204921 -13.839308 -0.7581095 -0.1937850 0.6033840 0.1537693 +VERTEX_SE3:QUAT 3263 31.671374 28.986713 -14.229601 -0.6116967 -0.7091234 0.3140646 0.1559950 +VERTEX_SE3:QUAT 3264 31.303691 29.880947 -14.562302 0.2189965 -0.8437525 -0.4472087 0.2003165 +VERTEX_SE3:QUAT 3265 30.801091 30.645625 -14.994731 0.8298167 0.4477892 0.0276734 0.3318483 +VERTEX_SE3:QUAT 3266 30.294612 31.266258 -15.698382 0.0266232 -0.4271665 0.6846277 0.5900042 +VERTEX_SE3:QUAT 3267 29.815231 32.162213 -16.146577 0.9257882 0.3022414 -0.2075553 0.0921255 +VERTEX_SE3:QUAT 3268 29.260038 32.828515 -16.759553 0.5208678 0.8204418 -0.1030244 0.2120327 +VERTEX_SE3:QUAT 3269 28.730257 33.640868 -17.269524 -0.0866865 -0.9748072 -0.0133960 0.2050779 +VERTEX_SE3:QUAT 3270 27.915764 34.141158 -17.677591 -0.2647932 -0.7828122 0.5558830 0.0899097 +VERTEX_SE3:QUAT 3271 27.276155 34.791585 -18.133354 0.1196420 -0.6346914 0.4574683 0.6112081 +VERTEX_SE3:QUAT 3272 26.531401 35.713979 -18.623730 -0.3928067 -0.7707409 -0.1983085 0.4607983 +VERTEX_SE3:QUAT 3273 25.871342 36.302199 -18.979740 0.9619131 -0.0115272 0.2353306 0.1385997 +VERTEX_SE3:QUAT 3274 25.195335 37.155770 -19.347707 -0.8095119 -0.5709692 0.1275444 0.0491641 +VERTEX_SE3:QUAT 3275 24.766428 38.025755 -19.820943 -0.5627346 0.7358986 -0.2165322 0.3080533 +VERTEX_SE3:QUAT 3276 24.278125 38.851114 -20.089679 0.8122273 -0.4014340 0.3779413 0.1905200 +VERTEX_SE3:QUAT 3277 23.538081 39.593397 -20.359464 0.6963508 -0.4705018 -0.4671814 0.2747090 +VERTEX_SE3:QUAT 3278 22.944695 40.350312 -20.754945 0.1325766 0.8982670 -0.4071758 0.0987300 +VERTEX_SE3:QUAT 3279 22.509360 41.019878 -21.404270 -0.6076422 -0.1426940 0.7214538 0.2998563 +VERTEX_SE3:QUAT 3280 21.714642 40.858922 -20.883649 -0.5007004 0.8505466 -0.1553294 0.0417413 +VERTEX_SE3:QUAT 3281 21.994834 40.082416 -20.512814 -0.0978828 -0.7061708 -0.0631382 0.6983948 +VERTEX_SE3:QUAT 3282 22.386110 39.226916 -20.147669 0.0124575 0.9543129 0.1053798 0.2793329 +VERTEX_SE3:QUAT 3283 22.745687 38.341376 -19.867466 -0.7486626 0.5268150 0.0291869 0.4013957 +VERTEX_SE3:QUAT 3284 23.145055 37.509364 -19.550518 0.5048818 0.7910555 -0.3391229 0.0657355 +VERTEX_SE3:QUAT 3285 23.669278 36.495206 -19.123395 0.4566233 -0.8066108 -0.3733834 0.0381972 +VERTEX_SE3:QUAT 3286 24.055350 35.579032 -18.829180 0.8058834 0.2758910 -0.0959475 0.5150050 +VERTEX_SE3:QUAT 3287 24.420900 34.578773 -18.438511 0.1505651 0.8777617 0.4466049 0.0860737 +VERTEX_SE3:QUAT 3288 24.571810 33.678787 -18.358288 0.0978047 -0.8914227 0.4422331 0.0151563 +VERTEX_SE3:QUAT 3289 24.629485 32.712369 -18.294482 -0.7807508 -0.5909667 -0.1430890 0.1439167 +VERTEX_SE3:QUAT 3290 24.838373 31.428617 -18.048310 0.5516692 -0.7743350 -0.3077221 0.0370606 +VERTEX_SE3:QUAT 3291 25.028962 30.431650 -17.878739 -0.7244222 -0.1709008 0.1533769 0.6499854 +VERTEX_SE3:QUAT 3292 25.203295 29.431547 -17.517639 0.9170805 0.2201577 0.2960520 0.1511526 +VERTEX_SE3:QUAT 3293 25.355572 28.585869 -17.250895 0.3418259 -0.6989050 0.4778518 0.4078534 +VERTEX_SE3:QUAT 3294 25.702089 27.527105 -17.155793 0.4663990 0.7032205 0.1800345 0.5055101 +VERTEX_SE3:QUAT 3295 26.117198 26.655461 -17.106275 0.0802172 0.8384008 -0.5388180 0.0180130 +VERTEX_SE3:QUAT 3296 26.352982 25.724176 -16.755985 0.9617544 -0.0527797 -0.1193704 0.2408185 +VERTEX_SE3:QUAT 3297 26.493489 24.603672 -16.471107 -0.0291127 -0.9855359 0.0618731 0.1550587 +VERTEX_SE3:QUAT 3298 26.686467 23.833569 -16.232242 0.7042089 -0.5182677 0.1923631 0.4455164 +VERTEX_SE3:QUAT 3299 27.019391 22.925844 -15.787359 0.0837835 0.8795584 0.3346958 0.3276217 +VERTEX_SE3:QUAT 3300 26.029233 22.974621 -15.559522 -0.6603451 -0.6930006 0.0248569 0.2882303 +VERTEX_SE3:QUAT 3301 25.848917 24.005306 -15.677173 -0.2271825 -0.6610404 0.7069672 0.1077549 +VERTEX_SE3:QUAT 3302 25.732089 24.920575 -15.988499 0.6466667 -0.4999475 0.5123028 0.2634780 +VERTEX_SE3:QUAT 3303 25.387162 25.605352 -16.363217 0.5840414 0.5198089 -0.1398050 0.6075762 +VERTEX_SE3:QUAT 3304 25.159743 26.412041 -16.480548 0.0517129 0.9707635 0.2310660 0.0394031 +VERTEX_SE3:QUAT 3305 25.083564 27.251200 -16.881362 0.9430964 -0.0015827 0.1952473 0.2691565 +VERTEX_SE3:QUAT 3306 25.122450 28.202992 -17.353485 0.0576541 0.9595139 0.0285577 0.2742143 +VERTEX_SE3:QUAT 3307 24.758137 29.151996 -17.850132 0.5978324 -0.5159470 0.4711282 0.3929799 +VERTEX_SE3:QUAT 3308 24.686648 30.139962 -18.157070 -0.2128571 -0.9060582 0.0652603 0.3598492 +VERTEX_SE3:QUAT 3309 24.764776 30.952032 -18.500074 0.5213955 -0.7067580 -0.4545663 0.1483550 +VERTEX_SE3:QUAT 3310 24.634741 31.793002 -18.947327 0.8433204 0.0282277 0.5299956 0.0843717 +VERTEX_SE3:QUAT 3311 24.553885 32.639570 -19.406483 0.1867350 -0.8901169 -0.0622965 0.4110244 +VERTEX_SE3:QUAT 3312 24.530321 33.605631 -19.938563 -0.7433454 0.0998361 0.6331614 0.1912513 +VERTEX_SE3:QUAT 3313 24.364651 34.370552 -20.532818 -0.3916760 0.4166631 -0.8203378 0.0052595 +VERTEX_SE3:QUAT 3314 24.044166 35.228648 -21.194159 -0.0232823 0.6667639 -0.7192525 0.1938033 +VERTEX_SE3:QUAT 3315 23.628014 35.901516 -21.792882 -0.3257112 -0.3409011 0.8752169 0.1081392 +VERTEX_SE3:QUAT 3316 23.288154 36.497302 -22.441791 0.6204432 0.6953810 0.1827875 0.3131839 +VERTEX_SE3:QUAT 3317 22.980401 37.102475 -23.073146 -0.1509534 0.5703348 -0.8036523 0.0779375 +VERTEX_SE3:QUAT 3318 22.580665 37.886884 -23.528455 0.0590917 -0.8144983 -0.1769529 0.5493526 +VERTEX_SE3:QUAT 3319 22.267033 38.673910 -24.213445 0.8407992 -0.4392554 -0.2855871 0.1362032 +VERTEX_SE3:QUAT 3320 21.252587 38.540470 -23.825420 0.4656090 0.5475961 -0.3877928 0.5770299 +VERTEX_SE3:QUAT 3321 21.421903 37.817532 -23.211695 0.2913665 0.7787884 0.0886437 0.5483944 +VERTEX_SE3:QUAT 3322 21.753460 36.843236 -22.488403 0.8378516 0.5006721 -0.0106325 0.2172995 +VERTEX_SE3:QUAT 3323 22.185432 35.970083 -22.240637 0.7493467 0.3031317 -0.5795065 0.1037442 +VERTEX_SE3:QUAT 3324 22.473018 35.254074 -21.725815 0.4398312 -0.4030778 0.2598977 0.7592957 +VERTEX_SE3:QUAT 3325 22.780072 34.450973 -21.228318 0.6814169 -0.5119683 -0.2686554 0.4487579 +VERTEX_SE3:QUAT 3326 22.946732 33.556188 -20.827513 0.7345457 0.4840045 0.3362861 0.3362944 +VERTEX_SE3:QUAT 3327 23.443064 32.564562 -20.409244 0.0711898 0.8419854 -0.3494944 0.4047792 +VERTEX_SE3:QUAT 3328 23.686106 31.693289 -19.920557 0.4423665 0.6719292 -0.4561896 0.3804130 +VERTEX_SE3:QUAT 3329 23.951071 30.928197 -19.369721 -0.0650041 0.9478637 -0.1354306 0.2810471 +VERTEX_SE3:QUAT 3330 24.420015 30.175349 -19.050166 0.1935093 -0.8985299 -0.3723243 0.1287349 +VERTEX_SE3:QUAT 3331 24.654129 29.405941 -18.722592 0.8309988 0.0449856 -0.4560398 0.3153490 +VERTEX_SE3:QUAT 3332 25.078284 28.344499 -18.374354 -0.1913056 -0.8965679 -0.0275133 0.3985112 +VERTEX_SE3:QUAT 3333 25.390028 27.612501 -17.968371 0.5095382 -0.2932698 0.0184276 0.8087175 +VERTEX_SE3:QUAT 3334 25.637907 26.910118 -17.342507 -0.8823585 0.1946811 0.4178326 0.0946504 +VERTEX_SE3:QUAT 3335 26.105490 25.894676 -16.849586 0.2773497 -0.5697913 0.1407649 0.7606578 +VERTEX_SE3:QUAT 3336 26.609292 25.008761 -16.437648 0.9044682 -0.2197909 -0.3443911 0.1225724 +VERTEX_SE3:QUAT 3337 27.125708 24.177464 -16.286338 -0.3990113 -0.9026109 -0.1551853 0.0447327 +VERTEX_SE3:QUAT 3338 27.637836 23.292400 -15.806821 0.0719103 0.9539875 0.2383618 0.1670939 +VERTEX_SE3:QUAT 3339 28.116299 22.431836 -15.466917 0.5838710 -0.7940464 0.1620894 0.0480829 +VERTEX_SE3:QUAT 3340 27.185125 22.190101 -15.387331 0.5149349 -0.6031278 -0.6083394 0.0316560 +VERTEX_SE3:QUAT 3341 26.719213 23.185182 -15.605135 -0.0857615 0.7057689 -0.5903616 0.3821106 +VERTEX_SE3:QUAT 3342 26.577641 24.113263 -15.766286 0.8387713 -0.4077136 -0.3594384 0.0321910 +VERTEX_SE3:QUAT 3343 26.113080 24.902956 -16.212383 -0.9165331 -0.1045443 0.1284740 0.3640495 +VERTEX_SE3:QUAT 3344 25.847041 25.780611 -16.387642 -0.8981419 0.0203118 0.0885186 0.4302243 +VERTEX_SE3:QUAT 3345 25.726943 26.644036 -16.573188 0.9065300 0.0593963 0.2833143 0.3072597 +VERTEX_SE3:QUAT 3346 25.596227 27.756581 -16.658349 -0.6518153 -0.6970271 0.1617869 0.2512269 +VERTEX_SE3:QUAT 3347 25.291072 28.692240 -16.854295 -0.5789536 -0.6345208 0.1861247 0.4770259 +VERTEX_SE3:QUAT 3348 25.250345 29.618543 -17.313411 -0.4513534 -0.8880670 -0.0590473 0.0642690 +VERTEX_SE3:QUAT 3349 25.148187 30.273038 -17.733053 -0.5397518 -0.6681082 0.1204793 0.4977792 +VERTEX_SE3:QUAT 3350 25.094473 31.220634 -18.039911 0.5585371 0.2399706 -0.1971494 0.7691440 +VERTEX_SE3:QUAT 3351 24.985748 32.258477 -18.292577 0.1595130 0.9646147 0.0292954 0.2078844 +VERTEX_SE3:QUAT 3352 25.265711 33.238125 -18.615899 -0.4629396 -0.5126753 0.5585507 0.4592082 +VERTEX_SE3:QUAT 3353 25.396442 34.154644 -18.768251 -0.5027728 -0.5411363 0.3497694 0.5762398 +VERTEX_SE3:QUAT 3354 25.524262 35.203203 -18.826501 0.8412623 0.4093267 -0.2361503 0.2626072 +VERTEX_SE3:QUAT 3355 25.699884 36.166726 -19.167800 -0.8291941 -0.2680932 0.4818234 0.0917025 +VERTEX_SE3:QUAT 3356 26.079173 37.013626 -19.518854 0.6500716 -0.4311335 0.3808756 0.4964520 +VERTEX_SE3:QUAT 3357 26.272335 38.048261 -20.010035 -0.5060629 0.6559902 -0.4252783 0.3643013 +VERTEX_SE3:QUAT 3358 26.371643 39.096351 -20.120703 0.5507936 -0.7821411 -0.1841336 0.2257800 +VERTEX_SE3:QUAT 3359 26.473204 40.071215 -20.334085 -0.8526946 0.0453326 0.4406618 0.2769010 +VERTEX_SE3:QUAT 3360 25.484755 40.161940 -20.616930 -0.4307263 -0.8736791 0.2054568 0.0945895 +VERTEX_SE3:QUAT 3361 25.291111 39.242292 -20.301749 -0.7422080 0.6661648 -0.0715626 0.0151817 +VERTEX_SE3:QUAT 3362 25.332217 38.363171 -20.013802 0.5884216 -0.4843920 -0.0715586 0.6434312 +VERTEX_SE3:QUAT 3363 25.084518 37.376813 -19.899642 0.2075854 -0.6150057 0.7598707 0.0356762 +VERTEX_SE3:QUAT 3364 25.222095 36.198973 -19.317026 -0.9673626 -0.2092218 0.0011306 0.1429491 +VERTEX_SE3:QUAT 3365 25.053592 35.394164 -18.865978 0.6074852 0.6499821 0.4376341 0.1302359 +VERTEX_SE3:QUAT 3366 25.080604 34.578848 -18.274592 -0.0675448 -0.9015771 0.3734142 0.2077458 +VERTEX_SE3:QUAT 3367 25.123708 33.779762 -17.674361 -0.8869672 0.3863244 0.1644967 0.1923109 +VERTEX_SE3:QUAT 3368 24.972381 32.864853 -17.023772 0.0612515 -0.6992713 0.5590589 0.4412721 +VERTEX_SE3:QUAT 3369 24.998332 31.990830 -16.346077 0.8555374 0.4391748 -0.0982201 0.2559963 +VERTEX_SE3:QUAT 3370 25.065762 31.204253 -15.995352 -0.2059826 -0.7719144 0.5719091 0.1861163 +VERTEX_SE3:QUAT 3371 25.136448 30.354960 -15.474674 0.7888456 -0.2087546 -0.4456937 0.3681051 +VERTEX_SE3:QUAT 3372 25.138497 29.458351 -14.787784 -0.1863697 0.6061088 -0.7511690 0.1834216 +VERTEX_SE3:QUAT 3373 25.149663 28.671779 -14.242888 0.4315502 -0.1323154 0.3461453 0.8224600 +VERTEX_SE3:QUAT 3374 25.114609 27.847238 -13.708093 0.8179697 0.1801133 -0.1559850 0.5235966 +VERTEX_SE3:QUAT 3375 25.169795 27.133726 -13.176221 -0.3660197 -0.9097878 0.1956786 0.0050676 +VERTEX_SE3:QUAT 3376 25.163373 26.295505 -12.580325 0.4452232 -0.2645829 0.3352872 0.7869909 +VERTEX_SE3:QUAT 3377 25.192525 25.516078 -11.865251 -0.1689158 -0.9328841 0.3133571 0.0547905 +VERTEX_SE3:QUAT 3378 25.181916 25.028419 -11.472973 0.7606000 -0.1857878 -0.5123169 0.3528483 +VERTEX_SE3:QUAT 3379 25.046128 24.220946 -11.016186 -0.8989823 -0.0992422 0.4226879 0.0575919 +VERTEX_SE3:QUAT 3380 23.933918 24.195692 -11.028238 0.3134809 -0.8737935 0.3217653 0.1862303 +VERTEX_SE3:QUAT 3381 23.884267 25.021358 -11.706806 0.2882681 0.6410385 -0.0649179 0.7083479 +VERTEX_SE3:QUAT 3382 23.906754 25.520753 -12.292941 0.4288583 0.3754236 -0.7988352 0.1923537 +VERTEX_SE3:QUAT 3383 24.021329 25.972721 -12.959116 0.8876183 -0.3536670 0.2333960 0.1804986 +VERTEX_SE3:QUAT 3384 24.141223 26.574790 -13.366415 0.5134594 -0.7815219 0.0967956 0.3409012 +VERTEX_SE3:QUAT 3385 24.198061 27.365971 -13.810504 -0.8575812 -0.1175112 0.4342867 0.2492802 +VERTEX_SE3:QUAT 3386 24.385225 28.312869 -14.455917 0.6006068 0.5095019 -0.3566835 0.5024502 +VERTEX_SE3:QUAT 3387 24.701429 29.004743 -14.855815 -0.8696743 -0.4739654 -0.1050764 0.0893442 +VERTEX_SE3:QUAT 3388 25.075069 29.912647 -15.163499 -0.8929254 -0.1455905 0.1036124 0.4132217 +VERTEX_SE3:QUAT 3389 25.102558 30.888579 -15.788293 0.8262906 -0.3016653 -0.4052832 0.2489727 +VERTEX_SE3:QUAT 3390 25.301029 31.630831 -16.554786 0.0567956 -0.9650003 0.0265785 0.2546416 +VERTEX_SE3:QUAT 3391 25.518010 32.372161 -17.039868 0.4410266 -0.7872091 -0.2753211 0.3316560 +VERTEX_SE3:QUAT 3392 25.791757 33.272898 -17.852767 -0.1460385 -0.5662973 0.7173397 0.3786871 +VERTEX_SE3:QUAT 3393 26.121800 33.992474 -18.555448 0.7095202 -0.6955439 0.0841685 0.0756007 +VERTEX_SE3:QUAT 3394 26.301583 34.664894 -19.159194 0.3955642 0.8941270 -0.1143654 0.1760297 +VERTEX_SE3:QUAT 3395 26.497135 35.286102 -19.597206 0.1009347 -0.7853203 -0.0354384 0.6097773 +VERTEX_SE3:QUAT 3396 26.648841 36.239801 -20.212735 0.6576219 -0.2794937 -0.5830149 0.3866655 +VERTEX_SE3:QUAT 3397 26.653993 36.970295 -20.620797 0.4370987 -0.6467372 0.3023958 0.5470214 +VERTEX_SE3:QUAT 3398 26.693582 37.868749 -21.184447 0.7251833 0.3517476 -0.5274791 0.2686047 +VERTEX_SE3:QUAT 3399 26.745996 38.591075 -21.675211 0.9874026 -0.1550467 -0.0200842 0.0243569 +VERTEX_SE3:QUAT 3400 25.801861 38.659952 -21.752123 0.3884239 0.5432272 -0.0145556 0.7441903 +VERTEX_SE3:QUAT 3401 25.630117 37.872231 -21.171744 0.7868376 -0.1892100 0.4023386 0.4280302 +VERTEX_SE3:QUAT 3402 25.369726 36.990179 -20.666759 0.4304417 0.7409501 -0.1110294 0.5033740 +VERTEX_SE3:QUAT 3403 25.385131 36.349640 -20.010534 -0.7337119 -0.0285454 0.6784184 0.0245031 +VERTEX_SE3:QUAT 3404 25.562659 35.714080 -19.327016 0.1102299 -0.6838683 0.4021139 0.5987302 +VERTEX_SE3:QUAT 3405 25.615128 35.200484 -18.641260 -0.7472216 -0.3029158 0.5505400 0.2163504 +VERTEX_SE3:QUAT 3406 25.636001 34.563362 -17.956504 0.7244038 -0.2840195 0.2890236 0.5577073 +VERTEX_SE3:QUAT 3407 25.771289 33.961648 -17.575785 -0.9293012 -0.1715425 -0.1732305 0.2774231 +VERTEX_SE3:QUAT 3408 25.756540 33.257048 -16.872850 -0.9660987 0.0722651 0.0290232 0.2461479 +VERTEX_SE3:QUAT 3409 25.759244 32.478836 -16.180164 0.2748653 0.6470408 -0.6504678 0.2875393 +VERTEX_SE3:QUAT 3410 25.722526 31.506754 -15.552972 0.5266980 -0.4765135 -0.4072634 0.5741607 +VERTEX_SE3:QUAT 3411 25.845915 30.703804 -14.924230 0.3811081 0.7321098 -0.5517397 0.1198129 +VERTEX_SE3:QUAT 3412 25.959180 29.763586 -14.441251 0.9264995 -0.2073725 -0.1319160 0.2849447 +VERTEX_SE3:QUAT 3413 26.131704 28.977722 -14.034070 -0.6930758 0.6658897 0.0139472 0.2757576 +VERTEX_SE3:QUAT 3414 26.284544 28.247802 -13.461758 0.8700820 -0.3107333 0.1297141 0.3599673 +VERTEX_SE3:QUAT 3415 26.551930 27.389276 -12.770066 0.2271352 -0.4663854 0.6337770 0.5737778 +VERTEX_SE3:QUAT 3416 26.754521 26.326606 -12.259505 -0.4940121 0.7992562 -0.3295648 0.0923501 +VERTEX_SE3:QUAT 3417 26.780538 25.641069 -11.698400 0.7703790 0.0165272 -0.2824023 0.5713947 +VERTEX_SE3:QUAT 3418 26.880997 24.934898 -11.121651 0.4991547 0.6238833 0.0376542 0.6001636 +VERTEX_SE3:QUAT 3419 26.703980 24.112160 -10.794669 0.7296725 0.2039864 -0.6006166 0.2553963 +VERTEX_SE3:QUAT 3420 25.937234 24.198203 -10.288620 -0.5138795 -0.8028039 0.0163962 0.3019351 +VERTEX_SE3:QUAT 3421 25.894562 25.149879 -10.778668 -0.0160923 -0.9542500 0.0845808 0.2863462 +VERTEX_SE3:QUAT 3422 25.504846 26.055789 -11.403244 0.6075911 -0.0084597 0.0352877 0.7934206 +VERTEX_SE3:QUAT 3423 25.370408 27.072198 -11.929774 0.1279836 -0.7478948 -0.3724479 0.5343745 +VERTEX_SE3:QUAT 3424 25.283776 27.941699 -12.587603 -0.3349832 -0.7917247 -0.1269374 0.4948182 +VERTEX_SE3:QUAT 3425 24.903434 28.910416 -13.043632 0.8229048 0.2689005 -0.2055412 0.4563695 +VERTEX_SE3:QUAT 3426 25.014056 29.968262 -13.368928 0.4272859 -0.4255656 -0.2730464 0.7495107 +VERTEX_SE3:QUAT 3427 24.910283 31.000492 -13.728056 -0.7733580 -0.6149227 0.0414663 0.1485529 +VERTEX_SE3:QUAT 3428 24.942124 31.812362 -13.964278 0.7021908 0.4751481 -0.4890591 0.2048989 +VERTEX_SE3:QUAT 3429 24.974304 32.690050 -14.367494 0.2835041 0.7768444 -0.4969348 0.2630474 +VERTEX_SE3:QUAT 3430 25.010453 33.678446 -14.608445 0.7098892 -0.4178221 -0.5650066 0.0474303 +VERTEX_SE3:QUAT 3431 25.004625 34.471933 -15.100423 0.0519247 -0.9421770 -0.0723596 0.3230641 +VERTEX_SE3:QUAT 3432 25.016099 35.406720 -15.556761 0.9017355 0.2742950 -0.2318607 0.2405743 +VERTEX_SE3:QUAT 3433 24.735296 36.301611 -16.008002 -0.8865120 0.3351875 0.3183443 0.0200669 +VERTEX_SE3:QUAT 3434 24.620184 37.027023 -16.491181 -0.3536224 0.8668083 -0.2926692 0.1947800 +VERTEX_SE3:QUAT 3435 24.509433 37.904596 -16.900745 0.6470889 -0.7416577 0.1745239 0.0275895 +VERTEX_SE3:QUAT 3436 24.218829 38.701163 -17.243966 0.6212073 -0.1796747 -0.6804015 0.3447786 +VERTEX_SE3:QUAT 3437 23.868694 39.594349 -17.798999 0.7384886 -0.2976920 -0.6035310 0.0420055 +VERTEX_SE3:QUAT 3438 23.732727 40.456903 -18.037921 0.6840653 0.2650791 -0.1836485 0.6542637 +VERTEX_SE3:QUAT 3439 23.698919 41.316851 -18.425236 -0.0343502 -0.4565828 0.5960269 0.6596243 +VERTEX_SE3:QUAT 3440 22.805953 41.233841 -18.037094 0.6367928 -0.6272570 0.3252497 0.3086362 +VERTEX_SE3:QUAT 3441 23.052149 40.428734 -17.364535 -0.6867186 0.6828323 -0.0389156 0.2462584 +VERTEX_SE3:QUAT 3442 23.237093 39.530008 -16.951718 -0.0096275 -0.8152936 0.4309446 0.3866398 +VERTEX_SE3:QUAT 3443 23.592205 38.715228 -16.237052 0.8417635 -0.4269678 0.2607959 0.2027760 +VERTEX_SE3:QUAT 3444 23.668752 37.981117 -15.856230 0.7591030 0.0239836 -0.0970335 0.6432510 +VERTEX_SE3:QUAT 3445 23.931481 37.346183 -15.195161 0.8948661 0.0311551 -0.4116545 0.1696605 +VERTEX_SE3:QUAT 3446 24.118180 36.601532 -14.499652 0.8981066 -0.2085149 0.3865618 0.0222745 +VERTEX_SE3:QUAT 3447 24.383816 36.169622 -13.915371 0.9034600 -0.3506229 -0.1737783 0.1749993 +VERTEX_SE3:QUAT 3448 24.619396 35.459563 -13.145860 -0.6486252 -0.5795531 0.2810418 0.4054863 +VERTEX_SE3:QUAT 3449 24.548556 34.629221 -12.565221 -0.0612348 -0.9144284 -0.2749501 0.2906432 +VERTEX_SE3:QUAT 3450 24.776096 33.776800 -12.062255 0.1818906 0.7942004 -0.4572960 0.3564294 +VERTEX_SE3:QUAT 3451 24.889307 32.950716 -11.496793 -0.1949806 -0.6589360 0.6167210 0.3839806 +VERTEX_SE3:QUAT 3452 25.051580 32.010540 -10.704153 0.5582431 -0.5681425 -0.1191387 0.5927771 +VERTEX_SE3:QUAT 3453 25.096682 31.231538 -9.956358 -0.4122019 -0.7545275 0.3897431 0.3299668 +VERTEX_SE3:QUAT 3454 25.407648 30.366939 -9.542843 0.6350468 -0.6796785 0.2939212 0.2199157 +VERTEX_SE3:QUAT 3455 25.415739 29.697060 -8.720002 -0.2336662 0.9188039 -0.0070536 0.3180405 +VERTEX_SE3:QUAT 3456 25.338463 28.959570 -8.213395 0.5890324 -0.2236353 0.7654141 0.1310317 +VERTEX_SE3:QUAT 3457 25.374445 27.960620 -7.636348 0.6343697 -0.1669535 -0.5148349 0.5519480 +VERTEX_SE3:QUAT 3458 25.438401 26.896095 -7.114345 0.8702155 0.4683860 0.1517350 0.0177754 +VERTEX_SE3:QUAT 3459 25.504570 26.024407 -6.517173 0.1152702 0.8620459 0.2143358 0.4445783 +VERTEX_SE3:QUAT 3460 24.333489 26.082787 -6.642988 0.5537426 0.6555912 0.3935104 0.3297255 +VERTEX_SE3:QUAT 3461 24.299990 26.872204 -7.216028 0.0591011 -0.6348787 0.7234348 0.2647227 +VERTEX_SE3:QUAT 3462 24.448397 27.414824 -7.810977 0.5878574 -0.3339894 -0.1333641 0.7246301 +VERTEX_SE3:QUAT 3463 24.574334 28.180291 -8.414351 -0.8220490 0.1868374 -0.4099823 0.3481979 +VERTEX_SE3:QUAT 3464 24.408130 28.976468 -9.116973 -0.4285343 0.8950075 0.0090861 0.1234399 +VERTEX_SE3:QUAT 3465 24.519792 29.643173 -10.032418 -0.9174040 0.3384831 0.0938162 0.1870763 +VERTEX_SE3:QUAT 3466 24.331989 30.401646 -10.844928 -0.2304352 -0.6262535 0.6077596 0.4305049 +VERTEX_SE3:QUAT 3467 24.374778 31.090350 -11.503663 -0.8672298 0.4605609 -0.1148445 0.1503560 +VERTEX_SE3:QUAT 3468 24.420034 31.702527 -12.308135 0.1880819 0.7963686 0.2983291 0.4913472 +VERTEX_SE3:QUAT 3469 24.333160 32.354902 -13.179090 0.4109966 -0.5227918 -0.0087378 0.7467892 +VERTEX_SE3:QUAT 3470 24.149262 33.070748 -13.966997 0.7110502 -0.5971607 -0.2576153 0.2672846 +VERTEX_SE3:QUAT 3471 24.031115 33.921147 -14.569604 -0.0320700 0.7619295 -0.6313786 0.1406982 +VERTEX_SE3:QUAT 3472 24.014819 34.596566 -15.202124 -0.9179602 -0.1766306 -0.0693078 0.3483491 +VERTEX_SE3:QUAT 3473 24.433463 35.373013 -15.822788 0.2885415 0.5780718 0.0815768 0.7588953 +VERTEX_SE3:QUAT 3474 24.579202 36.233842 -16.526483 0.6681516 -0.2655711 -0.1417572 0.6804045 +VERTEX_SE3:QUAT 3475 24.724962 37.205085 -16.957730 0.8108666 -0.3305193 -0.3324802 0.3502989 +VERTEX_SE3:QUAT 3476 24.979211 37.879268 -17.447283 0.5898785 -0.6048980 0.5109837 0.1582321 +VERTEX_SE3:QUAT 3477 25.094566 38.621383 -18.090344 0.7983840 0.0047490 0.5716800 0.1890566 +VERTEX_SE3:QUAT 3478 25.253079 39.520549 -18.617913 -0.0068113 -0.8952871 -0.0578717 0.4416622 +VERTEX_SE3:QUAT 3479 25.309487 40.275097 -19.264695 0.4410394 0.8626225 0.2413431 0.0558593 +VERTEX_SE3:QUAT 3480 24.411896 40.264076 -19.648796 0.4884357 0.6954391 -0.1879627 0.4924074 +VERTEX_SE3:QUAT 3481 24.498347 39.453346 -19.018465 0.8264557 -0.0197404 0.4524933 0.3344116 +VERTEX_SE3:QUAT 3482 24.334109 38.481209 -18.381586 -0.6935701 -0.4156144 0.5875281 0.0321845 +VERTEX_SE3:QUAT 3483 24.487485 37.791998 -17.842910 0.8275596 -0.5580015 -0.0610539 0.0071939 +VERTEX_SE3:QUAT 3484 24.213049 36.795103 -17.219941 -0.9163166 -0.1503420 0.1073839 0.3552884 +VERTEX_SE3:QUAT 3485 24.110981 35.929205 -16.581143 0.0344246 0.9443421 0.1334753 0.2986928 +VERTEX_SE3:QUAT 3486 23.980769 34.999535 -16.203612 -0.8594884 0.2127082 -0.1086972 0.4519069 +VERTEX_SE3:QUAT 3487 24.127910 33.969119 -15.810211 -0.2049724 -0.7190169 0.5655521 0.3480685 +VERTEX_SE3:QUAT 3488 24.226013 33.054184 -15.294509 0.9118807 -0.0107242 0.4016825 0.0837243 +VERTEX_SE3:QUAT 3489 24.252530 32.047222 -14.868290 0.6093876 0.5377776 -0.1552631 0.5615473 +VERTEX_SE3:QUAT 3490 24.251399 31.116986 -14.429999 -0.9297862 -0.2880925 0.1659928 0.1579452 +VERTEX_SE3:QUAT 3491 24.301924 30.322373 -13.832104 0.6102497 0.7313202 -0.1909418 0.2372917 +VERTEX_SE3:QUAT 3492 24.418354 29.425262 -13.183918 0.4457562 0.4035671 0.5376274 0.5910938 +VERTEX_SE3:QUAT 3493 24.347503 28.593225 -12.537389 0.5995571 -0.4083392 0.4448459 0.5252642 +VERTEX_SE3:QUAT 3494 24.373536 27.680030 -12.011673 -0.2497468 0.7328186 0.2167684 0.5946553 +VERTEX_SE3:QUAT 3495 24.397134 26.777585 -11.439193 0.8484987 0.2873333 -0.4425172 0.0408410 +VERTEX_SE3:QUAT 3496 24.487961 25.958150 -11.082935 -0.9268610 0.2057766 -0.2935765 0.1113443 +VERTEX_SE3:QUAT 3497 24.860933 25.265651 -10.516722 0.2054481 -0.7871352 0.3028084 0.4965041 +VERTEX_SE3:QUAT 3498 24.945934 24.241167 -10.098616 0.1125043 -0.7007894 0.6337999 0.3074649 +VERTEX_SE3:QUAT 3499 25.046809 23.386926 -9.642468 0.8128877 -0.5054804 -0.1432744 0.2513476 +VERTEX_SE3:QUAT 3500 24.075075 22.949698 -9.559116 0.3673294 -0.7406315 0.5612969 0.0384703 +VERTEX_SE3:QUAT 3501 23.786066 23.703473 -9.991132 0.9182339 0.2181853 -0.3305169 0.0005071 +VERTEX_SE3:QUAT 3502 23.585636 24.642991 -10.443154 -0.0608955 -0.9327539 -0.2677032 0.2336598 +VERTEX_SE3:QUAT 3503 23.275828 25.310967 -11.062253 -0.4973458 0.8094167 0.2317583 0.2092365 +VERTEX_SE3:QUAT 3504 22.932873 25.960950 -11.537817 -0.1033213 0.8673004 0.4869404 0.0019207 +VERTEX_SE3:QUAT 3505 22.506466 26.697803 -11.944958 -0.1192584 -0.8462810 0.3519120 0.3817642 +VERTEX_SE3:QUAT 3506 22.103353 27.459586 -12.342798 -0.5916938 0.7497553 0.1708005 0.2420593 +VERTEX_SE3:QUAT 3507 21.669706 28.111744 -12.873387 0.6377503 -0.7385704 0.1918674 0.1047631 +VERTEX_SE3:QUAT 3508 21.308510 28.879194 -13.183727 -0.8077366 -0.2227420 0.4812686 0.2575424 +VERTEX_SE3:QUAT 3509 20.949744 29.525036 -13.524516 0.9280867 0.0226432 -0.0990256 0.3582406 +VERTEX_SE3:QUAT 3510 20.474793 30.346454 -13.771330 0.8112938 -0.4634754 -0.3017719 0.1895435 +VERTEX_SE3:QUAT 3511 19.889036 31.388475 -14.075909 -0.7971392 0.2400078 -0.4003122 0.3830347 +VERTEX_SE3:QUAT 3512 19.560789 32.390977 -14.147647 -0.2344998 -0.8858788 0.3550771 0.1847941 +VERTEX_SE3:QUAT 3513 19.215154 33.419569 -14.375953 0.8048496 0.5204598 -0.2837657 0.0285604 +VERTEX_SE3:QUAT 3514 18.648608 34.138203 -14.624733 0.1397773 0.9764151 0.1040240 0.1274946 +VERTEX_SE3:QUAT 3515 18.336590 35.028440 -15.054603 0.4267487 -0.6984240 -0.1644843 0.5504856 +VERTEX_SE3:QUAT 3516 18.031305 35.872956 -15.135913 0.3036775 -0.6783624 -0.5340965 0.4029211 +VERTEX_SE3:QUAT 3517 17.832023 36.901534 -15.375966 -0.7965728 -0.4773977 -0.2418565 0.2811913 +VERTEX_SE3:QUAT 3518 17.530847 37.891964 -15.721903 0.5677906 -0.4783712 -0.6571076 0.1303243 +VERTEX_SE3:QUAT 3519 17.107685 38.937723 -15.882918 0.6295324 0.5693127 -0.0663895 0.5245612 +VERTEX_SE3:QUAT 3520 16.070293 38.616458 -15.722444 0.3837814 0.6162848 0.0757097 0.6835005 +VERTEX_SE3:QUAT 3521 16.244790 37.701067 -15.307153 0.6082603 0.3091988 -0.3973758 0.6136025 +VERTEX_SE3:QUAT 3522 16.672394 36.889695 -15.133938 -0.1921224 -0.7553404 0.5734266 0.2524514 +VERTEX_SE3:QUAT 3523 17.032814 35.905280 -14.862371 0.0711178 -0.8617700 0.3426790 0.3672409 +VERTEX_SE3:QUAT 3524 17.373537 34.824216 -14.306166 0.8817710 -0.0351703 -0.3640745 0.2978133 +VERTEX_SE3:QUAT 3525 17.589687 34.147771 -13.924126 -0.2023781 0.7748520 -0.4855233 0.3505918 +VERTEX_SE3:QUAT 3526 17.762263 33.207438 -13.495135 0.4430352 -0.8061082 -0.0416619 0.3900944 +VERTEX_SE3:QUAT 3527 17.958245 32.515575 -13.137899 -0.3708909 0.5548744 -0.3814113 0.6395934 +VERTEX_SE3:QUAT 3528 18.174771 31.640635 -12.701028 0.4073145 -0.8103189 0.0703160 0.4153719 +VERTEX_SE3:QUAT 3529 18.417737 30.897410 -12.202807 0.7648247 0.4411255 -0.4670982 0.0476521 +VERTEX_SE3:QUAT 3530 18.785406 30.129387 -11.710148 0.2815312 0.6501779 -0.0776954 0.7014074 +VERTEX_SE3:QUAT 3531 19.278871 29.198274 -11.283166 0.1343157 0.9516469 0.2306236 0.1521190 +VERTEX_SE3:QUAT 3532 19.535545 28.374758 -10.827359 0.0627832 0.8300097 -0.2650060 0.4867382 +VERTEX_SE3:QUAT 3533 19.920469 27.438759 -10.375722 0.1396932 -0.9083858 -0.3793919 0.1066905 +VERTEX_SE3:QUAT 3534 20.301223 26.662528 -10.030260 0.3124269 -0.8012741 -0.0878764 0.5026202 +VERTEX_SE3:QUAT 3535 20.614592 25.872169 -9.490481 -0.2522541 -0.8898455 -0.1904222 0.3290627 +VERTEX_SE3:QUAT 3536 21.149946 25.154214 -9.011493 -0.1405539 -0.9725041 -0.1684182 0.0782034 +VERTEX_SE3:QUAT 3537 21.577596 24.556410 -8.681962 0.7634802 -0.6035160 0.1406714 0.1818735 +VERTEX_SE3:QUAT 3538 22.125202 23.805618 -8.041378 0.6100035 0.2419820 0.1476651 0.7399564 +VERTEX_SE3:QUAT 3539 22.612434 23.204978 -7.482254 -0.9611144 0.1778588 0.0851382 0.1933307 +VERTEX_SE3:QUAT 3540 21.632830 22.830519 -7.457225 -0.9308097 -0.3440534 -0.1200245 0.0285434 +VERTEX_SE3:QUAT 3541 21.152840 23.849190 -8.028135 -0.1087123 -0.5296372 0.7909939 0.2863472 +VERTEX_SE3:QUAT 3542 20.607531 24.457856 -8.580445 -0.9825497 -0.0275622 -0.1455797 0.1124409 +VERTEX_SE3:QUAT 3543 20.239477 25.160032 -9.170490 -0.8758192 -0.2474865 -0.0853636 0.4054679 +VERTEX_SE3:QUAT 3544 19.903901 25.759909 -9.657610 -0.9250605 0.0411240 0.3454681 0.1523931 +VERTEX_SE3:QUAT 3545 19.508649 26.374922 -10.205887 0.5785477 -0.2586113 0.6999705 0.3293085 +VERTEX_SE3:QUAT 3546 19.040429 27.054312 -10.841250 0.7400004 0.5590289 0.3202785 0.1931525 +VERTEX_SE3:QUAT 3547 18.349945 27.705880 -11.417003 0.1275575 0.4374278 -0.1717445 0.8734356 +VERTEX_SE3:QUAT 3548 17.740657 28.202994 -12.159563 -0.8550443 -0.3786784 0.1713431 0.3100701 +VERTEX_SE3:QUAT 3549 17.233886 28.813991 -12.753700 -0.8194477 -0.2488694 -0.4566160 0.2409799 +VERTEX_SE3:QUAT 3550 16.727656 29.300054 -13.146508 -0.9653534 0.0241733 -0.1984148 0.1677497 +VERTEX_SE3:QUAT 3551 16.141973 29.879589 -13.861464 0.5826359 -0.3855372 0.5547236 0.4518607 +VERTEX_SE3:QUAT 3552 15.369213 30.433459 -14.505017 0.8684546 0.1764022 -0.2474586 0.3917055 +VERTEX_SE3:QUAT 3553 14.727296 30.969684 -15.127590 0.2230748 0.9497477 -0.0538763 0.2128715 +VERTEX_SE3:QUAT 3554 14.140604 31.585948 -15.605357 0.9249748 0.1886569 -0.3078791 0.1184933 +VERTEX_SE3:QUAT 3555 13.448212 32.043586 -16.057217 0.5926212 0.6607673 0.4395061 0.1379171 +VERTEX_SE3:QUAT 3556 12.885910 32.473696 -16.515313 0.5957898 0.1389907 0.1671736 0.7731553 +VERTEX_SE3:QUAT 3557 12.113270 32.917632 -16.877541 0.2802644 0.7226209 0.5087089 0.3748149 +VERTEX_SE3:QUAT 3558 11.424688 33.497467 -17.390987 -0.3774021 0.4603551 -0.5415769 0.5935784 +VERTEX_SE3:QUAT 3559 10.719912 33.855699 -17.815340 0.5914096 -0.5182684 -0.3667873 0.4970911 +VERTEX_SE3:QUAT 3560 9.981432 33.252360 -17.770924 -0.0096228 -0.9555038 -0.0458765 0.2912307 +VERTEX_SE3:QUAT 3561 10.814215 32.844166 -17.276165 0.8273612 0.3275981 -0.3846644 0.2453288 +VERTEX_SE3:QUAT 3562 11.632756 32.455462 -16.668699 0.7370126 -0.3651396 0.4345371 0.3669646 +VERTEX_SE3:QUAT 3563 12.524856 32.200974 -16.008299 -0.8664613 0.3316361 0.0238459 0.3724160 +VERTEX_SE3:QUAT 3564 13.285214 32.151125 -15.366373 0.6500786 -0.2706799 -0.0637663 0.7071520 +VERTEX_SE3:QUAT 3565 14.149411 31.981534 -14.683698 -0.2760495 0.3748137 -0.6041577 0.6467649 +VERTEX_SE3:QUAT 3566 14.824294 31.854880 -13.839849 -0.1055318 0.5845479 0.1271558 0.7943539 +VERTEX_SE3:QUAT 3567 15.651757 31.778873 -13.166398 0.7680186 -0.6206327 -0.0517997 0.1492628 +VERTEX_SE3:QUAT 3568 16.281449 31.709408 -12.478813 0.6265681 -0.5235457 0.5759609 0.0397669 +VERTEX_SE3:QUAT 3569 16.794896 31.414575 -11.891854 0.8114618 0.1040208 0.4641494 0.3395214 +VERTEX_SE3:QUAT 3570 17.514684 31.146792 -11.113046 -0.5287612 0.8400087 0.0330805 0.1170581 +VERTEX_SE3:QUAT 3571 18.320001 30.782474 -10.379767 0.6406518 0.6272769 0.3770444 0.2322209 +VERTEX_SE3:QUAT 3572 19.090288 30.502360 -9.545223 -0.4317978 0.6790614 -0.5797514 0.1277289 +VERTEX_SE3:QUAT 3573 19.830147 30.269336 -8.804076 0.5014501 0.3450350 0.2216842 0.7618102 +VERTEX_SE3:QUAT 3574 20.336518 30.026042 -7.975574 0.7425167 -0.3882407 0.5075953 0.2007117 +VERTEX_SE3:QUAT 3575 21.034206 29.710915 -7.201729 0.9636631 -0.0058930 -0.0677068 0.2583302 +VERTEX_SE3:QUAT 3576 21.689677 29.453431 -6.559399 -0.0777287 0.8173690 0.2059664 0.5323945 +VERTEX_SE3:QUAT 3577 22.323445 29.146080 -5.960699 0.2918152 0.7613880 0.3791475 0.4374693 +VERTEX_SE3:QUAT 3578 22.900298 28.805299 -5.366319 -0.6055377 0.0390410 -0.4580214 0.6496278 +VERTEX_SE3:QUAT 3579 23.393483 28.716732 -4.619006 0.8127964 0.5139004 0.1151196 0.2490298 +VERTEX_SE3:QUAT 3580 23.109889 27.782520 -4.834507 0.7389432 -0.3226976 0.5876052 0.0674490 +VERTEX_SE3:QUAT 3581 22.414062 28.078925 -5.512540 0.0983048 -0.9405266 0.3089127 0.1015819 +VERTEX_SE3:QUAT 3582 21.753774 28.323276 -6.166789 0.8075004 -0.3702433 0.0272410 0.4583896 +VERTEX_SE3:QUAT 3583 21.163207 28.407547 -6.950480 0.6779193 0.1047348 0.7233189 0.0791570 +VERTEX_SE3:QUAT 3584 20.640421 28.514743 -7.722665 -0.3807030 0.4955959 -0.7748489 0.0951798 +VERTEX_SE3:QUAT 3585 19.939047 28.506230 -8.413412 -0.6129574 0.3544355 -0.2417335 0.6634935 +VERTEX_SE3:QUAT 3586 19.291686 28.599861 -9.089654 -0.3251001 0.6540226 -0.4965236 0.4690721 +VERTEX_SE3:QUAT 3587 18.736773 28.699611 -9.743800 -0.7709208 0.5727778 0.2154515 0.1765994 +VERTEX_SE3:QUAT 3588 18.075794 28.626799 -10.493521 0.1184395 -0.9883558 0.0753394 0.0587276 +VERTEX_SE3:QUAT 3589 17.325551 28.531215 -11.185358 0.9624464 -0.2496085 0.0142150 0.1057851 +VERTEX_SE3:QUAT 3590 16.587526 28.393635 -11.783794 -0.1115325 0.8327868 0.1143263 0.5300529 +VERTEX_SE3:QUAT 3591 15.906261 28.478711 -12.390387 -0.3283249 0.8939723 -0.3049179 0.0064323 +VERTEX_SE3:QUAT 3592 15.237645 28.415669 -12.942963 0.8087981 0.1462113 0.1028427 0.5602601 +VERTEX_SE3:QUAT 3593 14.665014 28.245231 -13.612803 -0.7155488 -0.3902432 -0.5621166 0.1404461 +VERTEX_SE3:QUAT 3594 14.009029 28.138378 -14.147149 -0.9083950 0.0360392 0.0629267 0.4117766 +VERTEX_SE3:QUAT 3595 13.249708 28.129062 -14.653492 0.2115376 0.6738372 0.5171893 0.4834362 +VERTEX_SE3:QUAT 3596 12.491507 28.385389 -15.463559 0.4239628 0.6529785 0.1437101 0.6109190 +VERTEX_SE3:QUAT 3597 11.765061 28.533809 -16.102514 -0.5631432 0.6171079 -0.4529052 0.3113270 +VERTEX_SE3:QUAT 3598 11.057819 28.419996 -16.677590 -0.5657301 -0.7859016 0.2085021 0.1372408 +VERTEX_SE3:QUAT 3599 10.414667 28.215405 -17.024480 0.5407362 0.8209719 0.1377767 0.1209422 +VERTEX_SE3:QUAT 3600 28.452365 28.416606 -10.364947 0.9703892 0.0110491 0.1785977 0.1622515 +VERTEX_SE3:QUAT 3601 27.569003 28.456827 -10.720154 -0.4808544 0.2829741 -0.7159252 0.4197092 +VERTEX_SE3:QUAT 3602 26.633070 28.322498 -10.992604 0.9047987 0.3270447 0.2678771 0.0512140 +VERTEX_SE3:QUAT 3603 25.738885 28.089459 -11.366978 0.9198094 0.1508663 -0.2931047 0.2127902 +VERTEX_SE3:QUAT 3604 24.887857 27.818267 -11.844852 -0.7309583 -0.0982922 -0.3639761 0.5688234 +VERTEX_SE3:QUAT 3605 23.716156 27.704588 -12.408926 -0.7279302 0.5897560 0.0530311 0.3456780 +VERTEX_SE3:QUAT 3606 22.911311 27.488817 -12.736287 -0.3390619 0.6630009 -0.6424736 0.1808162 +VERTEX_SE3:QUAT 3607 21.881272 27.179030 -13.255380 -0.3352306 -0.7978961 0.3971942 0.3053180 +VERTEX_SE3:QUAT 3608 20.916317 27.086407 -13.492873 0.6081032 0.7417647 0.0591256 0.2765861 +VERTEX_SE3:QUAT 3609 20.076599 26.892604 -13.924181 0.7317463 0.0555927 0.6751651 0.0748930 +VERTEX_SE3:QUAT 3610 19.065776 26.927132 -14.349545 -0.5608713 0.6185053 0.3705615 0.4068891 +VERTEX_SE3:QUAT 3611 18.087963 26.639180 -14.876861 -0.7932069 0.2018726 -0.5660914 0.0980343 +VERTEX_SE3:QUAT 3612 17.184023 26.443009 -15.347934 -0.1002755 0.8705400 0.4799658 0.0416872 +VERTEX_SE3:QUAT 3613 16.337882 26.205679 -15.699741 -0.6048842 -0.6441430 -0.3016995 0.3580116 +VERTEX_SE3:QUAT 3614 15.507230 25.833675 -16.081417 -0.7891922 0.2754142 -0.5273502 0.1523956 +VERTEX_SE3:QUAT 3615 14.702079 25.450982 -16.731641 0.5216448 0.6304097 0.5099016 0.2654632 +VERTEX_SE3:QUAT 3616 14.038072 25.144501 -17.245548 0.8378161 0.3565608 -0.0651289 0.4082729 +VERTEX_SE3:QUAT 3617 13.257049 24.839126 -17.680006 0.2995148 -0.8714185 -0.1346083 0.3644191 +VERTEX_SE3:QUAT 3618 12.400017 24.450198 -18.220750 -0.3472112 0.8232492 0.3382285 0.2954770 +VERTEX_SE3:QUAT 3619 11.549728 24.110323 -18.949360 -0.1646431 0.9603614 -0.1970023 0.1085756 +VERTEX_SE3:QUAT 3620 11.402760 25.186238 -19.280433 -0.7393946 -0.4907562 -0.4148934 0.2007920 +VERTEX_SE3:QUAT 3621 12.189071 25.481985 -18.650732 0.2120334 0.6738988 -0.6022389 0.3717668 +VERTEX_SE3:QUAT 3622 13.055158 25.774893 -18.074167 0.4283829 0.8113706 -0.3654758 0.1568221 +VERTEX_SE3:QUAT 3623 13.945155 26.159132 -17.511405 -0.5585344 0.5189705 -0.3612922 0.5368211 +VERTEX_SE3:QUAT 3624 14.822122 26.388568 -17.127846 0.3191115 0.6110620 0.4641392 0.5561888 +VERTEX_SE3:QUAT 3625 15.590633 26.689297 -16.550951 -0.4407194 0.8670202 0.0456223 0.2279495 +VERTEX_SE3:QUAT 3626 16.613076 26.918796 -16.039257 0.4855548 0.2967100 0.6811803 0.4606442 +VERTEX_SE3:QUAT 3627 17.383162 27.054712 -15.353544 0.7600667 0.1322342 0.5603003 0.3014568 +VERTEX_SE3:QUAT 3628 18.195004 27.106736 -14.872469 0.7957430 0.2546250 0.5423959 0.0881238 +VERTEX_SE3:QUAT 3629 19.070010 27.293882 -14.233042 0.4675041 0.3187057 -0.0220641 0.8242450 +VERTEX_SE3:QUAT 3630 19.961634 27.346048 -13.676869 -0.9579405 -0.0287299 0.2694116 0.0945615 +VERTEX_SE3:QUAT 3631 20.820459 27.608448 -13.274518 0.2711814 -0.9417949 -0.1020964 0.1704680 +VERTEX_SE3:QUAT 3632 21.641763 27.878555 -12.843803 0.6032818 0.7368164 0.0398446 0.3025973 +VERTEX_SE3:QUAT 3633 22.520614 28.014009 -12.455933 0.8716046 0.0388336 -0.0800432 0.4820690 +VERTEX_SE3:QUAT 3634 23.478163 28.193150 -12.056676 -0.2167553 0.7336834 -0.6348225 0.1082878 +VERTEX_SE3:QUAT 3635 24.373985 28.432518 -11.841426 0.4061971 -0.7716776 0.0707750 0.4842608 +VERTEX_SE3:QUAT 3636 25.165172 28.562236 -11.341116 -0.7062173 -0.4172659 -0.2434991 0.5175466 +VERTEX_SE3:QUAT 3637 26.004885 28.738663 -10.870964 0.6325890 -0.6962823 0.0571389 0.3343011 +VERTEX_SE3:QUAT 3638 27.072623 28.749999 -10.556522 -0.3920267 0.5908386 -0.6378925 0.3005295 +VERTEX_SE3:QUAT 3639 27.961044 28.983301 -10.287830 0.3121502 0.5830415 0.0811012 0.7456859 +VERTEX_SE3:QUAT 3640 27.770192 29.918779 -10.392366 0.8741591 -0.4227967 0.1624408 0.1752193 +VERTEX_SE3:QUAT 3641 26.733769 29.749893 -10.494698 0.9661619 -0.1903652 0.0357864 0.1703280 +VERTEX_SE3:QUAT 3642 25.939798 29.462410 -10.625927 0.6900847 -0.2587797 0.3071215 0.6020736 +VERTEX_SE3:QUAT 3643 25.060612 29.450459 -10.823997 -0.8333456 0.3068490 0.2656992 0.3752102 +VERTEX_SE3:QUAT 3644 23.972016 29.232976 -10.921684 0.7177409 0.2841659 0.6254225 0.1137737 +VERTEX_SE3:QUAT 3645 22.993904 28.807833 -11.088893 -0.8638281 -0.3190409 0.2600023 0.2905386 +VERTEX_SE3:QUAT 3646 22.072685 28.665562 -11.188720 -0.5293955 -0.8130561 -0.1594063 0.1824003 +VERTEX_SE3:QUAT 3647 21.008463 28.554657 -11.489064 -0.8906231 -0.1854090 -0.1972188 0.3654022 +VERTEX_SE3:QUAT 3648 20.056257 28.417109 -11.494904 0.8260512 0.1850316 0.5250804 0.0877114 +VERTEX_SE3:QUAT 3649 19.036964 28.040001 -11.673135 -0.7452280 0.1455173 0.2505853 0.6005555 +VERTEX_SE3:QUAT 3650 18.100326 27.614166 -11.858675 0.2687218 0.6884693 -0.4434342 0.5071142 +VERTEX_SE3:QUAT 3651 17.245120 27.049884 -12.132160 -0.7931881 0.5148141 0.2254715 0.2344818 +VERTEX_SE3:QUAT 3652 16.252549 26.717921 -12.416017 0.5937506 0.5820553 0.5529230 0.0542955 +VERTEX_SE3:QUAT 3653 15.403960 26.374447 -12.764074 0.4155752 -0.7588682 0.0583272 0.4980103 +VERTEX_SE3:QUAT 3654 14.709872 25.931675 -12.872173 -0.4277616 0.8161208 0.0484657 0.3855099 +VERTEX_SE3:QUAT 3655 13.947819 25.539030 -13.011382 0.9090403 -0.3863862 -0.1093990 0.1112800 +VERTEX_SE3:QUAT 3656 13.028629 25.052034 -13.205135 0.3972327 -0.7060048 -0.3650342 0.4588174 +VERTEX_SE3:QUAT 3657 12.167854 24.459165 -13.395257 0.3572305 -0.8861591 0.0702990 0.2866468 +VERTEX_SE3:QUAT 3658 11.325275 24.129466 -13.360765 0.5926060 0.6652291 0.3900554 0.2326910 +VERTEX_SE3:QUAT 3659 10.359846 23.686319 -13.443356 -0.7732420 -0.2734093 0.2324568 0.5227887 +VERTEX_SE3:QUAT 3660 9.885097 24.527828 -13.339546 -0.4450245 0.6273128 0.0985493 0.6314427 +VERTEX_SE3:QUAT 3661 10.754191 25.097934 -13.256605 -0.4212890 -0.9001993 0.0422184 0.1018544 +VERTEX_SE3:QUAT 3662 11.485546 25.736667 -13.244419 0.4630505 0.8308024 -0.1582534 0.2651555 +VERTEX_SE3:QUAT 3663 12.401906 26.158203 -13.339957 -0.7193255 0.4951905 -0.1904705 0.4484175 +VERTEX_SE3:QUAT 3664 13.227489 26.609229 -13.173232 -0.5449807 0.5719757 -0.5987800 0.1315381 +VERTEX_SE3:QUAT 3665 14.015298 26.877231 -12.979582 0.2773057 -0.7889181 0.5110725 0.1987830 +VERTEX_SE3:QUAT 3666 14.903788 27.308614 -12.940679 0.8695249 -0.1394511 0.4663740 0.0835168 +VERTEX_SE3:QUAT 3667 15.840156 27.896105 -12.883044 0.5842470 -0.5923571 -0.4384685 0.3398734 +VERTEX_SE3:QUAT 3668 16.744854 28.424797 -12.799623 0.3965708 -0.7742726 0.1414690 0.4724618 +VERTEX_SE3:QUAT 3669 17.733906 28.950992 -12.917419 0.2557014 0.8886097 -0.3752846 0.0644283 +VERTEX_SE3:QUAT 3670 18.585261 29.641662 -12.904180 -0.3961549 -0.8639105 0.2304651 0.2088199 +VERTEX_SE3:QUAT 3671 19.697172 30.017928 -13.173519 -0.0454155 -0.9313449 -0.1657442 0.3210341 +VERTEX_SE3:QUAT 3672 20.611542 30.390733 -13.308877 0.4245479 0.8410682 -0.3219477 0.0933438 +VERTEX_SE3:QUAT 3673 21.638815 30.837094 -13.544475 -0.8482885 -0.1119959 -0.0205013 0.5171491 +VERTEX_SE3:QUAT 3674 22.466560 31.167545 -13.583204 -0.9295573 0.1639444 0.0431184 0.3273930 +VERTEX_SE3:QUAT 3675 23.405972 31.639092 -13.977708 0.1441193 -0.7945569 0.0289446 0.5891275 +VERTEX_SE3:QUAT 3676 24.477158 32.011271 -14.192790 -0.8047234 -0.5291609 0.2657738 0.0421100 +VERTEX_SE3:QUAT 3677 25.412314 32.491696 -14.356418 0.0109979 -0.8800363 -0.0735066 0.4690542 +VERTEX_SE3:QUAT 3678 26.338830 33.110708 -14.614793 0.0147097 -0.9929876 -0.1020580 0.0578218 +VERTEX_SE3:QUAT 3679 27.207314 33.456889 -14.984822 -0.7095124 -0.5778988 0.1245069 0.3835663 +VERTEX_SE3:QUAT 3680 26.684830 34.310379 -14.538021 0.4465513 -0.6731889 -0.5745215 0.1316576 +VERTEX_SE3:QUAT 3681 25.830613 33.769167 -14.323028 0.4886617 0.7803955 -0.2521509 0.2976784 +VERTEX_SE3:QUAT 3682 25.129580 33.310387 -14.079996 -0.2899863 -0.5838747 0.5826597 0.4852896 +VERTEX_SE3:QUAT 3683 24.264769 32.713629 -13.730833 -0.8636567 -0.2411813 0.0714324 0.4368365 +VERTEX_SE3:QUAT 3684 23.521729 32.275379 -13.427448 -0.6664966 -0.5980870 0.3407569 0.2862848 +VERTEX_SE3:QUAT 3685 22.639945 31.784773 -13.059122 -0.3025005 0.9370812 0.1727159 0.0232680 +VERTEX_SE3:QUAT 3686 21.740636 31.189160 -12.918909 0.8146539 -0.3119061 0.1476752 0.4660961 +VERTEX_SE3:QUAT 3687 20.886069 30.642827 -12.727119 -0.0111148 -0.9146401 0.2493205 0.3180397 +VERTEX_SE3:QUAT 3688 20.121458 29.884601 -12.470169 0.7411803 0.5853494 -0.1663468 0.2834548 +VERTEX_SE3:QUAT 3689 19.466695 28.979402 -12.125482 0.9161208 0.0374961 0.0425931 0.3968659 +VERTEX_SE3:QUAT 3690 18.981916 28.398448 -11.839545 0.7468778 -0.2796391 -0.2469188 0.5504604 +VERTEX_SE3:QUAT 3691 18.181250 27.633948 -11.523121 -0.0710269 -0.7638781 0.5343819 0.3547978 +VERTEX_SE3:QUAT 3692 17.518441 27.034367 -11.254774 0.7286191 -0.4016386 -0.4846621 0.2700061 +VERTEX_SE3:QUAT 3693 16.914152 26.340943 -10.821994 0.7134836 0.6172352 0.2775144 0.1815147 +VERTEX_SE3:QUAT 3694 16.253580 25.773641 -10.533998 0.2090410 0.7895842 0.1010350 0.5680234 +VERTEX_SE3:QUAT 3695 15.575446 25.217928 -10.259306 -0.3746191 0.7225350 -0.5028342 0.2911383 +VERTEX_SE3:QUAT 3696 14.861968 24.522892 -10.010620 0.9648152 0.1221276 -0.2327630 0.0061448 +VERTEX_SE3:QUAT 3697 14.246778 23.927518 -9.771583 0.5671495 0.4390152 -0.2520417 0.6496784 +VERTEX_SE3:QUAT 3698 13.885379 23.106814 -9.568804 -0.0865533 0.6297386 -0.7548317 0.1617619 +VERTEX_SE3:QUAT 3699 13.205382 22.347501 -9.190288 0.5259172 -0.3949053 -0.5122445 0.5523282 +VERTEX_SE3:QUAT 3700 12.363912 22.795326 -9.321226 -0.6373966 0.6365251 -0.3987875 0.1718426 +VERTEX_SE3:QUAT 3701 12.706237 23.679687 -9.548209 -0.9388125 -0.3128772 -0.0523263 0.1341678 +VERTEX_SE3:QUAT 3702 13.265363 24.559741 -9.741397 0.5016037 0.4578640 -0.7076400 0.1949356 +VERTEX_SE3:QUAT 3703 13.810728 25.421095 -10.266921 0.8115492 0.3875792 0.3735656 0.2271981 +VERTEX_SE3:QUAT 3704 14.431228 26.126138 -10.629076 -0.7009495 0.5926297 -0.0338630 0.3953645 +VERTEX_SE3:QUAT 3705 14.943388 26.871588 -10.949393 -0.5346603 0.3977137 -0.7256913 0.1712726 +VERTEX_SE3:QUAT 3706 15.475202 27.576600 -11.528515 -0.6746109 -0.6391407 0.2029796 0.3085428 +VERTEX_SE3:QUAT 3707 15.935736 28.265860 -11.948691 0.4082407 -0.7504169 0.4140250 0.3143204 +VERTEX_SE3:QUAT 3708 16.548024 29.001880 -12.233709 0.2934371 -0.6747345 0.6678405 0.1123256 +VERTEX_SE3:QUAT 3709 17.034608 29.661661 -12.767985 0.2538046 -0.9139448 0.3153516 0.0290092 +VERTEX_SE3:QUAT 3710 17.687108 30.446676 -13.321882 0.7270675 0.6142942 -0.2180115 0.2156071 +VERTEX_SE3:QUAT 3711 18.460142 31.275231 -13.860970 0.2348547 0.9442104 -0.1788472 0.1460261 +VERTEX_SE3:QUAT 3712 18.895420 32.039697 -14.178060 -0.6885814 0.3233927 -0.5919057 0.2663091 +VERTEX_SE3:QUAT 3713 19.437179 32.607208 -14.198487 -0.0984284 -0.9430189 -0.0658294 0.3109561 +VERTEX_SE3:QUAT 3714 20.064408 33.430629 -14.533271 -0.8164755 0.4960065 -0.2392962 0.1734436 +VERTEX_SE3:QUAT 3715 20.541309 34.158777 -14.716819 0.6554545 -0.4780806 0.1552625 0.5636594 +VERTEX_SE3:QUAT 3716 20.919642 34.795273 -14.728084 0.7392299 -0.0705829 0.4847331 0.4621592 +VERTEX_SE3:QUAT 3717 21.543419 35.557426 -14.852881 0.6014276 -0.7185630 -0.2044036 0.2831451 +VERTEX_SE3:QUAT 3718 22.061898 36.310893 -15.013036 -0.0100312 -0.7805225 0.4316171 0.4520958 +VERTEX_SE3:QUAT 3719 22.630269 37.198673 -15.268106 -0.8561159 -0.3277849 0.3742017 0.1399851 +VERTEX_SE3:QUAT 3720 21.805723 37.757659 -15.337700 -0.4370376 -0.7454198 0.2925096 0.4096165 +VERTEX_SE3:QUAT 3721 21.261823 36.943814 -15.122025 -0.2781763 -0.7519600 0.3906699 0.4522733 +VERTEX_SE3:QUAT 3722 20.726362 36.205363 -14.927673 -0.6485243 0.6982333 0.1807262 0.2433610 +VERTEX_SE3:QUAT 3723 20.022939 35.671985 -14.865805 -0.8131006 0.4533977 0.0074370 0.3650241 +VERTEX_SE3:QUAT 3724 19.386988 34.728032 -14.952058 0.3700474 -0.7321003 0.5660277 0.0818946 +VERTEX_SE3:QUAT 3725 18.804997 34.159836 -14.842480 -0.0941315 -0.8689234 -0.4198480 0.2446200 +VERTEX_SE3:QUAT 3726 18.139543 33.369870 -14.892381 0.3785319 0.9102825 -0.1670511 0.0139055 +VERTEX_SE3:QUAT 3727 17.335657 32.691678 -14.832548 0.5186359 -0.4697209 -0.2533242 0.6679865 +VERTEX_SE3:QUAT 3728 16.852838 31.836608 -14.660113 -0.5603598 -0.6922909 -0.0049408 0.4546490 +VERTEX_SE3:QUAT 3729 16.337089 30.978229 -14.394497 0.5994402 0.0220564 0.3331238 0.7274706 +VERTEX_SE3:QUAT 3730 15.822296 30.012257 -14.115640 -0.7948614 -0.5138965 -0.2115911 0.2435875 +VERTEX_SE3:QUAT 3731 15.227373 29.212281 -13.601857 -0.5683154 0.6217528 -0.3636835 0.3977126 +VERTEX_SE3:QUAT 3732 14.618117 28.451634 -13.411559 0.7284151 -0.1137192 0.4315299 0.5198665 +VERTEX_SE3:QUAT 3733 13.976708 27.737444 -13.168294 0.0877832 -0.9472576 -0.3019021 0.0620666 +VERTEX_SE3:QUAT 3734 13.477486 26.947667 -13.175399 -0.8664691 0.0194845 -0.1751933 0.4670749 +VERTEX_SE3:QUAT 3735 12.864638 26.180905 -13.202590 -0.3706472 0.6158917 -0.4106183 0.5609729 +VERTEX_SE3:QUAT 3736 12.082582 25.605127 -13.238326 -0.7718597 -0.5818271 0.2549849 0.0263155 +VERTEX_SE3:QUAT 3737 11.441230 25.043382 -13.408396 -0.5708432 -0.5123860 0.6402525 0.0409321 +VERTEX_SE3:QUAT 3738 10.753094 24.307811 -13.462908 -0.4149742 -0.8117878 0.3847232 0.1441703 +VERTEX_SE3:QUAT 3739 10.077866 23.664964 -13.416103 0.8762900 0.0932370 0.1340070 0.4532822 +VERTEX_SE3:QUAT 3740 9.379587 24.583830 -13.407489 0.8312495 -0.1132163 -0.4617823 0.2880338 +VERTEX_SE3:QUAT 3741 10.300069 25.141531 -13.697943 -0.8869246 -0.3740385 0.0880063 0.2563491 +VERTEX_SE3:QUAT 3742 11.107312 25.697997 -13.658834 0.3349648 -0.6936228 0.1439578 0.6212585 +VERTEX_SE3:QUAT 3743 11.896587 26.237600 -13.616902 0.3748586 0.7011471 -0.1349686 0.5913182 +VERTEX_SE3:QUAT 3744 12.716084 26.815199 -13.361715 0.4015259 -0.8241404 -0.3223128 0.2359746 +VERTEX_SE3:QUAT 3745 13.572448 27.284179 -13.285218 0.2359879 0.6469919 -0.5082042 0.5171457 +VERTEX_SE3:QUAT 3746 14.495190 27.833862 -13.221715 -0.3396174 0.9301364 0.0171068 0.1386131 +VERTEX_SE3:QUAT 3747 15.329069 28.331835 -13.081047 -0.2582292 0.8071917 -0.4823108 0.2216655 +VERTEX_SE3:QUAT 3748 16.275166 28.822298 -13.022382 0.4191670 -0.6408617 0.2005676 0.6110384 +VERTEX_SE3:QUAT 3749 17.149124 29.377870 -12.941643 -0.7085235 0.3801768 -0.5941700 0.0205452 +VERTEX_SE3:QUAT 3750 17.825154 30.122961 -12.895017 0.9115098 -0.3447156 0.0807944 0.2092686 +VERTEX_SE3:QUAT 3751 18.462232 30.775453 -12.841535 -0.1468159 -0.8700557 -0.4616117 0.0914484 +VERTEX_SE3:QUAT 3752 18.958334 31.562546 -12.751441 -0.8562104 -0.4272903 0.2880319 0.0369361 +VERTEX_SE3:QUAT 3753 19.459230 32.176854 -12.639993 0.4119054 0.3889745 0.2005932 0.7992466 +VERTEX_SE3:QUAT 3754 20.123913 32.932355 -12.669664 -0.3410976 0.5810352 -0.2006163 0.7111987 +VERTEX_SE3:QUAT 3755 20.706493 33.879809 -12.545318 -0.4960524 0.8489932 0.0344289 0.1787657 +VERTEX_SE3:QUAT 3756 21.137051 34.863676 -12.639581 -0.3177137 -0.9242302 0.0700484 0.1998744 +VERTEX_SE3:QUAT 3757 21.685311 35.569597 -12.515990 -0.6172621 0.2271040 -0.2564630 0.7082641 +VERTEX_SE3:QUAT 3758 22.198811 36.614779 -12.590633 -0.7162055 -0.3121138 -0.6239650 0.0173864 +VERTEX_SE3:QUAT 3759 22.581001 37.511632 -12.218098 -0.0526828 0.5468064 -0.6222785 0.5576708 +VERTEX_SE3:QUAT 3760 21.688343 37.852145 -12.654069 0.3733959 0.8864113 0.2735829 0.0017293 +VERTEX_SE3:QUAT 3761 21.352189 36.966526 -12.779467 -0.1450707 0.7368657 -0.6350750 0.1807294 +VERTEX_SE3:QUAT 3762 20.965700 35.910158 -13.044920 -0.6361529 0.5584981 -0.4970870 0.1905097 +VERTEX_SE3:QUAT 3763 20.498186 35.178623 -13.173279 -0.5458896 -0.6011313 -0.4875653 0.3208204 +VERTEX_SE3:QUAT 3764 20.042829 34.344007 -13.442887 0.1150884 0.9661483 0.0642403 0.2217777 +VERTEX_SE3:QUAT 3765 19.606501 33.540126 -13.851698 -0.7915058 -0.3719561 0.0511999 0.4822300 +VERTEX_SE3:QUAT 3766 19.295572 32.589218 -14.277623 -0.2883913 0.8097962 0.1816309 0.4775676 +VERTEX_SE3:QUAT 3767 18.957665 31.648237 -14.564133 -0.6194957 0.7436353 0.2496823 0.0298405 +VERTEX_SE3:QUAT 3768 18.507568 30.742100 -14.791843 0.0956004 -0.9572576 0.2472485 0.1157007 +VERTEX_SE3:QUAT 3769 18.113272 29.897107 -15.080965 -0.7810293 -0.3495484 0.0696512 0.5127941 +VERTEX_SE3:QUAT 3770 17.606601 29.112489 -15.370459 0.8963607 0.1892825 0.1562334 0.3691892 +VERTEX_SE3:QUAT 3771 16.935724 28.286511 -15.489309 -0.2123222 0.9723579 0.0581749 0.0778141 +VERTEX_SE3:QUAT 3772 16.734381 27.563976 -15.643506 -0.7970257 0.0871391 0.1516185 0.5780732 +VERTEX_SE3:QUAT 3773 16.212630 26.627051 -15.896817 -0.8331988 0.0766512 -0.5426684 0.0735891 +VERTEX_SE3:QUAT 3774 15.753884 25.842307 -16.003068 0.4124938 -0.8205677 -0.2700359 0.2891334 +VERTEX_SE3:QUAT 3775 15.441960 25.035816 -16.327601 -0.6326225 0.4804956 -0.6033412 0.0699433 +VERTEX_SE3:QUAT 3776 15.045543 24.356893 -16.646132 0.4646446 0.1614904 0.7715439 0.4034181 +VERTEX_SE3:QUAT 3777 14.629325 23.531642 -16.885571 0.7067014 -0.5999257 -0.0540820 0.3711298 +VERTEX_SE3:QUAT 3778 14.308251 22.566063 -17.158231 0.0403886 0.4831993 -0.4032056 0.7760879 +VERTEX_SE3:QUAT 3779 13.809802 21.708484 -17.520244 -0.4776618 0.7216939 -0.4919168 0.0949476 +VERTEX_SE3:QUAT 3780 12.982476 22.213062 -18.093393 -0.3609214 0.6851186 0.2099130 0.5968959 +VERTEX_SE3:QUAT 3781 13.479722 23.164437 -17.964075 -0.6386606 0.1832973 -0.7328985 0.1462001 +VERTEX_SE3:QUAT 3782 13.782099 24.025128 -17.614745 0.5745816 -0.7019607 -0.0623200 0.4162012 +VERTEX_SE3:QUAT 3783 14.270598 24.997420 -17.405608 0.6718988 -0.0510905 0.6001409 0.4310135 +VERTEX_SE3:QUAT 3784 14.449388 26.131196 -17.354294 0.3618516 0.3467364 0.5797143 0.6424707 +VERTEX_SE3:QUAT 3785 14.732091 26.906612 -17.096951 -0.7544008 -0.5185035 0.4001639 0.0436162 +VERTEX_SE3:QUAT 3786 15.048674 27.676961 -16.895497 0.7628753 -0.2532117 0.5463138 0.2354704 +VERTEX_SE3:QUAT 3787 15.481458 28.521052 -16.811181 0.3897992 0.5390671 0.1336557 0.7345743 +VERTEX_SE3:QUAT 3788 15.781690 29.412839 -16.620914 -0.6495194 0.5031266 -0.5013260 0.2714048 +VERTEX_SE3:QUAT 3789 16.181516 30.135906 -16.389078 0.6206693 0.5562360 -0.5472451 0.0767722 +VERTEX_SE3:QUAT 3790 16.612494 31.050646 -16.189711 -0.0316272 0.9678786 0.1754097 0.1773192 +VERTEX_SE3:QUAT 3791 16.976356 31.902068 -15.976012 0.8871025 0.4434547 -0.0977117 0.0827621 +VERTEX_SE3:QUAT 3792 17.354497 32.791939 -15.827786 -0.9420941 0.3151157 0.0149124 0.1137470 +VERTEX_SE3:QUAT 3793 17.808214 33.721662 -15.575492 -0.4248567 -0.7978621 0.3999061 0.1516178 +VERTEX_SE3:QUAT 3794 18.309313 34.621506 -15.521488 -0.6046467 0.7039529 -0.1278704 0.3500025 +VERTEX_SE3:QUAT 3795 18.547023 35.698311 -15.308756 -0.6284455 -0.3096354 -0.5249273 0.4833564 +VERTEX_SE3:QUAT 3796 18.954306 36.728343 -14.983622 -0.6004808 0.6449698 -0.3661819 0.2989106 +VERTEX_SE3:QUAT 3797 19.355942 37.621372 -14.994010 -0.8633455 0.0253613 -0.4904230 0.1160885 +VERTEX_SE3:QUAT 3798 19.651436 38.587544 -14.867521 0.9221136 0.3637245 0.1268702 0.0362616 +VERTEX_SE3:QUAT 3799 20.113933 39.729057 -14.694611 -0.6407184 -0.6783453 0.3363371 0.1272985 +VERTEX_SE3:QUAT 3800 19.499278 40.079455 -15.183898 -0.7495077 0.3727281 -0.0458302 0.5451711 +VERTEX_SE3:QUAT 3801 19.296895 39.385509 -15.497699 -0.7082230 0.0795004 -0.4712595 0.5196290 +VERTEX_SE3:QUAT 3802 19.099412 38.266441 -15.875237 -0.5599968 0.7214796 -0.2378102 0.3306313 +VERTEX_SE3:QUAT 3803 19.208644 37.374174 -16.056386 -0.6370799 0.0066538 -0.6718053 0.3778394 +VERTEX_SE3:QUAT 3804 19.230686 36.382111 -16.170286 0.6005529 -0.6037268 0.5229896 0.0364977 +VERTEX_SE3:QUAT 3805 19.076941 35.442016 -16.194170 -0.4214483 0.7444527 0.3310721 0.3981993 +VERTEX_SE3:QUAT 3806 18.822368 34.289373 -16.242624 -0.7811471 0.5966797 0.1746586 0.0572444 +VERTEX_SE3:QUAT 3807 18.895958 33.508681 -16.210705 0.5658758 -0.1647923 0.7221069 0.3622011 +VERTEX_SE3:QUAT 3808 18.824646 32.520830 -16.404888 -0.7636253 0.4469947 0.3820533 0.2666599 +VERTEX_SE3:QUAT 3809 18.929112 31.577678 -16.297330 0.8210006 -0.3624735 0.3758274 0.2309213 +VERTEX_SE3:QUAT 3810 18.711230 30.409655 -16.364885 0.8873313 -0.3532775 -0.0691520 0.2881946 +VERTEX_SE3:QUAT 3811 18.633884 29.449933 -16.405507 -0.0404295 0.7756148 0.4857838 0.4010004 +VERTEX_SE3:QUAT 3812 18.506750 28.533079 -16.490527 -0.4054399 -0.8918929 -0.1795266 0.0889705 +VERTEX_SE3:QUAT 3813 18.405189 27.569958 -16.522673 -0.4952501 0.6584107 -0.4327299 0.3660159 +VERTEX_SE3:QUAT 3814 18.260297 26.708326 -16.552643 -0.3327940 0.3499810 -0.3713727 0.7929967 +VERTEX_SE3:QUAT 3815 18.077732 25.668087 -16.906596 -0.2939609 -0.9221924 0.1305823 0.2147007 +VERTEX_SE3:QUAT 3816 17.837408 24.800793 -17.073198 -0.1250485 0.5362000 -0.7473983 0.3718175 +VERTEX_SE3:QUAT 3817 17.693888 23.863582 -17.315973 0.0233067 0.8519466 0.4314373 0.2958134 +VERTEX_SE3:QUAT 3818 17.315510 22.900531 -17.676466 0.8907934 0.3937408 -0.1822205 0.1350960 +VERTEX_SE3:QUAT 3819 17.094588 21.955295 -17.664462 0.5839931 0.2946942 0.7010785 0.2838949 +VERTEX_SE3:QUAT 3820 16.257632 22.163040 -18.290110 -0.8547553 -0.2477435 -0.2189016 0.4001232 +VERTEX_SE3:QUAT 3821 16.424361 23.200281 -18.058907 0.1930505 0.6337100 0.3210346 0.6768161 +VERTEX_SE3:QUAT 3822 16.710594 24.186590 -17.878049 0.3386723 0.9078981 0.2182739 0.1156659 +VERTEX_SE3:QUAT 3823 16.838724 25.381944 -17.784542 -0.8637458 0.1651847 -0.0323163 0.4749873 +VERTEX_SE3:QUAT 3824 17.033983 26.305104 -17.622907 0.4133454 0.7139313 0.5627808 0.0522060 +VERTEX_SE3:QUAT 3825 17.320404 27.201531 -17.440940 -0.2000466 0.5337520 -0.5004493 0.6516446 +VERTEX_SE3:QUAT 3826 17.540116 28.242941 -17.168069 0.7899617 -0.3498558 -0.1200824 0.4890211 +VERTEX_SE3:QUAT 3827 17.729674 29.094464 -17.092528 0.2883818 0.7609058 0.0457619 0.5794516 +VERTEX_SE3:QUAT 3828 17.805615 30.115090 -16.924781 -0.7822119 0.3419293 -0.4397717 0.2789798 +VERTEX_SE3:QUAT 3829 18.018553 31.137959 -16.615980 0.4014099 0.4782175 0.2830706 0.7280448 +VERTEX_SE3:QUAT 3830 18.317700 32.308434 -16.271056 0.9521065 -0.1569357 -0.1991993 0.1708332 +VERTEX_SE3:QUAT 3831 18.659291 33.061984 -15.906880 -0.2794559 0.8970049 -0.2607923 0.2219775 +VERTEX_SE3:QUAT 3832 18.823023 33.772054 -15.533744 -0.1033377 0.5355563 0.4920339 0.6785304 +VERTEX_SE3:QUAT 3833 19.132900 34.503228 -15.138156 -0.8440483 -0.0324294 0.2171867 0.4892451 +VERTEX_SE3:QUAT 3834 19.487238 35.393970 -14.767077 0.7432961 0.6601644 -0.0536786 0.0938748 +VERTEX_SE3:QUAT 3835 19.765827 36.156724 -14.574637 0.6051460 0.7323763 -0.2394558 0.2002102 +VERTEX_SE3:QUAT 3836 20.050202 37.063780 -14.316425 0.3124299 0.6055356 0.6279077 0.3760931 +VERTEX_SE3:QUAT 3837 20.351363 38.042337 -14.026911 -0.3900933 0.6210183 -0.3653488 0.5733095 +VERTEX_SE3:QUAT 3838 20.896089 38.985411 -13.884539 0.7740938 -0.4139780 0.4732643 0.0736343 +VERTEX_SE3:QUAT 3839 21.442792 39.849492 -13.483005 0.2796624 -0.9104763 0.1910510 0.2373213 +VERTEX_SE3:QUAT 3840 20.726901 40.324459 -13.810550 0.8711868 -0.1440044 0.3831964 0.2710293 +VERTEX_SE3:QUAT 3841 20.295553 39.556660 -14.151254 -0.1889894 0.7831647 -0.3416344 0.4839650 +VERTEX_SE3:QUAT 3842 19.802349 38.682603 -14.409224 0.0075444 -0.9535664 -0.3010881 0.0004331 +VERTEX_SE3:QUAT 3843 19.404843 37.735523 -14.620517 0.7154318 0.2996220 0.1512659 0.6127828 +VERTEX_SE3:QUAT 3844 18.957433 36.835555 -14.852622 0.4662232 0.7442830 0.4711288 0.0819535 +VERTEX_SE3:QUAT 3845 18.308284 35.838387 -15.037192 -0.6996266 -0.0384520 -0.6176757 0.3571006 +VERTEX_SE3:QUAT 3846 17.809130 35.037585 -15.129220 0.8397298 0.2201415 -0.4656785 0.1718580 +VERTEX_SE3:QUAT 3847 17.216194 34.107208 -15.262359 -0.3967690 0.8939304 -0.1083004 0.1781401 +VERTEX_SE3:QUAT 3848 16.819634 33.119725 -15.473765 -0.9896943 -0.0246297 -0.1410597 0.0007937 +VERTEX_SE3:QUAT 3849 16.358469 32.233003 -15.557651 0.5510354 -0.4569547 0.6924715 0.0896421 +VERTEX_SE3:QUAT 3850 15.796935 31.253193 -15.586887 0.2805149 0.8171569 0.2829855 0.4165155 +VERTEX_SE3:QUAT 3851 15.314626 30.494852 -15.425800 -0.5201518 0.6776290 -0.3265239 0.4045284 +VERTEX_SE3:QUAT 3852 14.618935 29.744514 -15.543925 -0.6582269 0.5912595 -0.4656352 0.0182606 +VERTEX_SE3:QUAT 3853 13.992377 28.905905 -15.441147 -0.4364174 0.0368105 -0.8956127 0.0778642 +VERTEX_SE3:QUAT 3854 13.545900 28.095880 -15.423508 -0.1630370 0.9276097 -0.2259122 0.2488431 +VERTEX_SE3:QUAT 3855 12.967933 27.291492 -15.511708 -0.6710946 -0.4072697 -0.4783555 0.3936236 +VERTEX_SE3:QUAT 3856 12.260182 26.420209 -15.549171 0.5393508 -0.4333720 0.7156089 0.0958817 +VERTEX_SE3:QUAT 3857 11.845682 25.672956 -15.691585 0.4390357 0.5761878 -0.3333626 0.6034274 +VERTEX_SE3:QUAT 3858 11.579154 24.663872 -15.714489 0.2852193 -0.9484591 0.1241288 0.0605577 +VERTEX_SE3:QUAT 3859 10.966004 23.725184 -15.803088 -0.6353376 -0.5309939 -0.4999893 0.2537761 +VERTEX_SE3:QUAT 3860 10.279086 24.157619 -16.694036 -0.3283438 0.5113811 0.3068735 0.7324673 +VERTEX_SE3:QUAT 3861 10.730718 25.011694 -16.638121 -0.4929369 0.6078267 0.4166274 0.4625813 +VERTEX_SE3:QUAT 3862 11.363954 26.037301 -16.473542 0.4837311 0.0109282 0.6958350 0.5307526 +VERTEX_SE3:QUAT 3863 11.910814 26.982725 -16.329582 0.8675925 -0.0221944 -0.0131373 0.4966066 +VERTEX_SE3:QUAT 3864 12.251534 27.830499 -16.182784 0.5674334 -0.0228724 0.3394277 0.7498567 +VERTEX_SE3:QUAT 3865 12.777693 28.655470 -15.854241 -0.6575096 -0.0392980 -0.4355535 0.6135389 +VERTEX_SE3:QUAT 3866 13.082235 29.500104 -15.669599 -0.2813534 0.0831629 -0.9366427 0.1913757 +VERTEX_SE3:QUAT 3867 13.539635 30.300669 -15.255069 -0.4945385 0.8577568 0.0771992 0.1171549 +VERTEX_SE3:QUAT 3868 13.922699 31.209557 -14.838418 0.3388825 0.3343739 -0.4817056 0.7357394 +VERTEX_SE3:QUAT 3869 14.243959 32.063539 -14.404005 -0.0242786 0.4206710 0.2769474 0.8635662 +VERTEX_SE3:QUAT 3870 14.608315 33.091629 -14.408811 0.8750804 -0.3044729 0.3689415 0.0735715 +VERTEX_SE3:QUAT 3871 14.943422 33.796476 -14.226035 0.1019103 0.8802847 0.4302283 0.1720950 +VERTEX_SE3:QUAT 3872 15.287715 34.639128 -14.087063 0.2637496 0.5648072 0.1558859 0.7662431 +VERTEX_SE3:QUAT 3873 15.616028 35.413833 -13.825343 -0.4678189 -0.8823504 0.0297829 0.0414278 +VERTEX_SE3:QUAT 3874 15.891357 36.544814 -13.674021 0.3553363 0.3793055 0.3865414 0.7618722 +VERTEX_SE3:QUAT 3875 16.421911 37.323651 -13.620243 0.2057949 0.6332799 -0.0471664 0.7445672 +VERTEX_SE3:QUAT 3876 17.014720 38.125369 -13.508229 0.8615447 -0.1184410 0.4932137 0.0212781 +VERTEX_SE3:QUAT 3877 17.467013 39.166937 -13.656978 0.6553970 0.5478948 -0.3344255 0.3980272 +VERTEX_SE3:QUAT 3878 17.844289 40.280220 -13.348153 0.4140070 0.6926194 0.5644131 0.1741102 +VERTEX_SE3:QUAT 3879 18.182134 41.317186 -13.219142 0.2280014 0.6675291 -0.6321456 0.3206434 +VERTEX_SE3:QUAT 3880 17.677355 41.615035 -13.957626 -0.0328731 0.5200605 0.1452352 0.8410488 +VERTEX_SE3:QUAT 3881 17.187084 40.576912 -14.134805 -0.6222729 -0.4205814 -0.6602055 0.0040417 +VERTEX_SE3:QUAT 3882 16.741444 39.680735 -14.223328 -0.5063540 0.4556536 -0.5590726 0.4726767 +VERTEX_SE3:QUAT 3883 16.504082 38.718602 -14.289842 0.3553631 -0.5606865 0.6223060 0.4148289 +VERTEX_SE3:QUAT 3884 16.136017 37.825706 -14.512714 0.3512271 -0.5300677 0.5605967 0.5304706 +VERTEX_SE3:QUAT 3885 15.876804 36.875999 -14.622879 0.8754894 -0.0267869 0.1074140 0.4703860 +VERTEX_SE3:QUAT 3886 15.265921 36.202612 -14.950416 -0.1718149 0.7704967 0.0092587 0.6137823 +VERTEX_SE3:QUAT 3887 14.680913 35.252343 -15.347083 0.0141623 0.7581820 0.6303612 0.1661450 +VERTEX_SE3:QUAT 3888 14.326034 34.496656 -15.601624 0.4593901 0.2956017 0.3351478 0.7676303 +VERTEX_SE3:QUAT 3889 14.085999 33.513698 -15.898927 -0.6854886 0.6060839 -0.1603454 0.3702122 +VERTEX_SE3:QUAT 3890 13.464130 32.734660 -16.161238 -0.3060122 0.5159168 -0.3488100 0.7200819 +VERTEX_SE3:QUAT 3891 13.178123 31.925769 -16.348141 0.3462111 -0.8687308 0.3362624 0.1112306 +VERTEX_SE3:QUAT 3892 12.739591 31.080092 -16.681878 0.7032037 -0.6660328 -0.1311908 0.2114092 +VERTEX_SE3:QUAT 3893 12.324758 30.303429 -17.122120 0.8373755 0.5132002 -0.1851438 0.0339063 +VERTEX_SE3:QUAT 3894 11.780319 29.407301 -17.250534 0.5473846 -0.3615028 0.7475211 0.1043935 +VERTEX_SE3:QUAT 3895 11.557670 28.493263 -17.653358 -0.2363653 0.9545126 -0.1042348 0.1489035 +VERTEX_SE3:QUAT 3896 11.179787 27.721947 -17.773615 0.6061037 0.4346776 0.3722427 0.5523850 +VERTEX_SE3:QUAT 3897 10.725665 26.840513 -17.962370 0.6543908 0.6623359 0.1988638 0.3058381 +VERTEX_SE3:QUAT 3898 10.699863 25.732079 -17.942869 0.8088393 0.5160650 -0.1155447 0.2571094 +VERTEX_SE3:QUAT 3899 10.367143 24.749111 -18.382798 -0.7910369 0.4172780 -0.4232801 0.1448228 +VERTEX_SE3:QUAT 3900 10.083246 25.091367 -19.129123 0.2196286 0.1964068 0.8752108 0.3836584 +VERTEX_SE3:QUAT 3901 10.084746 26.048434 -18.680370 0.2102313 0.5691729 0.5481644 0.5756395 +VERTEX_SE3:QUAT 3902 10.318810 27.013340 -18.429047 -0.6286029 0.5773927 0.2133877 0.4753333 +VERTEX_SE3:QUAT 3903 10.412911 28.050841 -18.119598 -0.8109841 0.3674370 0.2523884 0.3789393 +VERTEX_SE3:QUAT 3904 10.385180 28.842851 -17.756581 0.6914635 0.4652477 -0.1576770 0.5296799 +VERTEX_SE3:QUAT 3905 10.555808 29.907786 -17.374965 -0.6785395 0.4250796 0.2439713 0.5471467 +VERTEX_SE3:QUAT 3906 10.465704 30.965175 -16.901878 0.5356816 0.6256837 -0.1168158 0.5549047 +VERTEX_SE3:QUAT 3907 10.463382 31.871618 -16.730694 -0.7725468 0.1298224 -0.2014346 0.5879981 +VERTEX_SE3:QUAT 3908 10.535848 32.963754 -16.549772 0.5026016 -0.2843417 0.8123065 0.0818509 +VERTEX_SE3:QUAT 3909 10.701927 33.939530 -16.698466 -0.5165820 0.6510505 -0.0918462 0.5484894 +VERTEX_SE3:QUAT 3910 10.868329 34.750278 -16.650160 0.5847106 0.1204686 0.5343527 0.5983879 +VERTEX_SE3:QUAT 3911 11.015660 35.709425 -16.519775 0.3633161 0.7331025 -0.5524013 0.1594208 +VERTEX_SE3:QUAT 3912 11.095634 36.811127 -16.322306 0.3463152 0.0535392 0.1878373 0.9175601 +VERTEX_SE3:QUAT 3913 11.470544 37.780705 -16.234179 -0.4624522 0.7382449 -0.1391999 0.4709095 +VERTEX_SE3:QUAT 3914 11.845777 38.652689 -16.421106 -0.7410338 0.0012808 -0.1431653 0.6560267 +VERTEX_SE3:QUAT 3915 11.998171 39.591327 -16.289696 -0.3605184 -0.0708545 -0.8772217 0.3090117 +VERTEX_SE3:QUAT 3916 12.195478 40.547751 -16.279130 0.7869417 -0.3926957 0.4325580 0.1985105 +VERTEX_SE3:QUAT 3917 12.426303 41.430013 -16.219560 0.6018680 0.2627521 0.0680037 0.7510604 +VERTEX_SE3:QUAT 3918 12.915821 42.367318 -16.280679 -0.8614676 -0.1732444 -0.2147012 0.4263372 +VERTEX_SE3:QUAT 3919 13.087529 43.229293 -16.229748 0.8272711 0.4126165 0.2337491 0.3012168 +VERTEX_SE3:QUAT 3920 12.812122 43.282615 -17.120806 0.8489842 0.3428089 0.1269710 0.3815576 +VERTEX_SE3:QUAT 3921 12.715738 42.336290 -17.075626 0.7150459 0.3398379 0.1716709 0.5863008 +VERTEX_SE3:QUAT 3922 12.639916 41.324910 -16.940508 0.5311677 0.4874044 0.6776214 0.1453513 +VERTEX_SE3:QUAT 3923 12.394311 40.407600 -16.875512 -0.9223259 0.1596847 -0.2627180 0.2340832 +VERTEX_SE3:QUAT 3924 12.203977 39.472332 -16.914379 0.8236650 -0.0914435 0.4695492 0.3045284 +VERTEX_SE3:QUAT 3925 12.176389 38.731292 -16.689823 0.5708244 0.7628118 -0.2094415 0.2200271 +VERTEX_SE3:QUAT 3926 12.038071 37.701902 -16.478295 0.9253565 0.0152113 0.3302821 0.1854662 +VERTEX_SE3:QUAT 3927 11.806111 36.750512 -16.473460 0.4118416 0.3177722 0.7043838 0.4829605 +VERTEX_SE3:QUAT 3928 11.852958 35.606418 -16.374413 0.9268049 -0.1109561 0.2617442 0.2453802 +VERTEX_SE3:QUAT 3929 11.608336 34.737245 -16.226157 0.8315724 -0.4438776 0.3042511 0.1374458 +VERTEX_SE3:QUAT 3930 11.288773 33.940179 -16.231188 0.8067789 -0.3408627 0.3451460 0.3373348 +VERTEX_SE3:QUAT 3931 10.954373 33.095227 -16.019040 0.9214414 0.3069621 0.2197199 0.0918867 +VERTEX_SE3:QUAT 3932 10.514484 32.124768 -15.775123 -0.7990329 0.5908798 -0.0164614 0.1101661 +VERTEX_SE3:QUAT 3933 10.138436 31.282239 -15.437072 0.4950611 0.6576885 0.5213335 0.2248813 +VERTEX_SE3:QUAT 3934 9.800455 30.257022 -15.648171 -0.2168688 0.6192867 0.1872358 0.7310230 +VERTEX_SE3:QUAT 3935 9.377453 29.235057 -15.775282 0.8400575 0.3057331 0.3332450 0.2996304 +VERTEX_SE3:QUAT 3936 8.940368 28.473242 -15.747770 -0.3768938 0.7984415 -0.3229578 0.3407938 +VERTEX_SE3:QUAT 3937 8.447620 27.748319 -15.628653 -0.1107202 0.9049101 0.3240494 0.2527268 +VERTEX_SE3:QUAT 3938 8.067934 26.838519 -15.611621 0.4320415 -0.1025011 0.1745815 0.8788373 +VERTEX_SE3:QUAT 3939 7.702978 26.015539 -15.493634 0.7612895 0.2253901 -0.1241263 0.5951724 +VERTEX_SE3:QUAT 3940 7.342677 26.133968 -16.340677 -0.1671204 0.5026695 0.0826673 0.8441329 +VERTEX_SE3:QUAT 3941 7.977677 27.072494 -16.295466 0.2253073 -0.6071084 0.6599058 0.3810253 +VERTEX_SE3:QUAT 3942 8.745444 27.840333 -16.099126 0.0854532 -0.8049791 0.5860833 0.0348244 +VERTEX_SE3:QUAT 3943 9.314956 28.611445 -15.893930 0.4897258 0.7471754 -0.2565994 0.3688553 +VERTEX_SE3:QUAT 3944 10.020243 29.324958 -15.787468 0.0568135 0.9907291 -0.0285302 0.1200586 +VERTEX_SE3:QUAT 3945 10.714429 30.082629 -15.869264 0.1878430 0.2641361 0.3590681 0.8752241 +VERTEX_SE3:QUAT 3946 11.200944 30.890217 -15.572297 0.5850227 0.5927169 0.2437466 0.4970138 +VERTEX_SE3:QUAT 3947 11.669013 31.538768 -15.470991 -0.2081652 0.5078725 -0.7428522 0.3832799 +VERTEX_SE3:QUAT 3948 12.411952 32.244173 -15.144142 0.8823018 0.2318231 -0.3583396 0.1984803 +VERTEX_SE3:QUAT 3949 12.999129 33.025619 -14.950574 0.6058371 -0.0031504 0.7454807 0.2778669 +VERTEX_SE3:QUAT 3950 13.610371 33.662178 -14.695661 -0.6017741 0.1703374 -0.3693760 0.6873241 +VERTEX_SE3:QUAT 3951 14.105626 34.485415 -14.668447 0.1288420 0.9810211 -0.0025140 0.1448831 +VERTEX_SE3:QUAT 3952 14.630369 35.136740 -14.548431 0.8507965 -0.1751712 0.1268804 0.4789172 +VERTEX_SE3:QUAT 3953 15.318166 35.903885 -14.252889 -0.0618660 0.8018314 -0.5930340 0.0393661 +VERTEX_SE3:QUAT 3954 15.958603 36.618375 -14.082049 0.5129554 0.2655537 0.8163060 0.0015666 +VERTEX_SE3:QUAT 3955 16.519727 37.367323 -13.904967 0.3516837 0.3678997 0.1799119 0.8417839 +VERTEX_SE3:QUAT 3956 17.030025 38.245530 -13.540738 -0.5382301 0.3224637 -0.7360744 0.2540078 +VERTEX_SE3:QUAT 3957 17.556992 38.941991 -13.621665 0.0366776 0.6813429 0.4014344 0.6109641 +VERTEX_SE3:QUAT 3958 18.066177 39.860496 -13.429632 -0.6371660 0.5196876 -0.1361979 0.5526250 +VERTEX_SE3:QUAT 3959 18.594740 40.641864 -13.113792 0.5404072 0.6791083 -0.4954898 0.0355230 +VERTEX_SE3:QUAT 3960 18.240223 40.978840 -14.024207 0.5465479 -0.1529030 0.2599898 0.7812243 +VERTEX_SE3:QUAT 3961 17.614495 40.339886 -14.192055 0.6531554 -0.3661836 -0.0378230 0.6617152 +VERTEX_SE3:QUAT 3962 16.982963 39.474156 -14.378651 0.3550956 -0.8098940 0.3844938 0.2648458 +VERTEX_SE3:QUAT 3963 16.342983 38.651412 -14.547300 0.5444247 -0.3431797 0.6966961 0.3169288 +VERTEX_SE3:QUAT 3964 15.676454 37.923681 -14.688798 0.7200161 0.1656549 0.2409496 0.6293478 +VERTEX_SE3:QUAT 3965 15.059545 37.148880 -15.005440 -0.6724329 0.6267819 -0.3570643 0.1657818 +VERTEX_SE3:QUAT 3966 14.366578 36.336674 -15.283082 0.8220676 -0.5457501 0.1377447 0.0859543 +VERTEX_SE3:QUAT 3967 13.862979 35.724412 -15.581736 -0.8716697 0.1914754 -0.1518195 0.4248293 +VERTEX_SE3:QUAT 3968 13.227878 34.935521 -15.703156 -0.7266559 0.1565550 -0.5377913 0.3977967 +VERTEX_SE3:QUAT 3969 12.937433 34.097106 -15.936150 -0.3324300 0.5172730 -0.6309315 0.4731219 +VERTEX_SE3:QUAT 3970 12.391654 33.374809 -16.169908 -0.1776478 0.5238345 -0.3324845 0.7638670 +VERTEX_SE3:QUAT 3971 11.965211 32.365884 -16.492142 -0.6515815 0.6705014 0.2620000 0.2392183 +VERTEX_SE3:QUAT 3972 11.530623 31.489354 -16.889815 -0.5123507 -0.8564624 -0.0199094 0.0597715 +VERTEX_SE3:QUAT 3973 11.112954 30.778995 -17.328880 -0.4717941 0.3273229 -0.8090822 0.1251241 +VERTEX_SE3:QUAT 3974 10.705314 30.113630 -17.833376 0.7999354 -0.5196609 -0.2886450 0.0820978 +VERTEX_SE3:QUAT 3975 10.312679 29.451544 -18.206759 -0.1434232 0.7525999 -0.2843407 0.5763449 +VERTEX_SE3:QUAT 3976 10.174246 28.579149 -18.534370 -0.9577723 -0.2683421 -0.0879422 0.0541382 +VERTEX_SE3:QUAT 3977 9.701119 27.658491 -18.853921 0.9043115 0.2263200 0.3301589 0.1483072 +VERTEX_SE3:QUAT 3978 9.251723 26.942957 -19.053794 -0.5297475 0.3240343 -0.4152408 0.6647890 +VERTEX_SE3:QUAT 3979 8.592778 26.102044 -19.385694 -0.3394894 0.9152913 -0.2146882 0.0299625 +VERTEX_SE3:QUAT 3980 8.010572 26.710570 -20.056961 0.2283599 0.8899206 0.1051105 0.3805850 +VERTEX_SE3:QUAT 3981 8.386154 27.402970 -19.529672 0.6041510 -0.1348968 0.6697780 0.4101241 +VERTEX_SE3:QUAT 3982 8.891300 28.190660 -19.313444 -0.5322793 -0.8397319 -0.1008269 0.0369191 +VERTEX_SE3:QUAT 3983 9.326346 28.943543 -19.070291 0.1504174 0.6832246 -0.6912223 0.1810814 +VERTEX_SE3:QUAT 3984 9.747029 29.646951 -18.808483 0.2823626 0.8301469 -0.2248684 0.4249254 +VERTEX_SE3:QUAT 3985 10.181453 30.510507 -18.498233 0.8196199 -0.5202579 0.1178646 0.2089568 +VERTEX_SE3:QUAT 3986 10.509411 31.215655 -18.199999 0.9084844 -0.0070764 0.1946030 0.3697779 +VERTEX_SE3:QUAT 3987 11.001361 32.046594 -17.825256 0.2482171 0.9007714 0.3509294 0.0620306 +VERTEX_SE3:QUAT 3988 11.589227 32.934823 -17.352147 -0.6509689 -0.0804851 -0.6597171 0.3667901 +VERTEX_SE3:QUAT 3989 12.034240 33.810058 -17.195429 0.1016384 0.6930120 -0.1557351 0.6965275 +VERTEX_SE3:QUAT 3990 12.561034 34.605915 -16.902762 -0.6198537 0.6320129 0.1953341 0.4221205 +VERTEX_SE3:QUAT 3991 12.953541 35.532984 -16.629177 0.5018575 0.4657975 -0.3326454 0.6484742 +VERTEX_SE3:QUAT 3992 13.663206 36.249828 -16.139063 0.2734660 0.7016283 -0.5914964 0.2882119 +VERTEX_SE3:QUAT 3993 13.938321 37.021332 -15.979421 -0.0593694 0.9699544 -0.1870054 0.1438498 +VERTEX_SE3:QUAT 3994 14.435964 37.763057 -15.630020 -0.0327406 0.7880848 -0.0767680 0.6098829 +VERTEX_SE3:QUAT 3995 15.071205 38.680888 -15.269350 0.7360495 -0.6393347 -0.1792813 0.1316830 +VERTEX_SE3:QUAT 3996 15.772145 39.760160 -15.138869 0.3676419 -0.6316844 0.5347030 0.4241543 +VERTEX_SE3:QUAT 3997 16.367477 40.575304 -15.088374 -0.5509574 -0.1074436 -0.8022279 0.2033030 +VERTEX_SE3:QUAT 3998 17.116426 41.436489 -14.935181 0.0529999 0.8751635 0.1092928 0.4683322 +VERTEX_SE3:QUAT 3999 17.801108 42.189938 -14.937827 0.1233729 -0.9222488 0.1222539 0.3453841 +VERTEX_SE3:QUAT 4000 6.503220 26.877583 -16.015592 0.7681655 0.3645742 0.2478084 0.4643257 +VERTEX_SE3:QUAT 4001 7.099941 27.567556 -15.951206 -0.8411355 0.3250598 -0.3037763 0.3074853 +VERTEX_SE3:QUAT 4002 7.893448 28.452699 -16.039366 -0.5628426 0.2068884 -0.7577274 0.2573999 +VERTEX_SE3:QUAT 4003 8.688145 29.203945 -16.050572 -0.0147161 -0.9742619 0.1208665 0.1897062 +VERTEX_SE3:QUAT 4004 9.304668 30.003928 -16.038802 0.3980032 0.6573171 -0.4531801 0.4518356 +VERTEX_SE3:QUAT 4005 10.111793 30.798174 -15.999354 0.7587860 -0.2201077 0.2582565 0.5559676 +VERTEX_SE3:QUAT 4006 10.530162 31.700586 -16.018126 0.1474643 0.7301822 0.4476447 0.4946741 +VERTEX_SE3:QUAT 4007 11.117983 32.240765 -16.029054 -0.7254126 0.1934945 -0.3760524 0.5430664 +VERTEX_SE3:QUAT 4008 11.669343 32.926274 -15.964819 0.0566440 0.4565168 -0.8780931 0.1316679 +VERTEX_SE3:QUAT 4009 12.342309 33.662193 -16.277534 0.7989963 0.0516142 0.2658295 0.5369130 +VERTEX_SE3:QUAT 4010 12.984053 34.515334 -16.342826 -0.0395096 0.5903352 -0.3049161 0.7463039 +VERTEX_SE3:QUAT 4011 13.720793 35.232362 -16.682797 -0.4652299 0.7620250 -0.1483644 0.4252846 +VERTEX_SE3:QUAT 4012 14.504034 35.759759 -16.597461 0.2024056 0.5525523 -0.7451885 0.3137070 +VERTEX_SE3:QUAT 4013 15.242620 36.520881 -16.888371 0.6208322 -0.2023679 0.0100340 0.7573070 +VERTEX_SE3:QUAT 4014 16.075182 37.194841 -17.109062 0.1816724 0.5499777 0.1105912 0.8076442 +VERTEX_SE3:QUAT 4015 16.691174 37.678286 -17.398672 0.3512988 0.2231741 0.0222847 0.9090027 +VERTEX_SE3:QUAT 4016 17.305515 38.320264 -17.359726 -0.5965220 0.5063141 -0.4529803 0.4273364 +VERTEX_SE3:QUAT 4017 18.101990 38.959333 -17.482790 -0.6923312 0.6106074 0.0907365 0.3736349 +VERTEX_SE3:QUAT 4018 18.678519 39.786368 -17.491503 0.3207627 0.2039559 -0.0086881 0.9248988 +VERTEX_SE3:QUAT 4019 19.259154 40.691825 -17.642142 -0.1240416 0.7124107 0.2992431 0.6225257 +VERTEX_SE3:QUAT 4020 19.595845 40.424417 -16.894307 0.3325479 0.0193682 0.9349212 0.1223074 +VERTEX_SE3:QUAT 4021 18.933998 39.597919 -16.759960 0.3457246 0.6897164 -0.0151993 0.6360304 +VERTEX_SE3:QUAT 4022 18.202879 38.804184 -16.650384 0.1849110 0.7135951 -0.3381210 0.5850335 +VERTEX_SE3:QUAT 4023 17.592749 38.216535 -16.487302 0.8291500 -0.3510653 0.0603769 0.4308342 +VERTEX_SE3:QUAT 4024 17.090658 37.346292 -16.156031 -0.8059094 0.3038973 -0.3903483 0.3252456 +VERTEX_SE3:QUAT 4025 16.325096 36.579298 -15.844373 0.8071181 0.1637123 0.4247841 0.3759217 +VERTEX_SE3:QUAT 4026 15.791139 35.796513 -15.797832 0.0991347 0.2570919 -0.7973539 0.5369383 +VERTEX_SE3:QUAT 4027 14.953872 35.058820 -15.612169 0.3642893 0.6763336 0.2477060 0.5903456 +VERTEX_SE3:QUAT 4028 14.321144 34.386685 -15.506972 -0.2675417 0.9363734 -0.0021748 0.2272036 +VERTEX_SE3:QUAT 4029 13.571400 33.905794 -15.143154 0.5371827 -0.7082781 0.0177397 0.4576705 +VERTEX_SE3:QUAT 4030 12.704713 33.368861 -15.069021 0.3605073 0.0472254 -0.0183985 0.9313784 +VERTEX_SE3:QUAT 4031 12.095612 32.765114 -14.959345 0.2928932 0.5338484 -0.3090006 0.7305738 +VERTEX_SE3:QUAT 4032 11.314396 32.015706 -14.837665 0.3299529 0.3274608 0.6429606 0.6086889 +VERTEX_SE3:QUAT 4033 10.434782 31.341328 -14.393784 0.4369974 0.4226842 -0.6904792 0.3919310 +VERTEX_SE3:QUAT 4034 9.745032 30.767832 -14.184072 0.0733863 -0.5874626 0.6005484 0.5374419 +VERTEX_SE3:QUAT 4035 8.877239 30.142890 -13.885616 0.2445537 0.7107547 -0.1035195 0.6513870 +VERTEX_SE3:QUAT 4036 7.918888 29.516517 -13.541871 -0.5257729 0.0432243 -0.8165509 0.2343908 +VERTEX_SE3:QUAT 4037 7.029006 29.229853 -13.345307 0.5189837 -0.7903007 -0.0205362 0.3250523 +VERTEX_SE3:QUAT 4038 6.228061 28.772830 -13.132032 0.7113508 -0.3713118 0.5156058 0.3004300 +VERTEX_SE3:QUAT 4039 5.499744 28.229622 -13.080638 0.4387978 -0.6824421 0.3179262 0.4905631 +VERTEX_SE3:QUAT 4040 5.677059 28.012214 -12.075490 0.2733585 0.8569956 -0.4324691 0.0616781 +VERTEX_SE3:QUAT 4041 6.016084 28.739958 -12.095468 0.6925852 0.5890675 0.2998668 0.2887995 +VERTEX_SE3:QUAT 4042 6.613391 29.445863 -12.146486 0.1932876 0.1231304 0.5048193 0.8322477 +VERTEX_SE3:QUAT 4043 7.373058 29.974601 -12.083841 -0.0472704 -0.4107385 0.9103811 0.0162998 +VERTEX_SE3:QUAT 4044 7.998934 30.543643 -12.032240 0.8574215 0.1610650 -0.1049435 0.4773607 +VERTEX_SE3:QUAT 4045 8.727964 31.136455 -12.183082 0.7612007 -0.2763325 -0.1311550 0.5718499 +VERTEX_SE3:QUAT 4046 9.372411 31.954654 -12.210938 0.0520569 0.6868034 0.3862823 0.6134959 +VERTEX_SE3:QUAT 4047 10.250391 32.562726 -12.375008 -0.7335113 0.1737416 -0.5376985 0.3776975 +VERTEX_SE3:QUAT 4048 11.117410 33.238594 -12.396987 -0.5851309 0.1712674 -0.7752098 0.1653452 +VERTEX_SE3:QUAT 4049 11.857184 34.007790 -12.483706 0.0497920 0.8225511 -0.2156707 0.5238478 +VERTEX_SE3:QUAT 4050 12.617255 34.697098 -12.523614 0.2978715 0.1765664 0.3559911 0.8679673 +VERTEX_SE3:QUAT 4051 13.396242 35.507396 -12.654175 -0.4653830 -0.7225149 0.5047851 0.0811350 +VERTEX_SE3:QUAT 4052 14.024398 36.217217 -12.899703 0.5625212 0.5756769 -0.5738061 0.1513692 +VERTEX_SE3:QUAT 4053 14.820730 36.905887 -12.802916 0.2120008 0.4302886 0.6360132 0.6044788 +VERTEX_SE3:QUAT 4054 15.501398 37.603918 -12.891065 0.0722229 0.4232132 -0.8385799 0.3353478 +VERTEX_SE3:QUAT 4055 16.127340 38.520866 -12.872459 -0.7914868 0.5803260 -0.0253936 0.1900673 +VERTEX_SE3:QUAT 4056 16.673626 39.396650 -12.978219 -0.8383239 -0.4451534 -0.2265158 0.2184995 +VERTEX_SE3:QUAT 4057 17.221041 40.297084 -12.970416 0.0279956 0.4562376 0.2939569 0.8394360 +VERTEX_SE3:QUAT 4058 17.636249 41.180540 -12.896985 -0.7092832 0.4780399 -0.4961316 0.1491596 +VERTEX_SE3:QUAT 4059 18.122516 41.847512 -13.023661 0.7029110 -0.6865847 0.1015575 0.1555752 +VERTEX_SE3:QUAT 4060 18.268090 41.928858 -12.158734 0.9524176 0.1130953 -0.0176882 0.2824842 +VERTEX_SE3:QUAT 4061 17.477675 41.093207 -12.092242 -0.6787356 0.5440836 -0.3994501 0.2893625 +VERTEX_SE3:QUAT 4062 16.858165 40.331879 -12.117706 0.6454681 0.0525633 0.7318804 0.2120357 +VERTEX_SE3:QUAT 4063 16.156867 39.700710 -12.205189 0.8655445 0.1332066 -0.3073506 0.3723228 +VERTEX_SE3:QUAT 4064 15.436235 38.945473 -12.254942 0.6041990 -0.7831676 0.1151703 0.0912574 +VERTEX_SE3:QUAT 4065 14.626861 38.317842 -12.287572 0.6273853 0.4236897 -0.5747322 0.3107371 +VERTEX_SE3:QUAT 4066 13.891955 37.748554 -12.490980 0.3159412 0.3231854 -0.5428788 0.7078241 +VERTEX_SE3:QUAT 4067 13.019064 37.280934 -12.637014 0.4002882 0.6445209 -0.5675288 0.3198019 +VERTEX_SE3:QUAT 4068 12.145688 36.670426 -12.733889 0.1346563 0.9663577 0.1671507 0.1417075 +VERTEX_SE3:QUAT 4069 11.311866 36.284145 -12.965755 0.4412348 0.6475022 -0.5350791 0.3158213 +VERTEX_SE3:QUAT 4070 10.448723 35.685430 -13.082430 0.0188301 0.5102805 -0.7086729 0.4868695 +VERTEX_SE3:QUAT 4071 9.758286 35.235753 -13.431302 0.5284777 -0.5124388 0.6176769 0.2767546 +VERTEX_SE3:QUAT 4072 9.043407 34.665744 -13.801420 0.3469655 0.8530509 -0.0511679 0.3863949 +VERTEX_SE3:QUAT 4073 8.306096 34.055451 -13.997225 0.2601466 -0.4303218 0.6239391 0.5982031 +VERTEX_SE3:QUAT 4074 7.401808 33.531910 -14.169872 0.9713905 -0.2056877 0.0854236 0.0824367 +VERTEX_SE3:QUAT 4075 6.398046 33.005934 -14.440307 0.2322748 0.8175365 0.4600975 0.2568906 +VERTEX_SE3:QUAT 4076 5.495554 32.344693 -14.470837 0.5165676 0.3262733 -0.1035895 0.7848394 +VERTEX_SE3:QUAT 4077 4.879293 31.972145 -14.626614 0.1015864 0.4967552 0.2980559 0.8087504 +VERTEX_SE3:QUAT 4078 4.054928 31.329050 -14.675204 0.2892717 -0.8675082 0.4037235 0.0275438 +VERTEX_SE3:QUAT 4079 3.346000 30.783185 -14.767023 0.7509657 -0.5895946 -0.1203516 0.2719271 +VERTEX_SE3:QUAT 4080 3.500013 30.490902 -13.838982 -0.1146494 0.9270587 0.2852090 0.2146472 +VERTEX_SE3:QUAT 4081 4.570644 30.977834 -13.817194 -0.3206410 -0.8485241 0.4190571 0.0398412 +VERTEX_SE3:QUAT 4082 5.389705 31.599552 -13.536665 -0.1773569 -0.5045741 0.8406854 0.0848382 +VERTEX_SE3:QUAT 4083 6.123048 32.161381 -13.401418 0.6710656 0.7328155 -0.0111169 0.1119323 +VERTEX_SE3:QUAT 4084 6.983412 32.770518 -13.170585 0.1034176 0.6983282 -0.6997506 0.1095060 +VERTEX_SE3:QUAT 4085 7.812841 33.263462 -13.170165 0.7274163 -0.2840753 0.6106416 0.1314671 +VERTEX_SE3:QUAT 4086 8.594200 34.017117 -13.041740 -0.4585891 0.6720301 0.1541405 0.5606356 +VERTEX_SE3:QUAT 4087 9.114290 34.731567 -13.072315 -0.1081680 0.4471887 -0.8811307 0.1092275 +VERTEX_SE3:QUAT 4088 9.824494 35.540793 -13.019231 0.3213087 -0.3541673 0.7223020 0.4996060 +VERTEX_SE3:QUAT 4089 10.675867 36.270503 -12.759053 0.9353853 0.2136413 0.1176579 0.2560633 +VERTEX_SE3:QUAT 4090 11.457884 36.689143 -12.732371 -0.3654554 0.7208247 -0.1412556 0.5717525 +VERTEX_SE3:QUAT 4091 12.162541 37.286155 -12.715024 0.3664303 0.5403783 0.0973976 0.7511550 +VERTEX_SE3:QUAT 4092 13.130549 38.033422 -12.716612 0.4092895 0.6112111 0.3514372 0.5791329 +VERTEX_SE3:QUAT 4093 13.909392 38.472127 -12.740945 0.6934868 0.2865834 -0.3123281 0.5825780 +VERTEX_SE3:QUAT 4094 14.818923 39.016694 -12.814664 -0.9852810 -0.1638553 -0.0270909 0.0404839 +VERTEX_SE3:QUAT 4095 15.642007 39.533898 -12.998736 0.3466177 -0.9307494 0.0360328 0.1107399 +VERTEX_SE3:QUAT 4096 16.430507 40.227232 -13.278515 -0.2296675 0.9267182 -0.2406629 0.1747212 +VERTEX_SE3:QUAT 4097 17.331837 40.775132 -13.370899 0.6221163 0.4970799 0.5831199 0.1607921 +VERTEX_SE3:QUAT 4098 18.047344 41.274136 -13.461982 0.7147925 -0.0651256 -0.1561641 0.6785596 +VERTEX_SE3:QUAT 4099 18.737538 41.720763 -13.627345 -0.3170689 0.7181266 0.0142240 0.6193216 +VERTEX_SE3:QUAT 4100 18.810735 41.344060 -12.579216 0.3024212 0.3317084 -0.2970150 0.8427889 +VERTEX_SE3:QUAT 4101 17.936759 41.103103 -12.521070 0.7110067 0.5415093 -0.1838039 0.4092107 +VERTEX_SE3:QUAT 4102 17.053193 40.560908 -12.347984 -0.5074094 0.6158781 -0.5075437 0.3250064 +VERTEX_SE3:QUAT 4103 16.043824 39.934647 -12.409628 0.6997967 0.0457880 -0.0585575 0.7104640 +VERTEX_SE3:QUAT 4104 15.256919 39.499288 -12.426717 0.6591195 -0.5549912 -0.0538299 0.5046272 +VERTEX_SE3:QUAT 4105 14.431520 38.844723 -12.557864 -0.0532041 -0.9944049 0.0378555 0.0830372 +VERTEX_SE3:QUAT 4106 13.439577 38.350727 -12.593063 0.4565773 0.4754045 0.0427772 0.7507982 +VERTEX_SE3:QUAT 4107 12.671519 37.728570 -12.313609 -0.2177875 0.7719317 -0.4508333 0.3917134 +VERTEX_SE3:QUAT 4108 11.754509 37.245716 -12.320339 0.6541109 0.4929666 -0.2075374 0.5348374 +VERTEX_SE3:QUAT 4109 10.995301 36.573472 -12.234791 -0.8495013 -0.1149251 -0.4820590 0.1809943 +VERTEX_SE3:QUAT 4110 10.385963 35.998809 -12.403546 0.6391498 0.6413638 0.0925049 0.4142256 +VERTEX_SE3:QUAT 4111 9.554830 35.399268 -12.466719 -0.5330798 0.3163485 -0.7673925 0.1638850 +VERTEX_SE3:QUAT 4112 8.818904 34.896996 -12.414868 0.1415231 0.5968233 -0.4630298 0.6398254 +VERTEX_SE3:QUAT 4113 7.969228 34.222966 -12.243743 -0.7185778 0.5074691 -0.3402916 0.3321487 +VERTEX_SE3:QUAT 4114 7.005857 33.729665 -11.965161 -0.0281459 -0.3404660 0.9229741 0.1772270 +VERTEX_SE3:QUAT 4115 6.435651 33.147735 -11.831452 -0.3367822 0.0768678 -0.7889523 0.5081568 +VERTEX_SE3:QUAT 4116 5.606745 32.328460 -11.780433 0.6962084 -0.0535330 -0.0830506 0.7110068 +VERTEX_SE3:QUAT 4117 4.860087 31.591803 -11.715159 0.3867186 0.4999027 -0.4231407 0.6492287 +VERTEX_SE3:QUAT 4118 4.199218 31.071798 -11.608359 0.8344136 -0.2664457 0.1780479 0.4483966 +VERTEX_SE3:QUAT 4119 3.434484 30.355185 -11.589526 -0.6427265 0.5939504 -0.4722335 0.1054564 +VERTEX_SE3:QUAT 4120 3.555316 30.148443 -10.570195 0.6990460 0.6836956 -0.2032397 0.0508796 +VERTEX_SE3:QUAT 4121 4.281470 30.729176 -10.390634 -0.7542189 0.1747394 -0.3610237 0.5198863 +VERTEX_SE3:QUAT 4122 5.071175 31.325015 -10.358981 0.0187413 0.7007397 -0.5497380 0.4543134 +VERTEX_SE3:QUAT 4123 5.743563 31.963483 -10.335310 -0.5045200 0.1851056 -0.5694831 0.6220003 +VERTEX_SE3:QUAT 4124 6.640734 32.694043 -10.088871 0.7782842 0.5962402 0.1561463 0.1199575 +VERTEX_SE3:QUAT 4125 7.487681 33.224051 -9.949489 -0.1142657 0.2168529 -0.6804748 0.6905593 +VERTEX_SE3:QUAT 4126 8.293134 33.673514 -9.986499 -0.0868594 0.9886188 -0.1172657 0.0365650 +VERTEX_SE3:QUAT 4127 9.139931 34.144839 -10.020040 0.0126866 0.8448137 0.2289141 0.4834535 +VERTEX_SE3:QUAT 4128 10.034813 34.769076 -9.992432 0.9481058 -0.2529386 0.1234254 0.1479312 +VERTEX_SE3:QUAT 4129 10.902405 35.236168 -9.735068 0.8210292 0.3760469 0.0279930 0.4286213 +VERTEX_SE3:QUAT 4130 11.740464 35.802938 -9.717120 0.2878070 -0.8946362 0.1095983 0.3236995 +VERTEX_SE3:QUAT 4131 12.440217 36.498282 -9.771804 0.5331208 0.7918922 -0.2483919 0.1642877 +VERTEX_SE3:QUAT 4132 13.169015 37.164312 -9.693706 0.9610288 0.2464087 0.0345303 0.1204746 +VERTEX_SE3:QUAT 4133 13.854721 37.917656 -9.749050 0.0157130 0.6700046 -0.7119165 0.2098138 +VERTEX_SE3:QUAT 4134 14.642692 38.598209 -9.739257 0.3734598 0.4420592 -0.5469934 0.6049046 +VERTEX_SE3:QUAT 4135 15.358844 39.188562 -9.789073 0.6691144 0.3758299 0.0949245 0.6340561 +VERTEX_SE3:QUAT 4136 15.969785 39.919190 -9.688890 0.3345064 0.8993581 -0.0856445 0.2681893 +VERTEX_SE3:QUAT 4137 16.662327 40.758003 -9.653047 -0.4301979 0.4055116 -0.6268056 0.5075479 +VERTEX_SE3:QUAT 4138 17.222398 41.478225 -9.663782 0.5539806 -0.1691541 0.5260419 0.6227137 +VERTEX_SE3:QUAT 4139 17.928172 42.137558 -9.714868 0.3190460 -0.8283974 0.4095767 0.2102720 +VERTEX_SE3:QUAT 4140 18.178735 42.088309 -8.733737 -0.5575786 -0.6121881 -0.5578783 0.0557106 +VERTEX_SE3:QUAT 4141 17.681443 41.210362 -8.705983 0.5452707 0.1346564 -0.3272402 0.7599088 +VERTEX_SE3:QUAT 4142 16.903045 40.527948 -8.448333 -0.2971926 0.6772576 0.0053313 0.6730306 +VERTEX_SE3:QUAT 4143 16.367205 39.570982 -8.425318 -0.2385196 0.7744593 -0.4226093 0.4058603 +VERTEX_SE3:QUAT 4144 15.973986 38.857850 -8.078964 -0.4711901 0.3356732 -0.4422657 0.6853499 +VERTEX_SE3:QUAT 4145 15.542604 38.262552 -8.062361 0.6727098 0.6371130 -0.2489758 0.2820632 +VERTEX_SE3:QUAT 4146 15.108001 37.331770 -7.730898 -0.0319176 0.6917328 -0.7202644 0.0413067 +VERTEX_SE3:QUAT 4147 14.507459 36.681359 -7.247238 0.3211750 0.9349357 0.0090617 0.1505314 +VERTEX_SE3:QUAT 4148 14.016015 36.026367 -6.823250 0.3547274 0.8586070 -0.0504538 0.3666293 +VERTEX_SE3:QUAT 4149 13.578225 35.298185 -6.575557 -0.0716270 -0.7292537 0.6794261 0.0379321 +VERTEX_SE3:QUAT 4150 13.356689 34.462371 -6.084543 -0.4868466 0.6288424 -0.3295655 0.5088460 +VERTEX_SE3:QUAT 4151 13.035303 33.419789 -5.669172 0.5969748 0.7674368 0.2043483 0.1135940 +VERTEX_SE3:QUAT 4152 12.680311 32.465206 -5.360526 0.1601156 -0.9291902 0.3276573 0.0600776 +VERTEX_SE3:QUAT 4153 12.364532 31.515377 -4.998831 0.8318376 -0.3031437 0.2014055 0.4190298 +VERTEX_SE3:QUAT 4154 12.145129 30.777904 -4.553967 -0.0034512 0.8462728 -0.4396309 0.3008907 +VERTEX_SE3:QUAT 4155 11.652427 30.150765 -4.185103 0.4751973 0.3495335 -0.3716958 0.7168376 +VERTEX_SE3:QUAT 4156 11.349998 29.402342 -3.494217 0.3666071 0.5690288 -0.6906833 0.2544841 +VERTEX_SE3:QUAT 4157 10.585010 28.809789 -2.981635 0.9312498 -0.1444779 0.2312177 0.2417401 +VERTEX_SE3:QUAT 4158 10.085123 28.138840 -2.703672 0.8360932 -0.2986466 0.1792867 0.4238097 +VERTEX_SE3:QUAT 4159 9.632562 27.249239 -2.021430 0.4933884 -0.6090157 0.5660825 0.2553788 +VERTEX_SE3:QUAT 4160 10.041054 27.557380 -1.098492 0.3275125 -0.9003319 0.1582681 0.2389337 +VERTEX_SE3:QUAT 4161 10.496691 28.425472 -1.552547 -0.0253790 0.9818106 -0.1564794 0.1044893 +VERTEX_SE3:QUAT 4162 10.930471 29.168247 -1.853295 -0.4451295 -0.2191920 -0.8369749 0.2308411 +VERTEX_SE3:QUAT 4163 11.386240 29.918166 -2.184502 -0.3583052 0.8381977 -0.3843277 0.1460625 +VERTEX_SE3:QUAT 4164 11.667125 30.808137 -2.379983 0.5193187 0.8102027 -0.1872579 0.1970132 +VERTEX_SE3:QUAT 4165 11.855044 31.818552 -2.711333 -0.9862932 -0.0019335 -0.1167835 0.1165486 +VERTEX_SE3:QUAT 4166 12.363081 32.628560 -2.903242 0.1288187 -0.9078474 0.3623201 0.1671616 +VERTEX_SE3:QUAT 4167 12.697411 33.430606 -3.278311 -0.4476580 0.5522157 0.3100089 0.6313119 +VERTEX_SE3:QUAT 4168 12.854685 34.439738 -3.440419 -0.1859647 0.1038683 -0.9716935 0.1021778 +VERTEX_SE3:QUAT 4169 13.270889 35.544297 -3.677104 -0.4818044 0.6434587 0.3146294 0.5048106 +VERTEX_SE3:QUAT 4170 13.646032 36.393016 -3.806823 0.0382793 0.9038472 -0.2421335 0.3506656 +VERTEX_SE3:QUAT 4171 14.171427 37.353493 -4.191834 -0.5279652 0.3833801 -0.7239485 0.2239890 +VERTEX_SE3:QUAT 4172 14.587422 38.130975 -4.547580 -0.4611595 0.5732113 -0.6143097 0.2852793 +VERTEX_SE3:QUAT 4173 15.087305 39.024767 -4.532006 0.4250061 0.2449795 -0.5169872 0.7014835 +VERTEX_SE3:QUAT 4174 15.561989 39.785288 -4.735081 -0.1830920 0.7880223 0.4459195 0.3829544 +VERTEX_SE3:QUAT 4175 15.974840 40.722646 -4.837445 0.1029341 0.3875304 -0.6299179 0.6651528 +VERTEX_SE3:QUAT 4176 16.181522 41.705570 -5.180345 0.0415741 0.8720648 0.3941157 0.2871365 +VERTEX_SE3:QUAT 4177 16.509584 42.472784 -5.521934 -0.5706218 0.7497469 -0.1948812 0.2725649 +VERTEX_SE3:QUAT 4178 16.962021 43.256918 -6.041690 -0.0018409 0.9524353 -0.3018381 0.0419205 +VERTEX_SE3:QUAT 4179 17.464532 44.035392 -6.377707 0.7404766 0.0999104 -0.0670874 0.6612197 +VERTEX_SE3:QUAT 4180 17.944211 44.246559 -5.571724 -0.0151957 0.8330067 -0.5493424 0.0639675 +VERTEX_SE3:QUAT 4181 17.656323 43.436919 -5.280208 -0.0457076 0.8234902 0.1272629 0.5509800 +VERTEX_SE3:QUAT 4182 17.226113 42.656392 -4.805953 0.1717361 0.5129528 0.2860807 0.7909134 +VERTEX_SE3:QUAT 4183 16.980897 41.835427 -4.311246 0.4370539 0.6069474 -0.1793952 0.6390744 +VERTEX_SE3:QUAT 4184 16.540244 41.052026 -4.141065 -0.8289200 0.5473541 -0.0711826 0.0907092 +VERTEX_SE3:QUAT 4185 16.149475 39.963475 -3.869495 -0.6367368 -0.6006926 -0.4830907 0.0189228 +VERTEX_SE3:QUAT 4186 15.625445 39.048771 -3.887900 0.8629846 -0.4488430 0.1975121 0.1215996 +VERTEX_SE3:QUAT 4187 15.084525 38.280986 -3.564273 -0.6231867 0.5863350 -0.4069041 0.3198104 +VERTEX_SE3:QUAT 4188 14.587133 37.455760 -3.302829 0.8149329 0.2801052 -0.1927107 0.4693485 +VERTEX_SE3:QUAT 4189 14.005523 36.954727 -2.950397 0.4073464 0.4203497 -0.3078197 0.7500814 +VERTEX_SE3:QUAT 4190 13.498777 36.305620 -2.570884 -0.3863512 0.6284337 -0.2072020 0.6425505 +VERTEX_SE3:QUAT 4191 13.083249 35.547997 -2.262952 0.2090352 0.2990454 -0.5008565 0.7848687 +VERTEX_SE3:QUAT 4192 12.596608 34.752105 -1.915119 -0.7370077 -0.3472441 -0.5399484 0.2114164 +VERTEX_SE3:QUAT 4193 12.214681 33.701962 -1.582109 0.8406558 -0.4788408 -0.0303893 0.2511691 +VERTEX_SE3:QUAT 4194 11.780921 32.887824 -1.261380 -0.0165088 0.2551606 0.4203691 0.8705805 +VERTEX_SE3:QUAT 4195 11.479533 31.972503 -0.938938 -0.5213898 0.1981925 -0.8299288 0.0095217 +VERTEX_SE3:QUAT 4196 10.913391 31.184042 -0.515589 -0.0127087 -0.9840342 0.1174825 0.1330906 +VERTEX_SE3:QUAT 4197 10.435432 30.481949 -0.435486 0.2847714 0.8795140 0.0627401 0.3760639 +VERTEX_SE3:QUAT 4198 9.797418 29.683207 -0.082860 -0.9370021 0.1193708 -0.2838006 0.1650300 +VERTEX_SE3:QUAT 4199 9.243825 29.040803 0.493993 -0.2523208 0.3887119 -0.1019692 0.8802497 +VERTEX_SE3:QUAT 4200 9.461614 29.476876 1.243264 0.1114659 0.6551577 -0.1462452 0.7327729 +VERTEX_SE3:QUAT 4201 10.111736 30.092127 0.913343 0.9681886 -0.0205434 -0.0571223 0.2427466 +VERTEX_SE3:QUAT 4202 10.708564 30.519914 0.668349 0.3798589 -0.8407301 0.2651045 0.2803565 +VERTEX_SE3:QUAT 4203 11.335586 31.185412 0.499462 0.3726641 -0.1289086 0.4959216 0.7736704 +VERTEX_SE3:QUAT 4204 11.979048 31.930420 0.099195 0.6181771 0.4807920 -0.5829639 0.2164468 +VERTEX_SE3:QUAT 4205 12.742552 32.541999 -0.354620 -0.3746061 0.7134736 -0.4064313 0.4306268 +VERTEX_SE3:QUAT 4206 13.332780 33.261533 -0.612963 -0.0736722 0.7170592 0.2919086 0.6286397 +VERTEX_SE3:QUAT 4207 13.726551 34.114417 -1.054395 -0.2333747 -0.3322883 -0.9099530 0.0842991 +VERTEX_SE3:QUAT 4208 14.345937 34.877985 -1.484335 0.8246245 0.0119579 0.5623981 0.0596652 +VERTEX_SE3:QUAT 4209 14.743168 35.586688 -1.853490 0.2688620 0.3816547 0.5746183 0.6722103 +VERTEX_SE3:QUAT 4210 15.179077 36.344846 -2.045533 0.5472731 0.1232275 0.8062875 0.1876367 +VERTEX_SE3:QUAT 4211 15.748569 37.177432 -2.285282 0.8221752 0.1838411 -0.2220016 0.4908621 +VERTEX_SE3:QUAT 4212 16.176348 37.995903 -2.555836 0.5174437 -0.7156977 0.3826837 0.2712601 +VERTEX_SE3:QUAT 4213 16.581150 38.916291 -2.586301 0.7764301 0.5853307 -0.1786953 0.1503735 +VERTEX_SE3:QUAT 4214 17.089146 39.835471 -3.008464 0.1239907 -0.7051835 0.6440528 0.2693296 +VERTEX_SE3:QUAT 4215 17.556780 40.642803 -3.334041 0.1473621 -0.3074744 0.7124684 0.6132965 +VERTEX_SE3:QUAT 4216 18.241390 41.369129 -3.734618 0.0085907 0.4489061 -0.8930692 0.0289277 +VERTEX_SE3:QUAT 4217 18.663771 42.068106 -4.176473 0.2178590 0.4998434 -0.5802426 0.6049897 +VERTEX_SE3:QUAT 4218 19.051180 42.863098 -4.436353 0.2094979 0.5893899 -0.7688907 0.1324284 +VERTEX_SE3:QUAT 4219 19.728806 43.861727 -4.738231 0.3710807 0.2837769 -0.0656789 0.8817347 +VERTEX_SE3:QUAT 4220 19.854183 43.925836 -3.878472 0.4347260 0.7928178 0.1442990 0.4020337 +VERTEX_SE3:QUAT 4221 19.278249 43.159901 -3.663688 0.4320736 -0.5854803 0.6732051 0.1316061 +VERTEX_SE3:QUAT 4222 18.875646 42.271943 -3.235889 0.2020103 -0.2063737 0.4787175 0.8291148 +VERTEX_SE3:QUAT 4223 18.404811 41.380654 -2.915898 -0.8061688 0.5118528 -0.1640811 0.2473376 +VERTEX_SE3:QUAT 4224 17.887066 40.741661 -2.477453 0.6930600 -0.1853624 0.5839468 0.3798879 +VERTEX_SE3:QUAT 4225 17.452485 39.957611 -2.107484 0.6004172 0.6215935 0.3655063 0.3457251 +VERTEX_SE3:QUAT 4226 17.062453 39.245832 -1.674424 0.3570040 -0.0523873 0.1940885 0.9122135 +VERTEX_SE3:QUAT 4227 16.676614 38.444496 -1.366727 0.6086677 -0.2870701 0.0267094 0.7391894 +VERTEX_SE3:QUAT 4228 16.094486 37.766592 -1.175075 0.4985229 -0.1453369 0.7495016 0.4106087 +VERTEX_SE3:QUAT 4229 15.553140 36.951581 -0.695440 0.5293908 -0.4461482 0.6757045 0.2532206 +VERTEX_SE3:QUAT 4230 15.107123 36.247550 -0.398410 -0.4026356 0.3888856 -0.3571451 0.7477299 +VERTEX_SE3:QUAT 4231 14.598352 35.467515 -0.293917 -0.1042818 0.9309261 0.1850513 0.2970823 +VERTEX_SE3:QUAT 4232 14.096376 34.723065 0.094572 0.2520331 0.0848901 0.6824807 0.6808032 +VERTEX_SE3:QUAT 4233 13.694969 33.688719 0.380164 0.1435214 -0.4174335 0.8695772 0.2213287 +VERTEX_SE3:QUAT 4234 13.054202 32.931485 0.626062 0.2053065 -0.4920170 0.6396451 0.5537352 +VERTEX_SE3:QUAT 4235 12.548522 32.365177 0.813212 -0.7689291 0.4579040 -0.2849500 0.3433299 +VERTEX_SE3:QUAT 4236 11.972800 31.498323 0.893771 0.0547975 0.8700300 -0.4327969 0.2296343 +VERTEX_SE3:QUAT 4237 11.360399 30.656743 1.033348 0.0811602 0.2048576 -0.7981942 0.5606535 +VERTEX_SE3:QUAT 4238 10.808668 29.951611 1.360211 -0.3451071 0.1994947 -0.9170909 0.0068812 +VERTEX_SE3:QUAT 4239 10.318811 29.214372 1.617397 0.3401125 0.2604991 -0.1623131 0.8888859 +VERTEX_SE3:QUAT 4240 10.636125 29.208981 2.666957 0.2548754 -0.8601661 0.2525919 0.3624227 +VERTEX_SE3:QUAT 4241 11.068433 29.806624 2.708136 0.7920889 0.4155373 0.4471070 0.0043918 +VERTEX_SE3:QUAT 4242 11.718534 30.443869 2.414825 0.2365257 -0.5147357 0.8236624 0.0261352 +VERTEX_SE3:QUAT 4243 12.165471 31.171089 2.409833 0.6489356 -0.5923607 0.2001596 0.4335061 +VERTEX_SE3:QUAT 4244 12.555390 32.137506 2.204729 -0.3563671 0.0960410 -0.9264032 0.0745373 +VERTEX_SE3:QUAT 4245 12.981513 33.041876 2.300689 0.5782640 0.7179858 -0.3361403 0.1926571 +VERTEX_SE3:QUAT 4246 13.348934 33.790622 2.114615 0.3035059 -0.0020191 0.9519462 0.0409712 +VERTEX_SE3:QUAT 4247 13.862836 34.574902 1.929425 -0.2196904 0.4121426 -0.8661093 0.1781271 +VERTEX_SE3:QUAT 4248 14.440395 35.254619 1.719996 -0.8640699 0.4396411 -0.2315158 0.0806188 +VERTEX_SE3:QUAT 4249 15.104059 36.115560 1.563493 -0.0996729 0.2848342 -0.6660387 0.6821490 +VERTEX_SE3:QUAT 4250 15.671284 36.874451 1.549462 0.9758721 0.1858120 0.0999810 0.0561375 +VERTEX_SE3:QUAT 4251 16.302689 37.750317 1.480550 -0.5437534 -0.2617657 -0.7865262 0.1311009 +VERTEX_SE3:QUAT 4252 16.928850 38.635152 1.325498 0.8436988 0.1391858 0.0295180 0.5176179 +VERTEX_SE3:QUAT 4253 17.352302 39.542780 1.364196 0.1838857 -0.9093807 0.3722209 0.0257770 +VERTEX_SE3:QUAT 4254 17.841130 40.405716 1.223110 0.4373610 0.0538453 0.8976197 0.0097366 +VERTEX_SE3:QUAT 4255 18.441888 41.240434 1.178026 -0.2872681 0.5234727 -0.7499717 0.2845975 +VERTEX_SE3:QUAT 4256 18.806040 42.228966 1.281192 -0.1483523 0.5786047 -0.6953938 0.3995443 +VERTEX_SE3:QUAT 4257 19.261475 43.046688 1.136469 0.3946876 0.1742716 -0.5606413 0.7067760 +VERTEX_SE3:QUAT 4258 19.864977 43.700277 1.058665 0.4239475 0.7094887 0.4843368 0.2869012 +VERTEX_SE3:QUAT 4259 20.339128 44.540361 0.835427 -0.9985012 -0.0357620 -0.0196212 0.0364887 +VERTEX_SE3:QUAT 4260 20.622958 44.632181 1.709329 -0.2042877 0.3662831 -0.9020319 0.1021848 +VERTEX_SE3:QUAT 4261 19.906995 43.817041 1.816532 0.6826954 0.3160424 -0.4109306 0.5149565 +VERTEX_SE3:QUAT 4262 19.267145 42.966386 1.971939 -0.0353858 0.5776691 0.3082785 0.7549905 +VERTEX_SE3:QUAT 4263 18.800910 42.083345 2.110487 0.7437925 -0.1215998 0.6535355 0.0698393 +VERTEX_SE3:QUAT 4264 18.129419 41.299289 2.187413 0.1861940 -0.3945430 0.8308229 0.3455444 +VERTEX_SE3:QUAT 4265 17.752693 40.478064 2.343635 0.1199459 0.0289959 0.0432924 0.9914121 +VERTEX_SE3:QUAT 4266 17.407488 39.582396 2.424900 -0.3248371 0.7206464 0.2977420 0.5352564 +VERTEX_SE3:QUAT 4267 16.901904 38.666416 2.506061 -0.5019432 0.6756550 -0.4236234 0.3347933 +VERTEX_SE3:QUAT 4268 16.447250 37.892426 2.389000 0.0125472 0.6071320 0.2528591 0.7531903 +VERTEX_SE3:QUAT 4269 15.919227 37.130192 2.531582 -0.4185485 0.3590593 -0.8232601 0.1346712 +VERTEX_SE3:QUAT 4270 15.319206 36.431090 2.796024 0.2014950 0.6432727 0.2064458 0.7092110 +VERTEX_SE3:QUAT 4271 14.954030 35.424024 2.739438 0.2546814 0.1661364 0.8806137 0.3633946 +VERTEX_SE3:QUAT 4272 14.390498 34.479900 2.687814 0.4509546 0.5484022 0.1885305 0.6784919 +VERTEX_SE3:QUAT 4273 13.875309 33.643469 2.776762 -0.5946251 -0.4504329 -0.6307916 0.2136193 +VERTEX_SE3:QUAT 4274 13.473629 32.662349 2.719659 0.3360191 0.1574439 0.5384658 0.7565429 +VERTEX_SE3:QUAT 4275 12.918711 31.782238 2.736746 0.4540170 -0.5546556 0.5492072 0.4296476 +VERTEX_SE3:QUAT 4276 12.477361 30.740620 2.748863 -0.0579354 0.1841859 -0.8357908 0.5139774 +VERTEX_SE3:QUAT 4277 11.906643 29.830698 2.544047 -0.3723780 -0.1914590 -0.7606391 0.4960910 +VERTEX_SE3:QUAT 4278 11.392374 28.906905 2.570657 0.1185762 -0.4856437 0.8643190 0.0551587 +VERTEX_SE3:QUAT 4279 10.917152 28.125723 2.555531 -0.5784356 0.3615643 0.0027821 0.7312153 +VERTEX_SE3:QUAT 4280 10.769308 28.108964 3.803326 0.3643171 0.4135350 -0.7318515 0.4008182 +VERTEX_SE3:QUAT 4281 11.329078 29.157489 4.062937 0.6074395 0.4959591 -0.3367289 0.5212059 +VERTEX_SE3:QUAT 4282 11.818379 30.096340 4.159747 0.6056089 0.2990904 0.5118917 0.5308010 +VERTEX_SE3:QUAT 4283 12.375722 30.812706 4.161617 -0.7979893 0.2209417 -0.5080112 0.2373234 +VERTEX_SE3:QUAT 4284 12.744286 31.747743 4.117124 0.4043951 0.8626342 0.0715882 0.2952998 +VERTEX_SE3:QUAT 4285 13.114767 32.643484 4.283172 0.6576931 0.7240220 -0.1937032 0.0755718 +VERTEX_SE3:QUAT 4286 13.490505 33.479395 4.291114 0.3226920 0.8321559 -0.2294688 0.3882402 +VERTEX_SE3:QUAT 4287 14.123890 34.440231 4.462392 0.1753978 0.8707781 -0.1464620 0.4353503 +VERTEX_SE3:QUAT 4288 14.620169 35.256990 4.730573 0.8068848 -0.4909190 0.1970326 0.2628946 +VERTEX_SE3:QUAT 4289 15.295052 35.889163 4.813699 0.4431548 0.7457654 0.2797121 0.4113501 +VERTEX_SE3:QUAT 4290 15.951954 36.571444 5.077220 0.9274146 -0.2382844 0.2100268 0.1975131 +VERTEX_SE3:QUAT 4291 16.632896 37.355943 5.282210 -0.0900265 0.3703377 -0.9224008 0.0626259 +VERTEX_SE3:QUAT 4292 17.145124 38.197497 5.295720 0.2513338 0.6937401 0.3502730 0.5769444 +VERTEX_SE3:QUAT 4293 17.726968 39.089422 5.551869 0.3635257 0.3223171 0.6208136 0.6152652 +VERTEX_SE3:QUAT 4294 18.188404 39.972703 5.725226 0.8866084 0.4514890 -0.0557865 0.0834935 +VERTEX_SE3:QUAT 4295 18.818234 40.826725 5.961527 0.1123717 0.2131303 -0.5748838 0.7819570 +VERTEX_SE3:QUAT 4296 19.379276 41.619461 6.258711 -0.8007046 -0.5400403 -0.2592502 0.0042304 +VERTEX_SE3:QUAT 4297 19.756831 42.273680 6.568831 -0.2580411 0.2969504 -0.5689646 0.7221596 +VERTEX_SE3:QUAT 4298 20.317409 42.912842 6.856361 0.1136818 0.6020154 0.4124586 0.6741897 +VERTEX_SE3:QUAT 4299 20.848785 43.617263 7.393499 0.0192345 0.6583607 -0.2530270 0.7086385 +VERTEX_SE3:QUAT 4300 20.484746 43.244439 8.271553 0.3216709 0.0083994 -0.5815408 0.7471730 +VERTEX_SE3:QUAT 4301 19.705026 42.526741 7.953073 0.7035613 -0.5044540 0.5002127 0.0177480 +VERTEX_SE3:QUAT 4302 19.332623 41.872691 7.636285 -0.0758774 0.6724641 0.1650682 0.7174867 +VERTEX_SE3:QUAT 4303 18.767257 41.173565 7.502850 0.2962163 0.5850133 -0.4975815 0.5678274 +VERTEX_SE3:QUAT 4304 18.184796 40.392298 7.411349 -0.1291425 0.8427479 -0.1634834 0.4963580 +VERTEX_SE3:QUAT 4305 17.445240 39.739431 7.031622 -0.2694431 0.2559141 -0.7830561 0.4987300 +VERTEX_SE3:QUAT 4306 16.903930 38.864236 6.779594 0.4742361 0.6817269 0.3715237 0.4151128 +VERTEX_SE3:QUAT 4307 16.195950 38.101449 6.434856 0.3917040 0.2601886 0.7137894 0.5190131 +VERTEX_SE3:QUAT 4308 15.411716 37.427541 6.164524 0.8273747 -0.3145768 0.4191914 0.2019186 +VERTEX_SE3:QUAT 4309 15.008087 36.718296 5.931976 0.7603272 0.3437883 0.2239926 0.5035270 +VERTEX_SE3:QUAT 4310 14.232436 35.895441 5.877640 -0.2900625 0.5939761 -0.5876639 0.4665911 +VERTEX_SE3:QUAT 4311 13.599417 35.330360 5.844689 -0.8272044 0.2396793 -0.5080933 0.0113116 +VERTEX_SE3:QUAT 4312 12.919393 34.696363 5.544280 -0.1495364 0.7160493 -0.1625574 0.6621838 +VERTEX_SE3:QUAT 4313 12.000034 34.359397 5.171877 0.5324455 -0.1950231 0.7318785 0.3779174 +VERTEX_SE3:QUAT 4314 11.086131 33.812846 4.832135 -0.1310958 0.2732348 -0.6350712 0.7105218 +VERTEX_SE3:QUAT 4315 10.269161 33.163385 4.485894 0.0366966 -0.1830549 0.2147362 0.9586619 +VERTEX_SE3:QUAT 4316 9.594930 32.627695 4.212896 0.7844981 0.4787713 0.2957137 0.2605652 +VERTEX_SE3:QUAT 4317 8.835251 31.925276 4.055468 0.0967254 -0.3739411 0.9053029 0.1767455 +VERTEX_SE3:QUAT 4318 8.164389 31.334360 3.623324 -0.2620008 0.5425699 0.0279882 0.7976153 +VERTEX_SE3:QUAT 4319 7.355894 30.694903 3.485564 0.1477968 0.2850406 -0.9014678 0.2902820 +VERTEX_SE3:QUAT 4320 7.039316 30.548941 4.502460 0.6686115 0.0761362 0.0930874 0.7338233 +VERTEX_SE3:QUAT 4321 7.694184 31.217789 5.024650 0.2484660 0.5548294 -0.7902673 0.0768544 +VERTEX_SE3:QUAT 4322 8.573562 31.811928 5.142263 0.4582165 -0.3438247 0.1220714 0.8105065 +VERTEX_SE3:QUAT 4323 9.485448 32.365433 5.495438 0.4098047 -0.5840370 0.2303011 0.6617570 +VERTEX_SE3:QUAT 4324 10.254274 32.941191 5.779522 0.4119583 0.7048056 -0.2450587 0.5229585 +VERTEX_SE3:QUAT 4325 10.990041 33.514096 6.146948 -0.2883016 0.6594559 -0.6847966 0.1142527 +VERTEX_SE3:QUAT 4326 11.900581 33.774559 6.538551 0.1143794 -0.1240204 -0.9578082 0.2326796 +VERTEX_SE3:QUAT 4327 12.643372 34.410134 6.791004 0.1553694 -0.0433099 0.8394780 0.5189039 +VERTEX_SE3:QUAT 4328 13.301326 34.964104 7.059391 0.3104947 -0.8019145 0.1029217 0.4999333 +VERTEX_SE3:QUAT 4329 14.182299 35.506206 7.450961 0.4189995 0.2108113 0.8819157 0.0471462 +VERTEX_SE3:QUAT 4330 14.997533 35.697114 7.729246 0.1974170 -0.0224916 -0.8451599 0.4962111 +VERTEX_SE3:QUAT 4331 15.928907 35.938600 8.026936 0.5680205 -0.0228609 0.1420158 0.8103466 +VERTEX_SE3:QUAT 4332 16.697615 36.151840 8.347018 -0.1138540 -0.9030582 0.3435185 0.2313399 +VERTEX_SE3:QUAT 4333 17.391902 36.525640 8.740913 0.4284929 -0.5446199 0.6304793 0.3496840 +VERTEX_SE3:QUAT 4334 18.357920 36.839644 9.218683 0.6940731 0.0427939 -0.1019383 0.7113647 +VERTEX_SE3:QUAT 4335 19.135948 37.237102 9.655926 0.0487557 -0.4334532 0.7561264 0.4878669 +VERTEX_SE3:QUAT 4336 20.006653 37.568956 9.960395 0.1020858 0.9206179 -0.3743668 0.0434809 +VERTEX_SE3:QUAT 4337 20.842317 38.092542 10.222436 -0.1121542 -0.9382841 0.3039801 0.1209975 +VERTEX_SE3:QUAT 4338 21.653408 38.232447 10.548563 0.6102441 -0.6443966 0.1578205 0.4329526 +VERTEX_SE3:QUAT 4339 22.428333 38.264183 10.883104 0.2704882 0.1298939 0.6216885 0.7235102 +VERTEX_SE3:QUAT 4340 22.251588 38.210597 11.881962 0.5501113 0.1686707 0.7327180 0.3633897 +VERTEX_SE3:QUAT 4341 21.387425 37.598889 11.632992 0.2939540 0.2370885 -0.9173091 0.1261903 +VERTEX_SE3:QUAT 4342 20.699647 37.308909 11.500247 0.3279701 -0.0905029 0.6346855 0.6938437 +VERTEX_SE3:QUAT 4343 19.664878 37.031396 11.385454 0.4062030 0.1950114 0.7445328 0.4925856 +VERTEX_SE3:QUAT 4344 19.024865 36.901475 11.212409 0.7136295 0.3553334 -0.0563655 0.6010773 +VERTEX_SE3:QUAT 4345 18.089218 36.654290 11.139953 0.7903700 0.0767288 0.5204459 0.3139491 +VERTEX_SE3:QUAT 4346 17.192952 36.560394 11.184579 0.8358166 0.2828547 0.4360029 0.1769330 +VERTEX_SE3:QUAT 4347 16.381381 36.330935 11.104650 -0.0179986 0.1675886 -0.9530528 0.2515563 +VERTEX_SE3:QUAT 4348 15.365260 35.909524 10.800048 0.7384385 0.5969340 -0.0089410 0.3135258 +VERTEX_SE3:QUAT 4349 14.300642 35.709881 10.645397 0.5257443 -0.1391813 0.5750192 0.6112074 +VERTEX_SE3:QUAT 4350 13.271318 35.476275 10.814487 -0.1116082 -0.7142462 0.5847363 0.3680753 +VERTEX_SE3:QUAT 4351 12.456961 35.189039 10.775774 -0.0590125 -0.9373951 0.1493685 0.3090260 +VERTEX_SE3:QUAT 4352 11.572030 34.698051 10.710196 0.4922679 0.0864142 -0.8456866 0.1871338 +VERTEX_SE3:QUAT 4353 10.608729 34.364265 10.620802 0.6752952 0.4751043 -0.5605275 0.0637271 +VERTEX_SE3:QUAT 4354 9.653950 34.073783 10.739644 0.0157877 0.4497887 -0.8629877 0.2295497 +VERTEX_SE3:QUAT 4355 8.657764 33.637354 10.863045 -0.0528830 -0.7961791 0.3734311 0.4731295 +VERTEX_SE3:QUAT 4356 7.677019 33.113532 10.885008 0.3396436 -0.3798809 -0.0032705 0.8604197 +VERTEX_SE3:QUAT 4357 6.646790 32.906553 10.882946 0.7386818 0.6076036 -0.2398683 0.1662234 +VERTEX_SE3:QUAT 4358 5.611840 32.426461 10.826163 0.1851493 -0.6983808 0.5033710 0.4739215 +VERTEX_SE3:QUAT 4359 4.733667 31.961801 10.880214 0.2117620 -0.1434487 0.3673651 0.8942160 +VERTEX_SE3:QUAT 4360 4.875389 31.958711 11.912644 0.3188231 0.3217139 0.4871084 0.7467111 +VERTEX_SE3:QUAT 4361 5.843965 32.334382 11.958352 0.4423367 -0.5439480 0.4692869 0.5368693 +VERTEX_SE3:QUAT 4362 6.742490 32.584454 12.073401 0.2170555 0.0089514 0.2744001 0.9367558 +VERTEX_SE3:QUAT 4363 7.810713 32.698901 12.091674 0.7162734 -0.3084414 -0.1805702 0.5993419 +VERTEX_SE3:QUAT 4364 8.690524 32.700073 12.393333 0.3895229 0.8245551 -0.3022010 0.2775885 +VERTEX_SE3:QUAT 4365 9.862569 32.760214 12.430826 0.1918085 0.3078401 0.0910200 0.9274477 +VERTEX_SE3:QUAT 4366 10.847866 32.846883 12.607419 0.4963719 0.0431840 -0.7903663 0.3564705 +VERTEX_SE3:QUAT 4367 11.849542 32.959441 12.609076 0.8016644 0.2936199 0.4140066 0.3157847 +VERTEX_SE3:QUAT 4368 12.775469 32.990994 12.581978 0.7771504 -0.3621057 0.5112815 0.0592282 +VERTEX_SE3:QUAT 4369 13.708978 32.880565 12.705722 0.2369213 0.4510826 -0.5453932 0.6655367 +VERTEX_SE3:QUAT 4370 14.665813 32.800613 12.762913 0.3100334 -0.2398717 0.9144670 0.1004534 +VERTEX_SE3:QUAT 4371 15.408109 32.890859 12.825684 0.3677223 -0.8925609 0.1657086 0.2016336 +VERTEX_SE3:QUAT 4372 16.327026 32.818379 13.046372 -0.2823955 0.7764045 -0.5491535 0.1260129 +VERTEX_SE3:QUAT 4373 17.410785 32.888587 13.143910 0.1476015 0.9497428 -0.2557060 0.1040043 +VERTEX_SE3:QUAT 4374 18.264587 33.044344 13.132189 0.5000757 0.6521114 -0.1469076 0.5505390 +VERTEX_SE3:QUAT 4375 19.259960 33.102499 13.484563 -0.9839147 -0.0102507 -0.1581406 0.0824519 +VERTEX_SE3:QUAT 4376 20.437842 33.177051 13.643679 0.4110393 -0.0344913 0.5060994 0.7574434 +VERTEX_SE3:QUAT 4377 21.648900 33.175150 13.897171 0.6823270 0.5337765 -0.0704405 0.4945207 +VERTEX_SE3:QUAT 4378 22.583099 33.111127 14.446053 -0.4145623 -0.7179265 0.5432541 0.1326444 +VERTEX_SE3:QUAT 4379 23.600167 33.098794 14.757039 0.3884016 0.1119791 -0.8792955 0.2518814 +VERTEX_SE3:QUAT 4380 23.294257 32.925139 15.686271 -0.2031675 0.5841379 -0.6837203 0.3873401 +VERTEX_SE3:QUAT 4381 22.380328 32.838442 15.467284 -0.1827126 0.2007214 -0.9474751 0.1691685 +VERTEX_SE3:QUAT 4382 21.297312 33.220394 15.137286 0.7015042 -0.4792417 -0.1058714 0.5167306 +VERTEX_SE3:QUAT 4383 20.197816 33.400918 14.842608 0.9600302 0.0539377 0.2350648 0.1420470 +VERTEX_SE3:QUAT 4384 19.299228 33.480235 14.638950 -0.1764987 0.7694979 -0.1338731 0.5989985 +VERTEX_SE3:QUAT 4385 18.386680 33.667682 14.449557 -0.4887905 0.8515700 -0.0151005 0.1889031 +VERTEX_SE3:QUAT 4386 17.460062 33.765786 14.114730 0.5327055 -0.1251909 0.7068837 0.4481825 +VERTEX_SE3:QUAT 4387 16.227537 33.757062 13.783426 0.5326852 0.6698116 0.1818599 0.4842786 +VERTEX_SE3:QUAT 4388 15.198459 33.890699 13.462404 0.4219349 -0.8883693 0.0993595 0.1513229 +VERTEX_SE3:QUAT 4389 14.158968 33.970703 13.183519 0.5006396 0.6794325 0.0140635 0.5362217 +VERTEX_SE3:QUAT 4390 13.139836 34.085362 12.872573 0.5930685 0.5586370 0.2591532 0.5186849 +VERTEX_SE3:QUAT 4391 12.240185 33.953833 12.785940 0.0755621 0.4194990 -0.1467849 0.8926171 +VERTEX_SE3:QUAT 4392 11.343574 34.082173 12.718781 0.4325868 0.0392682 -0.8707067 0.2306437 +VERTEX_SE3:QUAT 4393 10.399675 34.126179 12.277232 0.0174289 0.5100978 -0.8579143 0.0589869 +VERTEX_SE3:QUAT 4394 9.307170 34.231235 12.102013 0.4063090 -0.3026980 -0.4438833 0.7390904 +VERTEX_SE3:QUAT 4395 8.267814 34.283682 11.889494 0.4654820 0.6944117 -0.3803068 0.3955827 +VERTEX_SE3:QUAT 4396 7.204260 34.291271 11.616898 0.0471080 -0.6709035 -0.0178858 0.7398307 +VERTEX_SE3:QUAT 4397 6.305851 34.449580 11.268726 0.3421911 0.0840781 0.8062641 0.4751572 +VERTEX_SE3:QUAT 4398 5.312392 34.707638 11.211446 0.5776794 -0.7677094 0.1529864 0.2313092 +VERTEX_SE3:QUAT 4399 4.520813 34.608404 11.052104 0.3572266 -0.8168280 0.1843723 0.4137488 +VERTEX_SE3:QUAT 4400 23.028001 32.880650 15.325834 0.7620713 -0.0731037 0.0910614 0.6368759 +VERTEX_SE3:QUAT 4401 21.984236 32.935988 15.178043 0.8259656 -0.3224864 -0.2175272 0.4080017 +VERTEX_SE3:QUAT 4402 21.107631 33.034813 15.088130 0.5936243 0.1767212 0.4351573 0.6534661 +VERTEX_SE3:QUAT 4403 20.116892 33.183679 14.887024 -0.9741751 -0.1890022 0.0144136 0.1226915 +VERTEX_SE3:QUAT 4404 19.233773 33.030315 14.644202 0.6376506 -0.3546024 0.6173023 0.2942734 +VERTEX_SE3:QUAT 4405 18.284929 33.006295 14.450271 -0.2751283 -0.5013276 0.6978276 0.4312908 +VERTEX_SE3:QUAT 4406 17.325600 33.076486 14.242536 0.4901159 0.6096190 0.4142863 0.4653149 +VERTEX_SE3:QUAT 4407 16.414614 33.202407 13.839768 0.1861904 0.8505863 -0.2732496 0.4088652 +VERTEX_SE3:QUAT 4408 15.426708 33.295946 13.646303 0.6784743 -0.4441135 0.4869379 0.3245416 +VERTEX_SE3:QUAT 4409 14.394278 33.374664 13.436294 0.6766603 -0.1129630 0.4947363 0.5334850 +VERTEX_SE3:QUAT 4410 13.437440 33.679745 13.296596 0.5109247 -0.3953296 -0.2903546 0.7059495 +VERTEX_SE3:QUAT 4411 12.500760 33.826220 13.082535 0.5358248 -0.5309158 -0.1038999 0.6482476 +VERTEX_SE3:QUAT 4412 11.435909 33.870409 12.965577 -0.8954132 0.4382153 -0.0149840 0.0773174 +VERTEX_SE3:QUAT 4413 10.690162 34.097246 12.557676 0.6183875 0.3779988 0.0837251 0.6838888 +VERTEX_SE3:QUAT 4414 9.699193 34.388102 12.362578 0.3901753 0.2960900 -0.8073987 0.3289397 +VERTEX_SE3:QUAT 4415 8.886326 34.673577 12.180880 0.8517129 0.3817364 0.1242135 0.3367988 +VERTEX_SE3:QUAT 4416 7.961519 34.763922 12.155996 -0.2316153 0.7528896 -0.4846097 0.3803486 +VERTEX_SE3:QUAT 4417 6.882890 34.833806 11.952816 -0.6252093 -0.7524095 -0.2063141 0.0206851 +VERTEX_SE3:QUAT 4418 5.761436 34.920880 11.889756 0.5323905 -0.4220084 0.7240358 0.1193371 +VERTEX_SE3:QUAT 4419 4.866722 35.215322 11.866133 -0.9265383 -0.2238744 -0.2901624 0.0849286 +VERTEX_SE3:QUAT 4420 4.888374 35.686951 11.170102 0.3606503 0.2282688 -0.9020110 0.0648146 +VERTEX_SE3:QUAT 4421 5.730792 35.434167 10.958697 0.8969597 0.2711157 -0.2110272 0.2782573 +VERTEX_SE3:QUAT 4422 6.750714 35.360728 10.835963 -0.5559456 -0.4853536 0.6747695 0.0065108 +VERTEX_SE3:QUAT 4423 7.775316 35.300881 10.721227 0.9060269 0.4221733 0.0291489 0.0059338 +VERTEX_SE3:QUAT 4424 8.793524 34.994420 10.808551 -0.2507856 -0.9317189 -0.1179235 0.2347349 +VERTEX_SE3:QUAT 4425 9.655010 34.835529 10.492701 0.1265852 -0.6215626 -0.1487792 0.7586177 +VERTEX_SE3:QUAT 4426 10.686516 34.594618 10.200368 0.5076089 0.0008401 -0.4734475 0.7198472 +VERTEX_SE3:QUAT 4427 11.518369 34.268386 9.824837 0.8908512 0.0872858 0.3402209 0.2881233 +VERTEX_SE3:QUAT 4428 12.337244 34.116790 9.446071 0.7157537 0.0165495 0.1845179 0.6733319 +VERTEX_SE3:QUAT 4429 13.210303 33.868643 8.788403 0.3940195 -0.3360953 -0.1982765 0.8321508 +VERTEX_SE3:QUAT 4430 13.956864 33.755537 8.301778 -0.6288154 -0.7180534 0.1077287 0.2781817 +VERTEX_SE3:QUAT 4431 14.796395 33.758734 7.651049 0.0806650 0.5627103 -0.4464828 0.6910162 +VERTEX_SE3:QUAT 4432 15.707440 33.634374 7.261392 0.4957216 0.4241527 -0.3907412 0.6493658 +VERTEX_SE3:QUAT 4433 16.376142 33.452024 6.745650 0.1468491 -0.8367702 0.3511116 0.3936644 +VERTEX_SE3:QUAT 4434 17.160299 33.378187 6.208348 0.0787813 -0.6375013 -0.0385665 0.7654399 +VERTEX_SE3:QUAT 4435 18.060283 33.327170 5.595415 0.5643203 -0.4949634 0.2818357 0.5975972 +VERTEX_SE3:QUAT 4436 18.838497 33.309554 4.985384 0.3517865 -0.6729633 0.3452750 0.5514996 +VERTEX_SE3:QUAT 4437 19.611553 33.379450 4.645247 0.5418177 0.1839388 -0.6703017 0.4725419 +VERTEX_SE3:QUAT 4438 20.559605 33.092935 4.180718 0.1166204 -0.7799971 -0.1747647 0.5894587 +VERTEX_SE3:QUAT 4439 21.358000 33.075061 3.642894 0.5457519 -0.0413033 0.2907488 0.7848019 +VERTEX_SE3:QUAT 4440 20.963565 33.808581 2.981699 -0.9803302 -0.0040224 -0.1867851 0.0636226 +VERTEX_SE3:QUAT 4441 20.098082 33.883601 3.459410 -0.6903308 -0.7124127 0.1136176 0.0547961 +VERTEX_SE3:QUAT 4442 19.276080 34.007644 3.916957 -0.3833789 -0.8196037 -0.1074866 0.4119673 +VERTEX_SE3:QUAT 4443 18.385616 34.167177 4.417700 -0.1079027 -0.8173231 0.4518329 0.3408622 +VERTEX_SE3:QUAT 4444 17.638283 34.070445 4.872428 0.4927350 -0.0396657 -0.4187053 0.7617905 +VERTEX_SE3:QUAT 4445 16.735911 33.908098 5.370810 -0.3374614 -0.8622261 0.2108626 0.3134052 +VERTEX_SE3:QUAT 4446 16.054278 33.819328 6.015669 -0.2829195 0.9443353 -0.1674449 0.0122282 +VERTEX_SE3:QUAT 4447 14.880112 33.898557 6.449535 0.1197910 0.7604760 -0.0973859 0.6307475 +VERTEX_SE3:QUAT 4448 14.013196 33.785424 6.958653 0.3651801 -0.2289263 0.7879492 0.4397411 +VERTEX_SE3:QUAT 4449 13.073697 33.750813 7.351875 0.8175339 -0.0221169 -0.5212844 0.2437451 +VERTEX_SE3:QUAT 4450 12.264791 33.660501 7.752350 0.3241481 -0.5081263 0.0826469 0.7936656 +VERTEX_SE3:QUAT 4451 11.279798 33.628162 8.070394 0.2947560 0.7737879 -0.2281924 0.5121517 +VERTEX_SE3:QUAT 4452 10.277117 33.694740 8.385341 0.5037353 0.3414172 0.4032707 0.6834162 +VERTEX_SE3:QUAT 4453 9.390272 33.629345 8.841043 -0.8098343 0.0782155 0.5812108 0.0156416 +VERTEX_SE3:QUAT 4454 8.532787 33.497494 9.100105 0.4762038 -0.8457158 0.0817779 0.2265107 +VERTEX_SE3:QUAT 4455 7.726893 33.683199 9.334965 0.8977579 -0.2187700 0.2746149 0.2660022 +VERTEX_SE3:QUAT 4456 6.567225 33.874281 9.527592 -0.8419420 -0.4328741 0.3093607 0.0897194 +VERTEX_SE3:QUAT 4457 5.554422 33.766313 9.682835 -0.8951925 -0.3681113 -0.2512430 0.0011535 +VERTEX_SE3:QUAT 4458 4.526824 33.751406 9.776571 0.4892539 0.1839137 -0.8375032 0.1593570 +VERTEX_SE3:QUAT 4459 3.444273 33.898181 9.906800 0.3953587 -0.8339284 0.2464674 0.2958186 +VERTEX_SE3:QUAT 4460 3.384219 34.103275 8.982292 -0.3731577 0.9271356 -0.0267244 0.0214179 +VERTEX_SE3:QUAT 4461 4.384774 34.161509 8.827223 0.4880955 -0.7375724 -0.0838189 0.4590470 +VERTEX_SE3:QUAT 4462 5.318347 34.049940 8.600335 0.6883423 -0.3586968 -0.3950898 0.4913507 +VERTEX_SE3:QUAT 4463 6.532257 34.163778 8.469399 -0.3593875 0.7180447 -0.5140731 0.3016311 +VERTEX_SE3:QUAT 4464 7.460585 34.104457 8.272556 0.0548103 0.9707113 -0.0139935 0.2334943 +VERTEX_SE3:QUAT 4465 8.660174 34.271069 8.117048 0.0788022 -0.6173299 0.2852696 0.7289138 +VERTEX_SE3:QUAT 4466 9.737162 34.073238 8.234814 -0.2226224 -0.6218033 0.6008056 0.4503693 +VERTEX_SE3:QUAT 4467 10.737571 33.788099 8.435222 0.0108480 -0.6151548 0.4660204 0.6358395 +VERTEX_SE3:QUAT 4468 11.841359 33.719125 8.547018 0.8370192 -0.1896238 -0.0197992 0.5128837 +VERTEX_SE3:QUAT 4469 12.775004 33.466606 8.589104 -0.6125342 0.6104271 -0.4669275 0.1848223 +VERTEX_SE3:QUAT 4470 13.777528 33.304119 8.807770 0.4576699 0.1925946 -0.8679931 0.0057970 +VERTEX_SE3:QUAT 4471 14.661564 33.127793 9.102966 -0.4656673 -0.2273228 0.8390895 0.1655510 +VERTEX_SE3:QUAT 4472 15.761924 32.946949 9.306163 0.4965495 0.3616254 -0.7462588 0.2564438 +VERTEX_SE3:QUAT 4473 16.529872 32.704460 9.511773 -0.7938075 0.2790275 -0.5384637 0.0454988 +VERTEX_SE3:QUAT 4474 17.628989 32.665055 9.747337 0.1615970 0.6233607 -0.3435170 0.6835964 +VERTEX_SE3:QUAT 4475 18.598852 32.491831 9.712543 0.1029862 -0.9340778 0.1340023 0.3145407 +VERTEX_SE3:QUAT 4476 19.588397 32.000383 9.990365 0.7087926 -0.0391266 0.6935660 0.1226721 +VERTEX_SE3:QUAT 4477 20.645875 31.739337 10.373756 0.9122130 -0.2044340 -0.2693231 0.2313855 +VERTEX_SE3:QUAT 4478 21.609981 31.580206 10.691496 -0.5675962 -0.5432237 0.5953830 0.1681122 +VERTEX_SE3:QUAT 4479 22.544147 31.015583 10.893481 0.3136270 -0.8107093 0.4258459 0.2510852 +VERTEX_SE3:QUAT 4480 22.989088 31.368391 9.949881 0.4639076 -0.4257049 0.4736643 0.6157980 +VERTEX_SE3:QUAT 4481 22.075766 31.782108 9.728858 0.4386105 -0.8142306 -0.1298526 0.3574740 +VERTEX_SE3:QUAT 4482 21.163147 32.262773 9.584838 0.7011501 0.0071035 -0.2805261 0.6554717 +VERTEX_SE3:QUAT 4483 19.963470 32.534984 9.415544 0.4297375 -0.8520223 -0.2914279 0.0667352 +VERTEX_SE3:QUAT 4484 18.938832 32.781531 9.242553 -0.5412391 -0.5202538 0.5951891 0.2866115 +VERTEX_SE3:QUAT 4485 17.953815 32.989435 9.074506 0.3875118 0.8238745 -0.3828759 0.1564338 +VERTEX_SE3:QUAT 4486 17.041932 33.400932 8.997456 -0.6071115 -0.6045992 0.5150300 0.0248905 +VERTEX_SE3:QUAT 4487 16.249548 33.609180 8.913072 -0.1857134 0.6868815 -0.6171172 0.3359623 +VERTEX_SE3:QUAT 4488 15.281395 33.727333 8.833446 0.0088876 0.8622786 0.1601753 0.4803546 +VERTEX_SE3:QUAT 4489 14.350838 34.054029 8.708283 0.1245446 -0.9267663 0.2340358 0.2661204 +VERTEX_SE3:QUAT 4490 13.313356 34.414344 8.606830 0.4933961 0.5019260 0.3039401 0.6420677 +VERTEX_SE3:QUAT 4491 12.266224 34.693352 8.442607 0.9361409 0.2845194 -0.0513225 0.2001375 +VERTEX_SE3:QUAT 4492 11.427560 34.994587 8.515409 0.6304681 -0.0201018 -0.5179097 0.5778196 +VERTEX_SE3:QUAT 4493 10.590566 35.346692 8.529889 0.5609996 0.5019656 0.1441058 0.6422955 +VERTEX_SE3:QUAT 4494 9.587598 35.668253 8.799272 0.7809837 -0.0705559 0.0323222 0.6197108 +VERTEX_SE3:QUAT 4495 8.730841 35.885622 8.864091 0.7520749 -0.2041328 0.5007487 0.3767810 +VERTEX_SE3:QUAT 4496 7.609287 36.102080 9.083491 0.8345789 0.5083374 -0.1048183 0.1846196 +VERTEX_SE3:QUAT 4497 6.784507 36.539576 9.206413 0.2917347 -0.4926432 0.7995881 0.1812523 +VERTEX_SE3:QUAT 4498 5.614179 37.062094 9.316348 -0.0703352 -0.9311484 -0.0817900 0.3483189 +VERTEX_SE3:QUAT 4499 4.612798 37.391725 9.488024 0.9628602 0.2356534 0.0341786 0.1272774 +VERTEX_SE3:QUAT 4500 4.853619 38.188071 8.751357 0.6722570 -0.2557510 0.3615344 0.5932578 +VERTEX_SE3:QUAT 4501 5.825106 37.978053 8.445305 -0.9281496 0.2453287 0.0190845 0.2792631 +VERTEX_SE3:QUAT 4502 6.812422 37.664663 8.342053 0.3402977 -0.5464117 0.6946184 0.3211494 +VERTEX_SE3:QUAT 4503 7.639188 37.221529 8.245177 -0.2904475 0.8401172 -0.3541511 0.2905517 +VERTEX_SE3:QUAT 4504 8.705163 36.881681 8.343609 -0.5786782 -0.4951118 0.5693389 0.3095950 +VERTEX_SE3:QUAT 4505 9.688754 36.541746 8.368882 0.8006104 0.4987521 0.2887376 0.1640118 +VERTEX_SE3:QUAT 4506 10.596576 36.131461 8.312937 -0.6839735 0.6918542 -0.2195834 0.0728091 +VERTEX_SE3:QUAT 4507 11.525050 35.691234 8.188935 -0.8613269 -0.4720698 -0.0392240 0.1836505 +VERTEX_SE3:QUAT 4508 12.509268 35.324800 8.054683 -0.9263641 -0.0210565 -0.2808220 0.2500904 +VERTEX_SE3:QUAT 4509 13.502780 34.759834 8.175658 0.8031464 0.4231789 -0.0373223 0.4177110 +VERTEX_SE3:QUAT 4510 14.496694 34.417877 8.109300 0.5587075 -0.2059412 -0.6234237 0.5067318 +VERTEX_SE3:QUAT 4511 15.321052 34.019068 8.001076 0.0542187 -0.8731421 -0.0205931 0.4840033 +VERTEX_SE3:QUAT 4512 16.225989 33.911761 7.852025 -0.0072247 0.9804231 0.1494418 0.1280061 +VERTEX_SE3:QUAT 4513 17.267052 33.734912 7.570685 -0.5648568 0.6387271 -0.4058447 0.3290206 +VERTEX_SE3:QUAT 4514 18.341055 33.498470 7.352403 0.3542658 0.9150105 -0.1896353 0.0359150 +VERTEX_SE3:QUAT 4515 19.239984 33.263451 7.166228 0.7378900 0.6241095 -0.2252186 0.1236216 +VERTEX_SE3:QUAT 4516 20.400496 33.097747 7.121795 0.7808252 0.0426939 0.2350464 0.5772716 +VERTEX_SE3:QUAT 4517 21.396537 32.758734 6.908018 0.0851196 0.6286327 -0.7713228 0.0513495 +VERTEX_SE3:QUAT 4518 22.504337 32.627199 6.599556 0.6898423 0.6486268 -0.1294232 0.2943648 +VERTEX_SE3:QUAT 4519 23.447570 32.459139 6.305498 0.3210214 -0.5628871 -0.3123425 0.6946550 +VERTEX_SE3:QUAT 4520 23.333213 33.345469 5.688023 0.3278143 -0.6401239 -0.3961353 0.5708380 +VERTEX_SE3:QUAT 4521 22.555249 33.726381 5.913573 -0.8535379 -0.2261820 0.1541757 0.4433336 +VERTEX_SE3:QUAT 4522 21.565274 33.981330 6.141888 0.5038734 -0.4442784 -0.0678617 0.7376470 +VERTEX_SE3:QUAT 4523 20.734055 34.197654 6.419814 -0.9318277 -0.2370700 -0.2523770 0.1086313 +VERTEX_SE3:QUAT 4524 19.591396 34.204312 6.706192 -0.8589524 -0.0950355 0.5029434 0.0147295 +VERTEX_SE3:QUAT 4525 18.605941 34.508456 7.039641 0.5555198 -0.3885713 0.6283151 0.3816152 +VERTEX_SE3:QUAT 4526 17.596492 34.741804 7.273990 0.4034827 -0.6514565 0.2833410 0.5766490 +VERTEX_SE3:QUAT 4527 16.635758 35.004369 7.215422 0.5591831 -0.1403703 0.2006304 0.7920593 +VERTEX_SE3:QUAT 4528 15.783188 35.285245 7.238250 -0.8868501 -0.4400722 0.0051597 0.1407361 +VERTEX_SE3:QUAT 4529 14.772179 35.649597 7.123419 -0.3296517 -0.8657646 -0.3128736 0.2095033 +VERTEX_SE3:QUAT 4530 13.965932 35.882614 7.229039 0.5045046 0.4140418 -0.3631095 0.6649782 +VERTEX_SE3:QUAT 4531 13.049517 36.315465 7.386164 -0.1075095 0.3946731 -0.9110544 0.0515248 +VERTEX_SE3:QUAT 4532 12.165307 36.465026 7.433145 -0.0181666 0.9158491 -0.1837525 0.3565465 +VERTEX_SE3:QUAT 4533 11.189120 36.549834 7.475938 0.0177787 0.9356753 0.1968423 0.2923161 +VERTEX_SE3:QUAT 4534 10.341919 36.820018 7.595448 0.5157383 0.6423019 -0.5542602 0.1194064 +VERTEX_SE3:QUAT 4535 9.407897 37.024541 7.754900 -0.1032057 0.9539816 0.0022420 0.2815364 +VERTEX_SE3:QUAT 4536 8.333746 37.207498 7.624350 0.0300592 -0.6491999 0.0720147 0.7566041 +VERTEX_SE3:QUAT 4537 7.388596 37.449765 7.572331 -0.6593899 0.7108181 -0.0440722 0.2408325 +VERTEX_SE3:QUAT 4538 6.442288 37.841555 7.423069 0.7662084 -0.1975839 -0.3990938 0.4632596 +VERTEX_SE3:QUAT 4539 5.489006 38.159753 7.544615 0.7424207 -0.5793929 -0.3217748 0.0978591 +VERTEX_SE3:QUAT 4540 5.663843 38.737490 6.796495 -0.3566110 0.7891421 -0.4628030 0.1894642 +VERTEX_SE3:QUAT 4541 6.505384 38.175853 6.462293 0.4694323 0.5568519 -0.6584200 0.1898220 +VERTEX_SE3:QUAT 4542 7.493534 37.606684 6.381923 0.5104771 -0.0503791 -0.0497236 0.8569729 +VERTEX_SE3:QUAT 4543 8.485516 37.019497 6.254824 0.8396045 0.2814048 -0.3886610 0.2545942 +VERTEX_SE3:QUAT 4544 9.338321 36.635566 6.211065 0.7204228 -0.1186541 -0.1394976 0.6689190 +VERTEX_SE3:QUAT 4545 10.235521 36.161203 6.092376 -0.2740870 0.9106944 -0.2963654 0.0876335 +VERTEX_SE3:QUAT 4546 10.998539 35.648252 5.952469 0.8954909 0.4075308 -0.1785409 0.0117458 +VERTEX_SE3:QUAT 4547 11.892512 34.964511 5.870004 -0.6622352 -0.4436670 0.6003221 0.0649425 +VERTEX_SE3:QUAT 4548 12.704770 34.498287 5.782507 -0.3945857 0.6678502 -0.6309321 0.0142431 +VERTEX_SE3:QUAT 4549 13.467628 34.042315 5.701365 0.3150879 0.7591812 -0.2014059 0.5327281 +VERTEX_SE3:QUAT 4550 14.387067 33.782468 5.869137 0.8997821 0.2098067 0.3284877 0.1961354 +VERTEX_SE3:QUAT 4551 15.351199 33.533367 6.066159 -0.5712950 0.7758213 0.2664261 0.0272120 +VERTEX_SE3:QUAT 4552 16.215767 33.163565 6.309558 0.4959417 -0.7728899 -0.3135853 0.2415519 +VERTEX_SE3:QUAT 4553 17.329373 32.906610 6.577041 0.3574306 -0.8916522 -0.2707378 0.0624567 +VERTEX_SE3:QUAT 4554 18.216788 32.487721 6.696336 0.2307689 0.8664849 0.0444892 0.4404206 +VERTEX_SE3:QUAT 4555 19.146534 32.209108 6.760669 -0.6476290 -0.7065160 0.2848174 0.0170559 +VERTEX_SE3:QUAT 4556 20.018526 31.835561 6.769635 0.3094881 0.8112820 -0.3034052 0.3924078 +VERTEX_SE3:QUAT 4557 20.859012 31.473635 6.813756 0.1077185 -0.9742045 -0.1904301 0.0553058 +VERTEX_SE3:QUAT 4558 21.672746 30.928162 6.979708 -0.0124205 -0.8054930 0.2633372 0.5307356 +VERTEX_SE3:QUAT 4559 22.610233 30.360039 7.286528 0.9651193 0.0087261 0.0236862 0.2605909 +VERTEX_SE3:QUAT 4560 23.141524 31.162275 6.707238 0.4484574 -0.7903945 0.0676348 0.4118107 +VERTEX_SE3:QUAT 4561 22.390945 31.585671 6.572446 -0.7749801 0.5726673 -0.0259907 0.2660496 +VERTEX_SE3:QUAT 4562 21.552979 32.104850 6.392651 -0.5224022 0.5504971 -0.6362600 0.1386435 +VERTEX_SE3:QUAT 4563 20.590287 32.843506 6.148445 -0.7765895 0.2137498 0.5748274 0.1441986 +VERTEX_SE3:QUAT 4564 19.962209 33.414682 6.129753 -0.9200868 -0.2570414 0.1906298 0.2258987 +VERTEX_SE3:QUAT 4565 19.076472 34.003783 6.301511 -0.3904350 0.8835178 0.2556148 0.0402233 +VERTEX_SE3:QUAT 4566 18.339698 34.632992 6.301587 0.7843199 0.0015674 0.3992928 0.4747684 +VERTEX_SE3:QUAT 4567 17.577401 35.276109 6.222357 0.7446054 0.3423316 -0.5464624 0.1724843 +VERTEX_SE3:QUAT 4568 16.867520 36.058709 6.072400 0.8644651 0.4311155 0.0750263 0.2474077 +VERTEX_SE3:QUAT 4569 16.008217 36.605822 5.815013 -0.0120934 -0.6105384 0.7915663 0.0227892 +VERTEX_SE3:QUAT 4570 15.279027 37.278060 5.644767 0.1427007 -0.9474462 -0.1307553 0.2547260 +VERTEX_SE3:QUAT 4571 14.430877 37.711868 5.389328 0.5768560 0.5402298 -0.3448570 0.5064213 +VERTEX_SE3:QUAT 4572 13.555603 38.160270 5.247416 0.6219750 -0.0590070 0.1429678 0.7676102 +VERTEX_SE3:QUAT 4573 12.874157 38.655695 4.845007 0.5947488 -0.4854622 0.0483072 0.6389575 +VERTEX_SE3:QUAT 4574 12.131224 39.220981 4.791147 0.7962737 -0.3067470 0.5211593 0.0157301 +VERTEX_SE3:QUAT 4575 11.113133 39.615171 4.631852 0.6934687 -0.0665522 -0.0823242 0.7126673 +VERTEX_SE3:QUAT 4576 10.126288 40.053031 4.466379 -0.5401548 -0.3898932 0.7450139 0.0342096 +VERTEX_SE3:QUAT 4577 9.108090 40.426070 4.325127 -0.2283563 0.6109712 -0.6354007 0.4133202 +VERTEX_SE3:QUAT 4578 8.475656 41.037099 4.160551 -0.4152642 -0.7815599 0.2209445 0.4097601 +VERTEX_SE3:QUAT 4579 7.458926 41.665495 4.008517 0.5776054 0.6595079 0.1317841 0.4626601 +VERTEX_SE3:QUAT 4580 7.913619 42.358524 3.427366 0.3479351 0.6010092 -0.5990002 0.3986576 +VERTEX_SE3:QUAT 4581 8.822838 41.805020 3.764864 0.2438701 0.4396563 -0.8495138 0.1598624 +VERTEX_SE3:QUAT 4582 9.621528 41.183973 3.933402 0.6483274 0.6374144 -0.3118330 0.2759251 +VERTEX_SE3:QUAT 4583 10.382659 40.520312 4.187896 0.5008349 -0.3150360 0.7344431 0.3324306 +VERTEX_SE3:QUAT 4584 11.168976 39.895907 4.353831 -0.0520302 -0.4894300 0.7724159 0.4014036 +VERTEX_SE3:QUAT 4585 12.145350 39.220655 4.609002 0.3209822 -0.5894516 0.2382666 0.7019589 +VERTEX_SE3:QUAT 4586 12.889974 38.667003 4.978055 -0.0155596 0.8849668 -0.2241716 0.4078465 +VERTEX_SE3:QUAT 4587 13.994971 38.114231 5.098249 -0.4566444 0.8719205 0.1761954 0.0136258 +VERTEX_SE3:QUAT 4588 14.834506 37.584165 5.344486 0.5800589 0.5839638 0.3815027 0.4206824 +VERTEX_SE3:QUAT 4589 15.712423 37.226260 5.494914 0.6123533 -0.4614625 -0.1783236 0.6166656 +VERTEX_SE3:QUAT 4590 16.645415 36.788939 5.672890 0.8646565 0.1348132 0.4539419 0.1677240 +VERTEX_SE3:QUAT 4591 17.830649 36.582921 5.859588 0.9491162 -0.0114518 0.0967349 0.2994824 +VERTEX_SE3:QUAT 4592 19.042393 36.210189 5.862600 0.3996486 -0.8718442 0.1150434 0.2587157 +VERTEX_SE3:QUAT 4593 19.905961 35.838668 6.040764 0.7010910 0.6710731 -0.2321294 0.0651792 +VERTEX_SE3:QUAT 4594 20.925555 35.433575 6.009537 0.0997063 -0.9439007 -0.2950188 0.1098817 +VERTEX_SE3:QUAT 4595 21.756190 35.079554 5.984670 0.7192584 0.2026241 -0.2708209 0.6068499 +VERTEX_SE3:QUAT 4596 22.756737 34.815808 5.977161 0.6048698 -0.5335064 0.4881013 0.3335574 +VERTEX_SE3:QUAT 4597 23.678839 34.446272 5.860864 0.1198159 -0.8717993 0.4710616 0.0609186 +VERTEX_SE3:QUAT 4598 24.785559 34.216184 5.826877 -0.5716497 0.6991493 -0.3965474 0.1647937 +VERTEX_SE3:QUAT 4599 25.879703 34.130098 5.784638 -0.3694894 -0.4869487 0.7730340 0.1696375 +VERTEX_SE3:QUAT 4600 26.016287 34.605419 5.025975 -0.4297328 -0.8290437 0.3091381 0.1801387 +VERTEX_SE3:QUAT 4601 25.163626 34.977779 4.969519 0.6658522 -0.2251943 -0.0783795 0.7069548 +VERTEX_SE3:QUAT 4602 24.159502 35.100735 4.869456 0.8217466 -0.0832933 -0.5337575 0.1813774 +VERTEX_SE3:QUAT 4603 23.284168 35.170628 4.699475 -0.1887620 -0.9159171 -0.0750995 0.3461573 +VERTEX_SE3:QUAT 4604 22.415101 35.377100 4.490791 0.2758453 0.5907687 -0.7084155 0.2702762 +VERTEX_SE3:QUAT 4605 21.434151 35.530506 4.352199 -0.8047059 -0.4696460 0.2606449 0.2528741 +VERTEX_SE3:QUAT 4606 20.447033 35.519877 3.951140 0.2056779 -0.5262666 -0.0226720 0.8247582 +VERTEX_SE3:QUAT 4607 19.644040 35.809463 3.728967 0.3250619 -0.6161042 -0.0706827 0.7139708 +VERTEX_SE3:QUAT 4608 18.676262 35.894188 3.578459 -0.9556906 -0.2591427 -0.1394452 0.0074541 +VERTEX_SE3:QUAT 4609 17.797265 36.049059 3.357226 -0.0041385 0.7185572 -0.6932947 0.0547801 +VERTEX_SE3:QUAT 4610 16.946874 36.397803 3.135667 0.3560994 -0.1780200 0.8605323 0.3177833 +VERTEX_SE3:QUAT 4611 15.903424 36.700681 2.769111 -0.5006581 0.6079233 -0.5281768 0.3174902 +VERTEX_SE3:QUAT 4612 14.918785 36.856405 2.494897 0.9220380 0.2282911 0.2968140 0.0981349 +VERTEX_SE3:QUAT 4613 13.894624 37.171957 2.205571 0.5583948 -0.4606036 0.6145535 0.3136296 +VERTEX_SE3:QUAT 4614 12.966072 37.601282 2.069349 -0.5104182 -0.5302427 0.5206692 0.4326886 +VERTEX_SE3:QUAT 4615 12.129392 37.929111 1.753245 0.3099389 0.8336066 0.1138543 0.4428037 +VERTEX_SE3:QUAT 4616 11.094865 38.392728 1.601174 0.7093778 -0.3488783 0.5553736 0.2581226 +VERTEX_SE3:QUAT 4617 10.287702 38.571530 1.360596 0.3295337 0.4634489 -0.8191130 0.0753424 +VERTEX_SE3:QUAT 4618 9.465387 38.893132 1.239937 -0.4479458 -0.3882860 0.7979489 0.1088859 +VERTEX_SE3:QUAT 4619 8.659149 39.126401 0.927557 0.5809323 -0.1548992 0.4767375 0.6412840 +VERTEX_SE3:QUAT 4620 9.289439 39.127641 0.062350 0.0990521 -0.9224866 -0.1800055 0.3268107 +VERTEX_SE3:QUAT 4621 10.285977 38.672921 0.643953 -0.2931008 0.8919794 -0.2880706 0.1883613 +VERTEX_SE3:QUAT 4622 11.272993 38.178113 0.958952 0.9145662 0.3828718 0.0296064 0.1268913 +VERTEX_SE3:QUAT 4623 12.233041 37.655121 1.449379 0.1985720 -0.2208769 -0.2918070 0.9091926 +VERTEX_SE3:QUAT 4624 13.223799 37.246585 1.899371 0.0018787 -0.2023366 0.7762052 0.5971280 +VERTEX_SE3:QUAT 4625 14.193199 36.834642 2.123652 -0.0792344 -0.4078738 0.7949997 0.4419688 +VERTEX_SE3:QUAT 4626 15.055989 36.206556 2.339297 -0.0774882 -0.4534130 0.2290065 0.8578859 +VERTEX_SE3:QUAT 4627 15.807556 36.068994 2.550209 0.8707602 -0.4069841 0.0657413 0.2679901 +VERTEX_SE3:QUAT 4628 16.651927 35.629188 2.872146 0.2532093 0.3337136 -0.6829205 0.5984479 +VERTEX_SE3:QUAT 4629 17.392818 35.176013 3.086874 0.6967692 -0.1093587 -0.7086928 0.0175459 +VERTEX_SE3:QUAT 4630 18.240331 34.660164 3.436754 0.7410759 -0.0786649 -0.1787245 0.6423986 +VERTEX_SE3:QUAT 4631 19.326631 34.394619 3.484035 0.6680564 0.3932638 0.0663425 0.6282061 +VERTEX_SE3:QUAT 4632 20.288073 34.214758 3.618659 0.3901917 -0.4639606 0.4209533 0.6747513 +VERTEX_SE3:QUAT 4633 21.020006 34.006158 3.647100 -0.8835216 0.4438148 -0.0166666 0.1487962 +VERTEX_SE3:QUAT 4634 22.056711 33.738873 3.898872 0.7584981 0.0388197 -0.4691860 0.4505976 +VERTEX_SE3:QUAT 4635 23.117218 33.607784 4.093214 -0.6225422 -0.2316313 0.7459460 0.0485051 +VERTEX_SE3:QUAT 4636 24.013095 33.517681 4.196191 0.2611565 0.9371645 -0.0850686 0.2151356 +VERTEX_SE3:QUAT 4637 25.059006 33.506869 4.303991 -0.0308412 0.6089245 -0.7924975 0.0144079 +VERTEX_SE3:QUAT 4638 26.046786 33.480524 4.179083 0.4047130 0.4538043 -0.0139943 0.7937715 +VERTEX_SE3:QUAT 4639 26.937317 33.332632 4.367012 0.5567201 0.0307443 -0.4134948 0.7198191 +VERTEX_SE3:QUAT 4640 27.101727 33.406179 3.335603 0.6938592 0.4029761 0.0932460 0.5894700 +VERTEX_SE3:QUAT 4641 26.260012 33.704846 2.914875 -0.1932335 -0.8181406 0.5287226 0.1172997 +VERTEX_SE3:QUAT 4642 25.238967 33.848732 2.779667 0.4384487 0.6888805 0.1048593 0.5676363 +VERTEX_SE3:QUAT 4643 24.295566 33.878810 2.586116 0.3200511 0.3798631 -0.7958423 0.3462751 +VERTEX_SE3:QUAT 4644 23.354846 34.092679 2.367817 0.2899536 -0.3101828 0.1614996 0.8908600 +VERTEX_SE3:QUAT 4645 22.130551 34.216479 2.325789 0.7065962 0.3064424 -0.5778899 0.2699225 +VERTEX_SE3:QUAT 4646 21.096361 34.366603 2.145962 -0.9156408 -0.1430593 0.3605229 0.1056368 +VERTEX_SE3:QUAT 4647 20.152486 34.420210 1.856348 0.5120174 0.4203988 -0.3584665 0.6577270 +VERTEX_SE3:QUAT 4648 19.061623 34.782343 1.755731 0.3789235 -0.4442720 0.3968596 0.7081962 +VERTEX_SE3:QUAT 4649 18.155430 34.908069 1.485181 0.1772509 -0.7552458 -0.1996171 0.5986141 +VERTEX_SE3:QUAT 4650 17.375104 34.892624 1.155153 0.7666475 -0.1017415 -0.5731494 0.2709244 +VERTEX_SE3:QUAT 4651 16.327555 34.933035 1.005436 0.7927025 -0.1703480 0.1572772 0.5637980 +VERTEX_SE3:QUAT 4652 15.322379 35.149739 0.683716 0.4631502 -0.5617919 -0.1386907 0.6713022 +VERTEX_SE3:QUAT 4653 14.319261 35.005533 0.282945 0.4277465 0.5136903 -0.5750413 0.4716808 +VERTEX_SE3:QUAT 4654 13.256348 35.152253 -0.008894 0.5384581 0.0894760 0.6662067 0.5081589 +VERTEX_SE3:QUAT 4655 12.148127 35.227141 -0.402788 0.1240410 -0.3803268 0.7063446 0.5839886 +VERTEX_SE3:QUAT 4656 11.286417 35.218043 -0.854176 0.9430306 0.1069789 -0.1703135 0.2650324 +VERTEX_SE3:QUAT 4657 10.316180 35.486967 -1.209065 0.1948515 0.0370402 -0.9607075 0.1941700 +VERTEX_SE3:QUAT 4658 9.274536 35.614957 -1.419746 0.4450499 -0.5713084 0.6640046 0.1861053 +VERTEX_SE3:QUAT 4659 8.401188 35.757904 -1.729016 0.6373245 0.3116511 -0.2141551 0.6714378 +VERTEX_SE3:QUAT 4660 8.745570 35.851210 -2.651952 -0.4880517 -0.4402740 0.6635880 0.3572329 +VERTEX_SE3:QUAT 4661 9.735227 35.592999 -2.069781 0.1857314 0.5160223 -0.1428058 0.8239122 +VERTEX_SE3:QUAT 4662 10.663852 35.596449 -1.664479 0.1833827 0.4124014 -0.3438956 0.8234268 +VERTEX_SE3:QUAT 4663 11.633596 35.401433 -1.294918 0.5858488 0.0103604 0.7571750 0.2887211 +VERTEX_SE3:QUAT 4664 12.566314 35.152074 -1.064711 0.7792525 0.1784393 -0.0870537 0.5944296 +VERTEX_SE3:QUAT 4665 13.456253 34.776531 -0.863414 -0.1917844 -0.2098137 0.9535749 0.0994575 +VERTEX_SE3:QUAT 4666 14.476086 34.498411 -0.638799 0.2439994 -0.2298867 -0.5616068 0.7564484 +VERTEX_SE3:QUAT 4667 15.272012 34.297635 -0.520920 -0.2883592 0.7894602 -0.2798399 0.4639949 +VERTEX_SE3:QUAT 4668 16.055002 33.899309 -0.575340 0.5562226 0.3946750 0.0328045 0.7305969 +VERTEX_SE3:QUAT 4669 17.099660 33.657886 -0.290002 0.5100675 -0.3024015 -0.4979990 0.6327571 +VERTEX_SE3:QUAT 4670 18.088797 33.326386 -0.264734 0.5348481 0.5557486 -0.4364780 0.4632147 +VERTEX_SE3:QUAT 4671 19.137750 33.174547 0.088089 0.6387639 0.6417300 -0.0485571 0.4216698 +VERTEX_SE3:QUAT 4672 20.071112 32.949114 0.397878 0.4859808 0.6233075 -0.5506795 0.2684446 +VERTEX_SE3:QUAT 4673 21.058154 32.847005 0.542055 0.1709372 0.9162033 -0.1380374 0.3351084 +VERTEX_SE3:QUAT 4674 21.969406 32.586261 0.654308 0.7091576 -0.4844740 0.3874939 0.3350059 +VERTEX_SE3:QUAT 4675 22.893463 32.555659 0.822604 0.6889144 0.1421208 0.5647333 0.4315957 +VERTEX_SE3:QUAT 4676 23.928128 32.345399 1.207068 -0.0784834 0.2569689 -0.5443944 0.7946333 +VERTEX_SE3:QUAT 4677 24.825611 32.235081 1.439972 0.7726869 -0.0626529 0.1169460 0.6207683 +VERTEX_SE3:QUAT 4678 25.769072 32.120714 1.765823 0.6494042 0.1902749 -0.7321771 0.0773711 +VERTEX_SE3:QUAT 4679 26.704452 31.900964 2.074092 0.8030433 0.1189436 0.3120466 0.4935594 +VERTEX_SE3:QUAT 4680 26.882599 31.932780 1.031469 -0.0028542 0.7577241 -0.2461433 0.6043671 +VERTEX_SE3:QUAT 4681 25.992392 32.281773 0.595743 0.9608970 0.1025385 0.1395190 0.2160955 +VERTEX_SE3:QUAT 4682 25.100674 32.422654 0.259219 0.6301276 0.0889526 0.5353435 0.5553683 +VERTEX_SE3:QUAT 4683 24.184637 32.741457 -0.117174 -0.2026619 -0.5734246 0.7849748 0.1180124 +VERTEX_SE3:QUAT 4684 23.395999 33.045029 -0.507020 -0.2984464 0.8714818 -0.3293690 0.2072806 +VERTEX_SE3:QUAT 4685 22.541098 33.162640 -0.818983 0.0518402 0.7588310 -0.5797245 0.2922459 +VERTEX_SE3:QUAT 4686 21.668049 33.392503 -1.189263 0.2484071 -0.1454144 0.9389070 0.1886856 +VERTEX_SE3:QUAT 4687 20.713535 33.536924 -1.540101 0.1132761 -0.2099058 0.1605891 0.9577678 +VERTEX_SE3:QUAT 4688 19.890929 33.821112 -1.904456 0.2634248 0.5765493 -0.7615933 0.1348105 +VERTEX_SE3:QUAT 4689 19.002195 34.042644 -2.344789 0.5274332 -0.5405972 0.5622876 0.3367515 +VERTEX_SE3:QUAT 4690 18.065929 34.501248 -2.606250 0.5086361 0.3474832 -0.3058466 0.7259495 +VERTEX_SE3:QUAT 4691 17.135379 34.952687 -2.940434 -0.0435907 -0.4418216 0.8803284 0.1670792 +VERTEX_SE3:QUAT 4692 16.344655 35.216112 -3.045441 0.3177726 -0.2258454 0.0831050 0.9171194 +VERTEX_SE3:QUAT 4693 15.255904 35.595222 -3.226927 0.2214592 -0.7937575 -0.2673448 0.4994312 +VERTEX_SE3:QUAT 4694 14.347758 35.720904 -3.473252 0.7105514 -0.1683559 0.0044304 0.6831935 +VERTEX_SE3:QUAT 4695 13.437857 35.917580 -3.721012 0.4899902 -0.1141916 -0.6378796 0.5830776 +VERTEX_SE3:QUAT 4696 12.461163 36.345929 -4.033695 -0.4877966 -0.5379976 0.6332402 0.2676187 +VERTEX_SE3:QUAT 4697 11.676028 36.662784 -4.094518 0.8700331 -0.2953036 0.3697624 0.1382530 +VERTEX_SE3:QUAT 4698 10.580825 36.794630 -4.337634 0.0747572 -0.0555675 0.8203140 0.5642771 +VERTEX_SE3:QUAT 4699 9.682497 36.984862 -4.646264 0.2214647 -0.1590404 0.1883176 0.9435020 +VERTEX_SE3:QUAT 4700 9.836811 36.884245 -5.737126 0.7649351 0.5084154 -0.3033518 0.2537042 +VERTEX_SE3:QUAT 4701 10.842118 36.544580 -5.390024 0.3203737 0.0615832 -0.6541892 0.6823524 +VERTEX_SE3:QUAT 4702 11.870373 36.268160 -5.121527 -0.5662732 -0.8055097 0.1254005 0.1215047 +VERTEX_SE3:QUAT 4703 13.054642 36.201442 -4.716437 0.3298385 0.5953897 -0.1026222 0.7253870 +VERTEX_SE3:QUAT 4704 14.032956 35.987939 -4.394975 0.6476345 0.6796491 -0.2716043 0.2118436 +VERTEX_SE3:QUAT 4705 14.869762 35.762908 -3.889569 0.4910173 -0.6558863 -0.1240221 0.5597621 +VERTEX_SE3:QUAT 4706 15.835066 35.610061 -3.540017 0.1184624 0.8975632 -0.3701643 0.2081475 +VERTEX_SE3:QUAT 4707 16.815903 35.337073 -3.344396 0.3887094 0.0717319 0.6798510 0.6177072 +VERTEX_SE3:QUAT 4708 17.741902 35.054238 -2.894809 0.8521997 0.2297158 -0.4370420 0.1731490 +VERTEX_SE3:QUAT 4709 18.598305 34.780907 -2.701321 -0.0416536 -0.0496461 -0.2586792 0.9637870 +VERTEX_SE3:QUAT 4710 19.470717 34.661642 -2.551333 0.1164956 -0.6874186 0.0938834 0.7106830 +VERTEX_SE3:QUAT 4711 20.220209 34.456439 -2.173318 -0.2772227 -0.7138048 0.6341502 0.1071627 +VERTEX_SE3:QUAT 4712 21.154883 34.292747 -1.858009 0.3738896 -0.7782196 0.0043458 0.5045413 +VERTEX_SE3:QUAT 4713 22.044014 34.092356 -1.553856 0.6988545 0.1387118 -0.6732068 0.1978736 +VERTEX_SE3:QUAT 4714 23.105865 34.188620 -1.206690 0.9087456 -0.2664638 0.2152552 0.2384190 +VERTEX_SE3:QUAT 4715 24.070752 34.047529 -0.883942 0.1636218 -0.1823514 -0.2578884 0.9345959 +VERTEX_SE3:QUAT 4716 25.018043 33.993501 -0.615030 -0.1713086 0.5855430 -0.3509541 0.7103689 +VERTEX_SE3:QUAT 4717 25.859054 33.961117 -0.367112 0.6652442 0.5898549 -0.4428473 0.1157909 +VERTEX_SE3:QUAT 4718 26.819759 33.898315 0.012441 0.4929322 -0.3567788 0.5933019 0.5269911 +VERTEX_SE3:QUAT 4719 27.475489 33.882738 0.439824 -0.2720665 0.8103967 -0.5019078 0.1316268 +VERTEX_SE3:QUAT 4720 27.738957 33.771091 -0.342612 0.5660596 0.1603875 -0.5920734 0.5507281 +VERTEX_SE3:QUAT 4721 26.741945 33.864085 -0.800248 -0.1813650 0.1662662 -0.9562201 0.1584469 +VERTEX_SE3:QUAT 4722 25.779146 34.045050 -1.005818 0.0238243 -0.9681085 0.0272244 0.2479054 +VERTEX_SE3:QUAT 4723 24.981035 34.086531 -1.324933 -0.2888771 -0.1389849 0.8113538 0.4888131 +VERTEX_SE3:QUAT 4724 24.124265 34.234876 -1.749199 0.7159617 0.2043629 -0.4358293 0.5056554 +VERTEX_SE3:QUAT 4725 23.123683 34.206850 -2.005121 -0.1638214 0.9366714 -0.2476033 0.1857470 +VERTEX_SE3:QUAT 4726 22.116138 34.138507 -2.352043 0.3143740 -0.0685552 -0.8154617 0.4811356 +VERTEX_SE3:QUAT 4727 21.244238 34.150771 -2.680504 0.2888020 -0.0362475 0.6471182 0.7046400 +VERTEX_SE3:QUAT 4728 20.326269 34.360990 -3.109856 0.4350767 -0.5560690 -0.2322948 0.6689803 +VERTEX_SE3:QUAT 4729 19.354064 34.576788 -3.557933 0.2435185 0.1998824 -0.5702832 0.7586322 +VERTEX_SE3:QUAT 4730 18.471041 35.161403 -4.070308 0.7260949 0.3934032 0.0707165 0.5594813 +VERTEX_SE3:QUAT 4731 17.756464 35.507457 -4.501539 0.1826554 -0.5178265 0.5068177 0.6645514 +VERTEX_SE3:QUAT 4732 16.913782 35.795680 -4.914265 -0.4071014 -0.6250933 0.2751617 0.6064757 +VERTEX_SE3:QUAT 4733 16.079732 35.943292 -5.455141 0.4326183 0.6039633 -0.3555731 0.5671310 +VERTEX_SE3:QUAT 4734 15.126058 36.110499 -5.977712 0.5401607 0.8370990 -0.0777514 0.0380315 +VERTEX_SE3:QUAT 4735 14.124221 36.082702 -6.371955 0.6961349 0.2410445 0.5571164 0.3832950 +VERTEX_SE3:QUAT 4736 13.363061 36.251405 -7.077851 0.4871942 -0.6232463 -0.1629951 0.5896088 +VERTEX_SE3:QUAT 4737 12.568930 36.454242 -7.637536 -0.4259318 -0.8274636 0.3556774 0.0859055 +VERTEX_SE3:QUAT 4738 11.688297 36.365480 -8.087732 0.0795871 -0.4213433 -0.0460012 0.9022304 +VERTEX_SE3:QUAT 4739 10.967664 36.440627 -8.510606 -0.7441004 0.5200476 -0.4155511 0.0564124 +VERTEX_SE3:QUAT 4740 11.447180 36.614972 -9.333164 0.5071092 0.4943477 -0.6123259 0.3514507 +VERTEX_SE3:QUAT 4741 12.204674 36.417267 -8.786709 0.1893399 -0.0484574 -0.1322772 0.9717536 +VERTEX_SE3:QUAT 4742 12.954945 36.333174 -8.363370 0.5512959 -0.7909446 0.0613509 0.2582936 +VERTEX_SE3:QUAT 4743 13.718948 36.210300 -7.841356 0.2323677 0.0394403 -0.0317621 0.9713089 +VERTEX_SE3:QUAT 4744 14.738022 36.058639 -7.230683 0.3315906 0.6660975 0.0704730 0.6643759 +VERTEX_SE3:QUAT 4745 15.755148 35.809361 -6.849519 0.5313125 0.6966614 -0.1843026 0.4454239 +VERTEX_SE3:QUAT 4746 16.627178 35.518491 -6.268484 0.7195748 0.0981941 0.3123767 0.6123649 +VERTEX_SE3:QUAT 4747 17.354833 35.188934 -5.768228 -0.0505377 -0.3712962 0.9237408 0.0792970 +VERTEX_SE3:QUAT 4748 18.020901 34.941797 -5.330573 0.1081663 0.3326129 -0.9275309 0.1317389 +VERTEX_SE3:QUAT 4749 18.862908 34.874764 -4.666701 -0.3852636 0.7598167 -0.5184025 0.0742252 +VERTEX_SE3:QUAT 4750 19.713864 34.751814 -4.007577 0.5101607 0.6541464 -0.5096133 0.2283042 +VERTEX_SE3:QUAT 4751 20.505821 34.762476 -3.390613 0.5341028 0.4192109 0.1314476 0.7223005 +VERTEX_SE3:QUAT 4752 21.380848 35.008510 -3.055785 0.6296145 0.1413219 -0.7394768 0.1918016 +VERTEX_SE3:QUAT 4753 22.384035 35.215731 -2.579695 -0.5432912 0.1741892 -0.8212600 0.0049757 +VERTEX_SE3:QUAT 4754 23.229688 35.196038 -2.131326 -0.0390306 -0.2383345 0.9349580 0.2598592 +VERTEX_SE3:QUAT 4755 24.051954 35.304554 -1.644580 0.6147355 -0.2147590 0.7541390 0.0851658 +VERTEX_SE3:QUAT 4756 24.867054 35.473452 -1.124461 0.1998173 0.2734087 -0.9066472 0.2516179 +VERTEX_SE3:QUAT 4757 25.795304 35.521920 -0.598491 0.4274075 -0.0079379 0.8666014 0.2574136 +VERTEX_SE3:QUAT 4758 26.700170 35.712669 -0.120172 0.8962430 0.1600521 -0.3533650 0.2150928 +VERTEX_SE3:QUAT 4759 27.351822 35.684072 0.336574 0.5304325 0.2294572 0.7810323 0.2365994 +VERTEX_SE3:QUAT 4760 27.585967 35.793128 -0.431516 -0.0684976 0.3314205 -0.2992471 0.8921433 +VERTEX_SE3:QUAT 4761 26.987539 35.697717 -0.829193 0.6856164 -0.0897138 -0.5455496 0.4735580 +VERTEX_SE3:QUAT 4762 26.241835 35.501979 -1.300236 0.6638124 -0.3254618 -0.0417471 0.6720751 +VERTEX_SE3:QUAT 4763 25.332417 35.087545 -1.680324 -0.0464254 -0.7723453 0.5037907 0.3840864 +VERTEX_SE3:QUAT 4764 24.653089 35.036409 -2.139703 0.3425881 -0.7628157 -0.0216610 0.5479748 +VERTEX_SE3:QUAT 4765 23.913993 34.705806 -2.375274 -0.2975807 0.7795801 -0.0014512 0.5510885 +VERTEX_SE3:QUAT 4766 23.007834 34.427987 -2.786558 0.9475695 -0.2876906 0.1342269 0.0364588 +VERTEX_SE3:QUAT 4767 22.210820 34.073630 -3.220993 0.2754921 -0.2051730 0.8601391 0.3770530 +VERTEX_SE3:QUAT 4768 21.316052 33.753934 -3.760377 -0.3536989 0.4120075 -0.6193949 0.5670069 +VERTEX_SE3:QUAT 4769 20.660517 33.264458 -4.223376 0.2352210 0.0836409 -0.9653825 0.0755775 +VERTEX_SE3:QUAT 4770 19.968784 32.926315 -4.405913 -0.0615885 -0.9364738 0.3419607 0.0478184 +VERTEX_SE3:QUAT 4771 19.283455 32.303600 -4.947455 0.1173002 0.1493407 -0.9664570 0.1729128 +VERTEX_SE3:QUAT 4772 18.838355 31.990356 -5.543204 -0.1223253 0.9895915 -0.0729291 0.0206537 +VERTEX_SE3:QUAT 4773 18.170405 31.605539 -6.131658 -0.4714063 0.7253189 -0.4911303 0.1023695 +VERTEX_SE3:QUAT 4774 17.535125 30.999562 -6.714400 0.6091352 0.6999189 -0.3552523 0.1134177 +VERTEX_SE3:QUAT 4775 16.745187 30.755755 -7.256520 0.6101498 -0.5086404 -0.1218911 0.5951006 +VERTEX_SE3:QUAT 4776 16.070611 30.331620 -7.837999 0.9462914 0.2206321 -0.2236152 0.0764877 +VERTEX_SE3:QUAT 4777 15.285095 30.098602 -8.340256 -0.9865856 0.1318993 -0.0863009 0.0424694 +VERTEX_SE3:QUAT 4778 14.456482 30.000376 -8.931681 -0.3929924 0.4059948 -0.7393178 0.3662436 +VERTEX_SE3:QUAT 4779 13.801693 29.609981 -9.533038 -0.1114748 0.4909176 -0.7383640 0.4487670 +VERTEX_SE3:QUAT 4780 14.311199 30.059292 -10.353029 0.8000933 -0.2139889 -0.2735690 0.4891007 +VERTEX_SE3:QUAT 4781 15.314147 30.468950 -9.665618 0.8991081 -0.0487145 0.2126015 0.3795157 +VERTEX_SE3:QUAT 4782 16.087419 30.775295 -9.180891 0.1998344 0.7114909 -0.6692479 0.0771631 +VERTEX_SE3:QUAT 4783 16.699699 30.874282 -8.449977 0.8963772 0.1308928 0.4177254 0.0698604 +VERTEX_SE3:QUAT 4784 17.408791 31.083581 -7.834838 0.3200535 -0.5054560 -0.0153342 0.8011522 +VERTEX_SE3:QUAT 4785 18.084306 31.382626 -7.257273 0.2520109 -0.7759101 0.0870552 0.5717301 +VERTEX_SE3:QUAT 4786 18.971854 31.717698 -6.540495 0.2837266 0.2716447 0.4408732 0.8070559 +VERTEX_SE3:QUAT 4787 19.830968 32.010930 -5.944942 0.1007427 -0.5682021 0.6253017 0.5253524 +VERTEX_SE3:QUAT 4788 20.735676 32.319232 -5.454014 0.3503644 0.5880751 0.3645733 0.6312676 +VERTEX_SE3:QUAT 4789 21.534908 32.660154 -4.903680 0.4784215 0.1712028 0.7273288 0.4612973 +VERTEX_SE3:QUAT 4790 22.173792 33.002291 -4.299352 0.0353786 0.5288623 0.0567437 0.8460693 +VERTEX_SE3:QUAT 4791 22.858761 33.253057 -3.700200 -0.7240972 0.5051347 -0.4632926 0.0766951 +VERTEX_SE3:QUAT 4792 23.416769 33.612274 -3.064553 0.5412298 -0.7141095 0.4434460 0.0217632 +VERTEX_SE3:QUAT 4793 24.055094 33.838282 -2.561472 0.6007850 -0.0838427 0.7197966 0.3375213 +VERTEX_SE3:QUAT 4794 24.818952 34.311843 -1.964781 0.8180032 -0.2737294 0.5009147 0.0709045 +VERTEX_SE3:QUAT 4795 25.532901 34.890829 -1.234769 0.7173178 0.3405887 -0.0078401 0.6077772 +VERTEX_SE3:QUAT 4796 26.127068 35.541605 -0.616000 0.5122672 -0.2704392 0.7902901 0.1997158 +VERTEX_SE3:QUAT 4797 26.697190 36.226933 0.019424 0.9454060 0.2538427 -0.0388643 0.2006514 +VERTEX_SE3:QUAT 4798 27.305248 36.754244 0.538634 -0.1409305 0.1240826 -0.9626666 0.1949745 +VERTEX_SE3:QUAT 4799 27.775485 37.599356 1.112578 -0.1817931 0.2719711 -0.8589738 0.3938871 +VERTEX_SE3:QUAT 4800 16.887228 26.182501 -9.170547 0.6517155 0.0244194 0.4630678 0.6001990 +VERTEX_SE3:QUAT 4801 17.429374 26.871560 -8.618408 0.6296784 0.7457540 -0.0443302 0.2130514 +VERTEX_SE3:QUAT 4802 18.116693 27.495909 -8.232127 -0.0699467 0.9476931 -0.1955620 0.2423648 +VERTEX_SE3:QUAT 4803 18.631495 28.324388 -7.772050 -0.4394866 0.5075903 -0.7403413 0.0331414 +VERTEX_SE3:QUAT 4804 19.104018 28.870539 -7.091621 -0.1058193 -0.2983487 0.7235856 0.6133630 +VERTEX_SE3:QUAT 4805 19.512155 29.426011 -6.422763 0.7355702 -0.4380116 0.3218934 0.4043105 +VERTEX_SE3:QUAT 4806 19.886918 29.986173 -5.709741 -0.2359581 0.8319033 -0.1756278 0.4705481 +VERTEX_SE3:QUAT 4807 20.497830 30.667555 -4.927879 -0.1406969 0.7682481 -0.4494725 0.4335594 +VERTEX_SE3:QUAT 4808 21.146933 31.139818 -4.380121 0.7705256 -0.0683871 0.1952231 0.6029108 +VERTEX_SE3:QUAT 4809 21.742151 31.761300 -3.684666 -0.1275034 0.8369423 -0.1600539 0.5075954 +VERTEX_SE3:QUAT 4810 22.084191 32.271399 -2.882688 0.2217545 -0.7946851 0.5155729 0.2312685 +VERTEX_SE3:QUAT 4811 22.636317 32.728030 -1.921811 0.5457742 -0.5228342 0.4702981 0.4556256 +VERTEX_SE3:QUAT 4812 23.305991 33.265031 -1.264386 0.7069423 -0.1010303 0.1646672 0.6803750 +VERTEX_SE3:QUAT 4813 23.809132 33.736710 -0.620305 0.3293438 -0.4993601 0.2473340 0.7622323 +VERTEX_SE3:QUAT 4814 24.427368 34.053598 -0.206326 0.3876415 0.2138567 0.8964917 0.0173763 +VERTEX_SE3:QUAT 4815 25.066085 34.494044 0.322684 0.7591655 0.4439152 -0.4327346 0.1983626 +VERTEX_SE3:QUAT 4816 25.635358 35.118716 0.661652 0.7649793 0.5655738 -0.2388311 0.1946604 +VERTEX_SE3:QUAT 4817 26.306236 35.584906 1.208710 0.2437923 0.5754024 -0.7050577 0.3352179 +VERTEX_SE3:QUAT 4818 26.917626 36.086229 1.631259 0.1013113 0.4391626 -0.8130819 0.3684699 +VERTEX_SE3:QUAT 4819 27.599317 36.719228 2.128452 0.7434844 0.2932917 0.2288128 0.5557479 +VERTEX_SE3:QUAT 4820 27.168976 36.404922 3.049748 0.0012364 0.0702739 0.7454847 0.6628067 +VERTEX_SE3:QUAT 4821 26.615860 35.947445 2.631460 0.5238077 0.2185124 0.8048354 0.1735447 +VERTEX_SE3:QUAT 4822 25.928030 35.557572 2.249135 0.0095546 -0.6857797 0.5147120 0.5144769 +VERTEX_SE3:QUAT 4823 25.328037 35.069550 1.838428 0.0799666 -0.3188630 0.7730488 0.5425194 +VERTEX_SE3:QUAT 4824 24.543105 34.441411 1.201399 -0.2192161 0.3905996 -0.7724921 0.4501469 +VERTEX_SE3:QUAT 4825 23.927210 33.965719 0.744993 0.1351677 0.5435398 -0.7563764 0.3379186 +VERTEX_SE3:QUAT 4826 23.201486 33.383414 0.245443 0.8420253 -0.3902174 0.1910694 0.3197129 +VERTEX_SE3:QUAT 4827 22.433596 32.763032 -0.134150 0.7146455 -0.3498498 0.2073500 0.5691159 +VERTEX_SE3:QUAT 4828 21.841662 32.448694 -0.489644 0.0017178 0.8959981 -0.2764860 0.3474766 +VERTEX_SE3:QUAT 4829 21.089546 31.992326 -0.922488 -0.1818513 0.3424247 0.2343772 0.8914834 +VERTEX_SE3:QUAT 4830 20.359914 31.357818 -1.411850 -0.1050379 0.0418775 -0.8368752 0.5355867 +VERTEX_SE3:QUAT 4831 19.873358 30.760347 -1.747962 -0.1951647 0.9002116 -0.2630412 0.2869479 +VERTEX_SE3:QUAT 4832 19.185595 29.856947 -2.156304 0.7917114 -0.5435079 0.2740025 0.0521032 +VERTEX_SE3:QUAT 4833 18.715189 29.298067 -2.550299 0.1146722 -0.6236631 0.7102329 0.3057185 +VERTEX_SE3:QUAT 4834 18.071458 28.683642 -3.116793 0.7079304 0.6858046 -0.0837531 0.1466016 +VERTEX_SE3:QUAT 4835 17.339176 27.970707 -3.291579 0.5715877 0.4286659 -0.3867562 0.5830546 +VERTEX_SE3:QUAT 4836 16.850526 27.200922 -3.607816 -0.2760701 0.8253369 -0.4435874 0.2140900 +VERTEX_SE3:QUAT 4837 16.245438 26.510115 -3.886897 0.3850544 -0.0206883 0.1113374 0.9159198 +VERTEX_SE3:QUAT 4838 15.635374 25.746328 -4.280729 0.7286967 -0.2557907 0.5502659 0.3174582 +VERTEX_SE3:QUAT 4839 15.004923 25.006840 -4.424243 -0.2489242 0.4014567 0.1125571 0.8741855 +VERTEX_SE3:QUAT 4840 14.436102 25.253635 -3.617981 0.2894725 0.3534033 -0.7037264 0.5441332 +VERTEX_SE3:QUAT 4841 15.169468 26.102666 -3.247601 0.1650786 0.7004047 0.0875599 0.6888509 +VERTEX_SE3:QUAT 4842 15.587554 26.867413 -2.955051 -0.3694078 -0.4244591 -0.8245440 0.0591577 +VERTEX_SE3:QUAT 4843 16.110830 27.513856 -2.729522 0.6747302 0.4645732 0.2316212 0.5246546 +VERTEX_SE3:QUAT 4844 16.625236 28.279995 -2.557712 0.5969423 0.3552805 -0.5891884 0.4126655 +VERTEX_SE3:QUAT 4845 17.210731 29.061038 -2.113198 -0.2900952 0.0098062 -0.9458644 0.1452212 +VERTEX_SE3:QUAT 4846 17.708287 29.910430 -2.010213 -0.5258622 0.3546961 -0.6246013 0.4555577 +VERTEX_SE3:QUAT 4847 18.519257 30.587057 -1.720731 0.3850855 -0.4767655 0.7824163 0.1105825 +VERTEX_SE3:QUAT 4848 19.261617 31.485333 -1.356080 0.3025531 0.3464788 -0.3329699 0.8231313 +VERTEX_SE3:QUAT 4849 19.712046 32.131985 -1.116628 0.3985635 -0.0329118 -0.7431219 0.5365014 +VERTEX_SE3:QUAT 4850 20.304482 32.855003 -0.776082 -0.0502431 -0.4533580 0.8899083 0.0022965 +VERTEX_SE3:QUAT 4851 20.966758 33.612866 -0.431328 0.6755858 0.0158220 -0.2720215 0.6850824 +VERTEX_SE3:QUAT 4852 21.510018 34.351140 -0.375707 -0.4345299 0.5991252 -0.2776782 0.6124766 +VERTEX_SE3:QUAT 4853 21.924128 35.113421 -0.100106 -0.5680442 0.6281014 -0.5314904 0.0182300 +VERTEX_SE3:QUAT 4854 22.299161 35.980414 0.210368 0.3173899 0.8271544 0.1024739 0.4523034 +VERTEX_SE3:QUAT 4855 22.746746 36.800904 0.613524 0.5175662 -0.1987591 0.2741363 0.7857922 +VERTEX_SE3:QUAT 4856 23.372256 37.774962 0.643766 -0.0043476 -0.4769010 0.8073932 0.3473656 +VERTEX_SE3:QUAT 4857 23.965791 38.584047 0.751013 0.6946345 0.5228168 0.4930988 0.0316080 +VERTEX_SE3:QUAT 4858 24.438922 39.434004 1.067183 0.1567677 0.4198680 -0.4693074 0.7608451 +VERTEX_SE3:QUAT 4859 25.004353 40.108742 1.306938 -0.4282418 0.8228058 -0.1392893 0.3466959 +VERTEX_SE3:QUAT 4860 24.833381 40.165781 2.228014 -0.7591378 0.1232264 -0.6276998 0.1204902 +VERTEX_SE3:QUAT 4861 24.225478 39.158621 2.045428 0.3545857 -0.1225922 0.2499673 0.8926122 +VERTEX_SE3:QUAT 4862 23.549489 38.320676 1.916522 0.4246064 0.3493413 0.8340937 0.0442474 +VERTEX_SE3:QUAT 4863 23.168495 37.480253 1.879944 0.3560389 -0.6538287 0.4392013 0.5028386 +VERTEX_SE3:QUAT 4864 22.726513 36.659664 1.690441 -0.5565243 0.3326381 -0.1365654 0.7489877 +VERTEX_SE3:QUAT 4865 22.519517 35.701089 1.522132 0.3413571 0.2678604 -0.5520734 0.7119980 +VERTEX_SE3:QUAT 4866 22.201525 34.779806 1.333779 -0.5224429 0.0575791 -0.6811632 0.5096614 +VERTEX_SE3:QUAT 4867 21.845292 33.811327 1.075002 0.9714624 0.1338345 0.0932316 0.1722123 +VERTEX_SE3:QUAT 4868 21.574493 32.999907 0.640840 -0.3583883 0.6681365 0.0655820 0.6487299 +VERTEX_SE3:QUAT 4869 21.080827 32.085610 0.210469 0.6193784 -0.2507769 0.6793747 0.3032019 +VERTEX_SE3:QUAT 4870 20.587055 31.370229 -0.068823 0.2249536 0.2847777 -0.2423685 0.8997528 +VERTEX_SE3:QUAT 4871 20.165839 30.211833 -0.257087 -0.4946616 0.0636855 -0.8536861 0.1499139 +VERTEX_SE3:QUAT 4872 19.510208 29.508914 -0.442056 0.3562792 -0.2086450 0.5457231 0.7291905 +VERTEX_SE3:QUAT 4873 18.878186 28.818413 -0.695314 0.5221562 0.3214901 0.7642906 0.1996417 +VERTEX_SE3:QUAT 4874 18.228172 28.131808 -1.043112 -0.6982201 0.5169466 -0.4941990 0.0319709 +VERTEX_SE3:QUAT 4875 17.676820 27.257026 -1.302349 0.6223235 -0.6571611 0.2958066 0.3055342 +VERTEX_SE3:QUAT 4876 17.056036 26.407821 -1.613836 0.4466980 0.7445756 0.4545758 0.1985671 +VERTEX_SE3:QUAT 4877 16.496438 25.517202 -1.827774 -0.0875856 -0.3675700 0.6585731 0.6507707 +VERTEX_SE3:QUAT 4878 15.657321 24.908087 -2.228914 0.1544791 0.2869081 -0.7890628 0.5207685 +VERTEX_SE3:QUAT 4879 15.086181 24.132815 -2.557478 0.4507417 -0.7722934 0.2819970 0.3476672 +VERTEX_SE3:QUAT 4880 14.535970 24.205908 -1.665606 -0.1164279 -0.1355235 -0.8481572 0.4987057 +VERTEX_SE3:QUAT 4881 15.190994 24.803350 -1.236568 -0.2682064 -0.2172427 0.9250136 0.1588102 +VERTEX_SE3:QUAT 4882 16.066085 25.453148 -0.789890 0.4510062 -0.5247985 0.4532731 0.5618928 +VERTEX_SE3:QUAT 4883 16.716372 26.297792 -0.325012 0.8757135 0.2595073 -0.2956131 0.2799905 +VERTEX_SE3:QUAT 4884 17.339642 26.796396 0.105255 0.3298763 -0.3117667 0.8192515 0.3504427 +VERTEX_SE3:QUAT 4885 17.995735 27.250703 0.722539 0.5609991 0.0965830 0.5943047 0.5681142 +VERTEX_SE3:QUAT 4886 18.524351 27.955309 1.184366 0.2098386 -0.6052459 0.1940286 0.7429657 +VERTEX_SE3:QUAT 4887 19.317668 28.484870 1.672163 0.2022000 0.4087428 -0.7413442 0.4923954 +VERTEX_SE3:QUAT 4888 19.976053 28.970506 2.111582 -0.1474679 -0.1698249 -0.8914152 0.3934358 +VERTEX_SE3:QUAT 4889 20.382952 29.444267 2.631734 -0.3148452 -0.3028469 0.6456020 0.6263819 +VERTEX_SE3:QUAT 4890 21.044918 30.004296 3.187366 0.4608848 0.5480438 -0.5654990 0.4091993 +VERTEX_SE3:QUAT 4891 21.845107 30.435009 3.958121 -0.0015988 -0.8123680 0.5100713 0.2826358 +VERTEX_SE3:QUAT 4892 22.532906 30.808289 4.538849 -0.3659318 -0.3540624 0.8034862 0.3084537 +VERTEX_SE3:QUAT 4893 23.442013 30.959453 5.180442 0.5954506 -0.5548920 0.1335966 0.5654072 +VERTEX_SE3:QUAT 4894 24.340256 31.278524 5.844769 0.3059809 0.0232111 -0.4256225 0.8512828 +VERTEX_SE3:QUAT 4895 25.226384 31.821861 6.351536 0.4795267 0.4811463 -0.1173752 0.7244139 +VERTEX_SE3:QUAT 4896 25.922223 32.110658 7.009651 0.2572376 -0.3748504 -0.1753005 0.8732615 +VERTEX_SE3:QUAT 4897 26.559261 32.190005 7.791409 0.0578662 -0.0336345 -0.8402053 0.5381220 +VERTEX_SE3:QUAT 4898 27.262612 32.466869 8.306307 0.1360298 -0.8897771 0.4009210 0.1704550 +VERTEX_SE3:QUAT 4899 27.939024 32.781621 8.721500 0.3049006 0.0133822 -0.3222675 0.8961028 +VERTEX_SE3:QUAT 4900 27.351964 33.005037 9.450166 -0.0566543 -0.7975585 0.3165635 0.5103707 +VERTEX_SE3:QUAT 4901 26.646530 32.737918 8.699818 0.4901226 0.5560990 0.0544284 0.6690077 +VERTEX_SE3:QUAT 4902 25.822405 32.567532 8.259416 -0.0183151 -0.2664932 0.6853104 0.6774921 +VERTEX_SE3:QUAT 4903 24.823974 32.329120 7.822411 -0.4151233 0.7046139 -0.5136720 0.2594860 +VERTEX_SE3:QUAT 4904 24.028201 32.025541 7.367158 0.1507439 0.9009530 -0.1516041 0.3775926 +VERTEX_SE3:QUAT 4905 23.233091 31.746924 6.789910 0.5924759 -0.6130104 0.4953542 0.1667774 +VERTEX_SE3:QUAT 4906 22.550955 31.584463 6.300033 -0.1657233 0.5724375 -0.4364859 0.6740409 +VERTEX_SE3:QUAT 4907 21.800129 31.416265 5.767819 -0.4423604 -0.7801478 0.4083136 0.1701958 +VERTEX_SE3:QUAT 4908 21.079078 30.988644 5.125014 0.7286958 -0.2036199 0.4200692 0.5010822 +VERTEX_SE3:QUAT 4909 20.505514 30.562500 4.578649 0.0758611 -0.2832091 0.1912321 0.9367326 +VERTEX_SE3:QUAT 4910 19.666466 30.296770 3.967245 -0.0413201 0.5501439 0.1846229 0.8133564 +VERTEX_SE3:QUAT 4911 18.953809 29.850350 3.486561 0.1123663 0.4075848 0.2760576 0.8631574 +VERTEX_SE3:QUAT 4912 18.380729 29.462746 2.795548 -0.0562088 -0.1266399 0.8579620 0.4946758 +VERTEX_SE3:QUAT 4913 17.790490 28.882143 2.255776 0.4185535 0.5099394 -0.7493905 0.0564688 +VERTEX_SE3:QUAT 4914 17.106452 28.384943 1.648037 -0.1760834 -0.6334460 0.7375005 0.1543820 +VERTEX_SE3:QUAT 4915 16.480768 27.994513 1.163808 0.7794587 -0.4611273 -0.0796597 0.4164855 +VERTEX_SE3:QUAT 4916 15.886602 27.496728 0.447065 0.4705652 -0.3240429 0.1665911 0.8036243 +VERTEX_SE3:QUAT 4917 15.087862 27.252689 -0.252043 0.0015205 -0.3185187 0.3911255 0.8634607 +VERTEX_SE3:QUAT 4918 14.717821 26.876203 -0.697932 0.6344928 -0.4352804 -0.0004988 0.6387094 +VERTEX_SE3:QUAT 4919 14.076738 26.394222 -1.327182 0.2197911 -0.4234519 -0.2650144 0.8379425 +VERTEX_SE3:QUAT 4920 13.332187 26.912667 -0.835932 0.1609220 -0.5000931 -0.0488741 0.8494836 +VERTEX_SE3:QUAT 4921 14.095741 27.255959 -0.312078 0.1295859 0.0614763 -0.5243811 0.8393167 +VERTEX_SE3:QUAT 4922 14.924025 27.559951 0.418882 -0.0101399 -0.3244067 0.2709796 0.9062161 +VERTEX_SE3:QUAT 4923 15.527599 27.919954 1.099027 0.7532326 -0.4418244 -0.2599300 0.4121507 +VERTEX_SE3:QUAT 4924 16.129241 28.294874 1.866236 0.7028799 -0.4951712 0.3555470 0.3665402 +VERTEX_SE3:QUAT 4925 16.836798 28.712109 2.494999 0.8445107 0.0338542 -0.4922383 0.2082234 +VERTEX_SE3:QUAT 4926 17.460053 29.068778 3.378242 0.1941957 -0.2457148 -0.0926624 0.9451592 +VERTEX_SE3:QUAT 4927 18.416921 29.443209 3.976212 0.5649574 0.2158463 0.1435531 0.7833429 +VERTEX_SE3:QUAT 4928 19.181438 29.788516 4.746734 -0.5908606 0.1023097 -0.7945112 0.0957520 +VERTEX_SE3:QUAT 4929 19.679344 30.201128 5.422837 0.6865603 -0.5307468 -0.3113488 0.3873044 +VERTEX_SE3:QUAT 4930 20.248677 30.491290 6.135791 0.3301007 0.2863663 -0.5535605 0.7089419 +VERTEX_SE3:QUAT 4931 20.995869 30.768543 6.613295 -0.3371186 -0.2337518 0.1162991 0.9045362 +VERTEX_SE3:QUAT 4932 21.726298 31.108356 7.398333 -0.1742727 -0.2882807 0.6004180 0.7252734 +VERTEX_SE3:QUAT 4933 22.310642 31.270484 7.958153 0.0837448 -0.2080101 0.8044128 0.5501261 +VERTEX_SE3:QUAT 4934 22.826674 31.748343 8.684079 -0.5267026 -0.4741443 0.4466550 0.5461418 +VERTEX_SE3:QUAT 4935 23.400107 31.949005 9.547573 0.0878260 0.0290212 -0.5422135 0.8351341 +VERTEX_SE3:QUAT 4936 23.834014 32.520996 10.419884 0.6022053 0.1168450 0.6995440 0.3665163 +VERTEX_SE3:QUAT 4937 24.209554 33.073809 11.171289 0.0094973 0.1611909 -0.8525221 0.4971252 +VERTEX_SE3:QUAT 4938 24.404572 33.786222 11.893984 0.4459287 0.3885751 0.1861301 0.7845461 +VERTEX_SE3:QUAT 4939 24.696483 34.472908 12.402825 0.1843689 -0.0318290 -0.6569051 0.7303908 +VERTEX_SE3:QUAT 4940 23.775856 34.858387 12.359733 0.3261119 -0.0753628 -0.8925657 0.3021554 +VERTEX_SE3:QUAT 4941 23.605592 34.210643 11.701583 0.4127613 -0.2935348 0.7755596 0.3767927 +VERTEX_SE3:QUAT 4942 23.309716 33.540514 11.095192 -0.0111152 0.1754533 -0.9821779 0.0664766 +VERTEX_SE3:QUAT 4943 22.990386 32.977029 10.345100 0.0378579 -0.2305840 0.6792203 0.6957425 +VERTEX_SE3:QUAT 4944 22.695995 32.414349 9.589439 -0.4835856 -0.1956270 0.4400133 0.7309332 +VERTEX_SE3:QUAT 4945 22.524484 31.881226 8.705905 0.4753786 -0.5342046 -0.5716201 0.4023569 +VERTEX_SE3:QUAT 4946 22.338522 31.299126 7.793079 0.5230147 0.1432811 -0.2969470 0.7859699 +VERTEX_SE3:QUAT 4947 22.097148 30.691355 6.958004 -0.5080810 -0.4425981 0.4754183 0.5656306 +VERTEX_SE3:QUAT 4948 21.860348 30.389920 6.349718 0.2984888 -0.5251713 0.2505464 0.7565223 +VERTEX_SE3:QUAT 4949 21.614016 29.725117 5.528278 0.8371069 0.0478814 -0.3828378 0.3878074 +VERTEX_SE3:QUAT 4950 21.366704 29.242186 4.708166 0.5596299 0.1857580 -0.1805095 0.7872259 +VERTEX_SE3:QUAT 4951 21.236869 28.688400 4.049576 0.0201753 0.1761362 -0.1123430 0.9777260 +VERTEX_SE3:QUAT 4952 21.212789 28.457893 3.243068 -0.1369821 -0.5387343 0.8304579 0.0366193 +VERTEX_SE3:QUAT 4953 21.034901 28.063604 2.511774 -0.3411340 0.4347335 -0.6223097 0.5544051 +VERTEX_SE3:QUAT 4954 20.842377 27.750436 1.664097 -0.0328660 -0.2382614 0.4150150 0.8774474 +VERTEX_SE3:QUAT 4955 20.823433 27.287448 0.896666 0.0913031 0.6400933 -0.1628589 0.7452659 +VERTEX_SE3:QUAT 4956 20.729701 26.690342 0.161296 0.1669110 0.7959570 -0.2172900 0.5397947 +VERTEX_SE3:QUAT 4957 20.521457 26.220793 -0.779269 0.3030206 -0.6103301 0.5581821 0.4734010 +VERTEX_SE3:QUAT 4958 20.393001 25.789005 -1.796344 -0.0343485 -0.3253415 0.7680019 0.5505871 +VERTEX_SE3:QUAT 4959 20.073245 25.162942 -2.650026 0.8725787 0.1946573 -0.2189208 0.3908819 +VERTEX_SE3:QUAT 4960 19.201789 25.568177 -2.563335 -0.3013390 -0.5508988 0.7781402 0.0142541 +VERTEX_SE3:QUAT 4961 19.484906 26.211890 -1.610207 -0.1546596 0.2362971 -0.7744907 0.5660462 +VERTEX_SE3:QUAT 4962 19.707437 26.834589 -0.788242 -0.0892448 0.0049740 -0.9420577 0.3233232 +VERTEX_SE3:QUAT 4963 19.770413 27.251421 -0.026488 0.2745657 -0.1999890 0.5004548 0.7963436 +VERTEX_SE3:QUAT 4964 20.044448 27.643483 0.841465 0.0086481 0.5142882 -0.7589263 0.3993292 +VERTEX_SE3:QUAT 4965 20.229097 28.079336 1.751224 -0.4356135 -0.4500674 0.6502732 0.4299128 +VERTEX_SE3:QUAT 4966 20.370561 28.579961 2.689460 0.8768986 0.1403878 -0.4422304 0.1255877 +VERTEX_SE3:QUAT 4967 20.654234 29.180292 3.588933 0.6974545 -0.5589257 0.2305798 0.3846977 +VERTEX_SE3:QUAT 4968 20.763420 29.653752 4.278162 0.3921827 0.2471194 -0.2342575 0.8545456 +VERTEX_SE3:QUAT 4969 20.950588 30.211189 5.133647 0.3799584 0.0688890 0.9190482 0.0789704 +VERTEX_SE3:QUAT 4970 21.204763 30.679937 5.856144 -0.4277595 0.0039997 -0.9035098 0.0259969 +VERTEX_SE3:QUAT 4971 21.430774 31.079592 6.806953 0.3000455 0.4941741 -0.5653489 0.5883411 +VERTEX_SE3:QUAT 4972 21.366963 31.558214 7.676428 0.4057339 -0.2825193 0.0344257 0.8685492 +VERTEX_SE3:QUAT 4973 21.433883 32.015946 8.690177 0.2318795 -0.0940714 0.9549537 0.1595179 +VERTEX_SE3:QUAT 4974 21.404879 32.360403 9.719585 0.6586655 -0.3953924 0.3085719 0.5608993 +VERTEX_SE3:QUAT 4975 21.685805 32.651964 10.725180 0.3772353 0.4532265 0.1411809 0.7952026 +VERTEX_SE3:QUAT 4976 21.947941 33.001359 11.753254 0.5080028 -0.1844240 -0.8246666 0.1668711 +VERTEX_SE3:QUAT 4977 22.141010 33.615053 12.702392 0.0247926 0.4781704 -0.7561423 0.4460797 +VERTEX_SE3:QUAT 4978 22.288118 34.113832 13.483635 0.2773289 0.8200692 -0.4154467 0.2792474 +VERTEX_SE3:QUAT 4979 22.621492 34.529366 14.209432 0.6425070 0.0718593 -0.0450729 0.7615703 +VERTEX_SE3:QUAT 4980 21.671641 34.596539 14.560087 -0.4533292 0.0083618 -0.8696670 0.1951973 +VERTEX_SE3:QUAT 4981 21.231902 34.308517 13.858480 0.1894787 -0.5462436 0.1957321 0.7920889 +VERTEX_SE3:QUAT 4982 20.829684 33.940832 13.015818 0.7529674 -0.1435694 -0.1321794 0.6284556 +VERTEX_SE3:QUAT 4983 20.573172 33.633463 12.135989 0.2147276 0.6908785 -0.6839081 0.0940672 +VERTEX_SE3:QUAT 4984 20.400138 33.173151 11.188494 0.5244527 -0.1608806 0.3849065 0.7422356 +VERTEX_SE3:QUAT 4985 19.789304 32.828824 10.201019 0.1069325 0.2520872 0.3223511 0.9061497 +VERTEX_SE3:QUAT 4986 19.453313 32.309540 9.622391 0.2752250 0.3476101 0.7720323 0.4553950 +VERTEX_SE3:QUAT 4987 19.163221 32.029179 8.798677 0.0225282 -0.0473467 0.6018526 0.7968841 +VERTEX_SE3:QUAT 4988 18.923335 31.580688 7.841414 0.6692047 -0.5236924 0.1354313 0.5094798 +VERTEX_SE3:QUAT 4989 18.548616 31.299181 6.979708 0.8004375 -0.2052012 0.5631958 0.0016757 +VERTEX_SE3:QUAT 4990 18.257146 30.739414 6.078080 -0.1986103 0.7167891 -0.2705700 0.6111950 +VERTEX_SE3:QUAT 4991 17.856073 30.350164 5.265290 0.2385921 -0.8435636 0.3704834 0.3069467 +VERTEX_SE3:QUAT 4992 17.425041 29.747365 4.418091 -0.1416581 -0.2326553 0.2484841 0.9295484 +VERTEX_SE3:QUAT 4993 17.035927 29.324708 3.708933 0.1509362 -0.0584022 0.9155664 0.3681652 +VERTEX_SE3:QUAT 4994 16.884907 28.950137 2.800388 0.7150577 -0.4884364 0.3881120 0.3154228 +VERTEX_SE3:QUAT 4995 16.663696 28.436064 2.109225 -0.2196046 -0.5328656 0.4302102 0.6948002 +VERTEX_SE3:QUAT 4996 16.378453 27.941038 1.262334 -0.1219988 -0.1228842 -0.2554837 0.9511803 +VERTEX_SE3:QUAT 4997 15.981200 27.302369 0.482128 0.1430018 -0.3998718 -0.0700401 0.9026336 +VERTEX_SE3:QUAT 4998 15.714412 26.804188 -0.508851 0.4653214 0.1984727 -0.3806196 0.7740887 +VERTEX_SE3:QUAT 4999 15.274466 26.247366 -1.345162 0.0296881 0.0348086 -0.9985351 0.0288898 +VERTEX_SE3:QUAT 5000 14.483001 26.285609 -0.949676 -0.1924098 -0.4496980 0.8482488 0.2030375 +VERTEX_SE3:QUAT 5001 14.838637 26.836872 -0.208974 0.6570015 0.0643657 -0.6603194 0.3580284 +VERTEX_SE3:QUAT 5002 14.964627 27.485130 0.587666 -0.2023979 0.5064260 -0.6567750 0.5207825 +VERTEX_SE3:QUAT 5003 15.189245 28.150012 1.320667 -0.0310702 0.0920909 0.0188618 0.9950870 +VERTEX_SE3:QUAT 5004 15.398504 28.749708 1.944845 0.6209843 -0.6566715 0.4157303 0.1016336 +VERTEX_SE3:QUAT 5005 15.672737 29.355691 2.573360 0.0071535 -0.4911291 0.7634855 0.4193219 +VERTEX_SE3:QUAT 5006 15.790105 30.027714 3.390144 0.3803067 0.0874202 -0.9153736 0.0990743 +VERTEX_SE3:QUAT 5007 15.891662 30.505408 4.151327 -0.0117617 0.7147929 -0.2528326 0.6519267 +VERTEX_SE3:QUAT 5008 16.082331 31.013008 5.085233 0.1098967 -0.0835083 -0.8618176 0.4880773 +VERTEX_SE3:QUAT 5009 16.294735 31.598686 5.832616 -0.0625325 -0.1627366 0.9601005 0.2186631 +VERTEX_SE3:QUAT 5010 16.675089 32.097029 6.673566 -0.1113669 0.1290126 -0.3439170 0.9234036 +VERTEX_SE3:QUAT 5011 16.763854 32.698346 7.363220 -0.1621169 -0.6254731 0.5026588 0.5743133 +VERTEX_SE3:QUAT 5012 16.944285 33.334690 8.115730 -0.3033196 0.8883553 -0.3147509 0.1405487 +VERTEX_SE3:QUAT 5013 17.056446 33.570149 8.847961 -0.4803401 0.6357583 -0.5286196 0.2926535 +VERTEX_SE3:QUAT 5014 17.294987 34.112069 9.728938 -0.2897042 0.4023776 -0.8200780 0.2857197 +VERTEX_SE3:QUAT 5015 17.408981 34.506750 10.478802 -0.2180484 -0.6398770 0.7037528 0.2185047 +VERTEX_SE3:QUAT 5016 17.756953 35.033987 11.393985 0.4389212 0.4730332 -0.6027559 0.4693327 +VERTEX_SE3:QUAT 5017 18.011080 35.444533 12.109621 0.5966295 -0.7432470 0.2824459 0.1088186 +VERTEX_SE3:QUAT 5018 18.300494 35.856628 12.848549 0.5383648 0.5944075 -0.2311527 0.5508281 +VERTEX_SE3:QUAT 5019 18.713969 36.047038 13.693512 -0.3358237 0.2474773 -0.7616737 0.4958131 +VERTEX_SE3:QUAT 5020 17.836551 36.012493 14.112096 -0.2210071 0.2683903 -0.0571311 0.9358731 +VERTEX_SE3:QUAT 5021 17.421300 35.570634 13.243414 0.2701218 0.2475242 -0.9301705 0.0234284 +VERTEX_SE3:QUAT 5022 17.098568 35.203314 12.376314 0.0050049 0.1902427 -0.2229181 0.9560806 +VERTEX_SE3:QUAT 5023 16.814511 34.816199 11.422372 0.5286212 -0.7511352 0.3850573 0.0899251 +VERTEX_SE3:QUAT 5024 16.572372 34.480398 10.418777 0.4936474 0.3039446 -0.7726193 0.2588231 +VERTEX_SE3:QUAT 5025 16.233466 34.125731 9.533621 0.2360851 -0.3615713 0.9014227 0.0310977 +VERTEX_SE3:QUAT 5026 15.840816 33.845894 8.765288 0.7630271 0.4274008 0.2818846 0.3945368 +VERTEX_SE3:QUAT 5027 15.425669 33.609075 8.051011 -0.3222894 0.9245897 -0.1897189 0.0725967 +VERTEX_SE3:QUAT 5028 15.262188 33.296166 7.208205 0.0133019 0.9753985 -0.1638491 0.1468821 +VERTEX_SE3:QUAT 5029 15.072704 32.962128 6.425899 0.3514971 0.3286730 0.2938270 0.8258871 +VERTEX_SE3:QUAT 5030 14.541156 32.843846 5.644418 0.7646252 0.5871325 0.0947382 0.2482910 +VERTEX_SE3:QUAT 5031 14.062525 32.514825 4.799218 0.1928258 0.8869537 -0.3320790 0.2566220 +VERTEX_SE3:QUAT 5032 13.508612 32.355238 3.736767 0.5587604 0.6990459 -0.3137380 0.3173170 +VERTEX_SE3:QUAT 5033 12.966477 32.147058 2.928159 0.0371729 0.5114010 -0.8512531 0.1116033 +VERTEX_SE3:QUAT 5034 12.518360 31.865570 1.974415 0.0692887 -0.8746635 0.4517651 0.1614653 +VERTEX_SE3:QUAT 5035 11.659517 31.806518 1.221707 0.1831495 0.0219920 -0.7279301 0.6603714 +VERTEX_SE3:QUAT 5036 11.092613 31.600580 0.415910 -0.1030596 0.3449898 -0.9016374 0.2396052 +VERTEX_SE3:QUAT 5037 10.697356 31.333727 -0.401961 0.0995122 -0.0738207 0.9816083 0.1452342 +VERTEX_SE3:QUAT 5038 10.160507 30.931935 -1.226238 0.5293101 0.4496098 -0.6961327 0.1818822 +VERTEX_SE3:QUAT 5039 9.591137 30.648467 -2.134143 0.7071790 -0.5258397 0.2659235 0.3907368 +VERTEX_SE3:QUAT 5040 8.703884 30.540043 -1.573639 0.1623152 0.3950516 0.4625614 0.7769330 +VERTEX_SE3:QUAT 5041 9.144507 30.957639 -0.960732 -0.0361096 0.9648974 -0.2144384 0.1472593 +VERTEX_SE3:QUAT 5042 9.561259 31.296074 -0.375190 0.4746997 0.1352517 0.6202771 0.6096093 +VERTEX_SE3:QUAT 5043 10.162499 31.708414 0.545075 -0.3888876 0.1232797 -0.7345915 0.5421658 +VERTEX_SE3:QUAT 5044 10.641940 32.188265 1.273969 0.8198302 0.4248203 -0.0625372 0.3788077 +VERTEX_SE3:QUAT 5045 10.929023 32.594147 2.175605 0.2846506 0.6419327 0.2153998 0.6786010 +VERTEX_SE3:QUAT 5046 11.104457 32.820938 2.897926 -0.2179233 0.4248660 -0.6253569 0.6171929 +VERTEX_SE3:QUAT 5047 11.598588 33.326816 3.517981 0.7681478 0.5241587 0.2538601 0.2660107 +VERTEX_SE3:QUAT 5048 12.126510 33.604981 4.250569 0.4048596 -0.5281734 0.5883531 0.4593061 +VERTEX_SE3:QUAT 5049 12.656970 34.106150 5.112859 0.4071848 0.5206239 0.3761849 0.6493352 +VERTEX_SE3:QUAT 5050 13.151037 34.725779 5.877005 -0.0821307 0.9871876 -0.0257979 0.1343488 +VERTEX_SE3:QUAT 5051 13.625386 35.035795 6.526641 0.3060686 -0.5033119 0.7867974 0.1842523 +VERTEX_SE3:QUAT 5052 14.259734 35.271645 7.210674 -0.5842543 0.0684067 -0.6664137 0.4581050 +VERTEX_SE3:QUAT 5053 14.786578 35.651837 7.922924 0.4421904 -0.8899695 0.1114157 0.0029122 +VERTEX_SE3:QUAT 5054 15.441916 35.923583 8.642890 0.0722173 0.2868660 0.5990497 0.7440645 +VERTEX_SE3:QUAT 5055 16.046209 36.322040 9.349287 0.9720390 -0.0937501 -0.0425077 0.2110549 +VERTEX_SE3:QUAT 5056 16.568466 36.920843 10.196332 0.7002251 0.6854161 -0.1611187 0.1180268 +VERTEX_SE3:QUAT 5057 17.148655 37.185945 10.988871 0.4742513 0.3409671 -0.3109041 0.7497771 +VERTEX_SE3:QUAT 5058 17.636715 37.383310 11.835771 0.9181407 -0.0207080 -0.2618550 0.2966830 +VERTEX_SE3:QUAT 5059 18.088623 37.579352 12.627948 0.8870299 -0.0021485 0.0664694 0.4568974 +VERTEX_SE3:QUAT 5060 17.394184 37.326304 12.896528 -0.5498448 0.5702565 -0.3050590 0.5285992 +VERTEX_SE3:QUAT 5061 17.120257 36.945410 12.088500 0.5228993 0.7713383 -0.2317783 0.2790920 +VERTEX_SE3:QUAT 5062 16.594758 36.722326 11.373132 0.4779852 0.2290928 -0.1462819 0.8352534 +VERTEX_SE3:QUAT 5063 16.094462 36.351716 10.525161 0.6744244 0.2413028 0.5156567 0.4701307 +VERTEX_SE3:QUAT 5064 15.613577 36.036033 9.734210 0.4555931 0.1878701 -0.8595722 0.1351863 +VERTEX_SE3:QUAT 5065 15.151230 35.737276 8.764629 -0.0342722 0.5677488 -0.4401753 0.6947895 +VERTEX_SE3:QUAT 5066 14.883178 35.329061 7.938664 -0.5653916 0.6696518 -0.4403952 0.1948098 +VERTEX_SE3:QUAT 5067 14.442878 35.026478 6.970380 0.2259889 0.1656753 -0.3152281 0.9067039 +VERTEX_SE3:QUAT 5068 13.666232 34.829292 6.020399 0.5485211 0.3305592 0.2763963 0.7165614 +VERTEX_SE3:QUAT 5069 13.172403 34.343211 5.293390 0.5064024 -0.0035315 0.2305227 0.8309052 +VERTEX_SE3:QUAT 5070 12.586871 34.134664 4.503971 0.2350998 -0.3244461 0.0430981 0.9152078 +VERTEX_SE3:QUAT 5071 12.080954 33.751900 3.853801 0.6248050 -0.2450768 0.4228573 0.6088906 +VERTEX_SE3:QUAT 5072 11.428095 33.302758 3.235316 0.1380178 0.8621563 -0.2837942 0.3963565 +VERTEX_SE3:QUAT 5073 10.915600 32.884079 2.430466 0.4684928 0.2548212 -0.6130023 0.5829312 +VERTEX_SE3:QUAT 5074 10.408158 32.616337 1.598176 0.7371084 0.6194279 -0.0492983 0.2656123 +VERTEX_SE3:QUAT 5075 10.019244 32.226994 0.795835 -0.0315792 -0.9248202 0.3644817 0.1042275 +VERTEX_SE3:QUAT 5076 9.502909 31.811014 0.136653 0.1932021 0.2853106 0.6647592 0.6628469 +VERTEX_SE3:QUAT 5077 8.921135 31.297740 -0.693312 -0.7968090 0.0024427 -0.5732326 0.1910337 +VERTEX_SE3:QUAT 5078 8.403876 30.898822 -1.413140 -0.4128515 0.5415165 -0.3707764 0.6315365 +VERTEX_SE3:QUAT 5079 7.973641 30.202098 -2.121489 0.3996270 0.7136154 0.2169525 0.5329005 +VERTEX_SE3:QUAT 5080 7.297673 30.005923 -1.423638 0.4729076 0.0444009 0.6797652 0.5588437 +VERTEX_SE3:QUAT 5081 7.916444 30.429367 -0.751182 0.5062626 0.5796162 -0.2455103 0.5894641 +VERTEX_SE3:QUAT 5082 8.555207 31.022908 -0.200464 0.1064320 -0.0498094 0.4840433 0.8671179 +VERTEX_SE3:QUAT 5083 9.299762 31.398338 0.250306 0.6177384 0.1606248 0.2967457 0.7103105 +VERTEX_SE3:QUAT 5084 10.083243 32.024455 0.758167 0.7113092 -0.6899543 0.0729205 0.1126272 +VERTEX_SE3:QUAT 5085 10.936337 32.700261 0.995716 -0.5055105 0.3621705 -0.7070569 0.3366930 +VERTEX_SE3:QUAT 5086 11.617432 33.370239 1.312757 0.7158334 -0.2182667 0.3641416 0.5543854 +VERTEX_SE3:QUAT 5087 12.505507 33.824022 1.641800 0.7698357 0.0441524 -0.2562619 0.5828665 +VERTEX_SE3:QUAT 5088 13.345938 34.455595 2.155998 0.0473419 0.0293068 0.0411898 0.9975987 +VERTEX_SE3:QUAT 5089 14.044589 35.064030 2.450100 0.8671171 -0.3649821 0.1565969 0.3006218 +VERTEX_SE3:QUAT 5090 14.901375 35.486864 2.966362 0.4247268 -0.7332994 0.4829724 0.2204922 +VERTEX_SE3:QUAT 5091 15.739553 35.985244 3.285695 0.2418602 0.3942934 -0.2745137 0.8430175 +VERTEX_SE3:QUAT 5092 16.672176 36.372751 3.617445 0.6453414 -0.2313151 0.5726032 0.4496147 +VERTEX_SE3:QUAT 5093 17.378459 36.617415 4.127737 0.4771310 0.2227270 -0.8208240 0.2213293 +VERTEX_SE3:QUAT 5094 18.179854 37.005271 4.461566 0.5280616 0.4300961 0.6365683 0.3618688 +VERTEX_SE3:QUAT 5095 18.908266 37.579594 4.868063 0.5258957 0.3795295 0.6103942 0.4547637 +VERTEX_SE3:QUAT 5096 19.698165 38.040135 5.362103 0.3384458 0.6731644 -0.5379372 0.3780578 +VERTEX_SE3:QUAT 5097 20.559759 38.346865 5.713079 0.4435503 0.6948645 -0.4222502 0.3770030 +VERTEX_SE3:QUAT 5098 21.295878 38.708882 6.312411 0.3992822 0.6338811 -0.3121857 0.5842162 +VERTEX_SE3:QUAT 5099 22.062146 38.963033 7.045981 0.2312635 0.9006475 -0.2062356 0.3046608 +VERTEX_SE3:QUAT 5100 21.299442 39.019441 7.771134 0.2424734 0.0615790 0.8472303 0.4686315 +VERTEX_SE3:QUAT 5101 20.515432 38.714431 7.229198 0.2030764 -0.5514312 0.7772824 0.2247571 +VERTEX_SE3:QUAT 5102 20.034547 38.428812 6.660094 -0.2221027 0.5644086 -0.6049908 0.5158482 +VERTEX_SE3:QUAT 5103 19.396184 38.180174 6.087954 0.8362176 0.0800118 0.5313931 0.1093603 +VERTEX_SE3:QUAT 5104 18.660645 37.836314 5.550286 -0.3269216 0.2937094 -0.8900864 0.1208438 +VERTEX_SE3:QUAT 5105 17.873304 37.532038 4.899495 0.3067708 0.7352542 -0.6043437 0.0078570 +VERTEX_SE3:QUAT 5106 17.066127 37.140155 4.427686 0.1496984 0.5995309 0.2653960 0.7400797 +VERTEX_SE3:QUAT 5107 16.346259 37.057350 3.766717 0.4945770 0.0355085 0.7013086 0.5121514 +VERTEX_SE3:QUAT 5108 15.274683 36.843013 3.251755 0.6446943 -0.4535188 0.5508694 0.2742861 +VERTEX_SE3:QUAT 5109 14.474956 36.600776 2.644825 -0.0392240 -0.1324648 0.3951737 0.9081587 +VERTEX_SE3:QUAT 5110 13.595298 36.474219 2.200252 0.1665038 -0.8754426 0.4249312 0.1590919 +VERTEX_SE3:QUAT 5111 12.790212 36.652539 1.618199 0.3760579 0.2926058 0.1568046 0.8650865 +VERTEX_SE3:QUAT 5112 11.742615 36.814464 1.149934 0.8358228 -0.4312073 0.2916131 0.1744200 +VERTEX_SE3:QUAT 5113 10.685580 36.749353 0.839808 0.2176952 0.1849863 -0.3795226 0.8799724 +VERTEX_SE3:QUAT 5114 9.842771 36.920783 0.684026 -0.3588637 0.8601879 -0.2583065 0.2541091 +VERTEX_SE3:QUAT 5115 8.922648 36.789287 0.533873 0.1052128 -0.2552245 0.0674710 0.9587692 +VERTEX_SE3:QUAT 5116 7.985366 36.764170 0.393232 -0.0780082 -0.7940596 0.5929991 0.1083331 +VERTEX_SE3:QUAT 5117 7.160935 36.880942 0.360094 0.6117217 -0.3654446 0.4280620 0.5558865 +VERTEX_SE3:QUAT 5118 6.380871 36.988248 0.154644 0.9207115 -0.2293764 -0.2109126 0.2349312 +VERTEX_SE3:QUAT 5119 5.447456 37.238481 0.051345 0.4695415 -0.2192737 -0.8420454 0.1496977 +VERTEX_SE3:QUAT 5120 5.314330 37.267500 1.129341 0.2866316 0.0846347 0.1487588 0.9426294 +VERTEX_SE3:QUAT 5121 6.367519 37.180536 1.174390 0.5492254 -0.1154219 0.1331904 0.8168780 +VERTEX_SE3:QUAT 5122 7.275935 37.248289 1.145939 0.7364474 0.4720322 0.0258664 0.4839026 +VERTEX_SE3:QUAT 5123 8.155106 36.972595 1.415180 -0.2533783 -0.1778332 0.9257380 0.2172186 +VERTEX_SE3:QUAT 5124 9.103146 36.626091 1.680263 0.5759901 0.4715093 -0.2975880 0.5977924 +VERTEX_SE3:QUAT 5125 10.047705 36.300291 1.792229 0.3252938 -0.3867023 0.6458815 0.5722607 +VERTEX_SE3:QUAT 5126 10.977464 36.082452 1.967648 0.7489027 -0.1179500 -0.4343307 0.4864045 +VERTEX_SE3:QUAT 5127 12.008932 35.818621 2.165160 0.1550871 0.6157722 -0.7698150 0.0644782 +VERTEX_SE3:QUAT 5128 13.130875 35.803920 2.405006 -0.1407263 0.4458618 -0.5330613 0.7051589 +VERTEX_SE3:QUAT 5129 13.935391 35.587004 2.731326 -0.0381013 -0.3605856 0.7209243 0.5905882 +VERTEX_SE3:QUAT 5130 14.874601 35.404374 3.090542 0.5997001 0.0627131 -0.3943262 0.6934939 +VERTEX_SE3:QUAT 5131 15.825693 35.209696 3.293972 0.0944542 -0.0024608 0.2721705 0.9575988 +VERTEX_SE3:QUAT 5132 16.920594 34.997977 3.345812 -0.8524697 -0.1006395 0.5129707 0.0053041 +VERTEX_SE3:QUAT 5133 17.717096 34.769143 3.391361 0.2300302 -0.0131677 -0.5624708 0.7940651 +VERTEX_SE3:QUAT 5134 18.591016 34.481176 3.325772 0.2831298 0.5538747 -0.7328118 0.2757666 +VERTEX_SE3:QUAT 5135 19.482012 34.088549 3.486868 0.0970920 -0.0153103 -0.2514830 0.9628577 +VERTEX_SE3:QUAT 5136 20.440293 34.061977 3.600750 0.1954604 0.9355880 -0.2066797 0.2091741 +VERTEX_SE3:QUAT 5137 21.615715 33.774273 3.653892 0.6357509 0.4657255 -0.5634326 0.2479198 +VERTEX_SE3:QUAT 5138 22.708340 33.804215 3.686371 0.8800737 0.4519479 0.0449552 0.1385368 +VERTEX_SE3:QUAT 5139 23.642445 33.778298 3.778454 -0.1540619 -0.1126766 0.8956577 0.4017042 +VERTEX_SE3:QUAT 5140 23.524239 33.822364 4.717434 0.8053343 0.0872046 0.3817532 0.4450803 +VERTEX_SE3:QUAT 5141 22.580841 33.890182 4.673673 0.7661863 -0.1103593 -0.0167048 0.6328509 +VERTEX_SE3:QUAT 5142 21.679663 33.767813 4.506623 0.5540445 -0.5560418 0.0399594 0.6182681 +VERTEX_SE3:QUAT 5143 20.605249 33.771166 4.313801 0.8695763 0.0127984 -0.4936232 0.0030468 +VERTEX_SE3:QUAT 5144 19.577773 33.619130 4.206677 0.4842297 -0.2730138 -0.3946029 0.7316239 +VERTEX_SE3:QUAT 5145 18.714649 33.346725 4.197278 0.3873784 -0.5290630 0.1135222 0.7464201 +VERTEX_SE3:QUAT 5146 17.960529 33.349536 3.970891 0.1885504 -0.0076418 0.1820910 0.9650043 +VERTEX_SE3:QUAT 5147 16.829901 33.476308 3.875403 -0.0877333 -0.5680658 0.2120994 0.7903277 +VERTEX_SE3:QUAT 5148 15.761842 33.277340 3.844738 -0.0485960 0.8604160 -0.0451921 0.5052528 +VERTEX_SE3:QUAT 5149 14.659575 33.356299 3.965499 0.3369544 -0.6973186 0.6308719 0.0470003 +VERTEX_SE3:QUAT 5150 13.640729 33.410320 3.838300 0.3632072 -0.7316974 0.5758417 0.0332529 +VERTEX_SE3:QUAT 5151 12.517258 33.339219 3.762386 0.5161382 -0.3567601 -0.0195146 0.7784232 +VERTEX_SE3:QUAT 5152 11.588298 33.123982 3.629458 0.4425736 0.3169654 -0.1758671 0.8202026 +VERTEX_SE3:QUAT 5153 10.557168 33.045515 3.801705 0.2232221 -0.8159080 0.4142882 0.3359038 +VERTEX_SE3:QUAT 5154 9.584271 32.838091 3.685716 0.4223819 -0.0708270 0.8776051 0.2153749 +VERTEX_SE3:QUAT 5155 8.708312 32.740216 3.467746 -0.2556644 -0.7931097 0.5264919 0.1685796 +VERTEX_SE3:QUAT 5156 7.754738 32.758332 3.593126 -0.2300994 -0.2308354 0.9146560 0.2391102 +VERTEX_SE3:QUAT 5157 6.844817 33.129429 3.599208 -0.2278135 -0.6438506 0.3614018 0.6347804 +VERTEX_SE3:QUAT 5158 5.758587 33.179627 3.602718 0.6485422 -0.2020454 -0.6762837 0.2849756 +VERTEX_SE3:QUAT 5159 4.630525 33.247654 3.718321 0.0168372 -0.8719722 0.4425197 0.2087036 +VERTEX_SE3:QUAT 5160 4.601186 33.340956 4.550748 0.2310041 0.7189281 0.0749128 0.6512815 +VERTEX_SE3:QUAT 5161 5.643748 33.268865 4.693408 0.7559309 -0.2011884 0.5286598 0.3295611 +VERTEX_SE3:QUAT 5162 6.764477 33.242672 4.788127 0.7694490 -0.4668547 -0.2051490 0.3845892 +VERTEX_SE3:QUAT 5163 7.593922 33.099838 4.822153 -0.1755345 -0.7820132 0.2581987 0.5394224 +VERTEX_SE3:QUAT 5164 8.456744 32.940626 5.009644 -0.6119803 0.3660141 -0.6942917 0.0973287 +VERTEX_SE3:QUAT 5165 9.604648 32.897516 5.140047 -0.1774529 -0.6471766 0.1852755 0.7178759 +VERTEX_SE3:QUAT 5166 10.783853 32.803044 5.405946 0.3175067 0.0285840 0.8211662 0.4733481 +VERTEX_SE3:QUAT 5167 11.634644 32.743206 5.392069 0.7679042 -0.0433473 0.0824995 0.6337491 +VERTEX_SE3:QUAT 5168 12.594576 32.738885 5.596435 0.4883114 0.0997970 0.8623155 0.0894677 +VERTEX_SE3:QUAT 5169 13.627110 32.618991 5.608191 0.6821568 0.4091420 -0.2725378 0.5412837 +VERTEX_SE3:QUAT 5170 14.548926 32.753420 5.579448 0.2292651 -0.4852911 0.6141494 0.5785763 +VERTEX_SE3:QUAT 5171 15.498469 32.601306 5.426254 0.3908932 0.1481524 0.2512628 0.8729950 +VERTEX_SE3:QUAT 5172 16.527452 32.389568 5.460053 0.4765102 0.2446550 0.0947113 0.8391137 +VERTEX_SE3:QUAT 5173 17.589511 32.466000 5.495084 0.5397574 0.6926245 -0.1374100 0.4583139 +VERTEX_SE3:QUAT 5174 18.610248 32.358625 5.562268 -0.3902090 -0.6095957 0.6254502 0.2914483 +VERTEX_SE3:QUAT 5175 19.620088 32.385464 5.667361 0.2180413 0.8906933 -0.2675219 0.2958977 +VERTEX_SE3:QUAT 5176 20.532115 32.345208 5.656365 0.2336160 0.4293540 -0.4285726 0.7598712 +VERTEX_SE3:QUAT 5177 21.525747 32.434466 5.968543 -0.2829754 0.7239137 -0.5201930 0.3539394 +VERTEX_SE3:QUAT 5178 22.552436 32.433836 6.199129 0.2856120 0.2177963 -0.8444747 0.3973072 +VERTEX_SE3:QUAT 5179 23.476747 32.595401 6.261099 0.5098856 0.3599972 0.4121698 0.6637279 +VERTEX_SE3:QUAT 5180 23.103516 32.742085 7.310587 0.3505112 -0.5116660 0.6804791 0.3902410 +VERTEX_SE3:QUAT 5181 21.966626 32.417022 7.246754 -0.0727598 -0.0984643 -0.8294492 0.5449998 +VERTEX_SE3:QUAT 5182 21.093381 32.303368 7.087919 0.4000873 -0.1404504 0.3477182 0.8362392 +VERTEX_SE3:QUAT 5183 20.120359 32.059949 6.669617 0.4635803 0.3726033 0.3701138 0.7136356 +VERTEX_SE3:QUAT 5184 19.262453 31.821153 6.584504 0.0776911 0.5789514 -0.7643753 0.2729648 +VERTEX_SE3:QUAT 5185 18.133574 31.474561 6.279840 0.3312172 -0.0426291 0.7478219 0.5737947 +VERTEX_SE3:QUAT 5186 17.218763 31.178391 6.155173 -0.2070221 -0.2851960 0.9109151 0.2145667 +VERTEX_SE3:QUAT 5187 16.357667 30.766485 5.934078 0.8350678 -0.1188695 0.0124416 0.5370075 +VERTEX_SE3:QUAT 5188 15.384229 30.446858 5.661496 0.0253731 -0.0956524 0.1377963 0.9855044 +VERTEX_SE3:QUAT 5189 14.582233 30.143527 5.571706 0.0856847 -0.4989412 0.6784938 0.5323176 +VERTEX_SE3:QUAT 5190 13.682138 29.895153 5.481687 0.4272287 -0.0152478 -0.3510469 0.8330722 +VERTEX_SE3:QUAT 5191 12.699832 29.527015 5.202917 0.0500366 -0.4575740 0.7183438 0.5216365 +VERTEX_SE3:QUAT 5192 11.537469 29.206945 5.290941 0.8633339 -0.2420072 -0.1392558 0.4203509 +VERTEX_SE3:QUAT 5193 10.482462 28.735948 5.356862 -0.1452774 -0.5774432 0.5277420 0.6057576 +VERTEX_SE3:QUAT 5194 9.638577 28.390156 5.424900 0.1646793 -0.3055199 -0.1689508 0.9224933 +VERTEX_SE3:QUAT 5195 8.881165 27.892964 5.367678 -0.5031803 0.6676456 -0.2977492 0.4608736 +VERTEX_SE3:QUAT 5196 7.869088 27.563420 5.390113 0.0935893 0.2878975 0.1431246 0.9422693 +VERTEX_SE3:QUAT 5197 7.051655 27.010696 5.525289 -0.8133175 0.1942450 -0.5408525 0.0908961 +VERTEX_SE3:QUAT 5198 6.339027 26.783632 5.612387 -0.0339825 0.2475331 -0.9680559 0.0209860 +VERTEX_SE3:QUAT 5199 5.459463 26.069962 5.552424 -0.1981701 0.0933714 -0.9018288 0.3724449 +VERTEX_SE3:QUAT 5200 22.694193 34.063125 7.440978 0.6294078 0.0797116 0.1978652 0.7472224 +VERTEX_SE3:QUAT 5201 21.758674 33.753254 7.191479 0.0035668 0.7552663 -0.4490752 0.4773799 +VERTEX_SE3:QUAT 5202 20.813179 33.212761 7.104063 -0.2689943 0.3799578 -0.6323221 0.6192277 +VERTEX_SE3:QUAT 5203 19.860144 32.828905 6.991036 0.4329853 0.0831929 -0.8578738 0.2639226 +VERTEX_SE3:QUAT 5204 18.874962 32.329059 6.764598 0.3258224 0.1554296 -0.4557222 0.8136330 +VERTEX_SE3:QUAT 5205 17.860744 32.141536 6.567545 0.1870839 0.4061993 -0.8486961 0.2823414 +VERTEX_SE3:QUAT 5206 16.859617 31.676518 6.474839 0.1315024 0.2777153 -0.1875353 0.9329586 +VERTEX_SE3:QUAT 5207 15.922770 31.283864 6.334559 0.7718564 -0.1412891 0.5175963 0.3411293 +VERTEX_SE3:QUAT 5208 14.936017 30.981994 6.379278 0.2342462 -0.5158638 -0.0242467 0.8236658 +VERTEX_SE3:QUAT 5209 14.146634 30.510889 6.484426 0.8938290 -0.2886606 -0.0070943 0.3430663 +VERTEX_SE3:QUAT 5210 13.164686 30.007132 6.385388 -0.0780722 -0.6200196 0.7627610 0.1663612 +VERTEX_SE3:QUAT 5211 12.110436 29.640365 6.321849 0.3137376 0.1192513 -0.7547336 0.5636710 +VERTEX_SE3:QUAT 5212 11.217151 28.984588 6.216702 0.1090496 0.5571381 0.3464365 0.7467845 +VERTEX_SE3:QUAT 5213 10.315169 28.500175 5.968016 0.0556964 0.2251571 0.9659009 0.1150547 +VERTEX_SE3:QUAT 5214 9.517586 27.873326 5.846039 0.8071109 -0.2180559 -0.2260404 0.4999293 +VERTEX_SE3:QUAT 5215 8.488494 27.360907 5.791720 0.3405750 0.0197661 -0.3911042 0.8547839 +VERTEX_SE3:QUAT 5216 7.755473 26.760760 5.738194 -0.1798516 0.7113676 -0.6343273 0.2433893 +VERTEX_SE3:QUAT 5217 6.837593 26.163433 5.636535 -0.0671425 0.3137332 -0.0133370 0.9470404 +VERTEX_SE3:QUAT 5218 5.945943 25.703627 5.471806 0.5861768 0.4249275 0.5095896 0.4649213 +VERTEX_SE3:QUAT 5219 5.224518 25.018388 5.304562 -0.0112542 -0.2322710 0.5555725 0.7982874 +VERTEX_SE3:QUAT 5220 5.435577 24.952060 4.291649 0.4530781 -0.5188464 0.6292281 0.3599871 +VERTEX_SE3:QUAT 5221 6.207297 25.816227 4.663957 0.2476080 0.8513636 -0.4532835 0.0916756 +VERTEX_SE3:QUAT 5222 6.896635 26.424281 5.213919 -0.1327958 0.5410327 -0.7623546 0.3293393 +VERTEX_SE3:QUAT 5223 7.670828 26.907818 5.574640 -0.4751126 0.4689793 -0.6267946 0.4018145 +VERTEX_SE3:QUAT 5224 8.547656 27.412604 5.993270 0.5750602 0.3266729 0.5254324 0.5352675 +VERTEX_SE3:QUAT 5225 9.258678 27.844667 6.345051 0.8861611 -0.0737598 0.4524898 0.0673118 +VERTEX_SE3:QUAT 5226 9.981368 28.310064 6.570104 0.0969988 0.1647387 -0.6841608 0.7038298 +VERTEX_SE3:QUAT 5227 10.778467 28.953558 6.849514 0.4598689 -0.2500588 0.8421574 0.1294686 +VERTEX_SE3:QUAT 5228 11.547180 29.663889 7.267711 0.8413300 0.4198265 0.1251594 0.3166145 +VERTEX_SE3:QUAT 5229 12.560352 30.060849 7.291735 0.3620478 -0.5291063 0.7550135 0.1375592 +VERTEX_SE3:QUAT 5230 13.606895 30.468401 7.554800 0.2688286 0.2005496 -0.8595605 0.3855734 +VERTEX_SE3:QUAT 5231 14.506987 30.938921 7.769887 0.0284657 0.3173269 -0.9415052 0.1098236 +VERTEX_SE3:QUAT 5232 15.337369 31.167241 7.890359 -0.1344360 0.2155344 -0.5222592 0.8140744 +VERTEX_SE3:QUAT 5233 16.391569 31.253881 8.143730 -0.2069082 0.2550928 -0.4901006 0.8074144 +VERTEX_SE3:QUAT 5234 17.336784 31.382242 8.379626 -0.3292029 0.6621809 -0.6596378 0.1342385 +VERTEX_SE3:QUAT 5235 18.389880 31.472971 8.676531 0.7089935 0.3663772 0.3248098 0.5075377 +VERTEX_SE3:QUAT 5236 19.334118 31.724529 9.083699 0.3059757 0.0440318 -0.4799673 0.8210185 +VERTEX_SE3:QUAT 5237 20.139884 32.053840 9.530230 0.4615693 -0.2990351 -0.1854428 0.8143358 +VERTEX_SE3:QUAT 5238 20.948874 32.151309 9.911062 0.7033253 0.3166908 0.1867137 0.6084229 +VERTEX_SE3:QUAT 5239 21.921040 32.283807 10.308734 0.9401838 0.2179559 0.0913543 0.2453652 +VERTEX_SE3:QUAT 5240 22.485037 32.038627 9.288717 0.6592196 -0.0670494 -0.6316517 0.4024301 +VERTEX_SE3:QUAT 5241 21.563740 31.862791 8.739229 0.1309495 0.2272054 0.3070176 0.9148607 +VERTEX_SE3:QUAT 5242 20.383122 31.645693 8.525605 0.0378453 0.6392961 -0.4731219 0.6049991 +VERTEX_SE3:QUAT 5243 19.308414 31.419225 8.301834 -0.5846081 0.5261596 -0.5992554 0.1492727 +VERTEX_SE3:QUAT 5244 18.384317 31.486695 8.264949 -0.7179490 0.2025221 -0.6232499 0.2347203 +VERTEX_SE3:QUAT 5245 17.689140 31.604176 8.131864 -0.1654314 -0.6387777 0.6169416 0.4289272 +VERTEX_SE3:QUAT 5246 16.717754 31.591794 7.749222 0.1370300 -0.2782670 -0.0064520 0.9506570 +VERTEX_SE3:QUAT 5247 15.807215 31.603698 7.488601 -0.2155007 0.9731062 0.0768084 0.0269103 +VERTEX_SE3:QUAT 5248 14.745417 31.575069 7.097041 0.4819585 0.0788091 0.5226891 0.6987856 +VERTEX_SE3:QUAT 5249 13.880242 31.398396 6.680721 0.9308345 0.2295764 0.2567039 0.1222494 +VERTEX_SE3:QUAT 5250 12.863888 31.147154 6.380161 -0.7907929 0.5179313 -0.2968260 0.1352334 +VERTEX_SE3:QUAT 5251 12.078617 30.989736 5.909179 -0.1746152 0.5891248 -0.7808045 0.1130741 +VERTEX_SE3:QUAT 5252 11.025517 30.781304 5.480030 0.2977595 0.3550846 0.2035463 0.8624518 +VERTEX_SE3:QUAT 5253 10.243212 30.366908 5.212648 0.5565994 -0.1801240 0.1513734 0.7967676 +VERTEX_SE3:QUAT 5254 9.306818 30.041555 5.048641 0.1227843 0.0913981 -0.8705132 0.4677362 +VERTEX_SE3:QUAT 5255 8.471180 29.797531 4.612249 0.5333476 -0.5285886 0.1302019 0.6474426 +VERTEX_SE3:QUAT 5256 7.549822 29.668380 4.397646 0.5431580 0.2545926 0.2478753 0.7607364 +VERTEX_SE3:QUAT 5257 6.625734 29.593897 3.890367 0.6549316 0.6353260 0.0320355 0.4079207 +VERTEX_SE3:QUAT 5258 5.940879 29.418729 3.506194 0.5144601 -0.6626218 -0.0712166 0.5396215 +VERTEX_SE3:QUAT 5259 5.132469 29.229244 3.146302 0.0837702 0.8962919 -0.4353800 0.0093635 +VERTEX_SE3:QUAT 5260 5.656800 29.261578 2.300302 0.8500852 -0.3051751 -0.2077601 0.3755783 +VERTEX_SE3:QUAT 5261 6.499781 29.543314 2.946351 0.0832938 -0.2551844 -0.0769858 0.9602168 +VERTEX_SE3:QUAT 5262 7.433700 29.849011 3.291569 0.5793823 -0.6975975 0.4152569 0.0723571 +VERTEX_SE3:QUAT 5263 8.274575 30.003490 3.598222 0.6491990 0.1703578 -0.5845663 0.4558520 +VERTEX_SE3:QUAT 5264 9.317212 30.155478 3.978799 0.8421926 -0.0216351 -0.4114436 0.3477897 +VERTEX_SE3:QUAT 5265 10.131513 30.474998 4.171478 0.4506812 0.7758336 -0.0283485 0.4406417 +VERTEX_SE3:QUAT 5266 10.993219 30.441132 4.638364 0.0709870 0.5271103 0.2052076 0.8215872 +VERTEX_SE3:QUAT 5267 11.754345 30.530409 4.968037 -0.5399481 -0.3586698 0.7274740 0.2249302 +VERTEX_SE3:QUAT 5268 12.729764 30.670181 5.180312 0.0783946 0.5191059 -0.5174926 0.6757105 +VERTEX_SE3:QUAT 5269 13.791784 30.901642 5.546044 0.1930731 -0.8031657 0.5163942 0.2257977 +VERTEX_SE3:QUAT 5270 14.607369 31.066106 5.782724 0.7496790 0.0759104 -0.5859305 0.2981684 +VERTEX_SE3:QUAT 5271 15.491441 31.527529 6.011885 0.9114434 0.2180578 0.0352468 0.3471014 +VERTEX_SE3:QUAT 5272 16.471533 31.954860 6.065530 0.8309469 -0.4214555 0.3368150 0.1358606 +VERTEX_SE3:QUAT 5273 17.377197 32.424051 6.256951 0.6116640 0.1729621 0.1640108 0.7543552 +VERTEX_SE3:QUAT 5274 18.254078 32.728061 6.563249 -0.5105423 0.7675401 -0.3109090 0.2314395 +VERTEX_SE3:QUAT 5275 19.108624 33.198862 7.087052 0.2248096 -0.7031825 0.6707252 0.0715725 +VERTEX_SE3:QUAT 5276 19.992799 33.479594 7.244332 0.6565065 0.1108512 0.6630848 0.3420962 +VERTEX_SE3:QUAT 5277 20.991531 33.910826 7.617542 0.4847277 -0.0292676 -0.4348994 0.7583172 +VERTEX_SE3:QUAT 5278 21.705382 34.447447 8.096450 0.9042625 -0.2766378 0.0547287 0.3206019 +VERTEX_SE3:QUAT 5279 22.571426 34.777505 8.784511 0.7354433 0.3806944 0.0056288 0.5605027 +VERTEX_SE3:QUAT 5280 22.929782 34.803964 7.928440 0.5494949 -0.7674793 0.0296239 0.3288667 +VERTEX_SE3:QUAT 5281 22.157080 34.284301 7.489515 -0.2274785 -0.0806300 -0.9379712 0.2489223 +VERTEX_SE3:QUAT 5282 21.397667 33.890602 6.910606 -0.1530594 0.8721457 -0.3154357 0.3412257 +VERTEX_SE3:QUAT 5283 20.694072 33.509365 6.393399 0.5048470 -0.1672341 0.2919643 0.7949334 +VERTEX_SE3:QUAT 5284 19.920957 33.060649 6.018279 -0.2000948 0.5978364 0.0893592 0.7710828 +VERTEX_SE3:QUAT 5285 19.322853 32.599082 5.553571 0.4754330 -0.2819579 -0.0532983 0.8316385 +VERTEX_SE3:QUAT 5286 18.733721 32.086562 4.960286 0.9296134 -0.1615643 -0.0798003 0.3214775 +VERTEX_SE3:QUAT 5287 17.945664 31.474689 4.554769 -0.1001068 0.4616608 -0.6462114 0.5993820 +VERTEX_SE3:QUAT 5288 17.054964 30.813840 3.938482 0.4339746 0.1668371 -0.6418980 0.6097528 +VERTEX_SE3:QUAT 5289 16.275930 30.297148 3.533810 0.6100822 -0.7425441 0.2130892 0.1761276 +VERTEX_SE3:QUAT 5290 15.367225 29.805277 3.214724 0.9898231 -0.0412375 0.0452298 0.1284676 +VERTEX_SE3:QUAT 5291 14.572254 29.519529 2.786899 0.5302146 0.3184689 0.7542216 0.2204538 +VERTEX_SE3:QUAT 5292 13.731629 29.134152 2.497981 0.1819754 -0.8996861 0.3954205 0.0330530 +VERTEX_SE3:QUAT 5293 12.917150 28.808398 1.972827 0.4420729 0.2767048 -0.1794512 0.8341482 +VERTEX_SE3:QUAT 5294 12.053185 28.460500 1.541646 -0.2446161 0.6695258 -0.7009463 0.0239253 +VERTEX_SE3:QUAT 5295 11.358509 28.267659 1.275170 0.2447730 0.7087000 -0.3266741 0.5754255 +VERTEX_SE3:QUAT 5296 10.447369 27.857104 0.876792 0.1734863 -0.4314874 0.6169818 0.6348658 +VERTEX_SE3:QUAT 5297 9.521075 27.652478 0.405455 0.2629490 0.6774377 -0.4137900 0.5483738 +VERTEX_SE3:QUAT 5298 8.600139 27.392876 -0.091478 0.6506547 0.1987311 -0.4343824 0.5903104 +VERTEX_SE3:QUAT 5299 7.700532 27.298075 -0.604781 0.7234515 0.1502093 0.5356467 0.4088248 +VERTEX_SE3:QUAT 5300 8.159128 27.540713 -1.553447 0.3843028 0.5652075 0.3908184 0.6165330 +VERTEX_SE3:QUAT 5301 9.039351 27.741527 -1.180573 0.7240323 0.4537870 0.3442678 0.3890169 +VERTEX_SE3:QUAT 5302 9.878007 28.008471 -0.910133 0.7145872 0.1400763 0.6563143 0.1974724 +VERTEX_SE3:QUAT 5303 10.733952 28.103500 -0.729560 0.8195313 0.4450252 0.3082182 0.1879428 +VERTEX_SE3:QUAT 5304 11.600121 28.235944 -0.488550 -0.0043271 -0.3796910 0.8404690 0.3865591 +VERTEX_SE3:QUAT 5305 12.523442 28.191962 -0.069161 0.5163330 -0.0424970 0.4663291 0.7170296 +VERTEX_SE3:QUAT 5306 13.429591 28.177736 0.300555 -0.6040216 0.1345297 -0.6884537 0.3782739 +VERTEX_SE3:QUAT 5307 14.278495 28.310449 0.773732 -0.1566223 0.1012707 -0.9190836 0.3471298 +VERTEX_SE3:QUAT 5308 15.216852 28.550203 1.161962 -0.1905509 -0.9786751 -0.0523420 0.0560860 +VERTEX_SE3:QUAT 5309 16.065399 28.800813 1.447565 -0.5958643 0.6462305 -0.4648344 0.1061172 +VERTEX_SE3:QUAT 5310 16.936180 28.964645 1.968311 0.5380916 -0.4225363 -0.2620138 0.6806389 +VERTEX_SE3:QUAT 5311 17.755087 29.224256 2.390578 0.5404277 0.1511919 -0.0810154 0.8237205 +VERTEX_SE3:QUAT 5312 18.556390 29.253942 2.907979 0.0995067 -0.5783452 0.7057196 0.3969573 +VERTEX_SE3:QUAT 5313 19.569377 29.450106 3.322334 0.8219853 -0.3455138 0.2737424 0.3605904 +VERTEX_SE3:QUAT 5314 20.454065 29.653408 3.661102 0.4326109 0.0358082 0.2880316 0.8535827 +VERTEX_SE3:QUAT 5315 21.188478 29.945018 4.156350 0.2897063 -0.7161151 0.4471650 0.4508801 +VERTEX_SE3:QUAT 5316 22.066674 30.107932 4.578733 0.4394379 0.1850231 -0.5309129 0.7005656 +VERTEX_SE3:QUAT 5317 22.848378 30.385770 5.020055 -0.9629500 -0.1072982 0.2311604 0.0882007 +VERTEX_SE3:QUAT 5318 23.742185 30.390652 5.625532 -0.2700154 -0.7729204 0.5307118 0.2191592 +VERTEX_SE3:QUAT 5319 24.751685 30.599270 6.017912 0.7942896 0.1411092 -0.5908318 0.0104875 +VERTEX_SE3:QUAT 5320 25.067226 30.874280 4.981526 0.8171501 0.3662171 -0.2715270 0.3527377 +VERTEX_SE3:QUAT 5321 24.141623 30.796077 4.581987 -0.2133523 0.2711848 -0.7379231 0.5800078 +VERTEX_SE3:QUAT 5322 23.285408 30.570873 4.195219 -0.8704452 -0.4859463 0.0557021 0.0554855 +VERTEX_SE3:QUAT 5323 22.528818 30.449122 3.671719 0.1911988 0.7338887 -0.6133638 0.2205340 +VERTEX_SE3:QUAT 5324 21.708693 30.473018 3.309520 0.4543466 0.2877963 -0.7803518 0.3190510 +VERTEX_SE3:QUAT 5325 20.871545 30.557544 2.821146 -0.2494616 0.8628187 -0.1673990 0.4065592 +VERTEX_SE3:QUAT 5326 20.033115 30.335122 2.364234 0.2272923 0.1837698 -0.8860426 0.3598546 +VERTEX_SE3:QUAT 5327 19.048619 30.028228 2.098843 0.3877927 0.7526003 -0.5051776 0.1673477 +VERTEX_SE3:QUAT 5328 18.310343 29.990471 1.715265 0.1266698 0.6157206 -0.7776352 0.0112426 +VERTEX_SE3:QUAT 5329 17.427301 29.866393 1.230585 0.6285713 0.4562859 0.3512426 0.5228096 +VERTEX_SE3:QUAT 5330 16.522189 29.868080 0.556585 -0.9794520 0.1057693 -0.1255328 0.1171674 +VERTEX_SE3:QUAT 5331 15.677144 29.872688 0.064104 -0.0045705 -0.5885930 0.7776779 0.2208041 +VERTEX_SE3:QUAT 5332 14.982672 29.826758 -0.415187 0.1878188 -0.6759539 0.0826801 0.7077955 +VERTEX_SE3:QUAT 5333 14.085806 29.818871 -0.966171 -0.0633990 0.5623299 -0.5130350 0.6454151 +VERTEX_SE3:QUAT 5334 13.320213 29.546149 -1.287400 -0.0238581 0.3735424 -0.7947792 0.4777268 +VERTEX_SE3:QUAT 5335 12.367729 29.243241 -1.817182 0.0208936 -0.8530252 0.4500400 0.2633923 +VERTEX_SE3:QUAT 5336 11.479024 28.861052 -2.228299 0.1116756 -0.2424874 0.5142771 0.8150138 +VERTEX_SE3:QUAT 5337 10.555846 28.682865 -2.598847 0.8963295 0.3666615 0.2469526 0.0341645 +VERTEX_SE3:QUAT 5338 9.375678 28.604280 -2.840362 0.0604322 -0.6098740 0.5654462 0.5519712 +VERTEX_SE3:QUAT 5339 8.626572 28.488940 -3.321157 0.2651926 -0.5349404 0.0144146 0.8020622 +VERTEX_SE3:QUAT 5340 9.023639 28.881346 -4.208790 0.5568351 0.6166332 0.2819215 0.4798107 +VERTEX_SE3:QUAT 5341 9.921732 28.859235 -3.786009 0.8476737 -0.2226713 0.3745900 0.3025708 +VERTEX_SE3:QUAT 5342 10.808371 28.995558 -3.327260 0.4846210 -0.0674951 0.8695830 0.0664249 +VERTEX_SE3:QUAT 5343 11.641019 29.026473 -2.939205 0.9810071 0.1669619 -0.0805644 0.0570808 +VERTEX_SE3:QUAT 5344 12.529017 28.959581 -2.604188 -0.1847400 -0.8748733 0.2032093 0.3989658 +VERTEX_SE3:QUAT 5345 13.282008 29.084036 -2.093544 0.7829518 -0.1166988 0.5828756 0.1833685 +VERTEX_SE3:QUAT 5346 14.241681 28.999871 -1.707718 0.4302714 0.7451562 0.2689227 0.4327693 +VERTEX_SE3:QUAT 5347 15.208852 29.033279 -1.194979 0.4400473 0.5552684 -0.6628707 0.2421525 +VERTEX_SE3:QUAT 5348 16.102618 29.104563 -0.743645 0.0434571 -0.9584714 0.2817061 0.0092593 +VERTEX_SE3:QUAT 5349 17.001620 29.163214 -0.190169 0.5079677 0.5837150 -0.6086003 0.1756455 +VERTEX_SE3:QUAT 5350 17.928565 29.187009 0.218447 0.3538924 -0.0436845 0.9326274 0.0552979 +VERTEX_SE3:QUAT 5351 18.811069 29.276708 0.624984 0.0020449 0.9836470 -0.1455031 0.1061284 +VERTEX_SE3:QUAT 5352 19.769097 29.452421 1.248563 -0.6920406 0.2986410 -0.6326684 0.1778317 +VERTEX_SE3:QUAT 5353 20.655654 29.625203 1.779457 0.6135557 -0.3988420 0.3381818 0.5916989 +VERTEX_SE3:QUAT 5354 21.549683 29.824089 2.383113 -0.1938851 0.7392738 -0.6403874 0.0760714 +VERTEX_SE3:QUAT 5355 22.389611 29.743748 3.084280 0.9445822 0.1754543 0.1761920 0.2143284 +VERTEX_SE3:QUAT 5356 23.144125 29.740400 3.622377 0.1173729 0.1802613 0.3156662 0.9241668 +VERTEX_SE3:QUAT 5357 24.082834 29.962276 4.235838 0.9597358 0.2148209 -0.1357943 0.1196626 +VERTEX_SE3:QUAT 5358 24.865879 30.009301 4.911381 0.7357973 0.2897692 -0.3099263 0.5278086 +VERTEX_SE3:QUAT 5359 25.610185 30.397184 5.243416 0.3740002 0.8640557 -0.1850693 0.2815688 +VERTEX_SE3:QUAT 5360 26.035102 30.861821 4.439499 0.6675423 0.1092677 -0.7127836 0.1854385 +VERTEX_SE3:QUAT 5361 25.070482 30.855120 3.992082 0.6546136 -0.1109619 -0.2202680 0.7145981 +VERTEX_SE3:QUAT 5362 24.251956 30.551242 3.194723 0.4913732 -0.2074258 0.7795394 0.3283979 +VERTEX_SE3:QUAT 5363 23.324415 30.425345 2.669940 -0.4362010 -0.6199095 0.6516317 0.0285817 +VERTEX_SE3:QUAT 5364 22.477919 30.347480 2.208138 -0.2661448 0.1387319 -0.9439956 0.1370867 +VERTEX_SE3:QUAT 5365 21.456227 30.144344 1.701549 0.3541925 -0.3262399 0.5119827 0.7113290 +VERTEX_SE3:QUAT 5366 20.540124 30.118843 1.316176 -0.1484666 0.3830270 -0.8154122 0.4078615 +VERTEX_SE3:QUAT 5367 19.678866 29.860611 0.910112 0.0377539 -0.6234464 0.7701392 0.1295175 +VERTEX_SE3:QUAT 5368 18.823654 29.678726 0.469344 0.4578311 0.3162242 -0.1864962 0.8096988 +VERTEX_SE3:QUAT 5369 17.749320 29.489918 0.044325 0.3969778 -0.8865052 0.2118852 0.1078045 +VERTEX_SE3:QUAT 5370 16.683494 29.487845 -0.291058 0.2433784 -0.8124788 0.0012890 0.5297579 +VERTEX_SE3:QUAT 5371 15.818033 29.515346 -0.629868 0.4455873 -0.0998138 0.8466598 0.2732331 +VERTEX_SE3:QUAT 5372 14.766979 29.769265 -0.887766 0.5926961 -0.5489510 -0.1421819 0.5719689 +VERTEX_SE3:QUAT 5373 13.793390 29.782050 -1.070955 0.7495215 -0.1736977 -0.6319520 0.0931840 +VERTEX_SE3:QUAT 5374 12.656027 30.052392 -1.442117 -0.4668033 0.8814108 0.0663206 0.0284824 +VERTEX_SE3:QUAT 5375 11.666454 30.366077 -1.591040 0.6407672 0.4114213 -0.5422718 0.3550933 +VERTEX_SE3:QUAT 5376 10.702970 30.414194 -1.787643 0.4384834 0.4971389 -0.5685857 0.4871300 +VERTEX_SE3:QUAT 5377 9.673799 30.384969 -1.923953 0.8404397 -0.1623552 -0.3145693 0.4103023 +VERTEX_SE3:QUAT 5378 8.545822 30.613544 -2.071285 0.4358649 0.0891039 -0.5240244 0.7262787 +VERTEX_SE3:QUAT 5379 7.458273 30.747856 -2.140241 0.8653577 -0.3980255 -0.1986642 0.2307909 +VERTEX_SE3:QUAT 5380 7.660806 30.937156 -3.286432 -0.9743398 0.1759892 -0.0340074 0.1361370 +VERTEX_SE3:QUAT 5381 8.565275 30.920993 -3.008679 -0.1530823 0.6991450 -0.5945341 0.3664577 +VERTEX_SE3:QUAT 5382 9.627804 30.939884 -3.004454 -0.0453427 0.9642551 -0.2558042 0.0521573 +VERTEX_SE3:QUAT 5383 10.773330 30.936127 -2.971483 0.8505378 0.3644893 -0.2267980 0.3038021 +VERTEX_SE3:QUAT 5384 11.826528 30.918762 -2.796260 0.5080290 -0.3482098 0.6595184 0.4309198 +VERTEX_SE3:QUAT 5385 13.071289 30.727774 -2.536914 0.4184491 -0.5083663 -0.3976744 0.6389985 +VERTEX_SE3:QUAT 5386 14.015901 30.582537 -2.380599 0.2578193 0.0388525 -0.3939195 0.8813893 +VERTEX_SE3:QUAT 5387 15.179171 30.591268 -2.288372 0.6203371 0.5255912 -0.3703606 0.4491868 +VERTEX_SE3:QUAT 5388 16.345813 30.613209 -2.174685 -0.2358607 0.9459801 -0.0136908 0.2220450 +VERTEX_SE3:QUAT 5389 17.403092 30.729629 -2.054457 -0.2122995 -0.7379231 0.5053052 0.3937831 +VERTEX_SE3:QUAT 5390 18.340449 30.952270 -1.915196 0.3659893 0.7420376 -0.0897530 0.5544153 +VERTEX_SE3:QUAT 5391 19.387995 30.961185 -1.576607 0.7256979 0.3920023 -0.5024061 0.2593935 +VERTEX_SE3:QUAT 5392 20.286047 31.081571 -1.418578 -0.6463844 -0.5421927 0.4671491 0.2645489 +VERTEX_SE3:QUAT 5393 21.473533 31.201458 -1.230261 0.2560041 0.5069357 -0.5193646 0.6385441 +VERTEX_SE3:QUAT 5394 22.539039 31.135880 -0.957057 0.3408819 -0.0388071 -0.3448622 0.8737068 +VERTEX_SE3:QUAT 5395 23.557233 31.006576 -0.912409 -0.0715929 -0.2103916 0.9449073 0.2403332 +VERTEX_SE3:QUAT 5396 24.732294 31.098001 -0.662268 -0.7777851 -0.5271184 0.2733358 0.2061166 +VERTEX_SE3:QUAT 5397 25.547812 31.044559 -0.449087 -0.4282309 0.8053005 -0.3459145 0.2201193 +VERTEX_SE3:QUAT 5398 26.472795 30.982702 -0.301562 0.6429901 -0.5818467 0.2070116 0.4529507 +VERTEX_SE3:QUAT 5399 27.452726 31.054039 -0.016093 0.1856076 0.7443187 -0.2808423 0.5767729 +VERTEX_SE3:QUAT 5400 27.501996 31.421831 -0.935180 -0.5353496 0.4009120 -0.7089704 0.2236770 +VERTEX_SE3:QUAT 5401 26.392039 31.441966 -1.195570 0.4032683 -0.7802487 -0.0114914 0.4779691 +VERTEX_SE3:QUAT 5402 25.341210 31.585690 -1.151535 -0.8729697 0.4617826 0.1509027 0.0436927 +VERTEX_SE3:QUAT 5403 24.347655 31.673855 -1.354460 0.8814053 -0.2397184 -0.3999360 0.0755712 +VERTEX_SE3:QUAT 5404 23.409129 31.670177 -1.523393 -0.2151298 0.9317728 -0.2641185 0.1255388 +VERTEX_SE3:QUAT 5405 22.393202 31.754083 -1.600347 -0.1284165 0.6936427 -0.2557618 0.6610257 +VERTEX_SE3:QUAT 5406 21.444500 31.983015 -1.805498 0.7221319 0.0778575 -0.3891200 0.5666122 +VERTEX_SE3:QUAT 5407 20.425739 31.793253 -1.986586 0.7611598 -0.1761109 -0.4483117 0.4343239 +VERTEX_SE3:QUAT 5408 19.458570 31.532707 -2.088226 0.3123284 0.0008382 0.1119400 0.9433556 +VERTEX_SE3:QUAT 5409 18.271775 31.518737 -2.124497 0.3033746 0.3784554 0.4461260 0.7521350 +VERTEX_SE3:QUAT 5410 17.335846 31.310566 -2.164362 -0.7400107 0.4556492 -0.4832455 0.1060272 +VERTEX_SE3:QUAT 5411 16.398259 31.139985 -2.389329 0.7624225 -0.4759075 0.3860796 0.2077655 +VERTEX_SE3:QUAT 5412 15.417673 30.779666 -2.485628 0.2669731 0.4232257 -0.8424019 0.1999112 +VERTEX_SE3:QUAT 5413 14.371560 30.495844 -2.581225 0.3396557 -0.8907521 0.0238110 0.3010443 +VERTEX_SE3:QUAT 5414 13.382232 30.375085 -2.688552 0.2172873 0.0627715 -0.9735492 0.0323705 +VERTEX_SE3:QUAT 5415 12.251057 30.352309 -2.839783 0.2146634 -0.0949597 0.8043600 0.5458089 +VERTEX_SE3:QUAT 5416 11.127041 30.354587 -3.034671 0.5924822 -0.6953748 0.0402040 0.4047252 +VERTEX_SE3:QUAT 5417 10.180794 30.230709 -3.110990 0.7406483 -0.2851464 0.3213151 0.5166123 +VERTEX_SE3:QUAT 5418 9.279214 30.332911 -3.144267 -0.0922786 -0.5899227 0.6524344 0.4666962 +VERTEX_SE3:QUAT 5419 8.381546 30.273882 -3.405850 0.4876334 0.0719887 -0.8416845 0.2204505 +VERTEX_SE3:QUAT 5420 8.532025 30.258461 -4.415305 0.9664470 -0.0647401 0.1794890 0.1719670 +VERTEX_SE3:QUAT 5421 9.638241 30.149397 -4.321660 0.8073130 0.2192032 0.4308503 0.3384727 +VERTEX_SE3:QUAT 5422 10.499887 30.435712 -4.364130 0.3317730 0.0308831 -0.1285500 0.9340491 +VERTEX_SE3:QUAT 5423 11.537575 30.572465 -4.086512 0.0807611 -0.8601344 0.3411955 0.3704486 +VERTEX_SE3:QUAT 5424 12.352950 30.480274 -3.965620 0.3019506 0.1979860 -0.9069716 0.2168640 +VERTEX_SE3:QUAT 5425 13.289108 30.442650 -3.818696 0.6528077 0.6935505 -0.0650171 0.2976618 +VERTEX_SE3:QUAT 5426 14.393558 30.560089 -3.655121 0.6719216 0.4252534 -0.5334538 0.2882844 +VERTEX_SE3:QUAT 5427 15.410059 30.694719 -3.665036 0.4022996 0.1535621 0.8340782 0.3448004 +VERTEX_SE3:QUAT 5428 16.465727 30.828709 -3.439163 -0.0460006 0.6870485 -0.5975523 0.4108280 +VERTEX_SE3:QUAT 5429 17.669834 30.867041 -3.451757 0.4304154 0.0927864 0.4422148 0.7813958 +VERTEX_SE3:QUAT 5430 18.769101 30.765176 -3.361298 0.2314103 -0.0011011 -0.9374472 0.2600785 +VERTEX_SE3:QUAT 5431 19.802747 30.740217 -3.477172 0.4564919 0.1845432 0.2631391 0.8296486 +VERTEX_SE3:QUAT 5432 20.626186 31.024627 -3.329717 0.5212925 -0.0848665 0.4501236 0.7200282 +VERTEX_SE3:QUAT 5433 21.554399 31.257657 -3.330784 0.1682347 0.1172544 -0.4543522 0.8668982 +VERTEX_SE3:QUAT 5434 22.655161 31.456237 -3.162690 0.4933404 -0.2416515 0.7367374 0.3942560 +VERTEX_SE3:QUAT 5435 23.665394 31.677220 -3.096675 0.9007422 0.3143528 0.1943798 0.2281718 +VERTEX_SE3:QUAT 5436 24.699369 31.652704 -2.876626 0.4055449 -0.7645049 0.3463991 0.3620403 +VERTEX_SE3:QUAT 5437 25.767325 31.520081 -2.647159 0.0734830 -0.4869256 0.6389348 0.5909873 +VERTEX_SE3:QUAT 5438 26.734402 31.663060 -2.471627 0.4597333 0.8683669 -0.1858434 0.0068113 +VERTEX_SE3:QUAT 5439 27.826108 31.754686 -2.193758 -0.5683119 -0.3145525 0.7098936 0.2722670 +VERTEX_SE3:QUAT 5440 28.141101 31.891193 -3.028950 0.0862439 -0.4732702 0.4639292 0.7438730 +VERTEX_SE3:QUAT 5441 26.982185 31.943889 -3.359051 0.4445352 -0.1046104 -0.7403159 0.4933330 +VERTEX_SE3:QUAT 5442 26.166687 31.992533 -3.708618 0.5785762 0.0560212 0.8052936 0.1166764 +VERTEX_SE3:QUAT 5443 25.274308 31.953741 -4.200104 0.3571732 0.1589990 -0.4094344 0.8243240 +VERTEX_SE3:QUAT 5444 24.279564 31.765405 -4.747971 0.6500726 0.0350008 -0.6875336 0.3216800 +VERTEX_SE3:QUAT 5445 23.378998 31.703655 -5.188801 0.8390705 0.2813451 0.4004147 0.2376420 +VERTEX_SE3:QUAT 5446 22.475718 31.694153 -5.804743 0.2190080 -0.2148142 0.1308118 0.9427506 +VERTEX_SE3:QUAT 5447 21.606018 31.695017 -6.362085 0.1103469 0.7822845 -0.0862396 0.6069738 +VERTEX_SE3:QUAT 5448 20.642814 31.779191 -6.871337 0.2156116 0.4917331 -0.8302105 0.1498691 +VERTEX_SE3:QUAT 5449 19.929240 31.824730 -7.316926 0.4582531 -0.3745873 -0.3713691 0.7153834 +VERTEX_SE3:QUAT 5450 18.991719 32.176126 -7.705005 -0.0836402 -0.9095095 0.1382939 0.3829773 +VERTEX_SE3:QUAT 5451 18.026612 32.157288 -7.962759 -0.0485179 0.8412874 -0.4853795 0.2329983 +VERTEX_SE3:QUAT 5452 17.114652 31.981279 -8.324189 -0.7243230 -0.3861371 0.5191602 0.2381740 +VERTEX_SE3:QUAT 5453 16.151724 32.012699 -8.797151 0.3108557 0.3691311 0.2184310 0.8481738 +VERTEX_SE3:QUAT 5454 15.217733 31.855371 -9.206944 0.5991450 0.4652154 -0.4339093 0.4861302 +VERTEX_SE3:QUAT 5455 14.210653 31.879720 -9.657700 0.4103908 0.3305865 0.0791544 0.8461835 +VERTEX_SE3:QUAT 5456 13.163677 31.909480 -9.830929 0.9101146 -0.0732752 -0.2812298 0.2953506 +VERTEX_SE3:QUAT 5457 12.151768 31.732138 -10.014765 0.6236514 0.5880054 -0.0300655 0.5142029 +VERTEX_SE3:QUAT 5458 11.322689 31.584834 -10.180810 0.2267804 -0.6024463 0.4965357 0.5823070 +VERTEX_SE3:QUAT 5459 10.224323 31.558355 -10.405517 -0.9968592 0.0297551 -0.0050389 0.0732192 +VERTEX_SE3:QUAT 5460 10.451080 31.715216 -11.207042 0.1050784 -0.2465162 0.5520850 0.7895508 +VERTEX_SE3:QUAT 5461 11.441312 31.790718 -10.745988 0.8422730 -0.0034800 -0.2591217 0.4726733 +VERTEX_SE3:QUAT 5462 12.296852 31.967003 -10.372594 0.5322072 -0.3686697 -0.0276880 0.7616243 +VERTEX_SE3:QUAT 5463 13.165431 32.205645 -10.047657 -0.7263447 0.3723855 -0.5528795 0.1675612 +VERTEX_SE3:QUAT 5464 13.997226 32.411973 -9.794373 -0.5778615 0.7908935 -0.1974535 0.0396959 +VERTEX_SE3:QUAT 5465 15.107579 32.676690 -9.556962 0.5724905 0.7329849 -0.2484048 0.2707078 +VERTEX_SE3:QUAT 5466 15.951374 33.005316 -9.158664 0.2367184 0.6711821 0.3311527 0.6195296 +VERTEX_SE3:QUAT 5467 16.770502 33.438714 -8.796577 0.7672714 0.0837512 -0.0277111 0.6352263 +VERTEX_SE3:QUAT 5468 17.800507 33.757277 -8.605980 0.9866565 0.0023955 0.0743995 0.1448030 +VERTEX_SE3:QUAT 5469 18.738479 34.070234 -8.272595 -0.7776883 0.4373067 -0.4498315 0.0401923 +VERTEX_SE3:QUAT 5470 19.779414 34.222035 -8.114497 0.3825216 0.1139613 -0.0090591 0.9168467 +VERTEX_SE3:QUAT 5471 20.587833 34.568829 -7.955552 0.5892864 -0.1967074 0.7614610 0.1849998 +VERTEX_SE3:QUAT 5472 21.531951 34.776638 -7.793100 0.0734582 -0.2735000 0.1195751 0.9515794 +VERTEX_SE3:QUAT 5473 22.462011 35.078215 -7.556048 -0.7774442 0.4018707 -0.4762282 0.0853654 +VERTEX_SE3:QUAT 5474 23.346843 35.173269 -7.102574 0.2181690 -0.8444040 0.2852784 0.3974927 +VERTEX_SE3:QUAT 5475 24.298505 35.213863 -6.570753 0.4068429 -0.3275740 0.4602267 0.7178896 +VERTEX_SE3:QUAT 5476 24.934885 35.451834 -6.229488 0.3732641 0.2953016 -0.8396890 0.2615210 +VERTEX_SE3:QUAT 5477 25.799979 35.700354 -5.814658 -0.0276445 0.5528490 0.0455246 0.8315776 +VERTEX_SE3:QUAT 5478 26.633560 35.925696 -5.410534 -0.3029168 -0.6625970 0.6741554 0.1213305 +VERTEX_SE3:QUAT 5479 27.588939 36.202466 -5.161276 0.8588920 0.1633465 -0.0450025 0.4833190 +VERTEX_SE3:QUAT 5480 27.751118 36.047690 -5.928760 0.2257432 0.2147110 -0.5377806 0.7834100 +VERTEX_SE3:QUAT 5481 26.771493 35.628973 -6.168600 0.6502109 -0.3262521 0.3518604 0.5890498 +VERTEX_SE3:QUAT 5482 25.842647 35.190036 -6.465421 0.4435765 0.4755793 -0.4639605 0.6015021 +VERTEX_SE3:QUAT 5483 25.053899 34.854037 -6.796319 -0.0911056 -0.3063136 0.6372819 0.7012442 +VERTEX_SE3:QUAT 5484 24.062327 34.401466 -7.180400 0.2271873 0.6575608 -0.4030659 0.5945903 +VERTEX_SE3:QUAT 5485 23.150459 34.105338 -7.442054 0.7158385 -0.0728667 -0.3240847 0.6141944 +VERTEX_SE3:QUAT 5486 22.149490 33.633220 -7.828908 0.9156438 -0.0091556 0.2149380 0.3395796 +VERTEX_SE3:QUAT 5487 21.317215 33.098032 -8.354387 0.7595219 -0.2815532 0.5800166 0.0862264 +VERTEX_SE3:QUAT 5488 20.549215 32.462511 -8.604628 -0.0183640 -0.5368044 0.8159609 0.2138029 +VERTEX_SE3:QUAT 5489 19.923542 31.935083 -8.986498 -0.3852345 0.0731889 -0.7941195 0.4643404 +VERTEX_SE3:QUAT 5490 19.145603 31.533281 -9.268487 0.6353514 0.4690816 0.5233705 0.3199599 +VERTEX_SE3:QUAT 5491 18.391853 30.989847 -9.694320 0.3147452 0.4488698 -0.1986529 0.8123967 +VERTEX_SE3:QUAT 5492 17.760082 30.485255 -10.095757 0.6509240 -0.1093447 -0.4554693 0.5974022 +VERTEX_SE3:QUAT 5493 17.069150 29.898716 -10.454963 -0.0069921 -0.3888650 -0.0772717 0.9180219 +VERTEX_SE3:QUAT 5494 16.320967 29.220440 -10.561392 0.0211318 0.5157465 -0.5674908 0.6414929 +VERTEX_SE3:QUAT 5495 15.519138 28.415580 -10.958147 0.3289495 -0.1586402 0.5813854 0.7270602 +VERTEX_SE3:QUAT 5496 14.946533 27.651376 -11.407274 -0.3937361 0.1052352 -0.9072435 0.1039549 +VERTEX_SE3:QUAT 5497 14.253344 26.869249 -11.990087 0.8156614 -0.0617530 0.2773082 0.5039675 +VERTEX_SE3:QUAT 5498 13.678957 26.247004 -12.388397 0.4358346 0.1477339 0.5414133 0.7036296 +VERTEX_SE3:QUAT 5499 12.995518 25.400345 -13.007137 0.2609629 -0.2440957 0.9338696 0.0142572 +VERTEX_SE3:QUAT 5500 13.856265 25.134348 -13.599521 -0.0483048 -0.4221966 0.7783977 0.4620754 +VERTEX_SE3:QUAT 5501 14.432211 25.516440 -13.073693 0.4714223 -0.8139128 0.2315205 0.2484052 +VERTEX_SE3:QUAT 5502 15.158823 26.010216 -12.617619 0.4737173 -0.1506225 0.7078834 0.5018026 +VERTEX_SE3:QUAT 5503 15.846245 26.497472 -12.170953 0.5179658 0.6195824 -0.5385444 0.2404142 +VERTEX_SE3:QUAT 5504 16.600487 26.862153 -11.713517 0.3707457 0.0745502 0.5531981 0.7422680 +VERTEX_SE3:QUAT 5505 17.150040 27.267299 -11.252926 0.7034392 -0.0974291 0.2340666 0.6639983 +VERTEX_SE3:QUAT 5506 17.848403 27.373644 -10.589586 0.5779043 0.3744737 -0.3935650 0.6090178 +VERTEX_SE3:QUAT 5507 18.570989 27.823294 -10.044655 0.7273404 -0.4018340 0.4560545 0.3186215 +VERTEX_SE3:QUAT 5508 19.335034 28.372046 -9.691915 0.4663000 0.4419333 -0.7602099 0.0966444 +VERTEX_SE3:QUAT 5509 20.221712 28.948577 -9.244883 0.4881091 0.0028596 0.0583140 0.8708277 +VERTEX_SE3:QUAT 5510 20.891576 29.209339 -8.705986 0.5720036 -0.0683069 0.7232522 0.3808572 +VERTEX_SE3:QUAT 5511 21.783414 29.481595 -8.138328 0.0468782 -0.4799412 0.4986724 0.7202671 +VERTEX_SE3:QUAT 5512 22.657393 29.795266 -7.734713 0.2493520 0.1356893 -0.9573851 0.0531571 +VERTEX_SE3:QUAT 5513 23.532446 30.072637 -7.342800 0.0230696 -0.1834386 -0.7435963 0.6425594 +VERTEX_SE3:QUAT 5514 24.581476 30.241839 -7.096439 0.6796653 0.2160459 0.3206056 0.6233709 +VERTEX_SE3:QUAT 5515 25.611620 30.325810 -6.808801 -0.3432956 0.0637895 -0.9346770 0.0667681 +VERTEX_SE3:QUAT 5516 26.607887 30.507533 -6.588752 -0.4189698 -0.2040766 0.5921941 0.6573608 +VERTEX_SE3:QUAT 5517 27.512215 30.672429 -6.279740 -0.1726166 0.0870874 -0.8890603 0.4149592 +VERTEX_SE3:QUAT 5518 28.340620 30.788977 -6.064168 0.6515654 0.3137388 0.3963781 0.5656102 +VERTEX_SE3:QUAT 5519 29.476234 30.929618 -5.956340 -0.0311194 -0.2646286 -0.9123648 0.3107954 +VERTEX_SE3:QUAT 5520 29.650538 30.125285 -6.587424 0.0702193 0.6569863 -0.2962525 0.6896903 +VERTEX_SE3:QUAT 5521 28.745055 30.115481 -6.597882 0.3038334 -0.3753939 -0.4570061 0.7469338 +VERTEX_SE3:QUAT 5522 27.869822 30.036164 -6.910252 -0.3572117 0.2899607 0.8459831 0.2695092 +VERTEX_SE3:QUAT 5523 26.966915 30.099811 -7.156582 0.6289330 0.4201742 -0.2594329 0.6004927 +VERTEX_SE3:QUAT 5524 26.062464 29.979769 -7.400895 0.6072195 -0.0380023 0.7363758 0.2959577 +VERTEX_SE3:QUAT 5525 25.136412 29.975447 -7.686754 0.0541456 0.1631561 -0.1141781 0.9784742 +VERTEX_SE3:QUAT 5526 24.449968 29.760292 -7.973175 -0.1651462 0.3167457 0.9045232 0.2328876 +VERTEX_SE3:QUAT 5527 23.645163 29.656145 -8.261108 -0.2190714 -0.0443566 -0.8959491 0.3838170 +VERTEX_SE3:QUAT 5528 22.724717 29.485501 -8.537593 0.2090434 -0.4818749 -0.7519855 0.3982653 +VERTEX_SE3:QUAT 5529 21.970843 29.257303 -8.656319 -0.5683732 -0.4908008 0.6214662 0.2232628 +VERTEX_SE3:QUAT 5530 20.848859 29.034542 -8.772748 0.1988642 0.6350093 -0.6259940 0.4066298 +VERTEX_SE3:QUAT 5531 19.783743 28.839193 -8.862107 0.5695012 -0.3534130 -0.3113864 0.6736514 +VERTEX_SE3:QUAT 5532 18.703003 28.612157 -9.073020 0.5771204 -0.4376078 -0.1719046 0.6677426 +VERTEX_SE3:QUAT 5533 17.692659 28.614744 -9.135073 0.4748113 -0.1973052 -0.8499920 0.1146237 +VERTEX_SE3:QUAT 5534 16.743059 28.670928 -9.100572 0.1332394 -0.3459598 -0.6063105 0.7035244 +VERTEX_SE3:QUAT 5535 15.749341 28.573019 -9.011784 -0.1446489 0.6447341 -0.5778719 0.4790185 +VERTEX_SE3:QUAT 5536 14.707232 28.638556 -9.221456 0.5320620 0.3543950 -0.7039012 0.3095760 +VERTEX_SE3:QUAT 5537 13.809488 28.653415 -9.375304 0.0224305 -0.5861945 0.3717425 0.7195000 +VERTEX_SE3:QUAT 5538 12.800723 28.698068 -9.464139 -0.3178051 0.1602643 0.9299297 0.0924451 +VERTEX_SE3:QUAT 5539 11.899025 28.678545 -9.651972 -0.4590953 -0.4911188 0.6024518 0.4302159 +VERTEX_SE3:QUAT 5540 11.773318 27.805739 -10.196226 0.1710377 -0.6750243 0.6767037 0.2390824 +VERTEX_SE3:QUAT 5541 12.963732 27.787197 -9.990683 0.4852564 -0.1598338 0.8529684 0.1068847 +VERTEX_SE3:QUAT 5542 13.935000 27.926834 -9.866477 -0.3312686 0.0224423 0.4397056 0.8345157 +VERTEX_SE3:QUAT 5543 14.784625 27.933513 -9.826110 -0.2926031 0.2264125 -0.6650725 0.6486905 +VERTEX_SE3:QUAT 5544 15.794405 28.063789 -9.530440 -0.2711614 -0.5706049 0.7739271 0.0437995 +VERTEX_SE3:QUAT 5545 16.787002 28.282330 -9.069256 -0.3369899 -0.3864805 0.1220317 0.8498111 +VERTEX_SE3:QUAT 5546 17.514441 28.552962 -8.710852 0.3067978 0.4219969 -0.5998661 0.6065925 +VERTEX_SE3:QUAT 5547 18.341610 28.745747 -8.519229 0.8495215 -0.0622785 -0.0660873 0.5196798 +VERTEX_SE3:QUAT 5548 19.297459 28.753963 -8.350591 0.1781019 -0.3654785 -0.1898103 0.8936874 +VERTEX_SE3:QUAT 5549 20.223536 28.803762 -7.918545 0.4886445 0.6115318 -0.4192299 0.4598931 +VERTEX_SE3:QUAT 5550 21.065166 28.700981 -7.512764 0.0124185 0.4540368 -0.8907971 0.0133023 +VERTEX_SE3:QUAT 5551 21.921414 28.544617 -6.982125 0.4639280 -0.5500510 0.6690566 0.1859516 +VERTEX_SE3:QUAT 5552 22.695510 28.367838 -6.541257 0.4339630 0.0460921 0.2554284 0.8627328 +VERTEX_SE3:QUAT 5553 23.678515 28.615488 -5.841907 0.4938694 -0.3886042 -0.4595869 0.6275824 +VERTEX_SE3:QUAT 5554 24.669191 28.648416 -5.637305 -0.0040695 0.2521462 0.7738532 0.5809966 +VERTEX_SE3:QUAT 5555 25.663893 28.469889 -5.171883 -0.0888021 0.3082668 -0.0025905 0.9471426 +VERTEX_SE3:QUAT 5556 26.637690 28.468510 -5.032965 0.5023359 -0.0405920 -0.8625609 0.0447176 +VERTEX_SE3:QUAT 5557 27.498454 28.378139 -4.836353 -0.2434990 -0.4880507 -0.2093209 0.8116031 +VERTEX_SE3:QUAT 5558 28.280136 28.133021 -4.508520 0.1658744 0.2390174 0.8002178 0.5244119 +VERTEX_SE3:QUAT 5559 29.207412 27.964803 -4.040534 0.7528112 -0.2719634 -0.5209002 0.2966044 +VERTEX_SE3:QUAT 5560 29.453002 27.415725 -4.850969 -0.2690676 0.5651209 -0.4440543 0.6411371 +VERTEX_SE3:QUAT 5561 28.459155 27.387553 -5.298179 0.5555013 0.2520713 -0.0784831 0.7884914 +VERTEX_SE3:QUAT 5562 27.557599 27.571824 -5.612593 -0.2308044 -0.8736203 0.2767682 0.3269804 +VERTEX_SE3:QUAT 5563 26.645017 27.668051 -6.028635 0.8818560 0.1159493 -0.1717113 0.4235576 +VERTEX_SE3:QUAT 5564 25.601203 27.766570 -6.350149 -0.3304931 -0.4811237 0.1270460 0.8019686 +VERTEX_SE3:QUAT 5565 24.566011 28.123518 -6.745832 0.0997367 -0.1822771 0.6504791 0.7305509 +VERTEX_SE3:QUAT 5566 23.619489 28.298212 -6.923992 0.1068907 -0.3090829 0.7213794 0.6104539 +VERTEX_SE3:QUAT 5567 22.663862 28.404560 -7.238963 0.3764291 -0.1335047 -0.8551080 0.3305568 +VERTEX_SE3:QUAT 5568 21.841703 28.382865 -7.465974 -0.3689635 0.3941745 0.8365772 0.0929026 +VERTEX_SE3:QUAT 5569 20.926970 28.387357 -7.608986 0.4162951 0.1721871 0.7434875 0.4942432 +VERTEX_SE3:QUAT 5570 20.076225 28.306382 -7.900393 -0.0955450 -0.7866159 0.2114029 0.5722022 +VERTEX_SE3:QUAT 5571 19.298222 28.363932 -8.114396 0.2845957 -0.5285350 0.6643875 0.4452474 +VERTEX_SE3:QUAT 5572 18.241943 28.333797 -8.419964 -0.3896875 -0.5607541 0.4582415 0.5689580 +VERTEX_SE3:QUAT 5573 17.240725 28.318381 -8.699528 0.7360420 -0.2382796 0.4652327 0.4301437 +VERTEX_SE3:QUAT 5574 16.140831 28.402947 -8.926306 0.1649544 -0.6132469 0.2559614 0.7288361 +VERTEX_SE3:QUAT 5575 15.183720 28.328904 -9.073266 0.7567839 -0.3494962 -0.0882513 0.5452909 +VERTEX_SE3:QUAT 5576 14.275505 28.319694 -9.386007 0.1923424 -0.4474864 -0.2429376 0.8388931 +VERTEX_SE3:QUAT 5577 13.372307 28.120136 -9.716715 0.1882293 -0.7158490 0.6342638 0.2232473 +VERTEX_SE3:QUAT 5578 12.364696 28.110207 -9.943796 0.5581669 0.2543731 0.4479738 0.6504334 +VERTEX_SE3:QUAT 5579 11.383553 28.070680 -10.122329 0.1578566 -0.5391852 -0.7445692 0.3605237 +VERTEX_SE3:QUAT 5580 11.506586 27.080433 -10.831370 -0.4138945 -0.0916108 -0.3894202 0.8177107 +VERTEX_SE3:QUAT 5581 12.385347 27.304331 -10.667257 0.3537070 -0.3502834 -0.8044454 0.3241304 +VERTEX_SE3:QUAT 5582 13.397498 27.249905 -10.378945 0.2537094 0.6698412 -0.4682392 0.5173939 +VERTEX_SE3:QUAT 5583 14.320809 27.315346 -10.421166 0.6627529 -0.2934841 0.4842566 0.4900216 +VERTEX_SE3:QUAT 5584 15.341952 27.467304 -10.158203 0.4552959 0.1255676 0.4573945 0.7534777 +VERTEX_SE3:QUAT 5585 16.339923 27.788672 -10.076398 0.3202646 -0.1464413 0.4239617 0.8344112 +VERTEX_SE3:QUAT 5586 17.415637 28.000824 -10.008567 0.1754910 -0.6499508 0.6039929 0.4265670 +VERTEX_SE3:QUAT 5587 18.249109 28.171160 -10.028192 0.5473517 -0.1622239 0.1103121 0.8135851 +VERTEX_SE3:QUAT 5588 19.316579 28.471644 -9.974001 0.6940679 -0.1500021 -0.5609481 0.4255659 +VERTEX_SE3:QUAT 5589 20.239255 28.592646 -9.923986 -0.2049259 -0.2293103 0.9494032 0.0636844 +VERTEX_SE3:QUAT 5590 21.144726 28.990082 -10.033727 -0.2784267 0.0803278 -0.7595720 0.5823027 +VERTEX_SE3:QUAT 5591 22.054258 29.128007 -10.043543 0.4014037 -0.2470772 0.3029121 0.8282947 +VERTEX_SE3:QUAT 5592 23.107392 29.491050 -9.946993 -0.3175341 0.2176529 -0.1776627 0.9056684 +VERTEX_SE3:QUAT 5593 23.910256 29.884174 -9.865418 -0.3545753 0.6838023 -0.4350714 0.4662657 +VERTEX_SE3:QUAT 5594 24.816464 30.191971 -9.648475 0.3927360 -0.5169532 0.4331176 0.6252416 +VERTEX_SE3:QUAT 5595 25.771988 30.727140 -9.434282 0.4453390 -0.3110105 0.3346089 0.7700536 +VERTEX_SE3:QUAT 5596 26.509801 31.174493 -9.236014 0.6849605 0.0169731 0.7248950 0.0711921 +VERTEX_SE3:QUAT 5597 27.492533 31.521732 -8.922443 0.2033283 0.2100161 0.3116372 0.9041201 +VERTEX_SE3:QUAT 5598 28.263742 31.954517 -8.845447 0.2351288 0.5914602 -0.1864080 0.7484259 +VERTEX_SE3:QUAT 5599 29.239617 32.455966 -8.638124 -0.4429417 -0.2388226 0.6461604 0.5737972 +VERTEX_SE3:QUAT 5600 12.104444 25.074382 -11.410951 0.2630529 -0.0323018 0.1729949 0.9485950 +VERTEX_SE3:QUAT 5601 13.103256 25.307110 -11.192609 0.3719845 -0.3126179 0.8639349 0.1323408 +VERTEX_SE3:QUAT 5602 14.116463 25.647834 -11.091644 -0.3344055 -0.1675051 -0.8886664 0.2653056 +VERTEX_SE3:QUAT 5603 14.978448 25.985545 -11.189160 0.0542770 -0.1847841 -0.9704827 0.1451623 +VERTEX_SE3:QUAT 5604 16.057344 26.325162 -11.107552 0.3458375 0.3258998 -0.5902126 0.6525602 +VERTEX_SE3:QUAT 5605 17.142668 26.622045 -10.832931 0.3936480 -0.4552788 -0.6262737 0.4955237 +VERTEX_SE3:QUAT 5606 18.162731 27.032548 -10.637758 0.6831598 0.1224578 -0.6722484 0.2576410 +VERTEX_SE3:QUAT 5607 19.162662 27.153983 -10.431020 -0.1962112 -0.4796804 0.8358222 0.1811326 +VERTEX_SE3:QUAT 5608 20.145643 27.322817 -10.337836 0.1539313 0.3466585 0.8520347 0.3607907 +VERTEX_SE3:QUAT 5609 21.149650 27.507637 -10.195828 0.1446392 -0.0092953 -0.7565551 0.6376656 +VERTEX_SE3:QUAT 5610 22.177122 27.554798 -10.137095 0.2527113 0.5555213 -0.7746485 0.1656888 +VERTEX_SE3:QUAT 5611 23.083755 27.606333 -9.951700 -0.1283282 0.3159380 -0.3630030 0.8671470 +VERTEX_SE3:QUAT 5612 24.039934 27.760618 -9.806518 -0.0740555 0.4853135 -0.8554204 0.1650533 +VERTEX_SE3:QUAT 5613 25.022223 28.105563 -9.687712 0.3925948 -0.4147597 0.2314384 0.7875785 +VERTEX_SE3:QUAT 5614 25.919924 28.476613 -9.333017 0.2425012 0.2645278 -0.1513655 0.9210357 +VERTEX_SE3:QUAT 5615 26.763369 28.955542 -9.163467 0.4080696 -0.4877611 0.7082673 0.3064730 +VERTEX_SE3:QUAT 5616 27.664075 29.402965 -9.020283 0.5182216 0.1026658 0.8469622 0.0596752 +VERTEX_SE3:QUAT 5617 28.712255 29.649116 -8.616120 0.0307096 -0.4797277 -0.6399637 0.5994703 +VERTEX_SE3:QUAT 5618 29.635365 29.885876 -8.457224 0.4116036 0.4459612 -0.5819534 0.5413236 +VERTEX_SE3:QUAT 5619 30.457562 30.112575 -8.149330 0.1719008 0.7200288 -0.6670647 0.0838649 +VERTEX_SE3:QUAT 5620 30.033461 31.034166 -7.705011 0.7449568 -0.1279867 -0.2453439 0.6070133 +VERTEX_SE3:QUAT 5621 29.097811 30.643180 -7.936538 0.6227146 0.3624832 -0.0699882 0.6898798 +VERTEX_SE3:QUAT 5622 27.947547 30.505970 -8.167781 0.1101017 0.5881605 -0.7328842 0.3237677 +VERTEX_SE3:QUAT 5623 26.992121 30.329653 -8.374765 -0.1396112 0.2600645 0.7199592 0.6281193 +VERTEX_SE3:QUAT 5624 25.946225 29.955841 -8.690925 -0.3425895 0.3496389 -0.8675436 0.0880523 +VERTEX_SE3:QUAT 5625 25.205518 29.671395 -8.993557 -0.2874195 0.1921154 0.9118663 0.2213177 +VERTEX_SE3:QUAT 5626 24.286122 29.226897 -9.550058 0.1772349 0.3814382 -0.3514789 0.8363942 +VERTEX_SE3:QUAT 5627 23.282177 28.922147 -10.025961 0.2491395 0.2221376 0.9392154 0.0803662 +VERTEX_SE3:QUAT 5628 22.469555 28.305928 -10.510236 0.4044444 0.2006833 -0.2075512 0.8677980 +VERTEX_SE3:QUAT 5629 21.786197 27.899753 -11.262770 0.4902281 -0.2082004 -0.8015788 0.2716624 +VERTEX_SE3:QUAT 5630 21.075937 27.662865 -11.821002 -0.2537986 -0.2040729 0.9435896 0.0598269 +VERTEX_SE3:QUAT 5631 20.075542 27.390572 -12.418967 -0.1596887 0.5607039 -0.7507673 0.3105787 +VERTEX_SE3:QUAT 5632 19.380068 27.206230 -13.154177 -0.1832776 -0.5882907 0.3511041 0.7050172 +VERTEX_SE3:QUAT 5633 18.630653 26.701532 -13.520028 0.5271080 0.0409665 0.6027638 0.5976243 +VERTEX_SE3:QUAT 5634 17.820290 26.444279 -13.930066 -0.1151716 0.0720837 0.6624443 0.7366865 +VERTEX_SE3:QUAT 5635 16.962215 26.256023 -14.429422 0.5059687 -0.0001268 0.8360189 0.2122923 +VERTEX_SE3:QUAT 5636 15.981250 26.000681 -14.907871 0.4928096 0.6307032 -0.3386575 0.4946345 +VERTEX_SE3:QUAT 5637 15.116770 25.706987 -15.586051 0.0920570 0.0823568 -0.8577846 0.4989474 +VERTEX_SE3:QUAT 5638 14.257497 25.487709 -16.044940 -0.4287022 -0.1399854 0.1714493 0.8759130 +VERTEX_SE3:QUAT 5639 13.494072 25.452579 -16.505072 0.0808438 -0.1862668 -0.9622344 0.1813115 +VERTEX_SE3:QUAT 5640 12.823581 26.210485 -16.132784 0.2316279 0.2533307 -0.7602865 0.5514857 +VERTEX_SE3:QUAT 5641 13.482786 26.462581 -15.575521 -0.0145025 0.2314636 0.0279236 0.9723346 +VERTEX_SE3:QUAT 5642 14.412842 26.822120 -15.126693 0.6511094 0.3049796 -0.6584459 0.2224702 +VERTEX_SE3:QUAT 5643 15.386531 26.986868 -14.538667 0.1496828 0.4120613 0.7634418 0.4742965 +VERTEX_SE3:QUAT 5644 16.039088 27.332409 -14.089584 -0.3823285 0.3428975 -0.4104540 0.7535076 +VERTEX_SE3:QUAT 5645 16.795483 27.494378 -13.797897 0.0485169 -0.0551726 0.5023702 0.8615256 +VERTEX_SE3:QUAT 5646 17.741941 27.546024 -13.560808 0.5354389 -0.2809306 -0.0473763 0.7950715 +VERTEX_SE3:QUAT 5647 18.690488 27.715450 -13.306081 -0.5735013 -0.0422335 -0.8178708 0.0199976 +VERTEX_SE3:QUAT 5648 19.574785 27.774570 -12.747166 0.0338890 0.6578616 -0.5802382 0.4789501 +VERTEX_SE3:QUAT 5649 20.419032 27.830050 -12.390013 0.0043401 0.4386760 0.6266455 0.6440961 +VERTEX_SE3:QUAT 5650 21.280693 27.905204 -11.823568 0.7865516 0.1691817 -0.1762755 0.5671340 +VERTEX_SE3:QUAT 5651 22.157772 27.932076 -11.417105 0.4675297 -0.1059491 0.6472514 0.5926689 +VERTEX_SE3:QUAT 5652 23.088072 28.172578 -11.082257 0.3030545 -0.2861252 -0.6090883 0.6747605 +VERTEX_SE3:QUAT 5653 23.968554 28.223142 -10.874839 0.6244046 -0.0547733 -0.6920577 0.3580153 +VERTEX_SE3:QUAT 5654 25.126674 28.315720 -10.476965 0.6174624 0.0893929 0.0251036 0.7811011 +VERTEX_SE3:QUAT 5655 26.140565 28.328338 -10.212757 -0.4177205 -0.2382148 0.8307700 0.2803294 +VERTEX_SE3:QUAT 5656 27.310239 28.419749 -10.091582 0.1374454 -0.2581651 -0.8636357 0.4106006 +VERTEX_SE3:QUAT 5657 28.153604 28.512842 -9.937224 0.0605837 0.0055314 -0.8410993 0.5374487 +VERTEX_SE3:QUAT 5658 29.252385 28.462112 -9.739750 -0.1704192 0.3200853 -0.0992890 0.9266307 +VERTEX_SE3:QUAT 5659 30.163747 28.501619 -9.634710 -0.1534791 0.4023759 -0.8676818 0.2483265 +VERTEX_SE3:QUAT 5660 30.102290 29.380075 -9.203715 0.0302721 -0.0507534 0.8823610 0.4668477 +VERTEX_SE3:QUAT 5661 29.136144 29.402622 -9.439988 0.1878197 0.7455346 -0.5006643 0.3977905 +VERTEX_SE3:QUAT 5662 28.208785 29.273078 -9.800223 -0.5106246 -0.3532589 -0.1380385 0.7716321 +VERTEX_SE3:QUAT 5663 27.159596 29.338529 -10.271288 0.2262140 -0.5174317 0.5532197 0.6124048 +VERTEX_SE3:QUAT 5664 26.225529 29.459823 -10.557792 -0.4553982 0.3081465 -0.5925181 0.5887109 +VERTEX_SE3:QUAT 5665 25.324987 29.753260 -10.539363 0.1880520 -0.0038970 0.7513567 0.6325223 +VERTEX_SE3:QUAT 5666 24.219030 30.046065 -10.613532 -0.3010371 0.1094722 0.3936610 0.8616400 +VERTEX_SE3:QUAT 5667 23.427246 30.144257 -10.659046 0.0864715 0.2736586 -0.7894313 0.5426157 +VERTEX_SE3:QUAT 5668 22.409740 30.267680 -10.812628 0.4319534 -0.0405724 -0.8936299 0.1148726 +VERTEX_SE3:QUAT 5669 21.495791 30.263877 -11.035473 0.3644354 0.0373682 -0.0334766 0.9298762 +VERTEX_SE3:QUAT 5670 20.601489 30.355224 -11.344812 0.1917860 0.0160838 -0.9779661 0.0808816 +VERTEX_SE3:QUAT 5671 19.837701 30.578353 -11.431606 -0.4099360 -0.1429392 -0.1996632 0.8784392 +VERTEX_SE3:QUAT 5672 18.873766 30.709103 -11.505021 0.4380508 -0.5220684 -0.6612294 0.3135789 +VERTEX_SE3:QUAT 5673 17.917971 30.795380 -11.732655 -0.0176347 -0.5487020 0.6099812 0.5714351 +VERTEX_SE3:QUAT 5674 16.884079 31.056712 -11.804637 -0.2526809 -0.1673087 -0.6251089 0.7193046 +VERTEX_SE3:QUAT 5675 15.885317 31.268327 -11.923962 0.2919989 0.5617801 -0.5700105 0.5236676 +VERTEX_SE3:QUAT 5676 15.142090 31.552426 -11.995005 -0.0747282 -0.4495007 -0.8893994 0.0365185 +VERTEX_SE3:QUAT 5677 14.268455 31.867676 -12.085615 0.2300366 -0.0490011 -0.9527050 0.1924455 +VERTEX_SE3:QUAT 5678 13.433929 32.086611 -12.190319 0.5193035 0.2352750 -0.4924050 0.6576525 +VERTEX_SE3:QUAT 5679 12.667932 32.429638 -12.539516 -0.0242116 0.1965437 -0.5986796 0.7761231 +VERTEX_SE3:QUAT 5680 12.836635 33.314874 -11.997041 -0.5069992 -0.3736975 0.7708455 0.0953900 +VERTEX_SE3:QUAT 5681 13.636508 33.114838 -11.744810 0.5702370 0.0972199 0.7328000 0.3583047 +VERTEX_SE3:QUAT 5682 14.401181 33.010780 -11.508920 -0.4980802 -0.1279194 0.6141608 0.5986312 +VERTEX_SE3:QUAT 5683 15.115358 32.711081 -11.205420 0.2361704 -0.1588765 0.9419621 0.1780144 +VERTEX_SE3:QUAT 5684 15.945761 32.567543 -11.091192 -0.4493562 -0.2894641 0.5370475 0.6525868 +VERTEX_SE3:QUAT 5685 16.905687 32.277388 -10.807604 0.0351928 -0.2775092 -0.3617969 0.8892992 +VERTEX_SE3:QUAT 5686 17.927805 31.946757 -10.593782 0.0199005 -0.2247114 0.2512496 0.9412664 +VERTEX_SE3:QUAT 5687 18.765606 31.618730 -10.323677 0.2823886 -0.6350049 0.2180378 0.6851898 +VERTEX_SE3:QUAT 5688 19.651142 31.426944 -10.165378 -0.5393346 -0.2080222 0.5856189 0.5682389 +VERTEX_SE3:QUAT 5689 20.559578 31.274813 -10.132740 -0.3013564 0.2439645 -0.0844734 0.9178943 +VERTEX_SE3:QUAT 5690 21.407828 31.270337 -9.844532 0.5042056 0.3219785 -0.7155048 0.3607762 +VERTEX_SE3:QUAT 5691 22.442323 31.036534 -9.573149 0.6332329 0.0259965 -0.5088099 0.5826258 +VERTEX_SE3:QUAT 5692 23.531710 30.964283 -9.318543 -0.3094298 -0.1628668 -0.6014441 0.7183262 +VERTEX_SE3:QUAT 5693 24.456725 30.992130 -9.085940 0.3182588 0.4259273 -0.6641584 0.5255388 +VERTEX_SE3:QUAT 5694 25.463273 30.874831 -8.977527 0.4891273 0.1377924 -0.8497319 0.1404400 +VERTEX_SE3:QUAT 5695 26.249967 30.872060 -8.767361 0.0529192 -0.6286205 0.2226353 0.7432828 +VERTEX_SE3:QUAT 5696 27.286570 30.792986 -8.520255 0.2669996 -0.4384835 -0.7176491 0.4705564 +VERTEX_SE3:QUAT 5697 28.266941 30.632988 -8.111770 0.1739678 0.2543619 0.2752935 0.9106309 +VERTEX_SE3:QUAT 5698 29.124376 30.590826 -7.752923 -0.4957962 -0.5414403 0.6717071 0.0991877 +VERTEX_SE3:QUAT 5699 30.066328 30.602484 -7.344146 0.1635254 0.2060157 -0.6680600 0.6960695 +VERTEX_SE3:QUAT 5700 29.976066 31.508647 -6.944575 0.2323397 0.1973126 0.7379860 0.6020487 +VERTEX_SE3:QUAT 5701 28.851044 31.379568 -7.165131 -0.5758205 -0.4927691 0.5738428 0.3103448 +VERTEX_SE3:QUAT 5702 28.132564 31.483659 -7.715196 -0.1350747 0.3523894 0.9252768 0.0379387 +VERTEX_SE3:QUAT 5703 27.219618 31.305878 -8.064578 -0.1386049 0.1926117 -0.6803595 0.6933977 +VERTEX_SE3:QUAT 5704 26.327284 31.194629 -8.623149 0.2680175 -0.6341979 -0.2144982 0.6927844 +VERTEX_SE3:QUAT 5705 25.325280 31.294510 -9.053261 0.1769123 -0.5988436 -0.5288063 0.5748498 +VERTEX_SE3:QUAT 5706 24.382794 31.342733 -9.310047 -0.1547178 0.1467249 0.7123287 0.6686719 +VERTEX_SE3:QUAT 5707 23.647064 31.162732 -9.502013 -0.0258050 -0.0012053 0.9968854 0.0745124 +VERTEX_SE3:QUAT 5708 22.729689 31.182564 -9.683998 -0.1674660 -0.1421221 0.3816875 0.8978146 +VERTEX_SE3:QUAT 5709 21.782952 31.122077 -10.039258 0.3397870 -0.0566861 0.8324040 0.4340911 +VERTEX_SE3:QUAT 5710 20.639612 31.267711 -10.113855 0.4654986 -0.2162476 -0.6160997 0.5974689 +VERTEX_SE3:QUAT 5711 19.648363 31.349113 -10.056401 0.0322241 0.4574994 -0.3994569 0.7937821 +VERTEX_SE3:QUAT 5712 18.707506 31.299606 -10.282367 -0.1066756 0.1542224 0.2683366 0.9448975 +VERTEX_SE3:QUAT 5713 17.762239 31.446633 -10.199695 0.3530497 0.2063481 0.5857346 0.6997795 +VERTEX_SE3:QUAT 5714 16.765223 31.146052 -10.416953 0.2281039 -0.5189983 -0.5804926 0.5844978 +VERTEX_SE3:QUAT 5715 15.659827 31.009460 -10.418179 0.3959587 -0.0500145 0.5339577 0.7453888 +VERTEX_SE3:QUAT 5716 14.656009 31.034151 -10.345919 0.1983335 0.5233987 -0.6285115 0.5400842 +VERTEX_SE3:QUAT 5717 13.829567 31.049118 -10.447223 0.3367019 -0.5568929 -0.4054340 0.6419700 +VERTEX_SE3:QUAT 5718 12.859547 30.782711 -10.371248 0.1387165 -0.4778249 0.7778871 0.3838394 +VERTEX_SE3:QUAT 5719 11.872248 30.579340 -10.395728 -0.4001380 -0.1146659 0.0151442 0.9091270 +VERTEX_SE3:QUAT 5720 11.668078 31.340334 -10.109993 0.6774318 0.0047546 -0.6508301 0.3427589 +VERTEX_SE3:QUAT 5721 12.726908 31.532498 -9.895988 0.3796114 -0.3818384 0.5543472 0.6346604 +VERTEX_SE3:QUAT 5722 13.788442 31.761955 -9.744620 -0.0612863 -0.6712895 0.2866558 0.6807664 +VERTEX_SE3:QUAT 5723 14.669412 32.210504 -9.780744 -0.2008256 0.6537025 -0.5438300 0.4864063 +VERTEX_SE3:QUAT 5724 15.825520 32.522728 -9.699363 -0.4895695 -0.0910894 0.6595395 0.5630560 +VERTEX_SE3:QUAT 5725 16.821195 32.659828 -9.457806 0.3476877 -0.0441829 -0.9256127 0.1428364 +VERTEX_SE3:QUAT 5726 17.843745 32.814164 -9.256869 0.0372234 -0.6769017 0.3838074 0.6269852 +VERTEX_SE3:QUAT 5727 18.698735 33.073043 -9.008171 -0.3931020 -0.4526076 0.7707295 0.2158547 +VERTEX_SE3:QUAT 5728 19.819240 33.323253 -8.804112 0.4712953 -0.2114500 0.8558611 0.0259111 +VERTEX_SE3:QUAT 5729 20.751200 33.436905 -8.708990 0.5601206 -0.3035892 -0.6604374 0.3973927 +VERTEX_SE3:QUAT 5730 21.823657 33.470735 -8.510262 -0.2459326 -0.1703907 0.0628555 0.9521204 +VERTEX_SE3:QUAT 5731 22.857163 33.471102 -8.530351 -0.1258881 -0.5009405 0.8305627 0.2082701 +VERTEX_SE3:QUAT 5732 23.760657 33.687552 -8.548561 0.4053517 -0.7627554 0.4761350 0.1648929 +VERTEX_SE3:QUAT 5733 25.099346 33.731200 -8.490961 -0.3202123 -0.2541287 -0.8991577 0.1561993 +VERTEX_SE3:QUAT 5734 26.145061 33.842606 -8.462069 -0.2138566 0.4802914 -0.1508415 0.8371573 +VERTEX_SE3:QUAT 5735 27.148550 33.629359 -8.642670 0.2392519 0.2867268 0.2689112 0.8878249 +VERTEX_SE3:QUAT 5736 28.416014 33.565321 -8.551097 0.2902854 0.0290679 0.9128590 0.2856184 +VERTEX_SE3:QUAT 5737 29.446264 33.373323 -8.694811 -0.1664066 0.1617541 0.7865058 0.5723225 +VERTEX_SE3:QUAT 5738 30.456695 33.316656 -8.551596 0.3658730 0.0303237 -0.9229440 0.1157225 +VERTEX_SE3:QUAT 5739 31.637927 33.219767 -8.440101 -0.3117902 -0.3851055 0.8159474 0.2978429 +VERTEX_SE3:QUAT 5740 31.346996 34.025423 -7.824567 -0.0789220 0.7487372 -0.5884822 0.2947077 +VERTEX_SE3:QUAT 5741 30.481593 34.225853 -7.946288 -0.0539852 0.0444810 0.8665155 0.4942246 +VERTEX_SE3:QUAT 5742 29.342566 34.208734 -8.073040 0.6846743 0.1072583 -0.7077780 0.1369929 +VERTEX_SE3:QUAT 5743 28.585736 34.199310 -8.240643 -0.0946856 -0.2073132 0.9285696 0.2929410 +VERTEX_SE3:QUAT 5744 27.741878 34.108240 -8.217270 0.1785232 0.3539303 -0.3572447 0.8457180 +VERTEX_SE3:QUAT 5745 26.708351 34.140752 -8.508605 -0.3545034 0.2167618 0.2569329 0.8725406 +VERTEX_SE3:QUAT 5746 25.729772 34.102872 -8.724158 -0.0140651 0.4684941 0.0992447 0.8777619 +VERTEX_SE3:QUAT 5747 24.784765 34.019329 -8.806792 -0.4309479 0.4200706 -0.5382320 0.5900262 +VERTEX_SE3:QUAT 5748 23.747235 34.201391 -9.047236 0.1512548 0.7156074 -0.6415858 0.2310751 +VERTEX_SE3:QUAT 5749 22.636819 34.185206 -9.085324 0.3280275 -0.2969712 0.8576845 0.2618842 +VERTEX_SE3:QUAT 5750 21.736204 34.097670 -9.226555 0.3399738 0.0242149 0.4068865 0.8475110 +VERTEX_SE3:QUAT 5751 20.785452 34.209386 -9.366136 -0.1076795 -0.6496492 0.7194822 0.2206952 +VERTEX_SE3:QUAT 5752 19.758725 34.164819 -9.424963 -0.3698762 0.3150901 -0.4112604 0.7712164 +VERTEX_SE3:QUAT 5753 18.934630 34.273083 -9.507041 0.6603516 -0.0424587 -0.7283855 0.1777288 +VERTEX_SE3:QUAT 5754 18.009229 34.318732 -9.768253 0.0752375 0.3447562 -0.7940074 0.4950098 +VERTEX_SE3:QUAT 5755 16.932852 34.366438 -9.880839 0.3359569 0.3642627 0.8682280 0.0250163 +VERTEX_SE3:QUAT 5756 15.924324 34.461908 -10.020932 -0.1756344 -0.2242228 -0.9318157 0.2249360 +VERTEX_SE3:QUAT 5757 14.997880 34.416665 -10.055488 -0.1754811 -0.3152630 0.3493023 0.8647563 +VERTEX_SE3:QUAT 5758 14.041996 34.371684 -9.900022 0.0843781 -0.2691315 -0.7281421 0.6247060 +VERTEX_SE3:QUAT 5759 13.129644 34.418529 -9.987694 0.2784018 -0.0034233 0.5902173 0.7577099 +VERTEX_SE3:QUAT 5760 13.212760 35.155512 -9.537915 -0.2834976 -0.5759961 0.6722817 0.3686393 +VERTEX_SE3:QUAT 5761 14.287050 34.909210 -10.011832 0.0491076 -0.7127850 0.6465620 0.2673641 +VERTEX_SE3:QUAT 5762 14.981743 34.698609 -10.154037 0.5390261 0.1271954 0.8049834 0.2127769 +VERTEX_SE3:QUAT 5763 15.898567 34.503784 -10.305574 0.3372110 0.6918463 -0.5451934 0.3322673 +VERTEX_SE3:QUAT 5764 16.880702 34.274662 -10.475932 -0.1366546 -0.1833537 -0.4432075 0.8667606 +VERTEX_SE3:QUAT 5765 18.018501 34.085710 -10.640471 -0.1407038 -0.5866096 0.7888019 0.1178273 +VERTEX_SE3:QUAT 5766 18.947211 33.890570 -10.886292 0.2683322 0.5707254 -0.6602914 0.4077812 +VERTEX_SE3:QUAT 5767 19.879009 33.815488 -11.211002 -0.2209815 -0.3932966 -0.2863914 0.8452603 +VERTEX_SE3:QUAT 5768 20.914786 33.795938 -11.183427 -0.2290398 -0.0273538 -0.5996506 0.7662974 +VERTEX_SE3:QUAT 5769 21.916683 33.572698 -11.352806 0.2263003 0.4249562 0.6160472 0.6234471 +VERTEX_SE3:QUAT 5770 23.174114 33.578690 -11.525862 -0.3467391 0.6743639 -0.6491032 0.0605831 +VERTEX_SE3:QUAT 5771 24.111290 33.606456 -11.771929 0.8669027 -0.1143337 -0.2214076 0.4317246 +VERTEX_SE3:QUAT 5772 25.200207 33.619033 -11.818821 0.1496029 0.8051180 -0.5725302 0.0401637 +VERTEX_SE3:QUAT 5773 26.306134 33.585713 -11.770121 0.4365791 -0.5070967 -0.5264408 0.5245109 +VERTEX_SE3:QUAT 5774 27.227355 33.720471 -11.902368 0.3696153 -0.2103187 0.6995629 0.5742494 +VERTEX_SE3:QUAT 5775 28.182928 33.755559 -12.002696 0.5792288 0.4933316 -0.3328505 0.5570712 +VERTEX_SE3:QUAT 5776 29.247334 33.692082 -11.932601 0.2689906 -0.2914855 0.6151399 0.6813833 +VERTEX_SE3:QUAT 5777 30.159782 33.749595 -12.085115 0.0898475 0.6155410 -0.7672499 0.1560904 +VERTEX_SE3:QUAT 5778 31.098611 34.001461 -12.074656 0.1224878 0.6271295 -0.7054762 0.3066083 +VERTEX_SE3:QUAT 5779 32.157242 34.068024 -12.357671 0.1031613 -0.0291674 -0.3343897 0.9363176 +VERTEX_SE3:QUAT 5780 32.204079 34.608906 -11.489374 0.4935993 -0.3952628 0.3618600 0.6849703 +VERTEX_SE3:QUAT 5781 31.151180 34.588343 -11.437764 -0.0270189 -0.8758784 0.2765966 0.3944633 +VERTEX_SE3:QUAT 5782 30.220264 34.611060 -11.311012 0.8339812 -0.2573090 -0.2602338 0.4129719 +VERTEX_SE3:QUAT 5783 29.236421 34.619610 -11.169085 0.6071675 0.0804163 -0.7692117 0.1821926 +VERTEX_SE3:QUAT 5784 28.156158 34.660601 -11.131847 0.4012029 -0.4395022 -0.1338587 0.7924367 +VERTEX_SE3:QUAT 5785 27.150341 34.851633 -10.973173 0.0731656 -0.2342971 0.6794988 0.6913994 +VERTEX_SE3:QUAT 5786 26.108325 34.699412 -11.205716 0.4740185 -0.2414937 -0.7954984 0.2901200 +VERTEX_SE3:QUAT 5787 25.090884 34.732199 -11.317090 0.4292541 -0.6026317 0.2615782 0.6198006 +VERTEX_SE3:QUAT 5788 24.281081 34.822249 -11.253674 0.3610333 -0.7577475 -0.0254165 0.5429803 +VERTEX_SE3:QUAT 5789 23.281990 34.822158 -11.116083 -0.2063372 0.4061156 -0.8425878 0.2872994 +VERTEX_SE3:QUAT 5790 22.379289 34.790577 -10.932057 0.2224829 0.0190470 -0.9309628 0.2888715 +VERTEX_SE3:QUAT 5791 21.499562 34.877664 -10.759933 0.3317099 -0.2162021 -0.5841860 0.7084857 +VERTEX_SE3:QUAT 5792 20.623048 35.002584 -10.641344 -0.5659398 -0.4267418 0.7048717 0.0275604 +VERTEX_SE3:QUAT 5793 19.805419 35.203348 -10.339932 -0.3976882 0.0273967 0.9021671 0.1648881 +VERTEX_SE3:QUAT 5794 18.797190 35.533313 -10.214164 -0.2366925 -0.7970703 0.3447121 0.4356939 +VERTEX_SE3:QUAT 5795 17.739743 35.678854 -9.663320 0.0584867 0.0579674 0.9745004 0.2087298 +VERTEX_SE3:QUAT 5796 16.861302 35.870771 -9.638664 0.7135718 -0.0584411 -0.6899570 0.1065800 +VERTEX_SE3:QUAT 5797 15.819110 36.129155 -9.490962 0.2796452 0.8018876 -0.1015480 0.5181340 +VERTEX_SE3:QUAT 5798 14.955907 36.442071 -9.453766 0.5167361 -0.1440568 0.7406714 0.4045212 +VERTEX_SE3:QUAT 5799 14.056837 36.771650 -9.439691 -0.3643645 -0.0119005 0.8155074 0.4494936 +VERTEX_SE3:QUAT 5800 14.440574 37.281253 -8.652451 0.2685917 -0.1754393 0.9046285 0.2805829 +VERTEX_SE3:QUAT 5801 15.386491 37.047740 -8.867189 0.2231101 -0.0857493 -0.7022921 0.6705630 +VERTEX_SE3:QUAT 5802 16.238714 36.692780 -8.910789 0.5346316 -0.1768255 -0.7845737 0.2595107 +VERTEX_SE3:QUAT 5803 17.133831 36.129155 -8.774868 -0.2742303 -0.6648427 0.3836976 0.5792737 +VERTEX_SE3:QUAT 5804 18.011340 35.827593 -8.892368 0.1652779 -0.1859899 -0.4729685 0.8452170 +VERTEX_SE3:QUAT 5805 18.984375 35.577801 -9.142646 -0.0130410 0.7325307 -0.1621026 0.6610231 +VERTEX_SE3:QUAT 5806 19.856203 35.391041 -9.190725 0.2884108 0.1570845 0.3364871 0.8825645 +VERTEX_SE3:QUAT 5807 20.904649 35.285224 -9.174787 0.1771018 0.7565811 -0.0659195 0.6259988 +VERTEX_SE3:QUAT 5808 21.762424 35.367000 -9.242366 0.5128749 0.1554843 0.5530782 0.6378781 +VERTEX_SE3:QUAT 5809 22.654680 35.352468 -9.280003 -0.0059598 -0.6275767 0.3144730 0.7121929 +VERTEX_SE3:QUAT 5810 23.605545 35.355144 -9.087730 0.0962959 -0.6091057 0.7470193 0.2483537 +VERTEX_SE3:QUAT 5811 24.637154 35.152397 -8.929716 0.3150244 -0.0871042 -0.8377646 0.4374048 +VERTEX_SE3:QUAT 5812 25.546582 35.004263 -8.963060 -0.0679842 0.4671609 -0.2704374 0.8390486 +VERTEX_SE3:QUAT 5813 26.455609 34.792132 -9.095316 -0.0641788 -0.1117867 -0.5529199 0.8232038 +VERTEX_SE3:QUAT 5814 27.382576 34.451423 -9.204593 0.5240645 -0.6215347 0.2489389 0.5263843 +VERTEX_SE3:QUAT 5815 28.413920 34.290662 -9.344651 -0.1329428 0.0870707 -0.1537132 0.9752523 +VERTEX_SE3:QUAT 5816 29.287578 34.101469 -9.343342 0.0601623 0.1937580 0.8822247 0.4248741 +VERTEX_SE3:QUAT 5817 30.308163 33.949296 -9.450937 0.2810053 0.1558439 0.3030833 0.8971562 +VERTEX_SE3:QUAT 5818 31.375404 33.733614 -9.548295 0.2675405 -0.5288094 0.1081816 0.7981725 +VERTEX_SE3:QUAT 5819 32.482616 33.553950 -9.571900 -0.2665006 0.4421045 -0.7378598 0.4348380 +VERTEX_SE3:QUAT 5820 32.661787 34.103466 -8.719953 0.2366533 -0.8325384 0.1986830 0.4597827 +VERTEX_SE3:QUAT 5821 31.650836 34.363028 -8.687956 -0.6124044 0.0031841 0.7904069 0.0144075 +VERTEX_SE3:QUAT 5822 30.661765 34.581638 -8.356744 0.6848895 0.2260651 -0.4033241 0.5631613 +VERTEX_SE3:QUAT 5823 29.718926 34.892071 -8.119883 -0.6947350 0.2745158 -0.6610220 0.0709524 +VERTEX_SE3:QUAT 5824 28.574382 35.170036 -7.909998 0.1672656 -0.0688823 -0.8321197 0.5242655 +VERTEX_SE3:QUAT 5825 27.601818 35.372639 -7.808751 -0.1014456 0.0926634 -0.9290488 0.3434976 +VERTEX_SE3:QUAT 5826 26.751452 35.483375 -7.716549 0.0377289 0.6082555 -0.5446184 0.5761879 +VERTEX_SE3:QUAT 5827 25.941231 35.600920 -7.588387 0.4376206 0.1910472 -0.4806715 0.7354890 +VERTEX_SE3:QUAT 5828 25.002618 35.663137 -7.633942 0.8437872 -0.3394006 -0.1073245 0.4016365 +VERTEX_SE3:QUAT 5829 24.089301 35.838751 -7.522026 0.0190973 -0.8025122 0.1098732 0.5861206 +VERTEX_SE3:QUAT 5830 22.931848 35.850827 -7.312959 0.8829175 -0.2447160 -0.1966248 0.3491553 +VERTEX_SE3:QUAT 5831 21.975232 35.974270 -7.148644 0.3729767 -0.4942757 0.7501542 0.2320530 +VERTEX_SE3:QUAT 5832 20.841886 36.064251 -7.141015 0.1199289 -0.1466072 -0.7954201 0.5756998 +VERTEX_SE3:QUAT 5833 20.000410 35.924178 -7.101900 0.5051850 0.3237656 0.2091799 0.7721449 +VERTEX_SE3:QUAT 5834 19.049098 35.972830 -7.121287 0.0911957 0.1996559 0.9606998 0.1699318 +VERTEX_SE3:QUAT 5835 18.017946 35.918838 -7.057697 0.4588957 -0.4559797 0.7457087 0.1594233 +VERTEX_SE3:QUAT 5836 17.074855 35.998010 -7.256164 -0.1529470 -0.1028135 -0.9232050 0.3372374 +VERTEX_SE3:QUAT 5837 15.995521 35.966875 -7.409443 0.5498021 -0.4567652 0.2650301 0.6471801 +VERTEX_SE3:QUAT 5838 15.113695 35.830330 -7.603366 0.0757304 -0.7016019 0.4662434 0.5335136 +VERTEX_SE3:QUAT 5839 14.342810 35.976388 -7.744041 -0.2575994 0.4666192 -0.3346898 0.7771048 +VERTEX_SE3:QUAT 5840 14.319889 36.446818 -6.582638 0.6113965 -0.1881641 0.7492088 0.1716821 +VERTEX_SE3:QUAT 5841 15.412002 36.639636 -6.415686 -0.4891831 -0.5330949 0.5075139 0.4679096 +VERTEX_SE3:QUAT 5842 16.391985 36.512873 -6.226346 0.4237841 -0.3818376 0.3806868 0.7277944 +VERTEX_SE3:QUAT 5843 17.323335 36.746581 -6.095058 0.5842849 -0.0857829 -0.0059065 0.8069805 +VERTEX_SE3:QUAT 5844 18.247027 36.648780 -6.076721 0.0152618 -0.4782656 0.1916739 0.8569074 +VERTEX_SE3:QUAT 5845 19.296303 36.620900 -6.106754 0.4835867 0.0382740 -0.0001967 0.8744593 +VERTEX_SE3:QUAT 5846 20.083580 36.723308 -6.153157 0.1198638 -0.5958212 0.2488670 0.7541186 +VERTEX_SE3:QUAT 5847 20.951037 36.892193 -6.089262 0.1174732 -0.2793721 -0.9510684 0.0601681 +VERTEX_SE3:QUAT 5848 22.024386 36.900928 -5.891405 -0.1978704 -0.4019151 0.8342574 0.3214439 +VERTEX_SE3:QUAT 5849 22.969184 36.860956 -5.697290 0.8724691 -0.0729233 0.0329426 0.4820734 +VERTEX_SE3:QUAT 5850 23.925852 36.874774 -5.758234 -0.4324760 0.5925019 -0.5822678 0.3505284 +VERTEX_SE3:QUAT 5851 24.939518 36.794351 -5.759618 0.6432367 0.1763952 -0.2647778 0.6964366 +VERTEX_SE3:QUAT 5852 26.040384 36.868787 -5.752071 -0.3809317 0.6076677 -0.5601948 0.4145031 +VERTEX_SE3:QUAT 5853 27.125864 37.028985 -5.868483 0.3476187 0.1502686 0.0408882 0.9246128 +VERTEX_SE3:QUAT 5854 28.130248 37.157932 -6.004735 0.1022421 0.5035282 -0.8499102 0.1168699 +VERTEX_SE3:QUAT 5855 29.249097 37.214050 -5.939020 0.0294648 -0.5652636 0.0296184 0.8238517 +VERTEX_SE3:QUAT 5856 30.279914 37.226664 -5.873431 0.5442535 -0.1729001 -0.8069032 0.1509996 +VERTEX_SE3:QUAT 5857 31.307643 37.159443 -5.715490 0.2375578 -0.2504611 -0.5302377 0.7743923 +VERTEX_SE3:QUAT 5858 32.314260 37.053865 -5.626769 -0.2506632 0.1902902 -0.3935129 0.8637738 +VERTEX_SE3:QUAT 5859 33.229227 37.115960 -5.815098 -0.4798149 -0.6826319 0.5511006 0.0089169 +VERTEX_SE3:QUAT 5860 32.969571 37.612707 -5.073240 -0.1471896 -0.1408821 0.8211239 0.5331444 +VERTEX_SE3:QUAT 5861 32.047919 37.457492 -5.334446 0.2794704 -0.0932164 -0.4555561 0.8400450 +VERTEX_SE3:QUAT 5862 31.099281 37.326160 -5.619505 0.4574112 0.2264254 -0.8573766 0.0664216 +VERTEX_SE3:QUAT 5863 30.084434 37.480241 -5.734695 0.3564863 -0.0312191 -0.7479435 0.5590380 +VERTEX_SE3:QUAT 5864 29.261682 37.520744 -5.934740 0.4741552 -0.0202146 0.8002798 0.3664977 +VERTEX_SE3:QUAT 5865 28.268707 37.492317 -6.438100 0.7819864 -0.2274957 0.4426603 0.3752263 +VERTEX_SE3:QUAT 5866 27.299669 37.506149 -6.822678 0.8782795 -0.0861507 0.3235387 0.3413590 +VERTEX_SE3:QUAT 5867 26.512009 37.552770 -7.348481 0.0042341 -0.8162756 0.2199588 0.5341296 +VERTEX_SE3:QUAT 5868 25.707640 37.468121 -7.879991 0.3626053 0.0673554 0.6290950 0.6842661 +VERTEX_SE3:QUAT 5869 24.726495 37.544572 -8.419087 0.3406733 0.1580410 0.3138517 0.8720446 +VERTEX_SE3:QUAT 5870 23.716289 37.499541 -8.616485 0.4371963 0.7561933 -0.0468041 0.4846035 +VERTEX_SE3:QUAT 5871 22.712476 37.648124 -8.962912 0.2549784 0.0432609 -0.6636437 0.7019199 +VERTEX_SE3:QUAT 5872 21.671380 37.674346 -9.433464 -0.1710876 0.1831482 -0.7804982 0.5727202 +VERTEX_SE3:QUAT 5873 20.673034 37.824184 -9.861015 -0.1206671 -0.4530064 0.6284670 0.6206882 +VERTEX_SE3:QUAT 5874 19.648025 37.927649 -10.192494 -0.1353385 -0.2652373 -0.1933931 0.9348432 +VERTEX_SE3:QUAT 5875 18.681669 37.870597 -10.491100 -0.0651437 -0.0701898 0.7655222 0.6362433 +VERTEX_SE3:QUAT 5876 17.775849 37.944658 -11.074858 0.0293963 0.4263315 -0.8617744 0.2733536 +VERTEX_SE3:QUAT 5877 16.808713 37.964710 -11.326263 0.7961834 -0.1244575 0.3687739 0.4632582 +VERTEX_SE3:QUAT 5878 15.941621 37.882614 -11.759685 0.1728901 0.3771556 0.1834394 0.8911861 +VERTEX_SE3:QUAT 5879 15.270542 37.860748 -12.319258 0.2937375 -0.1228501 -0.9379299 0.1375266 +VERTEX_SE3:QUAT 5880 14.879421 38.486794 -11.504500 -0.0118450 0.5661065 -0.7977609 0.2072696 +VERTEX_SE3:QUAT 5881 15.884889 38.342761 -11.177124 0.5483618 0.1523493 -0.6448533 0.5101502 +VERTEX_SE3:QUAT 5882 16.829428 38.229029 -10.817311 -0.2107398 -0.1667499 0.9182591 0.2908323 +VERTEX_SE3:QUAT 5883 17.939811 38.407246 -10.361910 -0.2166605 -0.1368317 0.4051218 0.8776170 +VERTEX_SE3:QUAT 5884 18.760905 38.527666 -9.830885 -0.2947809 0.5304535 -0.7378898 0.2953675 +VERTEX_SE3:QUAT 5885 19.610746 38.707394 -9.350621 -0.2234149 0.1158977 0.8777946 0.4075906 +VERTEX_SE3:QUAT 5886 20.433409 38.698031 -8.765173 0.4144040 0.1962248 0.8786826 0.1329737 +VERTEX_SE3:QUAT 5887 21.487621 39.016693 -8.313142 -0.1593286 0.2944231 -0.8155354 0.4720503 +VERTEX_SE3:QUAT 5888 22.443394 39.406023 -8.016530 0.6289965 0.0143106 0.7664588 0.1292264 +VERTEX_SE3:QUAT 5889 23.282456 39.612306 -7.771672 0.5262955 0.2395310 -0.8022578 0.1483923 +VERTEX_SE3:QUAT 5890 24.110545 39.531170 -7.618284 0.4330245 0.5122660 -0.1584580 0.7245443 +VERTEX_SE3:QUAT 5891 25.177994 39.769533 -7.373471 0.3968842 0.5273878 0.0327710 0.7505139 +VERTEX_SE3:QUAT 5892 26.165303 39.946236 -6.909149 0.2417624 -0.6931440 -0.1031443 0.6711658 +VERTEX_SE3:QUAT 5893 27.251765 39.988423 -6.742462 -0.2033411 -0.3830196 0.0979354 0.8957439 +VERTEX_SE3:QUAT 5894 28.179748 40.096126 -6.524603 0.0037455 0.0437703 0.9078847 0.4169120 +VERTEX_SE3:QUAT 5895 29.113708 40.314353 -6.413403 0.5523501 0.1762907 0.6354149 0.5099793 +VERTEX_SE3:QUAT 5896 30.128825 40.431682 -6.187258 0.1780814 -0.7005707 0.0822784 0.6860889 +VERTEX_SE3:QUAT 5897 31.115747 40.521474 -5.953510 0.0012525 0.0661566 -0.9720505 0.2252543 +VERTEX_SE3:QUAT 5898 32.183445 40.577968 -5.712514 0.6981960 -0.0901072 0.3973993 0.5886228 +VERTEX_SE3:QUAT 5899 32.982389 40.706816 -5.570091 -0.2889791 -0.5767431 0.7330610 0.2155923 +VERTEX_SE3:QUAT 5900 32.839914 41.003203 -4.689780 -0.1841778 0.1231594 -0.0726498 0.9724363 +VERTEX_SE3:QUAT 5901 31.830598 40.902064 -4.982643 -0.1407867 0.7887029 -0.3500282 0.4853938 +VERTEX_SE3:QUAT 5902 30.777519 40.685445 -5.411517 0.2833964 -0.0809955 0.2457117 0.9234457 +VERTEX_SE3:QUAT 5903 29.880118 40.620854 -5.433879 -0.2548361 0.7057197 -0.6039742 0.2687626 +VERTEX_SE3:QUAT 5904 28.727113 40.564056 -5.540799 0.3068116 -0.1397446 -0.3150436 0.8871784 +VERTEX_SE3:QUAT 5905 27.721677 40.583061 -5.871632 -0.4221619 -0.8857058 0.1765232 0.0783841 +VERTEX_SE3:QUAT 5906 26.711692 40.642623 -5.886506 0.0187822 0.2357129 -0.7778056 0.5823273 +VERTEX_SE3:QUAT 5907 25.833296 40.784804 -5.765846 -0.6035811 0.4176819 -0.6567406 0.1729840 +VERTEX_SE3:QUAT 5908 24.758897 40.806518 -5.621864 0.8191957 0.2744133 -0.3289774 0.3812999 +VERTEX_SE3:QUAT 5909 23.991794 40.908766 -5.593993 0.0257546 0.7825231 -0.6215583 0.0256827 +VERTEX_SE3:QUAT 5910 23.021861 41.198228 -5.683584 -0.6536216 -0.3387220 0.6716644 0.0831452 +VERTEX_SE3:QUAT 5911 21.884341 41.181212 -5.761466 0.8514487 0.3641930 0.0275093 0.3763532 +VERTEX_SE3:QUAT 5912 20.736081 41.282807 -5.947876 0.2647756 -0.2229407 0.7005048 0.6240868 +VERTEX_SE3:QUAT 5913 19.809960 41.438606 -5.838119 -0.1476888 -0.6741898 0.6423923 0.3331490 +VERTEX_SE3:QUAT 5914 18.686164 41.371670 -5.907992 0.0999636 0.0018492 0.8686535 0.4852267 +VERTEX_SE3:QUAT 5915 17.685315 41.390069 -6.046505 0.5766472 -0.1011613 -0.6152898 0.5278853 +VERTEX_SE3:QUAT 5916 16.613913 41.574938 -6.142527 -0.3513804 -0.1600485 0.8537379 0.3493535 +VERTEX_SE3:QUAT 5917 15.481704 41.786061 -6.377503 0.2811107 -0.8715147 -0.1432619 0.3753864 +VERTEX_SE3:QUAT 5918 14.473308 42.088740 -6.412481 0.4940202 -0.5272566 0.6888039 0.0591072 +VERTEX_SE3:QUAT 5919 13.415547 42.382458 -6.508629 0.8833211 0.3646299 -0.1864985 0.2280510 +VERTEX_SE3:QUAT 5920 13.302097 42.619349 -5.592275 0.7089731 -0.3153347 0.5123273 0.3680245 +VERTEX_SE3:QUAT 5921 14.175595 42.427154 -5.550866 -0.2125273 -0.0849698 0.9069429 0.3536480 +VERTEX_SE3:QUAT 5922 15.273659 42.156144 -5.541944 -0.0957273 -0.9318012 0.2908926 0.1948445 +VERTEX_SE3:QUAT 5923 16.295169 41.689779 -5.415671 0.0269379 0.4514157 -0.1035915 0.8858708 +VERTEX_SE3:QUAT 5924 17.253647 41.331750 -5.350392 0.1042820 -0.2838817 0.7454015 0.5940649 +VERTEX_SE3:QUAT 5925 18.395750 40.935785 -5.355803 -0.0601728 0.0844722 0.8650402 0.4908656 +VERTEX_SE3:QUAT 5926 19.354129 40.457530 -5.305653 0.8696094 0.1798464 -0.2121573 0.4079509 +VERTEX_SE3:QUAT 5927 20.167802 40.154777 -5.137319 0.0077564 -0.4820800 -0.2299988 0.8453634 +VERTEX_SE3:QUAT 5928 21.047460 39.854075 -4.938266 0.0926578 -0.1297911 -0.9852251 0.0624517 +VERTEX_SE3:QUAT 5929 21.809096 39.522194 -4.821135 0.4918609 0.0133067 -0.2716484 0.8271051 +VERTEX_SE3:QUAT 5930 22.870401 39.111653 -4.865252 0.1050205 -0.7620830 0.6337762 0.0807952 +VERTEX_SE3:QUAT 5931 23.804062 38.809342 -5.052235 0.8752302 0.2903576 -0.3270979 0.2065709 +VERTEX_SE3:QUAT 5932 24.710541 38.467445 -5.058665 0.2129618 -0.1643073 -0.7672228 0.5822538 +VERTEX_SE3:QUAT 5933 25.657381 38.204114 -5.090334 0.0878240 -0.7465231 0.5527733 0.3597664 +VERTEX_SE3:QUAT 5934 26.727202 37.833664 -5.263218 0.2556456 0.4181410 -0.8508422 0.1893966 +VERTEX_SE3:QUAT 5935 27.646156 37.579572 -5.344722 0.6436580 0.2268305 -0.6149047 0.3951513 +VERTEX_SE3:QUAT 5936 28.511662 37.327817 -5.425484 0.5654659 -0.0217382 0.7643060 0.3092120 +VERTEX_SE3:QUAT 5937 29.515303 37.001967 -5.552544 -0.1702106 0.6345059 -0.7005572 0.2786581 +VERTEX_SE3:QUAT 5938 30.450849 36.542603 -5.689379 -0.1347520 -0.7959981 0.5901093 0.0000504 +VERTEX_SE3:QUAT 5939 31.365512 36.178152 -5.708326 0.6476340 0.1137839 0.1556495 0.7371545 +VERTEX_SE3:QUAT 5940 31.548829 36.656826 -4.765663 0.2524368 -0.0589558 0.3543954 0.8984452 +VERTEX_SE3:QUAT 5941 30.536422 36.789522 -4.922849 0.6928331 0.0641777 0.6287743 0.3471403 +VERTEX_SE3:QUAT 5942 29.610144 36.867786 -5.032495 0.2433182 0.3015105 -0.6249872 0.6777011 +VERTEX_SE3:QUAT 5943 28.657863 37.106623 -5.073548 0.1613380 -0.3625068 0.3763829 0.8371946 +VERTEX_SE3:QUAT 5944 27.768492 37.312904 -5.200121 0.3689493 0.0245953 0.7799873 0.5048676 +VERTEX_SE3:QUAT 5945 26.851685 37.680833 -5.338819 0.0201263 0.1182239 0.9415703 0.3147433 +VERTEX_SE3:QUAT 5946 25.932196 37.899476 -5.592830 0.0058818 0.2353610 -0.8500018 0.4712403 +VERTEX_SE3:QUAT 5947 24.937840 38.220148 -5.695796 0.5937561 0.4539223 -0.2630860 0.6100771 +VERTEX_SE3:QUAT 5948 23.950830 38.403231 -5.735190 -0.3686443 -0.4542749 0.7240027 0.3654529 +VERTEX_SE3:QUAT 5949 22.919381 38.746293 -6.050377 0.2353340 0.1329815 -0.7469604 0.6074405 +VERTEX_SE3:QUAT 5950 22.130015 38.882760 -6.161400 -0.1662859 -0.1661659 0.6182434 0.7500086 +VERTEX_SE3:QUAT 5951 21.273531 39.173042 -6.237370 0.5545220 -0.5641771 -0.2242038 0.5691592 +VERTEX_SE3:QUAT 5952 20.299887 39.469587 -6.363945 0.2741652 -0.7478976 0.3282526 0.5076739 +VERTEX_SE3:QUAT 5953 19.358025 39.753628 -6.668189 -0.5116891 0.0099062 -0.8590616 0.0094497 +VERTEX_SE3:QUAT 5954 18.360302 39.856618 -6.808333 0.3638738 -0.0063476 0.5312905 0.7650398 +VERTEX_SE3:QUAT 5955 17.425315 40.023278 -6.749070 -0.0321004 0.3863344 -0.6150846 0.6865757 +VERTEX_SE3:QUAT 5956 16.240158 40.118108 -6.781775 0.3087111 0.2113970 0.8370604 0.3991725 +VERTEX_SE3:QUAT 5957 15.227470 40.184453 -6.861246 -0.3275996 -0.7378395 0.5873276 0.0575988 +VERTEX_SE3:QUAT 5958 14.237238 40.344929 -6.873938 0.0436993 0.1469288 -0.6102631 0.7772267 +VERTEX_SE3:QUAT 5959 13.392978 40.372892 -6.976142 0.1519900 0.0242642 0.8861499 0.4370912 +VERTEX_SE3:QUAT 5960 13.416554 40.863648 -6.140058 -0.4808120 -0.7033848 0.5164323 0.0858330 +VERTEX_SE3:QUAT 5961 14.358375 40.540826 -5.884870 0.3537632 -0.6210123 0.6422625 0.2769373 +VERTEX_SE3:QUAT 5962 15.358099 40.263986 -5.831700 0.3896071 -0.2516172 0.8562071 0.2276060 +VERTEX_SE3:QUAT 5963 16.329798 40.472798 -5.605060 0.5478956 0.1276188 -0.5485592 0.6185521 +VERTEX_SE3:QUAT 5964 17.327887 40.310197 -5.612850 0.1807651 -0.8117432 0.3493116 0.4317155 +VERTEX_SE3:QUAT 5965 18.306579 40.278705 -5.400317 -0.1850937 -0.6375665 0.6800505 0.3110958 +VERTEX_SE3:QUAT 5966 19.379523 40.121381 -5.382591 -0.0968528 -0.3167758 0.7283079 0.5998668 +VERTEX_SE3:QUAT 5967 20.528396 40.029048 -5.129179 0.4588427 0.6111092 -0.5016147 0.4054524 +VERTEX_SE3:QUAT 5968 21.447301 40.129658 -4.996841 0.5848250 0.3078662 -0.6689577 0.3401379 +VERTEX_SE3:QUAT 5969 22.494440 40.030535 -4.705195 0.3668030 0.0028247 0.8657545 0.3404655 +VERTEX_SE3:QUAT 5970 23.424654 39.830938 -4.511653 0.5092621 0.0711518 -0.7607354 0.3960697 +VERTEX_SE3:QUAT 5971 24.303448 39.765534 -4.392246 0.6662060 -0.5017246 0.1862096 0.5193919 +VERTEX_SE3:QUAT 5972 25.180876 39.661131 -4.200298 0.0476183 0.8023582 -0.3454218 0.4843940 +VERTEX_SE3:QUAT 5973 26.066639 39.480949 -4.081762 0.0502875 0.7337610 -0.5249360 0.4283785 +VERTEX_SE3:QUAT 5974 26.909233 39.351385 -4.103179 0.5191055 -0.3084967 -0.5347431 0.5911084 +VERTEX_SE3:QUAT 5975 27.764252 39.096586 -3.958565 0.3778930 -0.2937614 0.6153834 0.6262622 +VERTEX_SE3:QUAT 5976 28.813446 38.792984 -3.858446 0.3959615 -0.2045589 -0.7827839 0.4343034 +VERTEX_SE3:QUAT 5977 29.893992 38.606630 -4.016460 -0.3264801 0.7090815 -0.4921445 0.3852375 +VERTEX_SE3:QUAT 5978 30.714828 38.439790 -4.047379 0.0405050 -0.0410521 -0.5766660 0.8149420 +VERTEX_SE3:QUAT 5979 31.754152 38.045774 -4.005084 -0.7787384 -0.2058589 0.5674710 0.1707785 +VERTEX_SE3:QUAT 5980 31.794475 38.324579 -3.138001 0.8721604 -0.1936580 0.3497718 0.2819441 +VERTEX_SE3:QUAT 5981 31.032750 38.539488 -3.109162 -0.2489000 0.7835813 -0.4982306 0.2753460 +VERTEX_SE3:QUAT 5982 30.047278 38.588879 -3.152265 -0.3434367 -0.3401103 0.7936506 0.3694521 +VERTEX_SE3:QUAT 5983 29.049055 38.858623 -3.025077 -0.0520168 0.8743105 -0.4782297 0.0645892 +VERTEX_SE3:QUAT 5984 28.101412 39.160489 -3.018753 0.7709870 0.4364884 -0.4418500 0.1408034 +VERTEX_SE3:QUAT 5985 27.264056 39.509112 -3.030145 0.6486999 -0.6849378 0.1251572 0.3072201 +VERTEX_SE3:QUAT 5986 26.532689 39.818516 -3.056545 -0.8854851 -0.2276598 0.4050608 0.0035907 +VERTEX_SE3:QUAT 5987 25.551527 39.949858 -2.960716 0.2022734 -0.0114535 0.8177309 0.5387675 +VERTEX_SE3:QUAT 5988 24.633744 40.237411 -2.846677 0.2490344 0.5088516 -0.8082020 0.1608147 +VERTEX_SE3:QUAT 5989 23.518952 40.485259 -2.684332 0.1204661 -0.3583134 0.3001103 0.8758044 +VERTEX_SE3:QUAT 5990 22.630742 40.707797 -2.508152 0.9567065 -0.0508620 0.2326102 0.1673866 +VERTEX_SE3:QUAT 5991 21.610355 41.002829 -2.412881 0.0220942 0.1222688 0.1931486 0.9732707 +VERTEX_SE3:QUAT 5992 20.689855 41.200577 -2.430752 0.6929835 0.1601341 -0.6886344 0.1411154 +VERTEX_SE3:QUAT 5993 19.708364 41.395786 -2.405341 0.2999921 -0.5477625 -0.2472179 0.7408403 +VERTEX_SE3:QUAT 5994 18.843839 41.485403 -2.393553 0.6600934 -0.0864836 0.5132079 0.5416780 +VERTEX_SE3:QUAT 5995 17.928654 41.749483 -2.093279 0.5223031 -0.6840653 0.4417148 0.2532629 +VERTEX_SE3:QUAT 5996 16.801112 42.014880 -1.904030 0.8822118 -0.3242977 0.3210998 0.1158802 +VERTEX_SE3:QUAT 5997 15.783003 42.123444 -1.594185 -0.0097513 0.3892192 -0.8830930 0.2618400 +VERTEX_SE3:QUAT 5998 14.938745 42.225059 -1.270571 -0.1347858 -0.5830474 0.1251680 0.7913416 +VERTEX_SE3:QUAT 5999 14.027327 42.518103 -0.915017 0.3175400 -0.0082380 0.5927477 0.7401018 +VERTEX_SE3:QUAT 6000 31.635741 40.796957 -7.861442 0.5356179 0.1243045 -0.1416843 0.8231570 +VERTEX_SE3:QUAT 6001 30.441639 41.044353 -7.586849 0.3682531 0.2938651 -0.1902712 0.8612954 +VERTEX_SE3:QUAT 6002 29.551394 41.057005 -7.279800 -0.4541145 -0.6532152 0.3842340 0.4684594 +VERTEX_SE3:QUAT 6003 28.460745 41.148946 -6.782314 -0.4880834 0.3127303 -0.8044517 0.1297374 +VERTEX_SE3:QUAT 6004 27.547677 41.335648 -6.512571 0.7343798 -0.3593605 0.3831010 0.4298604 +VERTEX_SE3:QUAT 6005 26.489025 41.561365 -6.136052 -0.1053793 -0.8863107 0.4497993 0.0320813 +VERTEX_SE3:QUAT 6006 25.665992 41.722616 -5.687257 0.3965248 0.2849500 -0.3453072 0.8014577 +VERTEX_SE3:QUAT 6007 24.877644 41.911579 -5.379135 -0.1813154 -0.3077508 0.5683065 0.7412435 +VERTEX_SE3:QUAT 6008 23.948513 42.331460 -5.004146 0.4763461 -0.3560442 0.7059949 0.3845751 +VERTEX_SE3:QUAT 6009 23.126331 42.633641 -4.638617 0.2896641 0.0454513 -0.5248567 0.7990959 +VERTEX_SE3:QUAT 6010 22.422902 43.032059 -4.118615 0.5262808 0.2648784 -0.7971502 0.1319827 +VERTEX_SE3:QUAT 6011 21.688932 43.429514 -3.779259 0.3201860 -0.8872344 0.2812656 0.1765949 +VERTEX_SE3:QUAT 6012 20.970694 43.818161 -3.074381 0.0071336 0.2804054 -0.7690243 0.5743897 +VERTEX_SE3:QUAT 6013 20.130519 44.055016 -2.521394 0.3515416 -0.7288511 0.0705666 0.5832795 +VERTEX_SE3:QUAT 6014 19.395845 44.182020 -1.933906 0.7061674 0.3187001 -0.0709191 0.6282741 +VERTEX_SE3:QUAT 6015 18.642043 44.439859 -1.294647 0.4682010 -0.2679664 -0.7559183 0.3709033 +VERTEX_SE3:QUAT 6016 17.825862 44.686014 -0.625436 0.6794207 -0.1393968 -0.5758532 0.4328385 +VERTEX_SE3:QUAT 6017 17.064209 45.094386 -0.170169 0.8553251 0.2681545 0.1721943 0.4084866 +VERTEX_SE3:QUAT 6018 16.295235 45.573101 0.381091 -0.0709394 0.0461659 -0.6244133 0.7764949 +VERTEX_SE3:QUAT 6019 15.762658 45.917677 0.841916 0.3901517 0.0823015 -0.9164077 0.0347133 +VERTEX_SE3:QUAT 6020 15.203198 46.000212 0.096122 0.6346712 0.3690087 -0.5420070 0.4089663 +VERTEX_SE3:QUAT 6021 15.826086 45.652497 -0.461551 0.0183681 0.7711879 -0.5651542 0.2924596 +VERTEX_SE3:QUAT 6022 16.714924 45.357014 -0.828193 -0.4756302 -0.7208269 0.4277224 0.2669046 +VERTEX_SE3:QUAT 6023 17.497710 45.128083 -1.360584 0.4898512 0.6069888 -0.0649011 0.6224132 +VERTEX_SE3:QUAT 6024 18.342278 44.942610 -1.814740 0.4312297 -0.4010499 0.2435696 0.7706321 +VERTEX_SE3:QUAT 6025 19.072248 44.706069 -2.228288 0.3243507 -0.4428486 -0.3320981 0.7670675 +VERTEX_SE3:QUAT 6026 19.918089 44.506698 -2.791891 0.3685047 0.5680997 -0.2145200 0.7038809 +VERTEX_SE3:QUAT 6027 20.646182 44.239081 -3.236378 0.4577283 -0.3586304 0.5928918 0.5570891 +VERTEX_SE3:QUAT 6028 21.572860 44.064789 -3.625380 0.3957299 -0.0031142 -0.8929192 0.2146705 +VERTEX_SE3:QUAT 6029 22.317553 43.872374 -4.028516 -0.4636281 -0.5462940 0.6562647 0.2364920 +VERTEX_SE3:QUAT 6030 23.162198 43.941720 -4.605032 0.6420176 0.1660113 -0.0392534 0.7474710 +VERTEX_SE3:QUAT 6031 24.106996 43.900292 -5.294065 0.2365983 -0.4837178 0.1158183 0.8346403 +VERTEX_SE3:QUAT 6032 24.897963 43.752326 -6.001711 0.1502998 0.9836740 -0.0628044 0.0764922 +VERTEX_SE3:QUAT 6033 25.860453 43.688167 -6.447280 0.5424481 0.7353224 -0.2960418 0.2782270 +VERTEX_SE3:QUAT 6034 26.787973 43.393390 -7.038020 0.1792398 -0.0937207 0.9762398 0.0777515 +VERTEX_SE3:QUAT 6035 27.568652 43.201514 -7.433268 0.5862742 -0.2960350 0.2757111 0.7018755 +VERTEX_SE3:QUAT 6036 28.441853 43.027250 -8.055900 0.2496407 -0.6946996 -0.0404957 0.6733736 +VERTEX_SE3:QUAT 6037 29.154648 42.738716 -8.781795 0.5927763 -0.7539981 -0.0263870 0.2817921 +VERTEX_SE3:QUAT 6038 30.040725 42.671891 -9.405599 0.6163003 0.2710085 -0.6767571 0.2978726 +VERTEX_SE3:QUAT 6039 30.967679 42.386144 -9.731224 0.1126187 -0.6531514 -0.1432074 0.7349843 +VERTEX_SE3:QUAT 6040 30.624604 42.658683 -10.769359 0.1225207 0.1951066 -0.2858922 0.9301547 +VERTEX_SE3:QUAT 6041 29.688674 42.849031 -10.326244 0.4283291 -0.7902040 0.2180981 0.3801909 +VERTEX_SE3:QUAT 6042 28.747563 43.133622 -9.989820 -0.3162259 -0.5060345 0.6818473 0.4231012 +VERTEX_SE3:QUAT 6043 27.758791 43.205544 -9.579411 0.6003493 -0.5455706 0.5798979 0.0751792 +VERTEX_SE3:QUAT 6044 26.850448 43.411230 -9.224080 0.1031606 0.0627042 -0.6245231 0.7716197 +VERTEX_SE3:QUAT 6045 25.883913 43.706516 -8.891100 0.3580993 -0.2041234 -0.5272499 0.7430384 +VERTEX_SE3:QUAT 6046 24.940773 44.112054 -8.683458 0.4601103 -0.6169075 0.6134753 0.1771210 +VERTEX_SE3:QUAT 6047 23.844052 44.490651 -8.369152 0.4936480 0.6266814 -0.0999348 0.5946387 +VERTEX_SE3:QUAT 6048 22.735503 44.933469 -7.956358 0.4979118 -0.0397497 0.0471679 0.8650312 +VERTEX_SE3:QUAT 6049 22.128913 45.329414 -7.446461 0.5420555 -0.4630445 0.3562714 0.6040168 +VERTEX_SE3:QUAT 6050 21.085242 45.756240 -7.007397 0.7018801 -0.2516417 -0.4038465 0.5300460 +VERTEX_SE3:QUAT 6051 20.346978 45.979560 -6.492227 -0.7158405 -0.5222282 0.4565124 0.0802899 +VERTEX_SE3:QUAT 6052 19.638160 46.400494 -6.027171 -0.1050295 0.7689998 -0.4463512 0.4453973 +VERTEX_SE3:QUAT 6053 18.836860 46.663731 -5.610998 0.5556515 -0.5714546 0.0063545 0.6038632 +VERTEX_SE3:QUAT 6054 17.873889 47.048030 -5.058237 0.1715121 -0.5028098 -0.2458650 0.8107505 +VERTEX_SE3:QUAT 6055 16.980709 47.414854 -4.415592 -0.5449838 -0.7184128 0.3957883 0.1738603 +VERTEX_SE3:QUAT 6056 16.199923 47.652836 -3.799148 0.4706095 -0.2244519 0.3084233 0.7956275 +VERTEX_SE3:QUAT 6057 15.300837 47.955022 -3.426359 0.0132532 -0.5744352 0.7756814 0.2610878 +VERTEX_SE3:QUAT 6058 14.617673 48.166134 -3.021687 0.9215471 -0.3093626 -0.1955388 0.1296547 +VERTEX_SE3:QUAT 6059 13.947826 48.327536 -2.671143 0.5301802 0.1493454 -0.1991537 0.8105200 +VERTEX_SE3:QUAT 6060 13.558266 48.856140 -3.546501 0.2487664 -0.0780175 0.0607965 0.9635000 +VERTEX_SE3:QUAT 6061 14.314201 48.804998 -4.117945 -0.6390488 0.5127720 -0.5732943 0.0038945 +VERTEX_SE3:QUAT 6062 14.993872 48.690886 -4.920066 0.1365694 -0.0131038 -0.4161672 0.8988782 +VERTEX_SE3:QUAT 6063 15.632595 48.394931 -5.704322 0.2892363 -0.0895974 0.7408444 0.5995534 +VERTEX_SE3:QUAT 6064 16.372274 48.249259 -6.751465 0.3029640 -0.9084634 0.2174710 0.1887153 +VERTEX_SE3:QUAT 6065 17.059317 48.180691 -7.629934 0.0997577 -0.8434010 -0.0791308 0.5219784 +VERTEX_SE3:QUAT 6066 17.718420 48.229741 -8.476855 -0.5314243 -0.3532606 0.5297622 0.5587013 +VERTEX_SE3:QUAT 6067 18.356915 48.257780 -9.212630 0.4250810 0.2497389 -0.7074173 0.5064557 +VERTEX_SE3:QUAT 6068 19.008830 48.078374 -9.862795 0.8143460 -0.3631469 -0.4438642 0.0891598 +VERTEX_SE3:QUAT 6069 19.586081 48.044221 -10.763107 0.2549649 0.1524625 -0.4613736 0.8359919 +VERTEX_SE3:QUAT 6070 20.194234 48.126515 -11.662235 -0.7600843 -0.4333363 0.3138960 0.3687287 +VERTEX_SE3:QUAT 6071 20.855671 48.000316 -12.499145 -0.1613421 -0.5684729 0.7932219 0.1469907 +VERTEX_SE3:QUAT 6072 21.373328 48.203205 -13.305259 -0.2722017 -0.5345681 0.0917443 0.7948120 +VERTEX_SE3:QUAT 6073 21.811752 48.397984 -14.201217 0.6690135 0.3263444 -0.5186015 0.4206813 +VERTEX_SE3:QUAT 6074 22.293071 48.362114 -15.145595 0.8532830 -0.5010888 -0.1391499 0.0381512 +VERTEX_SE3:QUAT 6075 22.669812 48.444478 -15.951665 0.7315658 -0.1655026 -0.0115972 0.6612759 +VERTEX_SE3:QUAT 6076 23.135983 48.653958 -16.850784 -0.0332966 -0.8654878 0.1849185 0.4643569 +VERTEX_SE3:QUAT 6077 23.511047 48.907747 -17.684279 -0.8888473 0.3524686 -0.2918119 0.0237107 +VERTEX_SE3:QUAT 6078 24.020993 48.985948 -18.621394 0.6127513 -0.3242862 -0.4307037 0.5778136 +VERTEX_SE3:QUAT 6079 24.393504 49.250010 -19.401289 0.6326001 -0.7244095 0.2385355 0.1347176 +VERTEX_SE3:QUAT 6080 23.595525 49.973729 -19.294242 0.5908470 0.4058158 0.0836879 0.6922498 +VERTEX_SE3:QUAT 6081 23.061574 49.646441 -18.553652 -0.8221777 0.4902398 0.2844929 0.0524643 +VERTEX_SE3:QUAT 6082 22.781078 49.298211 -17.653202 -0.4205513 -0.8745330 -0.1977937 0.1385865 +VERTEX_SE3:QUAT 6083 22.458084 48.923098 -16.663342 0.5348293 -0.6698510 -0.0614655 0.5113504 +VERTEX_SE3:QUAT 6084 21.982735 48.613559 -15.725252 0.1686730 -0.9283457 -0.2936992 0.1531812 +VERTEX_SE3:QUAT 6085 21.810585 48.296415 -14.646534 0.8511418 0.1887348 -0.3479475 0.3447744 +VERTEX_SE3:QUAT 6086 21.272681 47.997158 -13.775075 0.1421117 0.9553431 0.0424490 0.2555814 +VERTEX_SE3:QUAT 6087 20.791782 47.392508 -12.995065 0.4134674 0.4046558 -0.7567309 0.3043957 +VERTEX_SE3:QUAT 6088 20.477828 46.954829 -12.168856 0.8008651 0.0981837 -0.5126574 0.2935260 +VERTEX_SE3:QUAT 6089 20.133056 46.609759 -11.237685 -0.0495711 -0.9779785 0.1666527 0.1154453 +VERTEX_SE3:QUAT 6090 19.825580 46.255702 -10.281086 -0.6196733 -0.6386820 -0.0042324 0.4561495 +VERTEX_SE3:QUAT 6091 19.438381 45.905806 -9.304259 0.2765852 0.7521279 -0.5188642 0.2976309 +VERTEX_SE3:QUAT 6092 19.297776 45.579410 -8.330795 0.9588990 -0.1024686 0.2045435 0.1678538 +VERTEX_SE3:QUAT 6093 19.057976 45.174678 -7.406058 -0.4213295 0.0818875 0.8920642 0.1414122 +VERTEX_SE3:QUAT 6094 18.805984 44.728698 -6.671746 0.6486440 -0.3266438 -0.2235452 0.6500711 +VERTEX_SE3:QUAT 6095 18.310773 44.299480 -5.797998 -0.0550881 -0.5299040 0.1122719 0.8387861 +VERTEX_SE3:QUAT 6096 18.175755 43.963502 -4.873665 -0.9438514 0.2150766 0.2472455 0.0419065 +VERTEX_SE3:QUAT 6097 17.857110 43.675506 -4.007546 -0.5246667 0.1690412 0.7494187 0.3667718 +VERTEX_SE3:QUAT 6098 17.545902 43.373842 -3.041987 0.6762481 -0.5131832 0.4747654 0.2322268 +VERTEX_SE3:QUAT 6099 17.317686 43.126340 -2.036577 -0.0488785 -0.3740670 0.4693152 0.7983909 +VERTEX_SE3:QUAT 6100 16.754593 44.025980 -1.939884 -0.6301237 0.2359208 0.7387236 0.0396603 +VERTEX_SE3:QUAT 6101 16.812877 43.990748 -3.047058 -0.2340347 -0.8521250 0.3199611 0.3416659 +VERTEX_SE3:QUAT 6102 17.056696 44.126059 -3.911852 -0.2459350 -0.6310320 0.4894827 0.5492916 +VERTEX_SE3:QUAT 6103 17.357748 44.191592 -4.800996 -0.6049730 -0.7552428 0.0688662 0.2426383 +VERTEX_SE3:QUAT 6104 17.596803 44.232870 -5.733460 0.3966827 -0.5317009 0.7092767 0.2384607 +VERTEX_SE3:QUAT 6105 17.932231 44.297208 -6.849968 0.5829872 0.1141174 -0.2362774 0.7689448 +VERTEX_SE3:QUAT 6106 18.323769 44.530029 -7.722172 0.4795513 -0.8489925 0.2204615 0.0252776 +VERTEX_SE3:QUAT 6107 18.692093 44.543992 -8.607367 0.6267058 -0.3978127 -0.0726401 0.6661143 +VERTEX_SE3:QUAT 6108 18.919104 44.541018 -9.674711 -0.6470693 -0.6269537 -0.1595917 0.4034363 +VERTEX_SE3:QUAT 6109 19.300961 44.711316 -10.592533 0.2332417 -0.7981567 0.4126216 0.3718704 +VERTEX_SE3:QUAT 6110 19.452658 44.759059 -11.531775 0.9435323 -0.2008167 -0.2625879 0.0216087 +VERTEX_SE3:QUAT 6111 19.670138 44.744929 -12.282786 0.2057245 -0.2713345 -0.1761767 0.9235891 +VERTEX_SE3:QUAT 6112 20.002539 44.715922 -13.271276 0.3574976 0.0857244 -0.6303331 0.6837595 +VERTEX_SE3:QUAT 6113 20.082820 44.697149 -14.076221 0.5550744 0.1897523 -0.7163305 0.3778320 +VERTEX_SE3:QUAT 6114 20.647906 44.443741 -15.094008 -0.9062910 -0.3563174 0.1539524 0.1672520 +VERTEX_SE3:QUAT 6115 20.873766 44.365587 -15.976610 -0.5085556 -0.2755586 0.5534543 0.5992721 +VERTEX_SE3:QUAT 6116 21.130916 43.987155 -16.901083 0.4854062 0.3856063 -0.7523641 0.2227932 +VERTEX_SE3:QUAT 6117 21.284941 43.878260 -18.058150 0.4161395 -0.8142006 -0.3792186 0.1417696 +VERTEX_SE3:QUAT 6118 21.404472 43.827862 -19.006988 -0.0145177 -0.9308607 0.1781937 0.3186449 +VERTEX_SE3:QUAT 6119 21.589395 43.841098 -19.957182 0.4181789 -0.8512159 -0.2079252 0.2394262 +VERTEX_SE3:QUAT 6120 21.400702 44.771349 -20.103897 0.2157720 0.8517492 -0.4244398 0.2186700 +VERTEX_SE3:QUAT 6121 21.329224 44.815462 -19.075799 0.5224574 -0.6968437 0.3389843 0.3557199 +VERTEX_SE3:QUAT 6122 21.022963 44.874529 -18.222163 -0.8316545 -0.4900506 0.2447069 0.0912127 +VERTEX_SE3:QUAT 6123 20.546568 44.881404 -17.089032 -0.6240415 0.7350832 0.2130923 0.1575326 +VERTEX_SE3:QUAT 6124 20.458081 45.068819 -16.116224 -0.0960722 -0.2651460 -0.5232462 0.8041649 +VERTEX_SE3:QUAT 6125 20.114089 45.263080 -15.127901 0.9145049 0.3486896 -0.0212961 0.2040656 +VERTEX_SE3:QUAT 6126 19.759215 45.393127 -14.314428 0.7915167 0.4776206 -0.3399727 0.1726220 +VERTEX_SE3:QUAT 6127 19.575171 45.602061 -13.288452 -0.8624716 -0.1571588 0.4734451 0.0854023 +VERTEX_SE3:QUAT 6128 19.095250 45.759890 -12.313922 -0.6959780 0.4758340 0.3696305 0.3906021 +VERTEX_SE3:QUAT 6129 18.813649 46.146407 -11.500913 -0.8762876 -0.3662787 0.3039606 0.0746185 +VERTEX_SE3:QUAT 6130 18.506922 46.209699 -10.498095 0.4140651 0.4906193 -0.5035223 0.5781938 +VERTEX_SE3:QUAT 6131 18.176180 46.426870 -9.524024 0.4615551 0.3907153 -0.6599472 0.4458454 +VERTEX_SE3:QUAT 6132 17.962570 46.742047 -8.390243 0.6253376 -0.2978154 -0.6964664 0.1875991 +VERTEX_SE3:QUAT 6133 17.846293 46.916272 -7.573179 -0.6656926 -0.7188619 -0.1113057 0.1664391 +VERTEX_SE3:QUAT 6134 17.955883 47.043644 -6.581739 0.2916040 -0.5043874 -0.5666626 0.5826267 +VERTEX_SE3:QUAT 6135 18.034629 47.062688 -5.482967 -0.6074724 -0.7475125 0.2385880 0.1236049 +VERTEX_SE3:QUAT 6136 18.028376 47.215556 -4.488600 -0.1503304 -0.6041891 -0.5843858 0.5204320 +VERTEX_SE3:QUAT 6137 17.919990 47.392123 -3.473252 -0.2147254 0.1207318 0.7965579 0.5520981 +VERTEX_SE3:QUAT 6138 18.135998 47.684169 -2.511681 0.1048490 -0.3821161 -0.6035275 0.6919166 +VERTEX_SE3:QUAT 6139 18.087221 47.985266 -1.511467 -0.2227742 -0.8498491 -0.1556177 0.4515654 +VERTEX_SE3:QUAT 6140 17.798831 48.856275 -1.632273 0.7378912 -0.5224366 -0.3185744 0.2847577 +VERTEX_SE3:QUAT 6141 17.979524 48.653834 -2.644417 -0.2197597 -0.7123062 0.3626802 0.5592751 +VERTEX_SE3:QUAT 6142 18.069272 48.644033 -3.587344 0.8518324 -0.2562111 -0.0737770 0.4508818 +VERTEX_SE3:QUAT 6143 18.110179 48.668845 -4.603125 0.8474822 -0.4223880 -0.3171396 0.0527713 +VERTEX_SE3:QUAT 6144 18.249208 48.790038 -5.587748 -0.2957281 -0.3936238 0.2319455 0.8389318 +VERTEX_SE3:QUAT 6145 18.339835 48.889228 -6.588626 -0.0486993 -0.4958301 0.2210098 0.8384125 +VERTEX_SE3:QUAT 6146 18.325916 49.009986 -7.479520 0.8607609 0.0628112 -0.3467538 0.3672971 +VERTEX_SE3:QUAT 6147 18.416015 49.068759 -8.480511 -0.8815294 -0.1773222 0.4188949 0.1264505 +VERTEX_SE3:QUAT 6148 18.374222 49.067491 -9.375227 0.6979589 -0.6881165 0.1461961 0.1340734 +VERTEX_SE3:QUAT 6149 18.390740 49.044756 -10.581724 -0.6539571 -0.2336212 0.4794906 0.5365166 +VERTEX_SE3:QUAT 6150 18.298045 49.175979 -11.551269 0.3488586 -0.8025108 0.4590406 0.1534790 +VERTEX_SE3:QUAT 6151 18.333451 49.477157 -12.425736 0.1889809 -0.3746083 0.5180721 0.7453564 +VERTEX_SE3:QUAT 6152 18.217955 49.669904 -13.251311 0.0108618 -0.5151922 -0.6710530 0.5330543 +VERTEX_SE3:QUAT 6153 18.476932 49.830763 -14.132392 0.5135583 0.2935464 -0.5304042 0.6072560 +VERTEX_SE3:QUAT 6154 18.534163 50.200153 -15.036136 -0.4238504 -0.7407538 0.3217501 0.4100140 +VERTEX_SE3:QUAT 6155 18.643396 50.220993 -16.093273 -0.7898350 -0.6072920 -0.0003446 0.0857729 +VERTEX_SE3:QUAT 6156 18.755466 50.300229 -17.050204 0.7234783 -0.6729692 0.0067059 0.1537747 +VERTEX_SE3:QUAT 6157 19.024979 50.231433 -17.894191 0.1526076 -0.7473801 0.2770656 0.5842676 +VERTEX_SE3:QUAT 6158 19.229783 50.189569 -19.055290 0.2895936 -0.8473498 -0.1371176 0.4234767 +VERTEX_SE3:QUAT 6159 19.261986 49.952808 -20.011830 -0.8272699 -0.5425609 0.0616635 0.1320976 +VERTEX_SE3:QUAT 6160 18.767538 50.519388 -20.131890 0.7530595 0.5933638 -0.2634427 0.1068587 +VERTEX_SE3:QUAT 6161 18.718805 50.509343 -19.119860 0.7382268 -0.1701379 0.1384320 0.6378957 +VERTEX_SE3:QUAT 6162 18.635879 50.757740 -18.352278 0.8037838 -0.1924283 0.2683381 0.4948714 +VERTEX_SE3:QUAT 6163 18.607568 51.125329 -17.520204 0.0390158 0.8817766 -0.4465881 0.1466522 +VERTEX_SE3:QUAT 6164 18.721114 51.552775 -16.747980 0.0967452 -0.2916872 0.2629075 0.9145702 +VERTEX_SE3:QUAT 6165 18.598502 51.717848 -15.851904 -0.7628777 0.0147182 0.5143882 0.3914151 +VERTEX_SE3:QUAT 6166 18.445973 51.751465 -14.672824 0.5083945 0.3026230 -0.7424065 0.3143039 +VERTEX_SE3:QUAT 6167 18.427309 51.739831 -13.663683 0.4097126 -0.1082499 -0.8909349 0.1632560 +VERTEX_SE3:QUAT 6168 18.266444 51.820999 -12.671066 0.6869932 -0.4282128 -0.5675485 0.1502092 +VERTEX_SE3:QUAT 6169 18.102985 51.961475 -11.423355 0.7770698 0.0442514 -0.0114065 0.6277533 +VERTEX_SE3:QUAT 6170 17.876120 51.946086 -10.305371 0.0100388 -0.7583834 -0.4203262 0.4980760 +VERTEX_SE3:QUAT 6171 17.439965 52.005408 -9.355117 0.9030867 -0.2027600 0.0569862 0.3742663 +VERTEX_SE3:QUAT 6172 17.181516 52.163141 -8.262118 0.3503808 0.1375242 -0.8760090 0.3015437 +VERTEX_SE3:QUAT 6173 16.953903 52.170513 -7.382507 0.1447065 0.9002273 -0.2364818 0.3357487 +VERTEX_SE3:QUAT 6174 16.658108 52.258576 -6.608540 0.3465480 0.4256983 -0.6799056 0.4862240 +VERTEX_SE3:QUAT 6175 16.321017 52.706269 -5.713241 0.6503814 -0.4327127 -0.5403987 0.3126227 +VERTEX_SE3:QUAT 6176 15.982620 53.041130 -4.993501 0.8315941 0.1988136 -0.4389111 0.2761908 +VERTEX_SE3:QUAT 6177 15.738227 53.377241 -4.062373 0.1560247 -0.3882026 0.4714030 0.7763596 +VERTEX_SE3:QUAT 6178 15.361111 53.623186 -3.093242 0.8175364 0.0844280 -0.1094858 0.5590340 +VERTEX_SE3:QUAT 6179 14.929809 53.954787 -2.210582 0.9156833 -0.3159441 -0.2401935 0.0633283 +VERTEX_SE3:QUAT 6180 14.219629 54.318750 -2.689126 0.5741613 -0.5710306 -0.3532016 0.4685206 +VERTEX_SE3:QUAT 6181 14.578313 54.040866 -3.743218 0.1138813 -0.5059674 -0.3234195 0.7914720 +VERTEX_SE3:QUAT 6182 14.793445 53.713474 -4.639042 -0.4195691 -0.5283734 0.3058042 0.6717642 +VERTEX_SE3:QUAT 6183 15.056952 53.254658 -5.634957 -0.0752875 -0.6282151 0.7606883 0.1450201 +VERTEX_SE3:QUAT 6184 15.264458 52.684453 -6.594835 0.7719205 -0.5466201 0.2375338 0.2211855 +VERTEX_SE3:QUAT 6185 15.454034 52.453402 -7.436685 0.0016251 -0.2735509 -0.0519037 0.9604547 +VERTEX_SE3:QUAT 6186 15.824937 51.917674 -8.375213 -0.3168511 0.2235320 0.9139785 0.1195078 +VERTEX_SE3:QUAT 6187 16.016761 51.333028 -9.092843 0.2795286 -0.6959260 0.5572204 0.3564493 +VERTEX_SE3:QUAT 6188 16.176408 50.695827 -10.027361 0.5482830 -0.5728935 0.0228433 0.6088160 +VERTEX_SE3:QUAT 6189 16.459483 50.160343 -10.870995 -0.2149667 -0.1770708 -0.0335851 0.9598475 +VERTEX_SE3:QUAT 6190 16.511793 49.725146 -11.685062 0.4176171 -0.4066294 0.3873147 0.7143079 +VERTEX_SE3:QUAT 6191 16.743790 49.233775 -12.527328 0.3519106 -0.1055795 0.4441604 0.8171496 +VERTEX_SE3:QUAT 6192 16.853425 48.865662 -13.401223 0.8177847 0.0147610 -0.5441847 0.1867440 +VERTEX_SE3:QUAT 6193 16.823750 48.408597 -14.311017 -0.0100085 0.2708686 -0.8368126 0.4756834 +VERTEX_SE3:QUAT 6194 16.725472 47.895668 -15.296736 -0.1330302 -0.1394330 -0.6773194 0.7099999 +VERTEX_SE3:QUAT 6195 16.870597 47.281422 -16.237134 0.2723984 -0.0538568 -0.0901135 0.9564403 +VERTEX_SE3:QUAT 6196 16.828885 46.609623 -17.277507 -0.3595697 0.1726819 0.6114534 0.6833852 +VERTEX_SE3:QUAT 6197 16.716628 46.226852 -18.216936 -0.7624608 -0.3601160 0.3824203 0.3777891 +VERTEX_SE3:QUAT 6198 16.679003 45.736791 -19.087543 -0.1624536 -0.3811377 -0.1462873 0.8983000 +VERTEX_SE3:QUAT 6199 16.701230 45.316080 -20.118498 -0.0388220 -0.7068170 -0.4068413 0.5773930 +VERTEX_SE3:QUAT 6200 16.196085 46.178071 -20.537114 0.9225089 -0.3191823 -0.1692335 0.1358677 +VERTEX_SE3:QUAT 6201 16.349067 46.578775 -19.664574 -0.5474009 -0.2265909 0.7849023 0.1814862 +VERTEX_SE3:QUAT 6202 16.436813 46.938756 -18.621281 -0.3429973 -0.5449647 0.5124856 0.5680888 +VERTEX_SE3:QUAT 6203 16.656633 47.333172 -17.561554 0.1472432 -0.2995150 0.4865173 0.8074101 +VERTEX_SE3:QUAT 6204 17.129131 47.847705 -16.531054 0.4455456 -0.7133637 -0.5268445 0.1226220 +VERTEX_SE3:QUAT 6205 17.099658 48.286774 -15.677106 0.1796483 0.0314396 -0.8265232 0.5325387 +VERTEX_SE3:QUAT 6206 17.297603 48.412212 -14.800313 -0.0014990 0.0449634 0.5145624 0.8562719 +VERTEX_SE3:QUAT 6207 17.563224 48.546896 -13.875928 0.3913053 -0.3462424 0.7330408 0.4354854 +VERTEX_SE3:QUAT 6208 17.862320 48.804376 -13.035882 0.0360062 -0.7661388 0.6375652 0.0724261 +VERTEX_SE3:QUAT 6209 17.980394 49.333882 -12.226808 -0.2163663 -0.0384426 -0.3879008 0.8951205 +VERTEX_SE3:QUAT 6210 18.026392 49.723618 -11.357510 0.1084481 -0.6857513 -0.4590783 0.5542844 +VERTEX_SE3:QUAT 6211 18.133020 50.121905 -10.483086 0.2733415 -0.0105127 0.9110128 0.3085930 +VERTEX_SE3:QUAT 6212 18.141443 50.774558 -9.751869 0.2034639 -0.6092111 0.7465350 0.1736369 +VERTEX_SE3:QUAT 6213 18.108949 51.460373 -8.897893 -0.4554992 0.1046441 0.8696357 0.1590718 +VERTEX_SE3:QUAT 6214 18.239115 51.983249 -8.138983 -0.2469713 -0.0744556 0.9488789 0.1819075 +VERTEX_SE3:QUAT 6215 18.213659 52.360785 -7.299165 0.3707985 -0.5592685 -0.7236384 0.1614768 +VERTEX_SE3:QUAT 6216 18.387122 52.912433 -6.290100 0.1659505 -0.2404665 0.2663947 0.9185152 +VERTEX_SE3:QUAT 6217 18.491163 53.400651 -5.191240 0.0642399 -0.4311312 -0.1215050 0.8917599 +VERTEX_SE3:QUAT 6218 18.443488 53.782706 -4.287478 0.1742484 -0.3854658 0.8300953 0.3633117 +VERTEX_SE3:QUAT 6219 18.219728 54.075595 -3.130523 -0.2682116 -0.9236712 0.2693358 0.0484995 +VERTEX_SE3:QUAT 6220 17.489158 54.686136 -3.477307 0.0971441 0.5093779 -0.7513083 0.4082071 +VERTEX_SE3:QUAT 6221 17.731574 54.159475 -4.589255 0.1029280 0.7810276 -0.3887848 0.4777531 +VERTEX_SE3:QUAT 6222 17.862187 53.784670 -5.525491 0.1230075 0.8999840 -0.3295068 0.2575329 +VERTEX_SE3:QUAT 6223 18.236476 53.415542 -6.491107 0.7637693 0.1282078 -0.4287695 0.4651623 +VERTEX_SE3:QUAT 6224 18.301479 52.791972 -7.258504 0.4041322 0.4116380 -0.7853415 0.2246552 +VERTEX_SE3:QUAT 6225 18.590865 52.540512 -8.215829 0.8691869 -0.4335614 -0.1005941 0.2154519 +VERTEX_SE3:QUAT 6226 18.614420 52.118998 -9.153978 0.1101082 0.0903250 0.6730809 0.7257270 +VERTEX_SE3:QUAT 6227 18.603053 51.852180 -10.240839 0.6765464 -0.1117727 0.0378131 0.7268852 +VERTEX_SE3:QUAT 6228 18.791398 51.447974 -11.222515 0.4966748 -0.4090181 -0.6685083 0.3729813 +VERTEX_SE3:QUAT 6229 18.856919 50.959959 -12.063356 0.8082463 -0.0237565 -0.3986768 0.4327013 +VERTEX_SE3:QUAT 6230 18.939096 50.537470 -13.052407 0.5498223 0.0027933 0.0393336 0.8343504 +VERTEX_SE3:QUAT 6231 19.151656 50.032174 -13.873434 0.6681185 -0.5720285 -0.4613212 0.1165498 +VERTEX_SE3:QUAT 6232 19.182279 49.548568 -14.654768 0.5386963 -0.3010266 -0.5841047 0.5272675 +VERTEX_SE3:QUAT 6233 19.452582 48.936624 -15.494605 0.8407854 -0.2444110 0.1716741 0.4515209 +VERTEX_SE3:QUAT 6234 19.540653 48.584553 -16.275795 -0.0335445 -0.3812472 0.0191893 0.9236650 +VERTEX_SE3:QUAT 6235 19.681232 48.053704 -17.131469 -0.7528904 -0.3231631 0.4935029 0.2918503 +VERTEX_SE3:QUAT 6236 19.911069 47.811256 -18.216786 0.4786551 -0.5236076 -0.6556042 0.2586647 +VERTEX_SE3:QUAT 6237 19.930989 47.429217 -19.205525 0.1520236 -0.5406866 -0.3205834 0.7627406 +VERTEX_SE3:QUAT 6238 19.901316 47.045106 -20.092152 -0.5199822 -0.7436110 0.4015129 0.1242926 +VERTEX_SE3:QUAT 6239 19.758124 46.768243 -20.910564 0.3445994 0.1066995 -0.1892276 0.9132685 +VERTEX_SE3:QUAT 6240 19.142641 47.576695 -21.102048 -0.5375872 -0.2742151 0.6055132 0.5188062 +VERTEX_SE3:QUAT 6241 19.174301 48.040138 -20.183100 0.7660212 -0.6109216 0.0291809 0.1978252 +VERTEX_SE3:QUAT 6242 19.233440 48.519399 -19.273603 0.7707603 0.3658842 -0.3885062 0.3480233 +VERTEX_SE3:QUAT 6243 19.331079 48.779211 -18.373616 0.2594181 0.2394606 -0.8060265 0.4750601 +VERTEX_SE3:QUAT 6244 19.455966 49.041485 -17.402565 0.7568716 0.1871979 -0.6071502 0.1532025 +VERTEX_SE3:QUAT 6245 19.518723 49.261909 -16.471019 -0.9863508 0.0786736 0.1442618 0.0105402 +VERTEX_SE3:QUAT 6246 19.699448 49.505173 -15.578629 -0.4384702 -0.5521626 0.1314787 0.6968312 +VERTEX_SE3:QUAT 6247 19.852533 49.795117 -14.551100 0.8546248 0.0919465 -0.2954659 0.4169679 +VERTEX_SE3:QUAT 6248 20.092205 49.966584 -13.470748 0.8541273 -0.4286611 -0.2763953 0.1015965 +VERTEX_SE3:QUAT 6249 20.064114 50.077210 -12.489749 0.1850908 0.0056288 -0.3551442 0.9162872 +VERTEX_SE3:QUAT 6250 20.242660 50.110899 -11.675251 -0.5518068 0.3516208 0.7137334 0.2499133 +VERTEX_SE3:QUAT 6251 20.308208 50.119473 -10.622150 -0.9118406 -0.1059676 0.3752511 0.1284689 +VERTEX_SE3:QUAT 6252 20.694264 50.143554 -9.698216 0.1531817 -0.2223949 0.0588758 0.9610461 +VERTEX_SE3:QUAT 6253 20.908594 50.212921 -8.720745 0.2281154 -0.2752345 0.6544902 0.6662222 +VERTEX_SE3:QUAT 6254 20.964114 50.253165 -7.765242 0.1843407 -0.1123085 0.8416481 0.4950088 +VERTEX_SE3:QUAT 6255 20.943513 50.108549 -6.571292 -0.3710934 -0.3966932 0.7552128 0.3668484 +VERTEX_SE3:QUAT 6256 21.189632 50.216763 -5.477908 0.6290334 -0.4258708 -0.5253072 0.3834103 +VERTEX_SE3:QUAT 6257 21.558571 50.199325 -4.420057 0.3331458 -0.6160174 -0.6114501 0.3683275 +VERTEX_SE3:QUAT 6258 21.695338 50.298518 -3.602924 0.0234629 -0.6298925 -0.4247676 0.6498134 +VERTEX_SE3:QUAT 6259 21.745966 50.261569 -2.530532 0.7705522 0.0003564 0.0062869 0.6373457 +VERTEX_SE3:QUAT 6260 21.173155 50.944729 -2.428650 0.1270072 -0.3859797 0.8754587 0.2616503 +VERTEX_SE3:QUAT 6261 21.153230 51.107087 -3.388743 -0.1405395 -0.9167298 -0.1077927 0.3581004 +VERTEX_SE3:QUAT 6262 20.982701 51.462167 -4.254958 -0.0944178 -0.4411719 -0.0600654 0.8904183 +VERTEX_SE3:QUAT 6263 20.735272 51.603491 -4.973288 0.4592318 -0.3365573 -0.8070607 0.1564873 +VERTEX_SE3:QUAT 6264 20.517462 51.851496 -6.056923 -0.5952615 -0.7597339 0.1441978 0.2183463 +VERTEX_SE3:QUAT 6265 20.039772 52.187503 -6.886541 0.3916458 0.1417121 -0.1848121 0.8901549 +VERTEX_SE3:QUAT 6266 19.646231 52.453180 -7.967082 0.5893969 0.2295088 -0.2348760 0.7380855 +VERTEX_SE3:QUAT 6267 19.430964 52.677672 -8.829196 0.4343284 0.5616077 -0.4656269 0.5283439 +VERTEX_SE3:QUAT 6268 19.307896 53.066539 -9.696205 -0.5079319 -0.7168413 0.3494178 0.3256546 +VERTEX_SE3:QUAT 6269 19.166681 53.357608 -10.685196 0.5453813 -0.2279458 0.5580618 0.5823804 +VERTEX_SE3:QUAT 6270 18.904186 53.571675 -11.715774 -0.2166488 -0.1696628 0.5107820 0.8144812 +VERTEX_SE3:QUAT 6271 18.623949 53.841200 -12.397182 -0.1903909 -0.2490487 0.5497616 0.7742663 +VERTEX_SE3:QUAT 6272 18.349685 54.054722 -13.338860 0.2951672 -0.7344966 -0.4508190 0.4124964 +VERTEX_SE3:QUAT 6273 18.058401 54.333784 -14.208440 0.8330739 0.1466346 -0.1542432 0.5105833 +VERTEX_SE3:QUAT 6274 17.627381 54.780116 -15.047966 0.5139496 -0.1791637 -0.2100416 0.8121814 +VERTEX_SE3:QUAT 6275 17.205497 54.943064 -16.024094 0.2151226 -0.6848087 -0.3330147 0.6114413 +VERTEX_SE3:QUAT 6276 16.921027 55.176714 -16.994223 -0.0755372 -0.3373194 0.3856330 0.8554513 +VERTEX_SE3:QUAT 6277 16.583007 55.556705 -17.761411 0.9582506 -0.0537296 -0.2791415 0.0308054 +VERTEX_SE3:QUAT 6278 16.206532 56.043506 -18.577150 -0.1004813 -0.4563238 0.7979184 0.3807865 +VERTEX_SE3:QUAT 6279 15.939869 56.441870 -19.616039 0.3922883 -0.4970098 0.1227951 0.7642071 +VERTEX_SE3:QUAT 6280 15.525736 57.111976 -19.121059 0.1172686 0.1199097 -0.9783737 0.1210560 +VERTEX_SE3:QUAT 6281 15.781494 57.015506 -18.078506 0.0996579 -0.3591566 0.9236640 0.0889921 +VERTEX_SE3:QUAT 6282 16.020009 56.722398 -17.174946 0.0190238 -0.2644693 0.0477357 0.9630241 +VERTEX_SE3:QUAT 6283 16.164028 56.603933 -16.353618 0.9204013 0.1731222 -0.1200625 0.3293558 +VERTEX_SE3:QUAT 6284 16.558366 56.285639 -15.443561 -0.5400706 -0.6929442 -0.0684190 0.4727272 +VERTEX_SE3:QUAT 6285 16.720191 55.905822 -14.617169 -0.6540523 0.0464038 0.7219681 0.2209623 +VERTEX_SE3:QUAT 6286 16.841281 55.534009 -13.708548 0.0370221 -0.8237041 0.5635530 0.0504871 +VERTEX_SE3:QUAT 6287 17.081165 55.130099 -12.910425 0.8616203 -0.1529850 0.2036341 0.4390207 +VERTEX_SE3:QUAT 6288 17.335892 54.809087 -11.916812 -0.6554787 0.5881864 0.4729289 0.0268823 +VERTEX_SE3:QUAT 6289 17.778543 54.465802 -10.950166 0.4726737 0.0592371 -0.8314615 0.2859062 +VERTEX_SE3:QUAT 6290 18.041574 54.070623 -10.167552 0.5365778 0.0227244 -0.2153514 0.8155928 +VERTEX_SE3:QUAT 6291 18.310996 53.475833 -9.530603 -0.0302457 -0.3124226 0.0263670 0.9490954 +VERTEX_SE3:QUAT 6292 18.378887 52.995587 -8.687044 0.6297635 0.5424729 -0.4874937 0.2673406 +VERTEX_SE3:QUAT 6293 18.693351 52.489817 -7.778631 0.4056476 -0.4466393 -0.5229793 0.6020433 +VERTEX_SE3:QUAT 6294 18.824859 52.194223 -7.106317 0.4565665 -0.3840404 -0.2086936 0.7749239 +VERTEX_SE3:QUAT 6295 19.091366 51.939938 -6.368136 0.6867441 -0.0417481 0.0965484 0.7192482 +VERTEX_SE3:QUAT 6296 19.418495 51.533742 -5.561770 0.3262444 -0.6736567 0.5477698 0.3737640 +VERTEX_SE3:QUAT 6297 19.675072 50.898194 -4.729598 0.6602915 -0.1690823 -0.5467159 0.4863415 +VERTEX_SE3:QUAT 6298 19.933979 50.373288 -3.941987 0.4548282 0.4962570 -0.4161853 0.6112693 +VERTEX_SE3:QUAT 6299 20.053054 49.938654 -2.905586 -0.0624104 -0.7463281 -0.3530406 0.5607688 +VERTEX_SE3:QUAT 6300 19.568108 50.773189 -2.325730 0.2312128 -0.4137187 0.4481664 0.7579739 +VERTEX_SE3:QUAT 6301 19.409012 51.319332 -3.088038 0.4894351 0.7150955 -0.4955224 0.0595749 +VERTEX_SE3:QUAT 6302 19.294107 51.703450 -4.067440 0.2791920 -0.8209867 -0.3246202 0.3776960 +VERTEX_SE3:QUAT 6303 19.308327 52.052690 -4.964563 0.2732170 -0.0477407 -0.5845394 0.7624873 +VERTEX_SE3:QUAT 6304 19.156859 52.606370 -5.947061 -0.4093150 -0.8924139 0.1091470 0.1553886 +VERTEX_SE3:QUAT 6305 19.061011 53.184641 -6.880847 0.6004748 0.5164722 -0.4048403 0.4569364 +VERTEX_SE3:QUAT 6306 18.894474 53.700918 -7.661352 0.3072438 -0.7277693 -0.1492442 0.5947094 +VERTEX_SE3:QUAT 6307 18.933810 54.233681 -8.505154 0.2780660 -0.7748905 0.1118770 0.5565137 +VERTEX_SE3:QUAT 6308 18.821243 54.704282 -9.287277 0.3287784 0.2396584 -0.4006453 0.8209458 +VERTEX_SE3:QUAT 6309 18.720993 55.414151 -10.015445 0.4130420 0.6301253 -0.4052271 0.5178121 +VERTEX_SE3:QUAT 6310 18.570521 55.939480 -10.800941 0.5514122 -0.1626892 0.2830754 0.7676882 +VERTEX_SE3:QUAT 6311 18.397364 56.507526 -11.550079 0.6830417 0.2128160 -0.2084344 0.6668722 +VERTEX_SE3:QUAT 6312 18.328911 57.046946 -12.351105 -0.3796616 -0.5341378 0.2853915 0.6993608 +VERTEX_SE3:QUAT 6313 18.189497 57.438223 -13.277721 -0.6995764 -0.2866010 0.6409364 0.1328654 +VERTEX_SE3:QUAT 6314 18.234236 58.025127 -14.119787 0.6509073 0.5783167 -0.3738322 0.3195605 +VERTEX_SE3:QUAT 6315 18.059259 58.394592 -14.746206 0.7251828 0.3326607 -0.5703582 0.1952904 +VERTEX_SE3:QUAT 6316 18.180954 59.017031 -15.576823 0.4784462 0.4452506 -0.3492967 0.6714409 +VERTEX_SE3:QUAT 6317 18.270043 59.526251 -16.454677 -0.3283062 -0.8407494 0.0789453 0.4232293 +VERTEX_SE3:QUAT 6318 18.260033 60.256719 -17.364079 0.1594916 -0.4251108 -0.4009903 0.7956444 +VERTEX_SE3:QUAT 6319 18.290146 60.816439 -18.260067 -0.8141867 -0.1061717 0.5354969 0.1976629 +VERTEX_SE3:QUAT 6320 18.050063 61.639020 -17.742192 -0.3367853 0.1234812 0.7399741 0.5690047 +VERTEX_SE3:QUAT 6321 17.991700 61.154791 -16.942004 -0.4004563 -0.4710129 -0.0701242 0.7828564 +VERTEX_SE3:QUAT 6322 18.151095 60.823908 -16.120534 0.3560207 -0.6916857 -0.4961701 0.3855327 +VERTEX_SE3:QUAT 6323 18.180103 60.556871 -15.142180 -0.0598517 -0.1759615 -0.1316798 0.9737124 +VERTEX_SE3:QUAT 6324 18.324114 60.264734 -13.979502 0.8660701 -0.2187224 -0.2476753 0.3751534 +VERTEX_SE3:QUAT 6325 18.526845 60.067815 -13.238128 0.3899888 -0.1483740 0.3071425 0.8553113 +VERTEX_SE3:QUAT 6326 18.572427 59.762557 -12.379559 -0.2154423 -0.6476306 0.4697646 0.5598932 +VERTEX_SE3:QUAT 6327 18.655742 59.517183 -11.429298 0.3182519 -0.3471446 -0.8803163 0.0570048 +VERTEX_SE3:QUAT 6328 18.618455 59.409453 -10.427997 -0.6999828 -0.5473265 0.1537699 0.4322183 +VERTEX_SE3:QUAT 6329 18.617067 59.370164 -9.442499 0.3636419 -0.2517844 -0.8939050 0.0728213 +VERTEX_SE3:QUAT 6330 18.865469 59.171742 -8.595536 0.6341146 0.1907428 -0.1441828 0.7353416 +VERTEX_SE3:QUAT 6331 19.197105 58.897192 -7.747701 -0.4872901 -0.0823109 0.7289099 0.4737760 +VERTEX_SE3:QUAT 6332 19.516900 58.947377 -6.678171 0.1719163 0.0092255 -0.4575635 0.8723504 +VERTEX_SE3:QUAT 6333 19.680030 58.690228 -5.716103 -0.1978091 -0.7245674 0.3296760 0.5720029 +VERTEX_SE3:QUAT 6334 19.866789 58.688703 -4.620566 0.5347398 -0.6703781 -0.3939636 0.3308161 +VERTEX_SE3:QUAT 6335 20.043858 58.266706 -3.731337 -0.8415697 0.2226971 0.4815855 0.1012021 +VERTEX_SE3:QUAT 6336 20.218316 57.983143 -2.885605 0.4727385 -0.5158459 -0.5487950 0.4574336 +VERTEX_SE3:QUAT 6337 20.842059 57.752183 -1.971738 -0.2749639 -0.3985094 0.8734212 0.0521578 +VERTEX_SE3:QUAT 6338 21.239732 57.413254 -1.076730 0.7254330 0.5669549 -0.3884544 0.0375818 +VERTEX_SE3:QUAT 6339 21.915270 57.162065 -0.236776 0.6982820 0.2604642 -0.4843560 0.4582139 +VERTEX_SE3:QUAT 6340 21.345140 57.866604 0.127809 0.4915354 -0.6656101 -0.4980089 0.2595058 +VERTEX_SE3:QUAT 6341 21.111112 58.211946 -0.845314 0.1673892 -0.3560693 0.4528405 0.8000819 +VERTEX_SE3:QUAT 6342 20.613378 58.619975 -1.635852 -0.4052030 -0.3743723 -0.0250808 0.8336827 +VERTEX_SE3:QUAT 6343 20.401709 58.978171 -2.638544 0.6149337 -0.0380901 -0.4255323 0.6628182 +VERTEX_SE3:QUAT 6344 20.197391 59.217927 -3.447197 0.9240839 -0.0795549 -0.1260114 0.3519390 +VERTEX_SE3:QUAT 6345 20.074587 59.454846 -4.385953 0.1922711 -0.7068738 0.4120143 0.5418538 +VERTEX_SE3:QUAT 6346 19.935001 59.896822 -5.223582 -0.5538153 -0.6783650 0.2671035 0.4022004 +VERTEX_SE3:QUAT 6347 19.567642 59.961444 -6.119642 -0.5321715 -0.7009226 0.3793046 0.2857080 +VERTEX_SE3:QUAT 6348 19.401791 60.131370 -7.002238 -0.2786443 -0.2886753 0.9101023 0.1036228 +VERTEX_SE3:QUAT 6349 19.174564 60.371504 -7.898124 -0.5286952 -0.4497024 0.5298200 0.4873806 +VERTEX_SE3:QUAT 6350 18.969583 60.585939 -8.823406 -0.3172041 -0.1849270 0.9139725 0.1727364 +VERTEX_SE3:QUAT 6351 18.530664 60.643566 -9.614867 0.5090817 -0.7490417 -0.1135418 0.4085102 +VERTEX_SE3:QUAT 6352 18.144772 60.902596 -10.551860 0.4845203 0.5372612 -0.6757674 0.1411698 +VERTEX_SE3:QUAT 6353 17.864196 61.257564 -11.607848 0.4088348 -0.1867439 -0.2260340 0.8642277 +VERTEX_SE3:QUAT 6354 17.520884 61.348573 -12.708285 -0.0366424 -0.0864619 0.9615098 0.2582257 +VERTEX_SE3:QUAT 6355 17.128195 61.796195 -13.721681 0.6442674 0.6601018 -0.2806676 0.2653503 +VERTEX_SE3:QUAT 6356 16.621052 61.964266 -14.737253 0.2436574 -0.3056195 0.8002023 0.4548672 +VERTEX_SE3:QUAT 6357 16.151858 62.232200 -15.630088 0.2190736 0.3939856 -0.3846575 0.8054941 +VERTEX_SE3:QUAT 6358 15.811539 62.679003 -16.308802 0.2845760 -0.0602046 0.3391686 0.8946265 +VERTEX_SE3:QUAT 6359 15.288937 62.960484 -17.159442 0.1927944 -0.1924387 -0.1510594 0.9502519 +VERTEX_SE3:QUAT 6360 14.835486 63.536955 -16.565764 -0.7122007 0.0706152 0.6368682 0.2866749 +VERTEX_SE3:QUAT 6361 15.593611 63.169709 -15.873347 0.0448118 -0.2114280 -0.3953296 0.8927512 +VERTEX_SE3:QUAT 6362 16.152942 62.813855 -15.168199 0.1992479 -0.0620111 -0.2381465 0.9485469 +VERTEX_SE3:QUAT 6363 16.638568 62.444203 -14.506101 -0.2702889 -0.0262880 0.7642067 0.5850136 +VERTEX_SE3:QUAT 6364 17.258359 62.056214 -13.922330 0.8327382 -0.3015898 0.4191198 0.1998233 +VERTEX_SE3:QUAT 6365 17.822424 61.797547 -13.334904 0.0824671 -0.0625910 0.4119773 0.9052934 +VERTEX_SE3:QUAT 6366 18.500262 61.617353 -12.563440 0.5904026 0.7464781 -0.1451175 0.2704371 +VERTEX_SE3:QUAT 6367 19.183042 61.455754 -11.772073 0.8729352 0.0352437 -0.4797139 0.0813424 +VERTEX_SE3:QUAT 6368 19.886480 61.052730 -11.208026 0.6501563 0.4062578 -0.4113496 0.4929938 +VERTEX_SE3:QUAT 6369 20.445832 60.853478 -10.645034 -0.4564080 -0.7315623 0.4728916 0.1813337 +VERTEX_SE3:QUAT 6370 21.046319 60.608552 -9.830985 0.4678902 -0.1171518 -0.5229614 0.7027557 +VERTEX_SE3:QUAT 6371 21.614880 60.343063 -9.132575 0.8613361 0.0676258 0.0373042 0.5021308 +VERTEX_SE3:QUAT 6372 22.378474 60.071574 -8.349713 -0.5588305 -0.4398564 0.6098919 0.3496665 +VERTEX_SE3:QUAT 6373 22.846221 59.742478 -7.814288 -0.7640225 -0.1455539 0.6036016 0.1753531 +VERTEX_SE3:QUAT 6374 23.577060 59.715443 -7.267347 0.4756105 -0.6679993 0.5577670 0.1283257 +VERTEX_SE3:QUAT 6375 24.320697 59.453995 -6.575932 -0.4008261 -0.3894553 0.7021963 0.4411160 +VERTEX_SE3:QUAT 6376 24.993104 59.193658 -5.772047 0.6844000 0.0794136 0.4819950 0.5412678 +VERTEX_SE3:QUAT 6377 25.569456 58.925108 -4.887300 0.5562204 -0.4805401 -0.5711968 0.3652865 +VERTEX_SE3:QUAT 6378 26.459548 59.002715 -4.145225 0.5457099 0.2771697 0.4910399 0.6198850 +VERTEX_SE3:QUAT 6379 27.293269 58.754100 -3.522171 0.8353351 -0.4298329 0.1953795 0.2815774 +VERTEX_SE3:QUAT 6380 26.934703 59.295829 -2.703940 0.1218131 0.9274370 -0.3289627 0.1296370 +VERTEX_SE3:QUAT 6381 26.202036 59.418919 -3.224911 -0.3392286 -0.8467120 0.1791448 0.3686595 +VERTEX_SE3:QUAT 6382 25.562895 59.541404 -3.874657 0.0628855 -0.8110767 0.5271574 0.2455709 +VERTEX_SE3:QUAT 6383 24.825310 59.933497 -4.457033 -0.0861938 -0.2232247 -0.6298726 0.7389194 +VERTEX_SE3:QUAT 6384 24.325795 59.982771 -5.243814 0.0150222 0.6484229 -0.6201897 0.4412334 +VERTEX_SE3:QUAT 6385 23.787287 60.209563 -6.271354 0.4519259 0.5943650 -0.6601347 0.0819480 +VERTEX_SE3:QUAT 6386 23.182802 60.322095 -6.963213 0.3317204 -0.0833249 -0.9205585 0.1886545 +VERTEX_SE3:QUAT 6387 22.506250 60.384889 -7.786218 -0.3929475 -0.0908386 0.9082462 0.1114873 +VERTEX_SE3:QUAT 6388 21.933986 60.590512 -8.480782 0.4519918 -0.3560019 0.8178637 0.0080667 +VERTEX_SE3:QUAT 6389 21.281130 60.624070 -9.145185 0.4831284 0.6891130 -0.2316670 0.4878940 +VERTEX_SE3:QUAT 6390 20.573052 60.730753 -9.789416 -0.0482768 -0.9273985 0.1424765 0.3424937 +VERTEX_SE3:QUAT 6391 19.973440 60.730275 -10.441892 0.8581838 -0.2259475 -0.4333567 0.1570678 +VERTEX_SE3:QUAT 6392 19.181213 60.814508 -11.048118 0.8039977 -0.4763003 0.1748721 0.3100733 +VERTEX_SE3:QUAT 6393 18.410142 60.661015 -11.794660 -0.0019414 0.1544533 -0.9422621 0.2971238 +VERTEX_SE3:QUAT 6394 17.919409 60.925365 -12.424028 0.4877231 0.4784700 -0.5809963 0.4423073 +VERTEX_SE3:QUAT 6395 17.283711 60.826271 -12.840338 0.7838585 -0.3168772 0.3075632 0.4365314 +VERTEX_SE3:QUAT 6396 16.397223 60.731888 -13.417187 -0.2312234 -0.1026695 0.8012647 0.5421896 +VERTEX_SE3:QUAT 6397 15.766870 60.715422 -14.089985 0.8808573 -0.0983919 -0.1850040 0.4244797 +VERTEX_SE3:QUAT 6398 15.157665 60.968146 -14.793991 0.1509922 0.6227417 -0.4794188 0.5996264 +VERTEX_SE3:QUAT 6399 14.521670 61.073164 -15.447794 -0.5890297 -0.6250646 0.2726983 0.4335596 +VERTEX_SE3:QUAT 6400 26.115364 58.964676 -0.485001 0.4104933 0.4931324 -0.7257272 0.2482656 +VERTEX_SE3:QUAT 6401 25.651573 59.089742 -1.384529 0.1625458 0.5482792 -0.6446302 0.5073664 +VERTEX_SE3:QUAT 6402 25.159909 59.161311 -2.118484 0.4972790 0.6269553 -0.5101932 0.3151881 +VERTEX_SE3:QUAT 6403 24.584565 59.188134 -2.885063 0.1872480 -0.0188117 -0.8717628 0.4523427 +VERTEX_SE3:QUAT 6404 23.973323 59.424408 -3.691876 0.1934167 0.1986980 0.2642565 0.9237303 +VERTEX_SE3:QUAT 6405 23.276818 59.686067 -4.469070 0.6703234 -0.3381619 -0.6281449 0.2043209 +VERTEX_SE3:QUAT 6406 22.662621 59.804341 -5.339989 0.9512212 -0.0802262 0.1439552 0.2608044 +VERTEX_SE3:QUAT 6407 21.952667 59.810021 -6.097398 -0.2060681 -0.7321311 0.6065156 0.2316435 +VERTEX_SE3:QUAT 6408 21.266898 59.954187 -7.018087 0.6683774 0.2437275 -0.2581150 0.6536400 +VERTEX_SE3:QUAT 6409 20.684838 60.011372 -7.806706 0.2263662 -0.2331190 0.8768602 0.3543021 +VERTEX_SE3:QUAT 6410 20.126819 60.028968 -8.583323 -0.2796321 -0.9090605 0.2552852 0.1739089 +VERTEX_SE3:QUAT 6411 19.648672 60.065584 -9.283015 0.4211626 0.0142424 0.7081999 0.5664558 +VERTEX_SE3:QUAT 6412 19.216398 60.002082 -10.212459 -0.6790741 -0.3100757 0.5850900 0.3168299 +VERTEX_SE3:QUAT 6413 18.846128 59.981845 -11.180813 0.2877490 -0.2972777 0.5676691 0.7117431 +VERTEX_SE3:QUAT 6414 18.498637 59.769232 -12.112686 0.1414660 -0.6859088 0.4558795 0.5492634 +VERTEX_SE3:QUAT 6415 18.076395 59.863720 -13.009413 -0.2455791 -0.0845676 0.7611984 0.5942358 +VERTEX_SE3:QUAT 6416 17.798763 59.985477 -13.778393 0.6965400 0.2953755 -0.4287020 0.4937611 +VERTEX_SE3:QUAT 6417 17.485347 59.860535 -14.668450 0.5338337 -0.2141209 -0.3930737 0.7174028 +VERTEX_SE3:QUAT 6418 17.122433 59.521956 -15.645636 -0.3453448 -0.0385022 0.9373292 0.0258543 +VERTEX_SE3:QUAT 6419 16.999542 59.668776 -16.605120 0.4054981 0.8136448 -0.0536678 0.4131262 +VERTEX_SE3:QUAT 6420 17.589996 59.345603 -16.903913 -0.2007698 -0.7476233 0.5517818 0.3103026 +VERTEX_SE3:QUAT 6421 17.752129 59.447555 -15.871999 0.8525058 -0.4080193 -0.0157486 0.3263527 +VERTEX_SE3:QUAT 6422 18.058748 59.577846 -15.075682 0.4961414 -0.2853536 0.7606321 0.3063592 +VERTEX_SE3:QUAT 6423 18.454900 59.538333 -14.115608 0.3682465 0.0763007 -0.8744103 0.3065606 +VERTEX_SE3:QUAT 6424 18.712669 59.811914 -13.307999 -0.1198436 -0.7923214 0.5981807 0.0066438 +VERTEX_SE3:QUAT 6425 19.206365 60.208352 -12.445387 0.0822193 0.5163884 -0.1957709 0.8296124 +VERTEX_SE3:QUAT 6426 19.496028 60.609231 -11.705270 0.2722287 -0.2794273 0.8703415 0.3005289 +VERTEX_SE3:QUAT 6427 19.850261 60.805950 -10.807689 -0.5346752 -0.2191215 0.7752505 0.2551368 +VERTEX_SE3:QUAT 6428 20.299863 61.104509 -9.942921 0.8580814 -0.2102730 -0.0584707 0.4648255 +VERTEX_SE3:QUAT 6429 20.772499 61.311637 -9.166438 0.8082282 -0.0493942 -0.5865526 0.0168360 +VERTEX_SE3:QUAT 6430 21.333454 61.697924 -8.256080 -0.3852079 -0.6278673 0.5562439 0.3846950 +VERTEX_SE3:QUAT 6431 21.913837 61.956915 -7.426135 -0.0991836 0.2286400 -0.8332809 0.4934869 +VERTEX_SE3:QUAT 6432 22.361599 62.554569 -6.560041 0.3108921 -0.4279009 0.3318597 0.7810993 +VERTEX_SE3:QUAT 6433 22.808197 62.823641 -5.815798 0.1349646 -0.5616254 0.3171614 0.7521769 +VERTEX_SE3:QUAT 6434 23.413178 63.043145 -5.199689 -0.0841961 0.1422353 0.8106718 0.5616862 +VERTEX_SE3:QUAT 6435 23.995413 63.319255 -4.273045 0.8033887 -0.0256918 -0.5347105 0.2607511 +VERTEX_SE3:QUAT 6436 24.509579 63.817331 -3.265542 0.4410230 0.2490370 -0.7500138 0.4253923 +VERTEX_SE3:QUAT 6437 24.981088 64.312321 -2.646329 -0.0863765 0.0806460 -0.2494626 0.9611471 +VERTEX_SE3:QUAT 6438 25.469235 64.714789 -1.919487 0.0113445 -0.8412632 0.3724752 0.3916756 +VERTEX_SE3:QUAT 6439 26.066523 64.852989 -1.310208 0.3097888 -0.5171080 -0.2716175 0.7502361 +VERTEX_SE3:QUAT 6440 26.759605 63.918194 -1.473186 0.8915381 -0.0518633 -0.1978520 0.4041345 +VERTEX_SE3:QUAT 6441 26.131364 63.748556 -2.143094 0.1197368 0.6488888 -0.3521086 0.6637967 +VERTEX_SE3:QUAT 6442 25.629164 63.348824 -2.879680 -0.0426076 -0.7370246 -0.0634106 0.6715344 +VERTEX_SE3:QUAT 6443 25.033597 63.092368 -3.779968 -0.1472376 0.5834713 -0.6621555 0.4465785 +VERTEX_SE3:QUAT 6444 24.232128 62.784139 -4.721050 0.2249793 -0.4405897 0.8637696 0.0957454 +VERTEX_SE3:QUAT 6445 23.649782 62.579808 -5.574954 0.5845464 -0.2912444 0.4590061 0.6023252 +VERTEX_SE3:QUAT 6446 23.130647 62.436971 -6.426713 0.2040729 0.1302921 -0.8912552 0.3834611 +VERTEX_SE3:QUAT 6447 22.663272 62.089714 -7.385831 -0.1987675 -0.1950363 -0.4411416 0.8531391 +VERTEX_SE3:QUAT 6448 22.262130 62.133328 -8.189763 0.5114096 0.7224524 -0.4063405 0.2267382 +VERTEX_SE3:QUAT 6449 21.672357 61.929048 -8.927908 -0.0173446 0.0693439 -0.1798465 0.9810942 +VERTEX_SE3:QUAT 6450 21.153345 61.454675 -9.765507 0.7327646 0.4255475 -0.5256249 0.0753910 +VERTEX_SE3:QUAT 6451 20.747886 61.271378 -10.766420 -0.2455576 0.0893716 -0.7461543 0.6123462 +VERTEX_SE3:QUAT 6452 20.281485 61.067888 -11.565435 -0.2912667 -0.3910965 0.6807321 0.5466362 +VERTEX_SE3:QUAT 6453 19.713793 61.010560 -12.408655 0.3147029 -0.7342076 0.4843563 0.3567915 +VERTEX_SE3:QUAT 6454 19.188926 60.825978 -13.344374 -0.1476554 -0.7911371 0.5933827 0.0140302 +VERTEX_SE3:QUAT 6455 18.679647 60.762203 -14.234057 0.6792297 -0.4680666 -0.2145236 0.5230108 +VERTEX_SE3:QUAT 6456 18.203252 60.411349 -15.199542 -0.4754995 0.2829599 0.7960878 0.2451082 +VERTEX_SE3:QUAT 6457 17.817413 60.031784 -16.040065 -0.4871592 0.2636944 0.7523273 0.3565736 +VERTEX_SE3:QUAT 6458 17.237421 59.621364 -16.913165 0.5661088 -0.1692729 -0.3667625 0.7185769 +VERTEX_SE3:QUAT 6459 16.750549 59.201599 -17.610817 0.5278719 0.1202058 0.3697262 0.7551188 +VERTEX_SE3:QUAT 6460 17.384718 58.130077 -17.847821 -0.4253133 -0.4615739 0.7497972 0.2094331 +VERTEX_SE3:QUAT 6461 18.086863 58.643295 -17.330168 0.4266990 0.1276775 -0.3677681 0.8163168 +VERTEX_SE3:QUAT 6462 18.663862 58.931422 -16.712773 0.3746956 -0.0470625 -0.0050138 0.9259391 +VERTEX_SE3:QUAT 6463 19.237098 59.344410 -15.926918 -0.7360316 0.1225980 0.6653466 0.0232616 +VERTEX_SE3:QUAT 6464 19.753711 59.752144 -15.380855 -0.6172643 0.2496816 0.6759093 0.3158964 +VERTEX_SE3:QUAT 6465 20.179800 60.114109 -14.679641 -0.2781449 0.2834239 0.8525215 0.3398725 +VERTEX_SE3:QUAT 6466 20.668284 60.386032 -13.983922 -0.4602725 -0.1667324 -0.2283806 0.8415413 +VERTEX_SE3:QUAT 6467 21.350991 60.671378 -13.337632 -0.3079459 -0.0481341 0.8645427 0.3942314 +VERTEX_SE3:QUAT 6468 21.743153 61.413494 -12.408804 0.3494753 0.2424753 -0.2020502 0.8821839 +VERTEX_SE3:QUAT 6469 22.049024 61.826455 -11.411990 -0.0959302 -0.1452551 0.4761189 0.8619798 +VERTEX_SE3:QUAT 6470 22.403762 62.043487 -10.627529 0.4205421 -0.2783573 0.1209013 0.8550114 +VERTEX_SE3:QUAT 6471 22.604722 62.445358 -9.804844 -0.0293017 -0.1871786 -0.4748540 0.8594296 +VERTEX_SE3:QUAT 6472 22.922928 62.895354 -9.073769 0.2200037 -0.5044656 0.5368141 0.6394869 +VERTEX_SE3:QUAT 6473 23.232620 63.324193 -8.245995 0.6226217 0.2483896 0.3138792 0.6724022 +VERTEX_SE3:QUAT 6474 23.615092 63.568333 -7.424731 -0.2699030 -0.1766161 -0.7088542 0.6272837 +VERTEX_SE3:QUAT 6475 24.078002 64.041186 -6.571415 0.3045257 -0.1179291 0.0736015 0.9423055 +VERTEX_SE3:QUAT 6476 24.443590 64.308955 -5.777660 0.0418151 -0.4392193 0.5621528 0.6995157 +VERTEX_SE3:QUAT 6477 24.790911 64.690407 -5.034279 0.6803261 -0.0981866 0.2689947 0.6746538 +VERTEX_SE3:QUAT 6478 25.222829 65.225377 -4.371610 -0.1576662 -0.5789468 0.7795384 0.1796718 +VERTEX_SE3:QUAT 6479 25.629801 65.734721 -3.501601 0.2519870 0.3466284 -0.8602858 0.2761516 +VERTEX_SE3:QUAT 6480 26.337696 64.911992 -3.410893 0.2925468 -0.2158753 0.0769307 0.9283835 +VERTEX_SE3:QUAT 6481 25.880565 64.545919 -4.189755 -0.3149862 -0.2975326 0.8736521 0.2213370 +VERTEX_SE3:QUAT 6482 25.484045 64.093046 -5.119376 -0.6745838 -0.5830796 0.4483798 0.0625333 +VERTEX_SE3:QUAT 6483 25.096506 63.650718 -6.113829 -0.1717546 0.1993823 0.8480700 0.4599177 +VERTEX_SE3:QUAT 6484 24.597240 63.259494 -6.941417 0.8815039 0.1064163 -0.2156441 0.4063545 +VERTEX_SE3:QUAT 6485 24.188951 62.847312 -7.802504 0.8336119 -0.0004623 0.0687416 0.5480562 +VERTEX_SE3:QUAT 6486 23.799677 62.698078 -8.713486 0.7087241 0.4626840 -0.5296677 0.0555501 +VERTEX_SE3:QUAT 6487 23.438767 62.450828 -9.511635 0.3919894 0.4218918 -0.3453240 0.7410148 +VERTEX_SE3:QUAT 6488 23.100095 62.088778 -10.353986 -0.4755417 -0.2859879 0.8121589 0.1801911 +VERTEX_SE3:QUAT 6489 22.610106 61.794996 -11.021080 0.1411292 0.0661624 -0.3192554 0.9347626 +VERTEX_SE3:QUAT 6490 22.192454 61.611269 -11.751799 0.2929918 -0.0881737 -0.9022414 0.3038777 +VERTEX_SE3:QUAT 6491 21.770422 61.352963 -12.549663 -0.6567196 -0.6140805 0.4196105 0.1247060 +VERTEX_SE3:QUAT 6492 21.343012 60.855597 -13.473884 0.3197238 -0.2467497 -0.5728252 0.7132759 +VERTEX_SE3:QUAT 6493 21.006198 60.454117 -14.365610 -0.2230408 0.3378818 -0.9101528 0.0878099 +VERTEX_SE3:QUAT 6494 20.789345 59.944044 -15.180813 0.1564690 -0.8978116 0.1138052 0.3956011 +VERTEX_SE3:QUAT 6495 20.448863 59.676337 -15.998311 0.3716858 0.7691182 -0.5185705 0.0373039 +VERTEX_SE3:QUAT 6496 20.063087 59.376092 -16.834092 -0.0621388 -0.5407828 -0.2754782 0.7923411 +VERTEX_SE3:QUAT 6497 19.706235 58.967551 -17.641864 0.0147115 -0.0008689 0.7642732 0.6447242 +VERTEX_SE3:QUAT 6498 19.319746 58.537908 -18.443410 -0.0345614 0.2552156 -0.6648500 0.7011740 +VERTEX_SE3:QUAT 6499 18.814497 58.300117 -19.295060 0.6633445 -0.5043009 0.5246947 0.1742130 +VERTEX_SE3:QUAT 6500 19.897515 57.938980 -19.320853 0.2970399 -0.8905037 0.1548687 0.3078737 +VERTEX_SE3:QUAT 6501 20.120679 58.500380 -18.587241 0.3335041 -0.7837761 0.5134165 0.1042763 +VERTEX_SE3:QUAT 6502 20.658611 58.906767 -17.791722 0.7175131 -0.1837908 -0.4758595 0.4742928 +VERTEX_SE3:QUAT 6503 21.056992 59.467599 -16.967036 0.2075737 0.0828958 0.9621133 0.1561395 +VERTEX_SE3:QUAT 6504 21.439962 60.047270 -16.290685 -0.2763518 0.2091364 -0.5645777 0.7490952 +VERTEX_SE3:QUAT 6505 21.811744 60.416147 -15.566611 0.6389452 -0.4924804 0.5296754 0.2620231 +VERTEX_SE3:QUAT 6506 22.410963 60.754201 -14.807077 -0.2642938 0.6111535 -0.6339822 0.3933277 +VERTEX_SE3:QUAT 6507 22.832398 61.177344 -14.127093 -0.3524564 -0.4858817 0.3418615 0.7230658 +VERTEX_SE3:QUAT 6508 23.320198 61.660812 -13.435752 -0.2506976 0.4471541 -0.5786937 0.6342850 +VERTEX_SE3:QUAT 6509 24.121975 62.112416 -12.794662 -0.0477003 -0.2937319 0.1972201 0.9341041 +VERTEX_SE3:QUAT 6510 24.811869 62.747203 -12.117191 -0.1555314 -0.1715759 -0.8379515 0.4941751 +VERTEX_SE3:QUAT 6511 25.371315 63.094521 -11.358151 -0.2611337 0.1499062 0.9446947 0.1299584 +VERTEX_SE3:QUAT 6512 26.002034 63.557641 -11.051503 0.6383143 0.4964787 -0.4918901 0.3226576 +VERTEX_SE3:QUAT 6513 26.559879 64.027007 -10.468245 -0.2963104 0.1468959 -0.5821351 0.7427923 +VERTEX_SE3:QUAT 6514 27.415009 64.426374 -9.858605 0.4678329 -0.2548687 -0.4888489 0.6907974 +VERTEX_SE3:QUAT 6515 28.109919 64.996592 -9.284194 0.3193117 -0.5280664 0.7665349 0.1777924 +VERTEX_SE3:QUAT 6516 28.842002 65.417645 -8.848086 0.7259878 0.3733088 0.1740623 0.5507128 +VERTEX_SE3:QUAT 6517 29.563002 65.976005 -8.541279 -0.1240684 0.1752028 -0.1050342 0.9710195 +VERTEX_SE3:QUAT 6518 30.430721 66.452147 -8.309822 0.7630099 0.2252714 -0.5757365 0.1886698 +VERTEX_SE3:QUAT 6519 31.142399 66.789813 -7.906578 -0.0882611 -0.4954624 0.0376206 0.8633143 +VERTEX_SE3:QUAT 6520 31.642219 66.280212 -8.609601 0.5911732 -0.4011512 -0.1301272 0.6875019 +VERTEX_SE3:QUAT 6521 30.947256 65.850310 -8.746013 0.5149541 0.4610240 -0.5095932 0.5124392 +VERTEX_SE3:QUAT 6522 30.246571 65.266622 -8.942390 -0.3346277 -0.5194197 0.4384034 0.6527096 +VERTEX_SE3:QUAT 6523 29.419022 65.024932 -9.363418 0.1624988 0.7885722 -0.1608761 0.5708475 +VERTEX_SE3:QUAT 6524 28.669742 64.808836 -9.328894 0.0608273 -0.6893279 0.7190509 0.0639757 +VERTEX_SE3:QUAT 6525 27.803800 64.292866 -9.469257 0.7324918 0.1198715 0.6336778 0.2180345 +VERTEX_SE3:QUAT 6526 26.767208 64.152954 -9.506104 0.2581059 0.5206278 -0.2475137 0.7752838 +VERTEX_SE3:QUAT 6527 26.020515 63.935807 -9.763324 -0.5095103 0.3273921 -0.7911224 0.0856680 +VERTEX_SE3:QUAT 6528 25.204595 63.560975 -9.946929 -0.0234577 0.6169497 -0.0501417 0.7850533 +VERTEX_SE3:QUAT 6529 24.288441 63.112006 -10.112377 0.2707954 0.8450337 -0.3713197 0.2733306 +VERTEX_SE3:QUAT 6530 23.550712 62.477987 -10.302228 0.1010655 0.8729686 -0.3455049 0.3291472 +VERTEX_SE3:QUAT 6531 22.513845 62.140209 -10.204791 -0.4178211 0.5651982 -0.5236194 0.4814553 +VERTEX_SE3:QUAT 6532 21.744667 61.833128 -10.202136 0.1780835 0.3619601 0.6935837 0.5968356 +VERTEX_SE3:QUAT 6533 20.938322 61.309749 -10.256020 -0.2865981 -0.5415452 0.7526085 0.2411861 +VERTEX_SE3:QUAT 6534 20.151296 60.950242 -10.305997 0.8193165 0.0519058 0.4003442 0.4071249 +VERTEX_SE3:QUAT 6535 19.444558 60.502672 -10.325432 -0.1807951 -0.2314193 0.9153892 0.2753560 +VERTEX_SE3:QUAT 6536 18.527217 59.980968 -10.438605 -0.1613148 -0.0554512 -0.1178751 0.9782679 +VERTEX_SE3:QUAT 6537 17.649868 59.472392 -10.431482 0.5241057 0.2983611 0.6443012 0.4702869 +VERTEX_SE3:QUAT 6538 16.737193 58.819502 -10.494067 -0.8247285 0.0239830 -0.5631238 0.0462531 +VERTEX_SE3:QUAT 6539 15.835959 58.149596 -10.525509 0.4480033 0.3243735 0.7722568 0.3125609 +VERTEX_SE3:QUAT 6540 16.377236 57.582823 -11.238787 0.7546911 -0.1297454 0.4417182 0.4674318 +VERTEX_SE3:QUAT 6541 17.159111 58.203011 -11.131929 -0.4548320 0.2276046 -0.8101718 0.2914543 +VERTEX_SE3:QUAT 6542 18.078512 58.901278 -11.209840 0.3810403 -0.0816052 -0.8090771 0.4399353 +VERTEX_SE3:QUAT 6543 18.634976 59.768826 -11.327031 0.2833886 0.3196692 -0.2961426 0.8542845 +VERTEX_SE3:QUAT 6544 19.206523 60.529047 -11.125923 0.6833983 0.2114217 0.0008811 0.6987609 +VERTEX_SE3:QUAT 6545 20.026654 61.141567 -11.133188 0.6650938 0.5170955 -0.2469763 0.4788164 +VERTEX_SE3:QUAT 6546 20.634599 61.890986 -11.241443 0.1222087 0.1779606 0.5556315 0.8029126 +VERTEX_SE3:QUAT 6547 21.637279 62.571868 -11.329839 0.3838802 -0.2617770 0.6636032 0.5862931 +VERTEX_SE3:QUAT 6548 22.371501 63.175249 -11.253786 -0.3369513 -0.2015747 0.7555863 0.5243289 +VERTEX_SE3:QUAT 6549 23.019767 63.796907 -11.393510 -0.3366651 0.0992392 -0.0525836 0.9349027 +VERTEX_SE3:QUAT 6550 23.932926 64.341685 -11.397695 0.1384779 0.2891395 -0.7456403 0.5841598 +VERTEX_SE3:QUAT 6551 25.010353 65.008296 -11.516279 0.8338067 -0.2110528 0.3373526 0.3826438 +VERTEX_SE3:QUAT 6552 25.838053 65.541830 -11.508282 0.1193870 0.2816750 -0.5494924 0.7774728 +VERTEX_SE3:QUAT 6553 26.706945 66.186012 -11.413796 -0.2924251 0.2086135 -0.2915145 0.8865592 +VERTEX_SE3:QUAT 6554 27.492638 66.772479 -11.339758 0.4772694 0.6387477 -0.0138373 0.6033439 +VERTEX_SE3:QUAT 6555 28.284813 67.259488 -11.514190 0.7346017 -0.0787170 0.1086208 0.6651057 +VERTEX_SE3:QUAT 6556 29.288296 67.836516 -11.531342 0.5253885 -0.2121006 0.8056808 0.1727967 +VERTEX_SE3:QUAT 6557 29.939886 68.187478 -11.555283 -0.2922108 0.1804574 -0.8820932 0.3224277 +VERTEX_SE3:QUAT 6558 30.796786 68.759993 -11.671808 0.3895741 -0.5195787 0.5841563 0.4868587 +VERTEX_SE3:QUAT 6559 31.775526 69.245615 -11.759316 -0.1338177 0.0660152 0.9858730 0.0760875 +VERTEX_SE3:QUAT 6560 32.095931 68.343764 -12.476327 0.0597544 -0.0684571 -0.4267182 0.8998081 +VERTEX_SE3:QUAT 6561 31.241134 67.845897 -12.276424 -0.2106389 -0.2982231 -0.7473772 0.5550870 +VERTEX_SE3:QUAT 6562 30.318691 67.230118 -12.382553 -0.6480264 -0.1499620 -0.7324753 0.1450971 +VERTEX_SE3:QUAT 6563 29.296186 66.771202 -12.279420 -0.3950214 0.7446101 -0.4461414 0.3007851 +VERTEX_SE3:QUAT 6564 28.425620 66.200888 -12.292617 0.7107390 -0.2061536 -0.0155086 0.6723915 +VERTEX_SE3:QUAT 6565 27.646083 65.617257 -12.132872 0.5234491 0.1312178 -0.7835465 0.3079575 +VERTEX_SE3:QUAT 6566 26.817889 65.100164 -11.997190 -0.1646251 0.4181491 0.8112814 0.3739951 +VERTEX_SE3:QUAT 6567 25.933970 64.492926 -11.916081 0.1318278 0.5463556 0.4732929 0.6783146 +VERTEX_SE3:QUAT 6568 25.163746 63.928082 -12.081558 0.0771178 -0.0179514 -0.1552051 0.9847040 +VERTEX_SE3:QUAT 6569 24.228136 63.569150 -12.131132 0.5873784 -0.1476221 -0.5504766 0.5746042 +VERTEX_SE3:QUAT 6570 23.516990 63.034498 -12.052944 0.3718003 -0.6631068 0.5191118 0.3906109 +VERTEX_SE3:QUAT 6571 22.767390 62.619031 -12.297421 0.1301686 -0.3400424 0.8945606 0.2592076 +VERTEX_SE3:QUAT 6572 21.863874 62.126453 -12.461105 -0.3041593 -0.1760098 0.5043105 0.7887830 +VERTEX_SE3:QUAT 6573 21.048225 61.444331 -12.577770 -0.1070544 -0.2338183 0.7206764 0.6438120 +VERTEX_SE3:QUAT 6574 20.415801 61.010156 -12.789505 0.1398933 0.0494914 0.7934508 0.5902680 +VERTEX_SE3:QUAT 6575 19.530842 60.597218 -12.911855 0.6821341 0.4007199 -0.4120838 0.4519995 +VERTEX_SE3:QUAT 6576 18.638762 60.008828 -13.179964 -0.3700100 -0.0652711 0.8814671 0.2860908 +VERTEX_SE3:QUAT 6577 17.798447 59.463279 -13.622518 -0.4497463 -0.5433721 0.6396245 0.3055413 +VERTEX_SE3:QUAT 6578 17.208323 58.851228 -14.081129 0.3640828 0.2874571 0.1501030 0.8730872 +VERTEX_SE3:QUAT 6579 16.752026 58.269799 -14.802328 -0.0791324 0.1940221 0.0997856 0.9726954 +VERTEX_SE3:QUAT 6580 17.534832 57.784691 -15.173445 -0.3670449 0.2534401 -0.0645996 0.8926775 +VERTEX_SE3:QUAT 6581 18.155859 58.476208 -14.885580 -0.1786875 0.3647019 -0.2913593 0.8661253 +VERTEX_SE3:QUAT 6582 18.783567 59.270881 -14.495033 0.1808818 -0.7756935 0.5623278 0.2221908 +VERTEX_SE3:QUAT 6583 19.251288 60.120008 -14.187339 -0.1924229 -0.0958483 -0.2564910 0.9423369 +VERTEX_SE3:QUAT 6584 19.847792 60.835571 -13.772868 0.6836631 0.0949380 0.0250840 0.7231614 +VERTEX_SE3:QUAT 6585 20.322348 61.634611 -13.552485 0.7466659 0.1574537 0.5090600 0.3981912 +VERTEX_SE3:QUAT 6586 20.743982 62.437684 -13.026463 0.3360806 0.2163250 -0.4956686 0.7710811 +VERTEX_SE3:QUAT 6587 21.190769 63.166829 -12.647969 0.6399626 -0.0363544 -0.7320921 0.2305804 +VERTEX_SE3:QUAT 6588 21.800207 63.983757 -12.295546 0.5255762 -0.0601673 -0.4410066 0.7250260 +VERTEX_SE3:QUAT 6589 22.260373 64.797658 -11.926400 0.2595410 -0.3782596 0.4998582 0.7346427 +VERTEX_SE3:QUAT 6590 22.654535 65.649342 -11.535343 -0.2029466 0.4446649 0.7840553 0.3825482 +VERTEX_SE3:QUAT 6591 23.043829 66.550387 -11.367581 -0.3050045 0.5863842 -0.6970472 0.2779406 +VERTEX_SE3:QUAT 6592 23.358968 67.495671 -11.088702 -0.2450852 -0.0849772 0.8057845 0.5323754 +VERTEX_SE3:QUAT 6593 23.616270 68.094444 -10.594369 -0.3273900 -0.3040045 -0.8619641 0.2396143 +VERTEX_SE3:QUAT 6594 23.968644 68.887918 -10.445454 0.0092642 -0.1959620 0.4803000 0.8548830 +VERTEX_SE3:QUAT 6595 24.299534 69.697363 -10.017910 0.0987798 0.7592432 -0.3032048 0.5673263 +VERTEX_SE3:QUAT 6596 24.630525 70.623100 -9.481520 -0.4163433 -0.1066459 0.5970685 0.6773435 +VERTEX_SE3:QUAT 6597 24.954686 71.515668 -8.976805 0.1550762 -0.5962125 0.3751168 0.6926539 +VERTEX_SE3:QUAT 6598 25.125960 72.238827 -8.318950 0.4366509 -0.0800399 -0.0424326 0.8950581 +VERTEX_SE3:QUAT 6599 25.473587 73.237517 -7.909305 0.4593120 0.3155726 -0.0257242 0.8299305 +VERTEX_SE3:QUAT 6600 26.444819 73.000858 -7.952479 -0.3621926 0.0079729 0.4697091 0.8050629 +VERTEX_SE3:QUAT 6601 26.009280 72.231248 -8.514241 -0.1115933 0.7503534 -0.4290930 0.4903018 +VERTEX_SE3:QUAT 6602 25.502188 71.491738 -8.760744 -0.4259919 0.0616981 0.1280784 0.8934876 +VERTEX_SE3:QUAT 6603 25.152325 70.572040 -9.217405 -0.0141217 -0.4677592 0.7851055 0.4057230 +VERTEX_SE3:QUAT 6604 24.843491 69.632194 -9.500061 0.7688527 -0.2578028 0.3368693 0.4784583 +VERTEX_SE3:QUAT 6605 24.475383 68.946963 -9.998569 -0.0541978 -0.4032053 -0.2929435 0.8652584 +VERTEX_SE3:QUAT 6606 24.097005 68.264934 -10.479739 0.0459344 0.3465363 0.2758640 0.8953779 +VERTEX_SE3:QUAT 6607 23.774194 67.385842 -10.895224 0.1501506 -0.2560436 0.9069397 0.2989261 +VERTEX_SE3:QUAT 6608 23.377193 66.545997 -11.426070 -0.3277083 -0.4106789 0.8419062 0.1230612 +VERTEX_SE3:QUAT 6609 22.924787 65.802665 -11.953394 0.2308172 0.6870515 -0.3742305 0.5784766 +VERTEX_SE3:QUAT 6610 22.445864 65.106916 -12.426858 0.6348550 0.1912834 0.4301595 0.6126439 +VERTEX_SE3:QUAT 6611 21.958361 64.283660 -12.913191 0.4486277 -0.4864926 0.5472558 0.5124151 +VERTEX_SE3:QUAT 6612 21.664644 63.661960 -13.440532 -0.3242810 -0.0905134 -0.0916372 0.9371509 +VERTEX_SE3:QUAT 6613 21.242999 62.951425 -13.779888 -0.1056442 -0.4345871 0.6352020 0.6296759 +VERTEX_SE3:QUAT 6614 20.848216 62.221116 -14.233040 -0.5370226 0.1793761 0.8143393 0.1276025 +VERTEX_SE3:QUAT 6615 20.237929 61.655943 -14.822271 0.2613713 -0.0137433 -0.4669448 0.8446649 +VERTEX_SE3:QUAT 6616 19.659646 60.811757 -15.186828 -0.0400325 -0.5667200 0.4800777 0.6683945 +VERTEX_SE3:QUAT 6617 18.985365 60.023154 -15.561239 0.4707125 0.3476073 0.8086673 0.0604654 +VERTEX_SE3:QUAT 6618 18.597665 59.254272 -15.799065 0.7506751 0.2355512 -0.3926507 0.4762646 +VERTEX_SE3:QUAT 6619 18.140405 58.401564 -16.158176 0.3626699 -0.2952881 -0.4135967 0.7811615 +VERTEX_SE3:QUAT 6620 19.045394 57.989716 -16.283579 -0.1817512 0.0923789 -0.9286168 0.3100056 +VERTEX_SE3:QUAT 6621 19.375795 58.918064 -15.878774 -0.4591124 0.2354231 -0.3338412 0.7888864 +VERTEX_SE3:QUAT 6622 19.872844 59.845322 -15.630420 0.1342283 -0.1156541 -0.5983859 0.7813714 +VERTEX_SE3:QUAT 6623 20.342463 60.744769 -15.469255 -0.2096861 0.3330618 0.4396906 0.8073251 +VERTEX_SE3:QUAT 6624 20.783360 61.578155 -15.400797 -0.2875985 -0.2543195 0.7899730 0.4780705 +VERTEX_SE3:QUAT 6625 21.171593 62.780613 -15.426276 0.3454168 -0.4931795 0.7319327 0.3189605 +VERTEX_SE3:QUAT 6626 21.568808 63.720292 -15.252046 0.4937951 -0.1918378 0.7492535 0.3974718 +VERTEX_SE3:QUAT 6627 22.114281 64.631341 -15.040816 -0.4429780 -0.0802552 -0.0818078 0.8891778 +VERTEX_SE3:QUAT 6628 22.653245 65.309244 -14.780437 0.3771376 -0.1728474 -0.0787952 0.9064669 +VERTEX_SE3:QUAT 6629 23.137396 66.072448 -14.597722 0.0138817 -0.1755667 -0.8246418 0.5375402 +VERTEX_SE3:QUAT 6630 23.408940 67.078584 -14.577613 0.1902174 -0.5218242 0.2653053 0.7881179 +VERTEX_SE3:QUAT 6631 23.789278 67.950064 -14.362874 0.3270833 0.0342236 0.6366069 0.6975506 +VERTEX_SE3:QUAT 6632 24.252333 68.832237 -14.183601 -0.1750217 0.0274549 0.5967470 0.7826280 +VERTEX_SE3:QUAT 6633 24.640395 69.700041 -13.979260 -0.2686129 -0.2165190 -0.0260594 0.9382364 +VERTEX_SE3:QUAT 6634 25.147328 70.575000 -13.666401 -0.1024435 0.0859334 -0.2527528 0.9582467 +VERTEX_SE3:QUAT 6635 25.668907 71.507531 -13.252696 -0.1125942 0.2982354 -0.9272080 0.1966304 +VERTEX_SE3:QUAT 6636 26.168482 72.233801 -12.855390 -0.3307601 0.3093330 -0.8824001 0.1275963 +VERTEX_SE3:QUAT 6637 26.745034 72.812452 -12.756965 0.2741843 -0.6647868 0.6868639 0.1053539 +VERTEX_SE3:QUAT 6638 27.444188 73.492490 -12.410426 -0.2328667 -0.1670954 0.2321326 0.9294981 +VERTEX_SE3:QUAT 6639 28.048686 74.330575 -12.223968 -0.1666148 -0.4618199 -0.6901943 0.5315955 +VERTEX_SE3:QUAT 6640 28.796969 73.622965 -12.605638 0.1186735 -0.4552517 0.6591621 0.5866582 +VERTEX_SE3:QUAT 6641 28.292835 73.049153 -12.816656 -0.4284150 0.4639513 -0.2370567 0.7382505 +VERTEX_SE3:QUAT 6642 27.610677 72.140588 -12.904308 -0.0097790 -0.1115154 0.8097234 0.5760353 +VERTEX_SE3:QUAT 6643 26.995168 71.264565 -13.100794 0.2943861 0.4461435 -0.3197224 0.7823493 +VERTEX_SE3:QUAT 6644 26.503975 70.681411 -13.233880 -0.0552594 0.1243273 -0.6955977 0.7054311 +VERTEX_SE3:QUAT 6645 25.951971 69.850250 -13.560497 -0.0689220 0.5431263 0.8323242 0.0866023 +VERTEX_SE3:QUAT 6646 25.345270 68.837096 -13.668188 -0.3044492 0.4820029 -0.8195741 0.0572912 +VERTEX_SE3:QUAT 6647 24.863703 68.073460 -13.747330 0.2809941 0.3069931 0.8781033 0.2360765 +VERTEX_SE3:QUAT 6648 24.366897 67.198577 -13.946688 0.2940949 0.2982994 0.0092909 0.9079864 +VERTEX_SE3:QUAT 6649 24.008785 66.411558 -14.281274 -0.2042852 -0.1319525 -0.6126583 0.7520013 +VERTEX_SE3:QUAT 6650 23.723613 65.533156 -14.584193 -0.3602974 -0.1636056 -0.8727113 0.2859964 +VERTEX_SE3:QUAT 6651 23.495085 64.653830 -14.798170 0.6122010 0.2952346 -0.3823389 0.6259900 +VERTEX_SE3:QUAT 6652 23.270910 63.993477 -15.149095 0.2281411 0.5359285 0.1942765 0.7892964 +VERTEX_SE3:QUAT 6653 23.155481 63.025421 -15.555902 0.2670892 -0.4012607 -0.1346623 0.8657478 +VERTEX_SE3:QUAT 6654 22.868343 61.769477 -15.755477 -0.3550975 -0.0953992 -0.5617512 0.7411075 +VERTEX_SE3:QUAT 6655 22.680921 60.922140 -16.266169 -0.2796614 0.7460192 -0.2772046 0.5370311 +VERTEX_SE3:QUAT 6656 22.326307 59.932549 -16.681905 0.5751042 -0.3862476 0.7186485 0.0601022 +VERTEX_SE3:QUAT 6657 21.748945 58.997031 -17.067087 0.5927243 -0.0854580 0.2088337 0.7731516 +VERTEX_SE3:QUAT 6658 21.175400 58.345698 -17.400539 0.5546066 0.2167347 -0.4606045 0.6582409 +VERTEX_SE3:QUAT 6659 20.774375 57.636469 -17.796436 0.0475876 -0.3883260 0.2628288 0.8819634 +VERTEX_SE3:QUAT 6660 21.743319 57.297179 -18.240850 -0.1988391 -0.6755375 0.6290725 0.3292111 +VERTEX_SE3:QUAT 6661 22.078472 58.009391 -17.904222 0.4611557 -0.1571817 -0.0871520 0.8689268 +VERTEX_SE3:QUAT 6662 22.519627 58.960838 -17.289403 0.4387925 0.1997517 0.6224081 0.6165781 +VERTEX_SE3:QUAT 6663 22.665550 59.831392 -16.789782 -0.4267009 0.2482346 -0.6759228 0.5472059 +VERTEX_SE3:QUAT 6664 23.046912 60.620486 -16.455945 -0.3757167 0.1560405 -0.8980643 0.1672390 +VERTEX_SE3:QUAT 6665 23.263723 61.666179 -15.866690 0.0913581 0.8097242 -0.5130262 0.2698233 +VERTEX_SE3:QUAT 6666 23.379219 62.641234 -15.271299 0.8306174 0.1040487 0.2639474 0.4791455 +VERTEX_SE3:QUAT 6667 23.506867 63.556878 -14.722018 0.7081740 0.1689326 0.0972390 0.6785985 +VERTEX_SE3:QUAT 6668 23.419971 64.515755 -14.135992 0.5224147 -0.3099087 0.5645620 0.5588463 +VERTEX_SE3:QUAT 6669 23.441145 65.238036 -13.374460 0.3812471 0.2508885 0.6549093 0.6023283 +VERTEX_SE3:QUAT 6670 23.492891 65.961913 -12.788477 0.7419813 -0.0958105 -0.4400281 0.4966481 +VERTEX_SE3:QUAT 6671 23.584766 66.734729 -12.258941 0.2833244 -0.4679055 0.4425172 0.7106126 +VERTEX_SE3:QUAT 6672 23.499949 67.594769 -11.524430 0.5969191 -0.1848335 0.2268831 0.7470263 +VERTEX_SE3:QUAT 6673 23.429359 68.264576 -10.845213 0.8394687 0.0645379 -0.0780233 0.5338909 +VERTEX_SE3:QUAT 6674 23.307132 69.133923 -10.237969 -0.3385279 -0.2780676 -0.8170607 0.3748188 +VERTEX_SE3:QUAT 6675 23.232677 69.767802 -9.602903 0.6637582 0.3835816 -0.4662493 0.4414768 +VERTEX_SE3:QUAT 6676 23.303392 70.497440 -8.864995 0.4609188 0.5036075 0.5845985 0.4383810 +VERTEX_SE3:QUAT 6677 23.263731 71.461515 -8.299158 0.5164586 -0.0791126 0.3448379 0.7798067 +VERTEX_SE3:QUAT 6678 23.023769 72.160553 -7.689586 0.6841278 0.3629884 -0.5879251 0.2335653 +VERTEX_SE3:QUAT 6679 22.922446 72.935298 -7.076019 0.2982801 0.4590918 -0.7102745 0.4424635 +VERTEX_SE3:QUAT 6680 23.747014 73.043685 -6.957122 -0.4392718 -0.0508732 0.8968956 0.0055194 +VERTEX_SE3:QUAT 6681 23.909719 72.388530 -7.629557 0.4423120 -0.0572607 -0.7057906 0.5504007 +VERTEX_SE3:QUAT 6682 24.073362 71.703115 -8.286972 -0.0262354 0.5368259 0.1069144 0.8364801 +VERTEX_SE3:QUAT 6683 24.407779 71.105361 -8.945776 -0.4317035 0.0623457 0.8991199 0.0364485 +VERTEX_SE3:QUAT 6684 24.736625 70.354683 -9.620251 -0.2668679 0.0345587 0.3224105 0.9075454 +VERTEX_SE3:QUAT 6685 25.057531 69.748567 -10.196832 -0.4219781 -0.1611914 -0.8908337 0.0486530 +VERTEX_SE3:QUAT 6686 25.244631 68.993405 -10.805846 0.3629884 -0.0255353 0.3066868 0.8795059 +VERTEX_SE3:QUAT 6687 25.523670 68.121957 -11.569483 0.2979469 -0.5240033 0.4728715 0.6426825 +VERTEX_SE3:QUAT 6688 25.720492 67.267855 -12.316252 0.2286967 -0.1133749 -0.0280654 0.9664659 +VERTEX_SE3:QUAT 6689 26.026556 66.435316 -12.859962 0.1277967 0.3334763 0.4283245 0.8300600 +VERTEX_SE3:QUAT 6690 26.330337 65.792745 -13.409545 0.5131117 -0.2043023 0.3518012 0.7557863 +VERTEX_SE3:QUAT 6691 26.520047 65.151719 -13.999788 0.8705560 0.0710568 -0.2960796 0.3865489 +VERTEX_SE3:QUAT 6692 26.670949 64.225657 -14.613542 0.4494276 0.3757461 -0.7656481 0.2657305 +VERTEX_SE3:QUAT 6693 26.996738 63.357581 -15.134716 -0.5191498 -0.4956507 0.6196112 0.3176410 +VERTEX_SE3:QUAT 6694 27.390864 62.698925 -15.624977 -0.3735248 -0.0558964 -0.9236877 0.0644659 +VERTEX_SE3:QUAT 6695 27.504709 62.120691 -16.300561 0.4688586 -0.5478400 0.6866997 0.0921221 +VERTEX_SE3:QUAT 6696 27.682040 61.340366 -16.877002 -0.2528860 -0.3025478 -0.9032060 0.1695064 +VERTEX_SE3:QUAT 6697 27.897833 60.571300 -17.394190 0.7538895 -0.4309400 0.1035847 0.4849861 +VERTEX_SE3:QUAT 6698 28.149741 59.974589 -17.945529 0.0550136 -0.1845969 0.2818648 0.9399201 +VERTEX_SE3:QUAT 6699 28.310134 59.254332 -18.470455 0.7678221 0.0223962 -0.3412771 0.5417358 +VERTEX_SE3:QUAT 6700 29.344093 59.489682 -18.255444 -0.1977451 -0.0601608 0.9700195 0.1278270 +VERTEX_SE3:QUAT 6701 29.127842 60.203009 -17.663632 -0.1458175 -0.3540715 0.4354321 0.8147206 +VERTEX_SE3:QUAT 6702 29.071319 60.875503 -17.173903 -0.2787386 0.3522112 -0.2164589 0.8668320 +VERTEX_SE3:QUAT 6703 28.689693 61.695836 -16.637701 0.7075942 -0.4210502 -0.1463536 0.5482771 +VERTEX_SE3:QUAT 6704 28.350465 62.456565 -15.957621 0.1850655 0.5055046 -0.2151981 0.8148041 +VERTEX_SE3:QUAT 6705 27.943442 63.275238 -15.281820 -0.0310047 -0.2142674 0.6716760 0.7085052 +VERTEX_SE3:QUAT 6706 27.515490 63.699876 -14.711127 -0.4451192 0.5669344 -0.5180210 0.4605524 +VERTEX_SE3:QUAT 6707 26.837846 64.247139 -14.093688 -0.1782549 0.2878858 0.3729444 0.8638631 +VERTEX_SE3:QUAT 6708 26.416115 64.874872 -13.326984 0.6023033 -0.0972258 -0.2766461 0.7424586 +VERTEX_SE3:QUAT 6709 25.964757 65.556345 -12.736360 0.0029444 0.2936621 0.9076274 0.2999440 +VERTEX_SE3:QUAT 6710 25.518865 66.237882 -11.977160 0.0308819 0.4873408 -0.4736835 0.7329183 +VERTEX_SE3:QUAT 6711 25.214818 66.944156 -11.232533 0.0744463 -0.1379301 -0.7639760 0.6259182 +VERTEX_SE3:QUAT 6712 24.902920 67.677869 -10.673245 0.0621889 0.2325604 -0.6775390 0.6949742 +VERTEX_SE3:QUAT 6713 24.442524 68.239968 -10.138696 0.6508670 0.0157915 -0.3671938 0.6642977 +VERTEX_SE3:QUAT 6714 24.185023 68.847254 -9.415171 0.6576977 -0.0085063 -0.7291911 0.1887902 +VERTEX_SE3:QUAT 6715 24.036397 69.692095 -8.716285 -0.2768498 -0.1203062 -0.9443923 0.1303988 +VERTEX_SE3:QUAT 6716 23.923821 70.215758 -8.026806 0.3969536 0.3142820 -0.3024455 0.8075775 +VERTEX_SE3:QUAT 6717 23.771090 71.099057 -7.500850 0.4730087 0.4923198 0.3069930 0.6630530 +VERTEX_SE3:QUAT 6718 23.629897 71.794106 -6.794419 0.1112583 -0.6522229 0.7382623 0.1311319 +VERTEX_SE3:QUAT 6719 23.311376 72.626317 -6.272949 0.0281771 0.2375131 -0.1461586 0.9599121 +VERTEX_SE3:QUAT 6720 24.155753 73.002441 -5.899719 -0.1088110 0.2561966 0.4000611 0.8731979 +VERTEX_SE3:QUAT 6721 24.357987 72.293230 -6.504051 0.2964194 -0.1810853 0.1404484 0.9271558 +VERTEX_SE3:QUAT 6722 24.650864 71.656550 -6.993914 -0.3282089 0.6800693 -0.5703986 0.3231565 +VERTEX_SE3:QUAT 6723 25.139967 70.922385 -7.741310 0.2652705 0.1383865 -0.4860057 0.8211450 +VERTEX_SE3:QUAT 6724 25.583172 70.174500 -8.264744 0.3005633 0.6314433 0.5047607 0.5061203 +VERTEX_SE3:QUAT 6725 25.955150 69.610869 -8.849224 0.6325251 0.3276498 -0.1718689 0.6804548 +VERTEX_SE3:QUAT 6726 26.422627 69.031664 -9.436116 -0.0192475 0.3779676 -0.4046347 0.8324907 +VERTEX_SE3:QUAT 6727 26.773567 68.384800 -10.234137 -0.3254470 -0.0535427 0.2914586 0.8979250 +VERTEX_SE3:QUAT 6728 27.224947 67.562426 -10.809819 0.4829665 0.2518680 0.5281265 0.6514509 +VERTEX_SE3:QUAT 6729 27.583703 67.063808 -11.574697 -0.4875956 -0.3101650 0.8161045 0.0046496 +VERTEX_SE3:QUAT 6730 27.998714 66.526757 -12.228063 0.1274065 -0.4417666 0.2666340 0.8470633 +VERTEX_SE3:QUAT 6731 28.428007 65.873047 -12.816979 0.4857249 -0.4153608 0.7120863 0.2906542 +VERTEX_SE3:QUAT 6732 28.772968 65.246142 -13.630112 0.1691582 0.7786318 -0.0464974 0.6024584 +VERTEX_SE3:QUAT 6733 29.237267 64.867515 -14.225251 0.1568370 -0.0278434 0.0013006 0.9872311 +VERTEX_SE3:QUAT 6734 29.703635 64.270632 -15.010786 -0.2907000 0.1064135 -0.0252855 0.9505421 +VERTEX_SE3:QUAT 6735 29.928422 63.764567 -15.878516 0.6353198 0.1878494 0.2434650 0.7083828 +VERTEX_SE3:QUAT 6736 30.413591 63.061390 -16.685979 -0.2895678 -0.1230807 -0.9273195 0.2026823 +VERTEX_SE3:QUAT 6737 30.892798 62.553303 -17.221127 -0.2099163 0.2919845 -0.6186603 0.6985268 +VERTEX_SE3:QUAT 6738 31.313501 61.826119 -17.558044 0.6101913 -0.2427696 -0.2051949 0.7256891 +VERTEX_SE3:QUAT 6739 31.578320 61.162707 -18.012871 0.3479230 -0.4302704 -0.4556154 0.6973031 +VERTEX_SE3:QUAT 6740 32.489743 61.507586 -17.624108 -0.0977861 0.0833707 -0.8238620 0.5520313 +VERTEX_SE3:QUAT 6741 32.041732 62.038721 -17.031706 0.1395697 -0.3751864 0.4708790 0.7861479 +VERTEX_SE3:QUAT 6742 31.478475 62.677756 -16.319090 -0.0845637 -0.3630007 0.9207154 0.1155968 +VERTEX_SE3:QUAT 6743 30.787020 63.316506 -15.868937 -0.3306933 0.2299514 0.8658741 0.2966923 +VERTEX_SE3:QUAT 6744 30.120903 63.911524 -15.394134 0.6191424 0.3711597 0.4537477 0.5225094 +VERTEX_SE3:QUAT 6745 29.495289 64.323505 -14.920882 0.5771590 0.3222221 -0.2793027 0.6964556 +VERTEX_SE3:QUAT 6746 29.136828 64.912695 -14.164986 0.1759322 0.4919655 -0.2812842 0.8049205 +VERTEX_SE3:QUAT 6747 28.601159 65.343375 -13.426243 0.1034138 0.4139939 -0.8960425 0.1225658 +VERTEX_SE3:QUAT 6748 28.026311 65.971864 -12.838637 0.0909797 0.3069621 0.1678370 0.9323775 +VERTEX_SE3:QUAT 6749 27.563765 66.428867 -12.285825 -0.0155003 0.0299897 0.3953055 0.9179291 +VERTEX_SE3:QUAT 6750 27.090818 67.062159 -11.607196 -0.2971913 -0.5078779 0.5563816 0.5866659 +VERTEX_SE3:QUAT 6751 26.408878 67.687520 -11.010840 -0.2859349 -0.1566451 0.9451879 0.0179815 +VERTEX_SE3:QUAT 6752 25.691233 68.425603 -10.555803 0.5715430 0.4381989 0.5600420 0.4094793 +VERTEX_SE3:QUAT 6753 25.114802 68.937062 -10.051504 -0.3821846 0.2899518 -0.5697629 0.6672579 +VERTEX_SE3:QUAT 6754 24.903773 69.537291 -9.429970 0.5267729 0.2715461 -0.5261027 0.6099090 +VERTEX_SE3:QUAT 6755 24.566411 70.254406 -8.973336 0.2101987 0.2769567 0.8267538 0.4422552 +VERTEX_SE3:QUAT 6756 24.240853 70.878451 -8.629822 0.2494156 -0.4500230 -0.8168289 0.2608864 +VERTEX_SE3:QUAT 6757 23.649240 71.499319 -8.027366 0.1622715 -0.6125741 0.5076427 0.5837121 +VERTEX_SE3:QUAT 6758 23.244788 72.270003 -7.563384 0.4295732 0.4079375 0.7075742 0.3852177 +VERTEX_SE3:QUAT 6759 22.762373 73.129234 -7.176849 -0.5677411 -0.3836337 0.6596989 0.3086949 +VERTEX_SE3:QUAT 6760 23.767659 73.407498 -7.002891 -0.1376133 0.1206048 -0.4674994 0.8648476 +VERTEX_SE3:QUAT 6761 24.144785 72.791074 -7.413487 -0.5365914 0.0786738 0.0340620 0.8394760 +VERTEX_SE3:QUAT 6762 24.371203 71.904665 -7.715738 -0.2195282 -0.2140110 -0.9178306 0.2521778 +VERTEX_SE3:QUAT 6763 24.796747 71.034854 -7.950004 0.4922475 0.4415120 0.4649792 0.5886883 +VERTEX_SE3:QUAT 6764 25.186320 70.243049 -8.264200 0.4596316 -0.4487022 0.1418555 0.7531814 +VERTEX_SE3:QUAT 6765 25.770327 69.322923 -8.447412 0.3090329 -0.6835093 0.5974683 0.2834524 +VERTEX_SE3:QUAT 6766 26.074734 68.598664 -8.907013 -0.1909187 -0.3637850 -0.8887642 0.2032452 +VERTEX_SE3:QUAT 6767 26.541944 67.829907 -9.282442 0.2477961 -0.3262220 -0.6603890 0.6293350 +VERTEX_SE3:QUAT 6768 26.844634 66.996346 -9.530005 -0.6678054 -0.4263325 0.5626102 0.2361065 +VERTEX_SE3:QUAT 6769 27.337643 66.252947 -9.783788 0.1198930 -0.5926826 -0.7233855 0.3332664 +VERTEX_SE3:QUAT 6770 27.785847 65.432225 -10.067647 0.1781542 0.0983373 -0.9548903 0.2162760 +VERTEX_SE3:QUAT 6771 28.128564 64.460279 -10.432910 0.6047239 0.1243394 -0.3859792 0.6854697 +VERTEX_SE3:QUAT 6772 28.544646 63.663433 -10.848274 -0.4043136 0.1283128 -0.3977229 0.8135618 +VERTEX_SE3:QUAT 6773 28.837503 62.855279 -11.438710 -0.2333032 0.1104430 -0.8554854 0.4489062 +VERTEX_SE3:QUAT 6774 29.141885 62.111028 -11.737646 0.4592598 -0.1493960 -0.5925483 0.6447076 +VERTEX_SE3:QUAT 6775 29.469917 61.448199 -11.953873 0.0933103 -0.4428699 -0.6585793 0.6011927 +VERTEX_SE3:QUAT 6776 29.954215 60.825439 -12.236510 0.2818095 0.2259782 -0.9236463 0.1280417 +VERTEX_SE3:QUAT 6777 30.309213 60.100905 -12.542407 0.5082056 -0.2192449 0.6306841 0.5439636 +VERTEX_SE3:QUAT 6778 30.769968 59.264137 -12.883591 0.0706903 -0.4391137 0.7074400 0.5492821 +VERTEX_SE3:QUAT 6779 31.112748 58.458363 -13.263559 0.1067963 -0.0497167 0.9167048 0.3818050 +VERTEX_SE3:QUAT 6780 31.915676 58.608328 -12.654002 -0.3815577 0.4478902 -0.7657469 0.2596915 +VERTEX_SE3:QUAT 6781 31.508046 59.627811 -12.303999 0.2892240 0.0766275 -0.0315857 0.9536666 +VERTEX_SE3:QUAT 6782 31.139035 60.416320 -11.932835 0.2363087 0.0267278 -0.0334947 0.9707327 +VERTEX_SE3:QUAT 6783 30.850130 60.915102 -11.523498 0.2479719 -0.5929328 -0.5890071 0.4899095 +VERTEX_SE3:QUAT 6784 30.631131 61.773984 -11.148353 -0.0982312 0.2147577 0.7523802 0.6149422 +VERTEX_SE3:QUAT 6785 30.484676 62.526589 -10.574097 0.2171937 0.7670430 -0.5170115 0.3117226 +VERTEX_SE3:QUAT 6786 30.191598 63.400732 -10.063823 0.6247866 -0.6013643 -0.2206524 0.4464472 +VERTEX_SE3:QUAT 6787 29.917708 64.251480 -9.551989 -0.4633740 -0.3950022 0.2723808 0.7450278 +VERTEX_SE3:QUAT 6788 29.642136 65.197891 -9.189554 0.0937958 0.0263544 -0.1543698 0.9831977 +VERTEX_SE3:QUAT 6789 29.240950 66.228000 -8.766960 0.2840397 0.2133914 -0.7330102 0.5800703 +VERTEX_SE3:QUAT 6790 28.972438 67.052588 -8.269838 0.0374329 -0.4416931 0.3953939 0.8044685 +VERTEX_SE3:QUAT 6791 28.750589 67.844578 -7.783697 -0.5179663 -0.3444679 0.6940924 0.3623377 +VERTEX_SE3:QUAT 6792 28.089805 68.724062 -7.415482 0.2738465 -0.6880209 0.6714739 0.0275328 +VERTEX_SE3:QUAT 6793 27.702433 69.644720 -7.073648 0.4404812 -0.4957071 -0.1399570 0.7352978 +VERTEX_SE3:QUAT 6794 27.373454 70.547280 -6.565784 0.5987205 0.1171071 -0.7747058 0.1662848 +VERTEX_SE3:QUAT 6795 26.822708 71.458480 -6.074278 0.6730939 -0.2532429 0.2523194 0.6474160 +VERTEX_SE3:QUAT 6796 26.577469 72.213567 -5.635109 0.6189368 -0.3695735 0.4628868 0.5158182 +VERTEX_SE3:QUAT 6797 26.219934 73.097709 -5.230598 -0.0746299 -0.3555599 -0.7459039 0.5582427 +VERTEX_SE3:QUAT 6798 25.739481 73.895395 -5.029749 -0.1596381 -0.0168895 0.9247735 0.3449992 +VERTEX_SE3:QUAT 6799 25.247961 74.871160 -4.660751 -0.0181548 0.6440873 -0.1048321 0.7575171 +VERTEX_SE3:QUAT 6800 31.581468 57.944259 -10.751546 0.1356357 0.0726744 -0.5742469 0.8040907 +VERTEX_SE3:QUAT 6801 31.390427 58.874399 -10.600887 0.4354806 0.2500322 0.8609840 0.0809140 +VERTEX_SE3:QUAT 6802 31.040306 59.637022 -10.186549 -0.4807643 0.2582111 -0.0991813 0.8320792 +VERTEX_SE3:QUAT 6803 30.857712 60.629856 -10.011835 -0.5411737 -0.0310231 0.2376962 0.8060205 +VERTEX_SE3:QUAT 6804 30.561870 61.620733 -9.864076 -0.3960278 0.4636941 -0.7064189 0.3593356 +VERTEX_SE3:QUAT 6805 30.499224 62.555164 -9.850532 -0.0124432 -0.2859591 0.4200967 0.8611570 +VERTEX_SE3:QUAT 6806 30.037651 63.534838 -9.729457 -0.1890810 -0.1037092 0.0013888 0.9764686 +VERTEX_SE3:QUAT 6807 29.789330 64.499241 -9.716754 0.0929007 0.0284122 -0.1658357 0.9813566 +VERTEX_SE3:QUAT 6808 29.451237 65.352335 -9.592352 0.4531891 -0.2060141 -0.4140117 0.7620840 +VERTEX_SE3:QUAT 6809 29.296031 66.377851 -9.626782 -0.6600001 -0.0148563 -0.5172061 0.5446807 +VERTEX_SE3:QUAT 6810 28.941931 67.272196 -9.386304 0.2485594 0.4010425 0.8686010 0.1513784 +VERTEX_SE3:QUAT 6811 28.640374 68.473375 -9.204051 0.0106114 -0.4496048 -0.4416123 0.7763514 +VERTEX_SE3:QUAT 6812 28.414185 69.346567 -9.164996 -0.3697055 -0.3161988 -0.6360363 0.5989942 +VERTEX_SE3:QUAT 6813 27.997862 70.280130 -9.012218 0.2038716 0.2674098 0.0984455 0.9366092 +VERTEX_SE3:QUAT 6814 27.567310 71.126067 -8.887388 0.1588522 0.3456425 0.0608906 0.9228161 +VERTEX_SE3:QUAT 6815 27.147747 72.199569 -8.961623 0.1889683 0.3012373 -0.6339219 0.6867970 +VERTEX_SE3:QUAT 6816 26.787784 73.283622 -8.921924 -0.2368565 -0.1735260 -0.8832983 0.3654747 +VERTEX_SE3:QUAT 6817 26.458039 74.213703 -8.883044 -0.4116889 -0.1086459 0.8236771 0.3745189 +VERTEX_SE3:QUAT 6818 26.215092 75.222219 -8.964145 0.4455309 -0.1275672 -0.5871716 0.6636703 +VERTEX_SE3:QUAT 6819 26.040931 76.192349 -9.002663 0.2757425 -0.3446175 0.6809124 0.5844340 +VERTEX_SE3:QUAT 6820 25.028643 75.650081 -9.025662 0.0214799 -0.3890715 0.6862671 0.6141656 +VERTEX_SE3:QUAT 6821 25.365183 74.647108 -9.108148 0.2123824 0.5076661 0.8330173 0.0570171 +VERTEX_SE3:QUAT 6822 25.558320 73.453427 -9.039674 0.0792177 -0.2867713 -0.5427437 0.7854400 +VERTEX_SE3:QUAT 6823 25.810278 72.367606 -9.018643 -0.0653614 0.0202252 0.2807817 0.9573299 +VERTEX_SE3:QUAT 6824 26.165862 71.555622 -8.926340 -0.1021280 -0.1548081 -0.6739896 0.7150820 +VERTEX_SE3:QUAT 6825 26.508476 70.468430 -9.065728 -0.1308811 -0.1331476 -0.7600576 0.6224582 +VERTEX_SE3:QUAT 6826 26.701006 69.533467 -9.009672 -0.5535409 0.0605686 0.7473881 0.3624016 +VERTEX_SE3:QUAT 6827 27.088201 68.658849 -8.755224 -0.1075160 0.4902998 0.2113929 0.8386653 +VERTEX_SE3:QUAT 6828 27.482917 67.670898 -8.579034 -0.3955191 0.3466264 -0.6958543 0.4890824 +VERTEX_SE3:QUAT 6829 27.614284 66.845934 -8.662648 0.1013998 0.4753451 -0.0855018 0.8697440 +VERTEX_SE3:QUAT 6830 27.696135 65.842248 -8.458722 0.1798779 -0.1002992 -0.5278755 0.8239730 +VERTEX_SE3:QUAT 6831 27.637939 64.905095 -8.228275 0.2622092 0.5382283 0.2659570 0.7555286 +VERTEX_SE3:QUAT 6832 27.652285 63.958174 -8.108289 -0.3324199 -0.2070841 -0.9192715 0.0394086 +VERTEX_SE3:QUAT 6833 27.768953 63.068266 -7.969156 -0.2780435 -0.3704321 0.7714937 0.4361987 +VERTEX_SE3:QUAT 6834 27.880485 62.065341 -7.834324 -0.0363808 0.4671563 0.8740900 0.1280940 +VERTEX_SE3:QUAT 6835 28.023078 60.984894 -7.742751 -0.0348109 -0.2363865 0.9263258 0.2912560 +VERTEX_SE3:QUAT 6836 28.112073 60.150470 -7.683188 -0.2084386 -0.4699452 -0.8524103 0.0954018 +VERTEX_SE3:QUAT 6837 28.030250 59.092781 -7.662290 0.4835341 0.3986635 0.1107069 0.7713664 +VERTEX_SE3:QUAT 6838 28.195018 58.022165 -7.625029 0.0384881 -0.5431790 -0.5934596 0.5926896 +VERTEX_SE3:QUAT 6839 28.155081 57.044195 -7.708667 0.5206283 -0.1440799 0.6800470 0.4957048 +VERTEX_SE3:QUAT 6840 27.228774 56.990283 -7.430379 0.0967945 0.8094215 0.4319793 0.3858258 +VERTEX_SE3:QUAT 6841 27.255280 57.918727 -7.446685 0.3743167 -0.0194891 -0.7700389 0.5162822 +VERTEX_SE3:QUAT 6842 27.344478 58.833396 -7.649390 0.1041511 -0.0434742 -0.1688093 0.9791660 +VERTEX_SE3:QUAT 6843 27.456029 59.481597 -7.689663 0.2135971 0.0568839 -0.9720200 0.0794830 +VERTEX_SE3:QUAT 6844 27.594501 60.555732 -7.812529 -0.2816516 -0.1218819 0.5061201 0.8060146 +VERTEX_SE3:QUAT 6845 27.476754 61.447799 -8.199242 -0.7606525 0.1097177 0.0872949 0.6338371 +VERTEX_SE3:QUAT 6846 27.477683 62.480812 -8.481418 0.4400636 -0.1449866 0.1975372 0.8638877 +VERTEX_SE3:QUAT 6847 27.702505 63.670456 -8.609531 0.5713996 0.3932918 -0.0506533 0.7185111 +VERTEX_SE3:QUAT 6848 27.636933 64.602462 -8.770095 -0.3264281 0.0651981 0.0214446 0.9427269 +VERTEX_SE3:QUAT 6849 27.780495 65.481467 -9.355174 -0.0183610 -0.0262267 -0.0768228 0.9965306 +VERTEX_SE3:QUAT 6850 28.004516 66.506670 -9.769793 -0.4815907 0.1680188 0.2253127 0.8301050 +VERTEX_SE3:QUAT 6851 28.190194 67.523941 -10.103964 -0.4797096 -0.3489605 -0.7961508 0.1193698 +VERTEX_SE3:QUAT 6852 28.484893 68.469570 -10.459239 0.0279450 0.4957289 0.5294305 0.6878774 +VERTEX_SE3:QUAT 6853 28.628655 69.396814 -10.982854 -0.2879150 0.1646014 0.7798041 0.5309584 +VERTEX_SE3:QUAT 6854 28.772452 70.194722 -11.243566 0.3129330 -0.0048803 -0.5286090 0.7890638 +VERTEX_SE3:QUAT 6855 28.858991 71.064270 -11.609747 -0.7432782 0.1283841 -0.0089579 0.6564867 +VERTEX_SE3:QUAT 6856 28.917866 71.984798 -11.901897 0.1158613 0.4369673 -0.6707606 0.5879761 +VERTEX_SE3:QUAT 6857 29.329772 72.794057 -12.336401 0.1373869 0.4926688 -0.8587297 0.0313942 +VERTEX_SE3:QUAT 6858 29.469435 73.689004 -12.600789 0.0777267 0.5043669 -0.3119384 0.8014156 +VERTEX_SE3:QUAT 6859 29.731102 74.700678 -12.940858 -0.4449414 -0.1505359 -0.6702000 0.5746286 +VERTEX_SE3:QUAT 6860 28.900496 75.022956 -12.563711 0.1329103 -0.3437405 -0.6346530 0.6792591 +VERTEX_SE3:QUAT 6861 28.966222 74.094310 -12.042870 -0.7152875 -0.1842103 -0.1580089 0.6553347 +VERTEX_SE3:QUAT 6862 28.935482 73.026769 -11.582665 -0.5029305 0.1446555 -0.8462688 0.0998240 +VERTEX_SE3:QUAT 6863 28.907568 72.125857 -11.218453 -0.0420536 0.4255071 -0.6299099 0.6483739 +VERTEX_SE3:QUAT 6864 28.878393 71.265105 -10.686092 -0.1625558 -0.0074806 0.3752371 0.9125332 +VERTEX_SE3:QUAT 6865 28.598840 70.528404 -10.245439 0.1118793 0.3755377 -0.2300076 0.8908148 +VERTEX_SE3:QUAT 6866 28.544091 69.666839 -9.781804 -0.3708906 -0.1334127 0.9132830 0.1027392 +VERTEX_SE3:QUAT 6867 28.541234 68.683217 -9.426180 0.0233809 -0.2221562 -0.3429673 0.9123998 +VERTEX_SE3:QUAT 6868 28.670933 67.878772 -8.991677 -0.1651220 -0.5010588 -0.4319519 0.7315001 +VERTEX_SE3:QUAT 6869 28.637900 67.140013 -8.439620 0.1579263 0.3585891 -0.5173051 0.7608341 +VERTEX_SE3:QUAT 6870 28.682264 66.327044 -7.917701 -0.0627619 0.0360815 -0.9352965 0.3463805 +VERTEX_SE3:QUAT 6871 28.441871 65.322838 -7.462433 0.1070879 -0.4515346 -0.8707498 0.1626143 +VERTEX_SE3:QUAT 6872 28.241863 64.429849 -7.351155 0.3220074 -0.1373661 -0.3761011 0.8578985 +VERTEX_SE3:QUAT 6873 27.887527 63.670535 -6.781462 -0.1195799 0.4422158 0.7047853 0.5416858 +VERTEX_SE3:QUAT 6874 27.779538 62.823417 -6.515098 -0.5319663 0.3813476 0.0221583 0.7557082 +VERTEX_SE3:QUAT 6875 27.615696 61.888462 -6.168927 0.2181526 0.2205018 -0.9506229 0.0102249 +VERTEX_SE3:QUAT 6876 27.460586 60.790679 -5.992795 -0.7818211 -0.0390814 -0.2138267 0.5843856 +VERTEX_SE3:QUAT 6877 27.334520 59.909755 -5.713601 -0.1053372 0.5452155 0.7811925 0.2852760 +VERTEX_SE3:QUAT 6878 27.175999 59.053503 -5.365752 0.2277075 -0.0965475 0.9677166 0.0485027 +VERTEX_SE3:QUAT 6879 26.939480 58.107692 -5.010247 -0.4118574 0.4294858 -0.5499870 0.5860288 +VERTEX_SE3:QUAT 6880 26.072786 58.254717 -4.816378 -0.3535930 0.2487395 0.0231745 0.9014231 +VERTEX_SE3:QUAT 6881 26.461487 59.235486 -5.068122 -0.3464256 -0.1475982 -0.2703297 0.8860733 +VERTEX_SE3:QUAT 6882 26.749970 60.074949 -5.494670 0.1066418 -0.6267138 -0.7326770 0.2429851 +VERTEX_SE3:QUAT 6883 27.138597 60.848269 -5.891493 -0.3809667 0.1154127 -0.9173506 0.0034855 +VERTEX_SE3:QUAT 6884 27.404760 61.716123 -6.015235 0.5284300 -0.2062991 0.2136897 0.7953233 +VERTEX_SE3:QUAT 6885 27.689256 62.656698 -6.462372 -0.2824533 0.2309424 0.7712470 0.5215973 +VERTEX_SE3:QUAT 6886 27.935522 63.555846 -6.696186 0.4079316 -0.2599423 0.2886928 0.8262435 +VERTEX_SE3:QUAT 6887 28.328953 64.575413 -6.909467 0.0129270 -0.1181367 0.3680051 0.9221978 +VERTEX_SE3:QUAT 6888 28.566576 65.586858 -6.981205 -0.5618986 -0.1962867 0.6048022 0.5291085 +VERTEX_SE3:QUAT 6889 28.836870 66.639085 -7.218534 -0.0852483 0.2329250 -0.5670589 0.7854444 +VERTEX_SE3:QUAT 6890 29.139020 67.633450 -7.285054 -0.7207440 0.0948617 0.4703173 0.5003309 +VERTEX_SE3:QUAT 6891 29.322677 68.397404 -7.569404 -0.3984508 0.5278537 -0.7492939 0.0341481 +VERTEX_SE3:QUAT 6892 29.750281 69.274656 -7.982678 -0.5576277 -0.1561625 0.7849645 0.2202165 +VERTEX_SE3:QUAT 6893 30.053666 70.091907 -8.174164 -0.5830813 0.2972606 0.4295727 0.6221894 +VERTEX_SE3:QUAT 6894 30.364919 71.056472 -8.463057 -0.4302857 -0.3181468 -0.5437845 0.6464791 +VERTEX_SE3:QUAT 6895 30.848051 71.816235 -8.791848 0.0591141 0.3920803 0.3982639 0.8271424 +VERTEX_SE3:QUAT 6896 31.413045 72.689247 -9.301885 0.1626291 -0.5902853 -0.0100207 0.7905786 +VERTEX_SE3:QUAT 6897 31.746560 73.534161 -9.622797 0.2277652 -0.0948761 0.9681400 0.0427376 +VERTEX_SE3:QUAT 6898 32.023447 74.399343 -10.243745 0.5182011 0.5097869 0.6844890 0.0553144 +VERTEX_SE3:QUAT 6899 32.428375 75.338626 -10.659316 -0.0512677 0.2865801 -0.5598909 0.7757355 +VERTEX_SE3:QUAT 6900 31.486442 75.638376 -10.772282 0.3605887 -0.1405398 -0.1674559 0.9067430 +VERTEX_SE3:QUAT 6901 31.161665 74.825805 -10.271627 0.5414781 -0.2394161 0.7973607 0.1170358 +VERTEX_SE3:QUAT 6902 30.795495 73.900110 -9.760991 -0.3786279 -0.0233289 0.7467349 0.5463366 +VERTEX_SE3:QUAT 6903 30.383930 73.334499 -9.196743 -0.6158620 0.0299074 0.4115212 0.6711705 +VERTEX_SE3:QUAT 6904 29.959566 72.550658 -8.684705 -0.0276304 -0.6255101 -0.7088096 0.3249039 +VERTEX_SE3:QUAT 6905 29.438217 71.630147 -8.246145 -0.1142184 -0.5473791 -0.1167574 0.8207911 +VERTEX_SE3:QUAT 6906 28.935938 70.870062 -7.980447 -0.2020124 -0.1561285 -0.9426579 0.2149675 +VERTEX_SE3:QUAT 6907 28.426131 70.284847 -7.426513 -0.0011767 0.3314658 -0.5444265 0.7705380 +VERTEX_SE3:QUAT 6908 27.887332 69.677882 -6.881507 0.3540332 -0.4027677 -0.7062103 0.4622832 +VERTEX_SE3:QUAT 6909 27.423792 68.926270 -6.475420 -0.6926529 -0.1196202 -0.2411683 0.6691493 +VERTEX_SE3:QUAT 6910 26.801217 68.379558 -5.929191 -0.0569730 0.3275603 -0.8344759 0.4394409 +VERTEX_SE3:QUAT 6911 26.231336 67.761580 -5.491804 -0.0307702 -0.1272387 0.9577262 0.2561718 +VERTEX_SE3:QUAT 6912 25.551020 67.216222 -4.937530 0.3890637 -0.5956442 -0.5918178 0.3789316 +VERTEX_SE3:QUAT 6913 24.903240 66.404528 -4.465752 -0.1408054 -0.2312735 0.3133014 0.9102355 +VERTEX_SE3:QUAT 6914 24.445103 65.832360 -3.982713 -0.5049647 -0.0750791 0.5920726 0.6235574 +VERTEX_SE3:QUAT 6915 23.836589 65.312004 -3.494261 0.1191996 0.5952939 -0.0031590 0.7946110 +VERTEX_SE3:QUAT 6916 23.186028 64.574665 -2.998147 -0.5239357 -0.2816302 -0.4370956 0.6746282 +VERTEX_SE3:QUAT 6917 22.614955 63.993333 -2.522644 0.2205842 -0.1570922 -0.5225846 0.8084368 +VERTEX_SE3:QUAT 6918 21.950892 63.280597 -2.032786 -0.1749361 -0.4944108 -0.1469088 0.8386734 +VERTEX_SE3:QUAT 6919 21.571339 62.354006 -1.532653 -0.4228365 0.2426759 0.2752453 0.8285878 +VERTEX_SE3:QUAT 6920 20.744025 62.870106 -1.730449 0.1756093 -0.4587160 0.0321813 0.8704627 +VERTEX_SE3:QUAT 6921 21.046300 63.641823 -2.189363 0.4718983 -0.1035626 0.8368522 0.2574202 +VERTEX_SE3:QUAT 6922 21.402880 64.494631 -2.835089 -0.3741497 0.5831895 -0.2825609 0.6633712 +VERTEX_SE3:QUAT 6923 21.819815 65.238677 -3.384910 0.2043497 -0.2333133 -0.8520468 0.4216898 +VERTEX_SE3:QUAT 6924 22.270163 66.007462 -3.958800 -0.6055430 -0.2564542 -0.2626785 0.7060799 +VERTEX_SE3:QUAT 6925 22.469928 66.612242 -4.412247 0.2384046 0.1172359 -0.7055694 0.6569558 +VERTEX_SE3:QUAT 6926 23.121261 67.619715 -5.125212 -0.1767200 -0.1378479 0.3942677 0.8912469 +VERTEX_SE3:QUAT 6927 23.482127 68.217500 -5.478390 -0.4199693 -0.6149467 -0.6464025 0.1662235 +VERTEX_SE3:QUAT 6928 23.806215 68.971719 -5.869144 -0.2608782 0.5919573 0.6269032 0.4341906 +VERTEX_SE3:QUAT 6929 24.028497 69.519072 -6.200081 -0.5558304 0.5288919 0.2343846 0.5969839 +VERTEX_SE3:QUAT 6930 24.591823 70.170512 -6.723612 -0.5446044 0.2020099 -0.7997291 0.1517613 +VERTEX_SE3:QUAT 6931 24.974735 70.947560 -7.424227 -0.6670098 -0.2538592 -0.5043969 0.4860423 +VERTEX_SE3:QUAT 6932 25.479985 71.736194 -7.937464 -0.4516581 0.2018207 -0.6799593 0.5412289 +VERTEX_SE3:QUAT 6933 25.932275 72.410772 -8.220810 0.0203157 0.3995669 0.6727679 0.6223479 +VERTEX_SE3:QUAT 6934 26.382943 73.192373 -8.545546 0.4390271 -0.2062912 -0.1318829 0.8644687 +VERTEX_SE3:QUAT 6935 26.800242 74.060255 -8.890708 0.1385292 -0.4809201 -0.1522484 0.8522593 +VERTEX_SE3:QUAT 6936 27.228626 74.821650 -9.340452 0.1332522 0.0476783 -0.2201610 0.9651424 +VERTEX_SE3:QUAT 6937 27.565997 75.626996 -10.029839 -0.4690564 -0.0978004 -0.2754669 0.8333901 +VERTEX_SE3:QUAT 6938 28.037437 76.485595 -10.598187 -0.1204593 0.1211939 -0.0689869 0.9828746 +VERTEX_SE3:QUAT 6939 28.490642 77.426719 -10.863644 -0.3123210 -0.1299414 0.0923543 0.9365049 +VERTEX_SE3:QUAT 6940 27.514938 77.807310 -10.827143 -0.2576431 -0.0098381 -0.8147340 0.5193570 +VERTEX_SE3:QUAT 6941 27.079341 76.957793 -10.585289 -0.2964699 0.2788744 0.8265099 0.3888652 +VERTEX_SE3:QUAT 6942 26.740502 76.128019 -10.110309 -0.5829738 -0.2329823 0.7486918 0.2128884 +VERTEX_SE3:QUAT 6943 26.501972 75.275148 -9.731690 0.0321011 -0.0308417 0.8606405 0.5072635 +VERTEX_SE3:QUAT 6944 26.177559 74.411031 -9.424788 -0.1721074 0.7249538 0.6667694 0.0154799 +VERTEX_SE3:QUAT 6945 25.885095 73.402328 -9.179613 -0.2296868 -0.3339999 -0.2282851 0.8851971 +VERTEX_SE3:QUAT 6946 25.452442 72.468076 -8.878922 0.0653186 0.1452587 -0.9865461 0.0368814 +VERTEX_SE3:QUAT 6947 25.043630 71.774262 -8.768207 -0.4469269 0.5747151 0.0612548 0.6827934 +VERTEX_SE3:QUAT 6948 24.277876 70.920217 -8.419096 -0.5748511 -0.3061125 -0.7424103 0.1570618 +VERTEX_SE3:QUAT 6949 23.835114 70.273616 -8.227444 -0.5963621 -0.0025553 0.4126818 0.6885052 +VERTEX_SE3:QUAT 6950 23.373382 69.402861 -8.010636 -0.4106106 -0.3726084 0.2482702 0.7943071 +VERTEX_SE3:QUAT 6951 23.123545 68.432540 -7.778599 0.0835413 0.4520162 0.2778123 0.8435179 +VERTEX_SE3:QUAT 6952 22.790706 67.606262 -7.487969 -0.6022222 -0.0036107 -0.2106091 0.7700384 +VERTEX_SE3:QUAT 6953 22.248554 66.693990 -7.093109 0.2890823 0.7497543 0.4004913 0.4403483 +VERTEX_SE3:QUAT 6954 21.722799 65.859077 -6.704375 -0.0972515 -0.3438464 0.9043077 0.2335365 +VERTEX_SE3:QUAT 6955 21.241856 65.195895 -6.432319 -0.7097941 0.1965590 0.1414089 0.6614835 +VERTEX_SE3:QUAT 6956 20.919672 64.419001 -5.995592 -0.3639315 0.6900061 -0.2394028 0.5780413 +VERTEX_SE3:QUAT 6957 20.542949 63.633120 -5.717334 -0.0851864 0.3478312 0.8260715 0.4351582 +VERTEX_SE3:QUAT 6958 20.029559 62.790062 -5.331184 -0.5920921 -0.2555067 -0.1196540 0.7548683 +VERTEX_SE3:QUAT 6959 19.635761 62.034725 -4.682983 0.2899743 0.1478730 0.8955061 0.3035082 +VERTEX_SE3:QUAT 6960 18.906737 62.665861 -4.593643 0.1086094 0.5718272 -0.2755130 0.7650557 +VERTEX_SE3:QUAT 6961 19.196520 63.525500 -5.174118 0.5591412 0.0864398 0.0818862 0.8204779 +VERTEX_SE3:QUAT 6962 19.446832 64.342535 -5.707930 -0.2558853 -0.3446877 0.3792692 0.8196755 +VERTEX_SE3:QUAT 6963 19.732471 64.973632 -6.312085 0.2772706 0.1009419 0.3299351 0.8967020 +VERTEX_SE3:QUAT 6964 20.044790 65.827140 -6.846467 0.3086647 -0.0679462 0.6160671 0.7215058 +VERTEX_SE3:QUAT 6965 20.187227 66.652377 -7.203117 0.1877507 -0.0479410 -0.6988274 0.6885431 +VERTEX_SE3:QUAT 6966 20.573821 67.573535 -7.766008 -0.6658409 0.3379889 -0.2409852 0.6199560 +VERTEX_SE3:QUAT 6967 20.986573 68.529917 -8.127702 0.2996831 -0.3429147 -0.4801095 0.7497295 +VERTEX_SE3:QUAT 6968 21.476191 69.426075 -8.626617 -0.2918015 0.6689926 -0.2204938 0.6470574 +VERTEX_SE3:QUAT 6969 21.912288 70.151501 -8.942667 -0.2099924 0.1664983 0.1393545 0.9532900 +VERTEX_SE3:QUAT 6970 22.342743 71.044743 -9.214789 0.2491892 0.4078508 0.7947167 0.3741495 +VERTEX_SE3:QUAT 6971 22.848977 71.944179 -9.546351 -0.4103452 -0.2222959 0.0597428 0.8824014 +VERTEX_SE3:QUAT 6972 23.144001 72.702629 -9.880714 0.2948863 0.3389336 0.0909676 0.8887581 +VERTEX_SE3:QUAT 6973 23.529478 73.556797 -10.223595 0.1657764 0.3421799 0.9212668 0.0818443 +VERTEX_SE3:QUAT 6974 24.045373 74.282447 -10.748247 0.2551690 0.4912207 -0.3666985 0.7477454 +VERTEX_SE3:QUAT 6975 24.351325 74.975476 -11.413131 0.3220584 -0.0873054 0.6496430 0.6830960 +VERTEX_SE3:QUAT 6976 24.735253 75.547138 -12.003005 0.2003763 0.0767690 0.6617392 0.7183711 +VERTEX_SE3:QUAT 6977 25.055860 76.090442 -12.884593 -0.7579574 -0.0140350 -0.5003978 0.4182172 +VERTEX_SE3:QUAT 6978 25.208795 76.711777 -13.683728 0.0319240 -0.1338256 0.4201758 0.8969526 +VERTEX_SE3:QUAT 6979 25.609372 77.338947 -14.303333 -0.0210892 -0.2662281 0.9513851 0.1534411 +VERTEX_SE3:QUAT 6980 24.943241 78.143189 -13.979243 0.4202920 0.1523102 0.8564850 0.2580496 +VERTEX_SE3:QUAT 6981 24.678355 77.320268 -13.204236 -0.2387294 0.2162574 -0.3795521 0.8672838 +VERTEX_SE3:QUAT 6982 24.179076 76.675323 -12.673737 -0.2951103 -0.1561039 -0.3744765 0.8650485 +VERTEX_SE3:QUAT 6983 23.911284 76.158705 -11.819685 -0.1716320 0.8279535 0.3080980 0.4360173 +VERTEX_SE3:QUAT 6984 23.649670 75.522480 -11.138075 0.2585197 0.6195577 0.3152087 0.6707901 +VERTEX_SE3:QUAT 6985 23.294001 75.004940 -10.388438 -0.0466035 0.1831680 -0.3453364 0.9192499 +VERTEX_SE3:QUAT 6986 22.867289 74.343237 -9.700150 0.3447172 0.6067247 0.2864835 0.6564925 +VERTEX_SE3:QUAT 6987 22.698284 73.746438 -8.809098 -0.5960018 0.2052381 -0.5375183 0.5601190 +VERTEX_SE3:QUAT 6988 22.478258 73.140092 -8.072835 0.0630763 0.5529133 -0.5007255 0.6630100 +VERTEX_SE3:QUAT 6989 22.218055 72.432879 -7.225148 -0.6175121 0.4520860 -0.4195891 0.4881005 +VERTEX_SE3:QUAT 6990 21.969346 72.206942 -6.363512 -0.0093595 -0.2796833 -0.9559561 0.0885306 +VERTEX_SE3:QUAT 6991 21.702415 71.664947 -5.471969 -0.3484599 -0.3685404 -0.7280136 0.4612482 +VERTEX_SE3:QUAT 6992 21.579742 71.155139 -4.673200 -0.7532512 0.4100696 -0.4420002 0.2628522 +VERTEX_SE3:QUAT 6993 21.260739 70.820865 -3.882991 -0.5579494 -0.6469395 -0.5161927 0.0608834 +VERTEX_SE3:QUAT 6994 20.986326 70.471641 -2.930384 0.2814518 0.7801286 0.4321650 0.3541436 +VERTEX_SE3:QUAT 6995 20.766229 70.045344 -2.197774 0.1905987 0.0314220 -0.0621838 0.9791925 +VERTEX_SE3:QUAT 6996 20.517459 69.481042 -1.384565 -0.2994189 0.3425443 0.0653400 0.8881117 +VERTEX_SE3:QUAT 6997 20.058943 69.009247 -0.677583 0.0912244 0.1180555 0.3310722 0.9317361 +VERTEX_SE3:QUAT 6998 19.655453 68.515800 0.168975 0.3527684 0.4961818 0.7685529 0.1966838 +VERTEX_SE3:QUAT 6999 19.170237 68.080313 0.871644 -0.1871411 -0.2991411 -0.9329567 0.0713064 +VERTEX_SE3:QUAT 7000 18.671567 69.009319 1.042140 0.4396515 0.5003728 0.6800747 0.3063200 +VERTEX_SE3:QUAT 7001 19.042532 69.330718 -0.012366 -0.2015546 0.3108707 -0.4860401 0.7915176 +VERTEX_SE3:QUAT 7002 19.359922 69.546336 -0.766688 -0.1998140 0.2880714 -0.9351211 0.0513586 +VERTEX_SE3:QUAT 7003 19.852586 69.686891 -1.733209 0.6194757 0.2949600 0.5900226 0.4255841 +VERTEX_SE3:QUAT 7004 20.045776 70.035398 -2.542932 0.2062616 0.4926479 0.1556862 0.8309729 +VERTEX_SE3:QUAT 7005 20.339484 70.577595 -3.311782 -0.2694358 0.4137931 -0.8292974 0.2616208 +VERTEX_SE3:QUAT 7006 20.738223 71.162991 -4.094890 -0.2155737 0.0672979 -0.9232414 0.3108446 +VERTEX_SE3:QUAT 7007 21.057159 71.509313 -5.047836 -0.1510649 0.0281755 0.8448578 0.5124459 +VERTEX_SE3:QUAT 7008 21.355894 71.804097 -5.713469 -0.2025653 0.1753932 0.9111973 0.3129280 +VERTEX_SE3:QUAT 7009 21.659787 72.209573 -6.578009 0.0976061 0.2510679 0.7424981 0.6132981 +VERTEX_SE3:QUAT 7010 22.124294 72.721137 -7.420103 -0.7474626 -0.4441566 -0.4628220 0.1726856 +VERTEX_SE3:QUAT 7011 22.345955 73.320609 -8.343507 -0.3430203 0.1796258 0.7415194 0.5479239 +VERTEX_SE3:QUAT 7012 22.506713 73.878482 -9.147103 -0.0601540 0.5149664 0.7835932 0.3423052 +VERTEX_SE3:QUAT 7013 22.933566 74.591930 -10.007684 0.2200360 0.5394968 -0.5907720 0.5581360 +VERTEX_SE3:QUAT 7014 23.371512 75.185906 -10.769608 -0.5894455 -0.1773909 -0.6519010 0.4428448 +VERTEX_SE3:QUAT 7015 23.816768 75.747185 -11.588559 -0.5814444 0.5627669 0.3410202 0.4784569 +VERTEX_SE3:QUAT 7016 24.353057 76.290340 -12.318264 -0.3207510 -0.0136665 -0.5616215 0.7625702 +VERTEX_SE3:QUAT 7017 24.793946 76.853798 -12.962987 -0.2416315 0.1723083 0.1404205 0.9445666 +VERTEX_SE3:QUAT 7018 25.173955 77.496331 -13.568853 -0.6925088 0.0966630 -0.6571342 0.2815360 +VERTEX_SE3:QUAT 7019 25.650820 78.128673 -14.350856 0.5406259 -0.1275282 0.5234935 0.6460764 +VERTEX_SE3:QUAT 7020 25.091330 78.835986 -13.948717 -0.2769973 0.5525107 -0.5551194 0.5566390 +VERTEX_SE3:QUAT 7021 24.549942 78.214839 -13.372749 0.3597438 0.6784210 -0.2858833 0.5732365 +VERTEX_SE3:QUAT 7022 24.081797 77.682822 -12.843287 -0.1413742 0.7733577 0.1146172 0.6072842 +VERTEX_SE3:QUAT 7023 23.663871 77.039642 -12.319894 -0.5359957 0.2395870 0.0115818 0.8094273 +VERTEX_SE3:QUAT 7024 23.186755 76.293939 -11.859544 -0.3283357 0.6803689 -0.3881482 0.5278587 +VERTEX_SE3:QUAT 7025 22.437131 75.642530 -11.229037 -0.0630453 0.0086139 0.8511858 0.5209932 +VERTEX_SE3:QUAT 7026 21.889028 74.941112 -10.838556 -0.5587869 -0.2964790 -0.6998033 0.3318624 +VERTEX_SE3:QUAT 7027 21.380360 74.265964 -10.309263 0.5326306 0.4065708 0.6062441 0.4283374 +VERTEX_SE3:QUAT 7028 20.898044 73.740819 -9.672712 -0.2815343 0.2678708 0.5919898 0.7060678 +VERTEX_SE3:QUAT 7029 20.477885 73.180851 -8.875456 0.8107587 0.5242233 0.1973127 0.1700822 +VERTEX_SE3:QUAT 7030 19.981076 72.641716 -8.307102 0.5698487 0.3756563 0.5555632 0.4748730 +VERTEX_SE3:QUAT 7031 19.602876 71.913711 -7.817484 -0.4839882 -0.3638179 -0.7502599 0.2655221 +VERTEX_SE3:QUAT 7032 19.216106 71.142591 -7.279739 0.0804914 0.3002059 0.9257849 0.2152205 +VERTEX_SE3:QUAT 7033 18.930252 70.487171 -6.709127 0.2363309 0.6332535 0.1458443 0.7224038 +VERTEX_SE3:QUAT 7034 18.672662 69.866176 -6.168582 -0.7159629 -0.0357315 -0.6789717 0.1584856 +VERTEX_SE3:QUAT 7035 18.361888 68.973648 -5.576756 -0.3067607 -0.2520146 -0.6865907 0.6090811 +VERTEX_SE3:QUAT 7036 18.044605 68.120207 -4.974886 0.2545525 -0.0021709 0.9543657 0.1561551 +VERTEX_SE3:QUAT 7037 17.615151 67.233366 -4.350647 -0.5350943 -0.2878209 -0.5636997 0.5595319 +VERTEX_SE3:QUAT 7038 17.202936 66.322022 -3.706717 -0.4619468 -0.0161057 0.1874452 0.8667238 +VERTEX_SE3:QUAT 7039 17.009476 65.540922 -3.042279 -0.7500947 -0.3671119 -0.5426092 0.0903437 +VERTEX_SE3:QUAT 7040 16.790454 66.117344 -2.240577 -0.1897465 0.3200725 -0.9228848 0.0991643 +VERTEX_SE3:QUAT 7041 16.898370 66.965311 -2.630796 -0.6924369 0.5604860 -0.4408951 0.1095364 +VERTEX_SE3:QUAT 7042 17.027419 67.947005 -3.029499 0.2476246 0.3245374 -0.0611259 0.9108354 +VERTEX_SE3:QUAT 7043 17.107852 68.712801 -3.578796 0.4566476 0.7504995 -0.1800913 0.4424823 +VERTEX_SE3:QUAT 7044 17.347714 69.487583 -4.272858 0.6996314 0.1568235 0.5155873 0.4691397 +VERTEX_SE3:QUAT 7045 17.661038 70.383014 -4.877568 -0.6450069 0.6147964 -0.4494005 0.0634875 +VERTEX_SE3:QUAT 7046 17.766580 71.221569 -5.404963 0.2036116 0.7062461 0.0505038 0.6761717 +VERTEX_SE3:QUAT 7047 17.896661 72.155923 -5.957008 0.7993895 0.2564958 0.3410419 0.4229382 +VERTEX_SE3:QUAT 7048 18.130271 72.865776 -6.570423 0.6704175 -0.3806605 0.4717163 0.4279271 +VERTEX_SE3:QUAT 7049 18.279021 73.629410 -7.027608 -0.5754078 0.7338411 -0.3059925 0.1917074 +VERTEX_SE3:QUAT 7050 18.579812 74.212151 -7.790355 0.4346108 0.8433455 0.1951829 0.2485668 +VERTEX_SE3:QUAT 7051 18.733053 75.055838 -8.283640 -0.3859885 0.0135213 -0.8594943 0.3348127 +VERTEX_SE3:QUAT 7052 19.123754 75.867307 -8.857800 0.4830078 0.3973583 -0.3027652 0.7191266 +VERTEX_SE3:QUAT 7053 19.368357 76.610492 -9.383098 -0.3358969 0.6173840 -0.4019706 0.5868815 +VERTEX_SE3:QUAT 7054 19.638111 77.191746 -10.146940 0.2303034 0.4629818 0.7975353 0.3107179 +VERTEX_SE3:QUAT 7055 20.126420 77.842193 -10.756388 -0.5604426 -0.2092243 -0.5457771 0.5867338 +VERTEX_SE3:QUAT 7056 20.546994 78.465570 -11.312259 -0.2203942 0.7769001 0.2481107 0.5350642 +VERTEX_SE3:QUAT 7057 21.231829 79.321313 -11.885862 0.4978329 0.7628068 -0.1926994 0.3649044 +VERTEX_SE3:QUAT 7058 21.497404 80.042847 -12.577393 0.1193281 -0.1779934 0.9073524 0.3616502 +VERTEX_SE3:QUAT 7059 21.824198 80.625028 -13.220434 -0.4011173 0.5758375 0.5733945 0.4227705 +VERTEX_SE3:QUAT 7060 21.561137 81.376539 -12.721426 -0.3290509 0.2180291 -0.1933510 0.8982228 +VERTEX_SE3:QUAT 7061 21.240946 80.657700 -12.024176 0.3310940 0.3424767 -0.7486498 0.4610964 +VERTEX_SE3:QUAT 7062 20.939929 79.885790 -11.359540 -0.3160058 0.4342116 0.7621176 0.3616314 +VERTEX_SE3:QUAT 7063 20.628073 79.188757 -10.679645 -0.6875944 0.5739042 -0.3266142 0.3019455 +VERTEX_SE3:QUAT 7064 20.471891 78.530006 -10.139114 -0.5475612 -0.0168125 -0.4887623 0.6789739 +VERTEX_SE3:QUAT 7065 20.153165 77.791000 -9.560198 -0.3309441 0.4618669 0.2947327 0.7683018 +VERTEX_SE3:QUAT 7066 20.031257 76.855230 -8.881211 -0.4040674 0.8337859 -0.2660605 0.2659745 +VERTEX_SE3:QUAT 7067 19.753319 76.182125 -8.005037 0.7907911 0.2733512 0.4352513 0.3323926 +VERTEX_SE3:QUAT 7068 19.629769 75.403630 -7.363591 -0.0041394 -0.0118753 0.9211694 0.3889586 +VERTEX_SE3:QUAT 7069 19.492492 74.652757 -6.884115 0.3164524 0.6429557 0.1352650 0.6842289 +VERTEX_SE3:QUAT 7070 19.189496 73.913466 -6.239606 0.6236741 0.1637354 0.0873636 0.7593346 +VERTEX_SE3:QUAT 7071 19.161276 73.254420 -5.777331 0.0645712 0.2298936 0.9516643 0.1931695 +VERTEX_SE3:QUAT 7072 18.845222 72.320308 -5.150961 0.6646272 0.3764909 -0.1612026 0.6249312 +VERTEX_SE3:QUAT 7073 18.567348 71.411888 -4.766339 -0.4604346 0.2815628 0.4490378 0.7121007 +VERTEX_SE3:QUAT 7074 18.278905 70.520809 -4.489630 -0.5147741 0.2652683 -0.1760576 0.7960176 +VERTEX_SE3:QUAT 7075 18.007403 69.709363 -4.091297 -0.2835544 0.2607750 -0.7538821 0.5322172 +VERTEX_SE3:QUAT 7076 17.795092 68.674248 -3.509087 -0.1203061 0.6651838 0.4296664 0.5987018 +VERTEX_SE3:QUAT 7077 17.763972 67.681355 -2.832680 0.2745785 -0.3675327 0.8608707 0.2200637 +VERTEX_SE3:QUAT 7078 17.482044 66.714850 -2.224281 -0.0801252 0.7947851 0.2263755 0.5573604 +VERTEX_SE3:QUAT 7079 17.322720 65.918909 -1.554636 0.0105388 0.6770755 0.5854078 0.4458198 +VERTEX_SE3:QUAT 7080 17.215726 66.322995 -0.790806 -0.7299576 0.1305581 -0.4283342 0.5163780 +VERTEX_SE3:QUAT 7081 17.595901 67.107877 -1.258297 -0.1418997 0.3990667 -0.1365476 0.8955250 +VERTEX_SE3:QUAT 7082 17.916192 67.863100 -1.741658 -0.4379853 -0.6069007 -0.6586672 0.0774462 +VERTEX_SE3:QUAT 7083 17.949572 68.657129 -2.285175 -0.5241133 0.7562606 -0.3317841 0.2080731 +VERTEX_SE3:QUAT 7084 18.007554 69.378920 -2.910492 -0.4274321 0.8648873 -0.2030089 0.1675090 +VERTEX_SE3:QUAT 7085 18.182332 70.320660 -3.295218 0.4597666 -0.2683599 0.8261174 0.1847369 +VERTEX_SE3:QUAT 7086 18.392676 71.378715 -3.789321 0.5500839 -0.6476588 0.5149504 0.1130126 +VERTEX_SE3:QUAT 7087 18.531605 72.201274 -4.288045 0.0837010 -0.0370827 0.6287924 0.7721652 +VERTEX_SE3:QUAT 7088 18.582107 73.088766 -4.636758 0.1904483 -0.1466481 0.6480683 0.7226557 +VERTEX_SE3:QUAT 7089 18.579249 74.013854 -5.101741 -0.8634387 0.1721398 -0.4511057 0.1460996 +VERTEX_SE3:QUAT 7090 18.738028 74.864948 -5.490530 0.3440312 0.6888157 0.4629533 0.4391466 +VERTEX_SE3:QUAT 7091 18.680002 75.729498 -6.170362 0.4827263 0.5117729 0.4839597 0.5204295 +VERTEX_SE3:QUAT 7092 18.893413 76.593583 -6.694522 0.7762657 -0.3953701 0.3845749 0.3052803 +VERTEX_SE3:QUAT 7093 18.803252 77.437762 -7.250337 0.3771850 0.4253941 -0.3304936 0.7533561 +VERTEX_SE3:QUAT 7094 18.889940 78.281342 -7.909660 -0.5114893 -0.3101456 -0.6750770 0.4318095 +VERTEX_SE3:QUAT 7095 18.798821 79.154354 -8.490439 0.2197450 0.7597664 0.4654813 0.3972333 +VERTEX_SE3:QUAT 7096 18.634986 80.061905 -9.065900 0.1031623 0.5690096 0.8105449 0.0927507 +VERTEX_SE3:QUAT 7097 18.560622 80.886550 -9.882293 0.8325243 0.0421470 0.5510311 0.0386221 +VERTEX_SE3:QUAT 7098 18.189050 81.918556 -10.507569 0.4014729 0.6534017 0.3575012 0.5329903 +VERTEX_SE3:QUAT 7099 17.943526 82.719759 -11.227045 0.5582963 0.6694977 0.4794784 0.1008890 +VERTEX_SE3:QUAT 7100 17.459667 83.219992 -10.512652 -0.8592069 0.1809377 -0.2482375 0.4091493 +VERTEX_SE3:QUAT 7101 17.723234 82.313940 -9.982290 0.4311661 0.3201933 -0.0515796 0.8419689 +VERTEX_SE3:QUAT 7102 17.942451 81.401793 -9.633898 0.4596171 0.3250658 0.1931090 0.8036126 +VERTEX_SE3:QUAT 7103 18.117843 80.569964 -9.235321 -0.4461728 -0.4907959 -0.2757091 0.6957253 +VERTEX_SE3:QUAT 7104 18.342532 79.910399 -8.639727 0.0324600 0.1836440 -0.6713892 0.7172571 +VERTEX_SE3:QUAT 7105 18.305851 79.021198 -8.259734 -0.5247307 -0.1963043 -0.7667868 0.3133054 +VERTEX_SE3:QUAT 7106 18.371965 78.144383 -7.805277 0.3774164 0.5426611 0.6202415 0.4223462 +VERTEX_SE3:QUAT 7107 18.696850 77.193508 -7.233958 -0.6695331 0.5951364 0.2393040 0.3745287 +VERTEX_SE3:QUAT 7108 18.678180 76.516049 -6.717474 -0.5161070 -0.8153562 -0.2607573 0.0288682 +VERTEX_SE3:QUAT 7109 18.656258 75.514151 -6.305226 0.7935123 0.3741001 0.0859526 0.4722282 +VERTEX_SE3:QUAT 7110 18.779979 74.593523 -5.840722 0.1978093 0.3748098 0.0689309 0.9031266 +VERTEX_SE3:QUAT 7111 18.921000 73.720530 -5.332403 0.2280073 0.8877497 0.3996374 0.0142532 +VERTEX_SE3:QUAT 7112 19.030286 73.049748 -4.716822 0.5888297 0.6606839 0.4199781 0.2009844 +VERTEX_SE3:QUAT 7113 19.224920 72.132644 -4.019859 -0.5094945 0.6474860 -0.5423493 0.1644218 +VERTEX_SE3:QUAT 7114 19.245142 71.313267 -3.362097 -0.7821287 -0.5950210 -0.1810107 0.0382073 +VERTEX_SE3:QUAT 7115 19.274924 70.695595 -2.676129 -0.8918800 -0.0593115 -0.3435944 0.2880542 +VERTEX_SE3:QUAT 7116 19.299412 70.014578 -1.924737 -0.2363419 -0.0266789 -0.4414086 0.8652105 +VERTEX_SE3:QUAT 7117 19.379159 69.162275 -1.183400 -0.6638871 0.5270477 0.2557476 0.4648309 +VERTEX_SE3:QUAT 7118 19.450027 68.457856 -0.386388 -0.5820509 0.6523128 0.4083829 0.2625418 +VERTEX_SE3:QUAT 7119 19.518802 67.633178 0.328448 -0.2677591 0.3578597 0.1201167 0.8864612 +VERTEX_SE3:QUAT 7120 18.953727 68.171148 1.070312 -0.6376409 -0.2050123 -0.2634096 0.6942618 +VERTEX_SE3:QUAT 7121 18.794305 69.103401 0.532100 -0.1914596 0.6895116 0.3735224 0.5902525 +VERTEX_SE3:QUAT 7122 18.730015 69.912910 -0.081127 -0.1075414 -0.1395369 -0.6054399 0.7761487 +VERTEX_SE3:QUAT 7123 18.607968 70.706381 -0.664361 -0.1600326 0.6598617 -0.2476299 0.6911234 +VERTEX_SE3:QUAT 7124 18.353769 71.461777 -1.112968 -0.4368191 0.0093590 0.1808523 0.8811322 +VERTEX_SE3:QUAT 7125 18.286715 72.315732 -1.659501 0.1489041 0.2601686 -0.3252371 0.8968616 +VERTEX_SE3:QUAT 7126 18.149571 73.121260 -2.028495 -0.0671701 -0.8423124 -0.5297239 0.0734210 +VERTEX_SE3:QUAT 7127 17.843164 73.831599 -2.717834 -0.0936064 -0.1892662 -0.7985894 0.5636232 +VERTEX_SE3:QUAT 7128 17.644441 74.800473 -3.151628 -0.0950138 -0.2571523 -0.9588608 0.0736958 +VERTEX_SE3:QUAT 7129 17.690764 75.648560 -3.777448 -0.0558038 0.8571062 0.4690154 0.2056199 +VERTEX_SE3:QUAT 7130 17.645361 76.354487 -4.386393 0.6178709 0.5169329 0.0461318 0.5906672 +VERTEX_SE3:QUAT 7131 17.326921 77.108823 -5.080364 -0.3560394 0.4192911 -0.8331688 0.0571031 +VERTEX_SE3:QUAT 7132 17.023794 77.700412 -5.684790 -0.0964495 -0.0817876 -0.2674756 0.9552304 +VERTEX_SE3:QUAT 7133 16.727546 78.581330 -6.376449 -0.5227848 0.4465868 -0.6199186 0.3780967 +VERTEX_SE3:QUAT 7134 16.410974 79.368287 -7.124502 -0.2519007 0.2711085 -0.9028301 0.2189613 +VERTEX_SE3:QUAT 7135 16.106495 80.169744 -7.706385 -0.2032599 -0.2418981 -0.9141387 0.2540100 +VERTEX_SE3:QUAT 7136 15.810673 80.802891 -8.439682 0.4621775 0.7694042 0.4065029 0.1707763 +VERTEX_SE3:QUAT 7137 15.543379 81.574035 -9.030066 -0.3030429 -0.4986455 -0.5946997 0.5530370 +VERTEX_SE3:QUAT 7138 15.451793 82.297295 -9.795429 -0.1808093 0.5441392 0.7699331 0.2800421 +VERTEX_SE3:QUAT 7139 15.309498 82.997888 -10.489182 -0.8800511 0.1530294 -0.4054353 0.1942019 +VERTEX_SE3:QUAT 7140 14.515764 83.493750 -9.844836 -0.1855063 0.3002846 0.3067368 0.8839282 +VERTEX_SE3:QUAT 7141 14.408370 82.660778 -9.017093 -0.4798003 0.4396689 0.6151320 0.4450792 +VERTEX_SE3:QUAT 7142 14.235493 81.994349 -8.239462 -0.0211737 0.0776199 -0.9588413 0.2723052 +VERTEX_SE3:QUAT 7143 14.053950 81.416252 -7.626097 -0.2265988 -0.0374097 0.9442174 0.2360232 +VERTEX_SE3:QUAT 7144 14.006274 80.483356 -6.981893 0.6399506 -0.0228155 0.7532512 0.1501843 +VERTEX_SE3:QUAT 7145 13.878208 79.704070 -6.298551 -0.7271619 0.2201507 -0.5034629 0.4114540 +VERTEX_SE3:QUAT 7146 13.823979 78.876161 -5.778871 0.3744966 0.3779047 0.3869645 0.7531261 +VERTEX_SE3:QUAT 7147 13.771045 78.170575 -5.140304 -0.7019501 0.0282900 -0.6496781 0.2904893 +VERTEX_SE3:QUAT 7148 13.711009 77.333505 -4.659949 -0.8156031 -0.0534192 -0.1081542 0.5658981 +VERTEX_SE3:QUAT 7149 13.625507 76.679911 -3.985369 0.3955050 0.7450773 0.2291704 0.4857124 +VERTEX_SE3:QUAT 7150 13.537827 75.871658 -3.408673 0.3575255 0.1798916 -0.4620764 0.7913912 +VERTEX_SE3:QUAT 7151 13.731287 75.025063 -2.963135 -0.7918790 0.1363160 -0.5936984 0.0432171 +VERTEX_SE3:QUAT 7152 13.799985 74.268559 -2.328646 -0.5584101 0.0570328 -0.6243864 0.5432007 +VERTEX_SE3:QUAT 7153 13.689982 73.487404 -1.884170 -0.6269199 -0.0383886 -0.5550168 0.5453935 +VERTEX_SE3:QUAT 7154 13.372541 72.770354 -1.155984 0.6696650 0.2476969 0.6483682 0.2642227 +VERTEX_SE3:QUAT 7155 13.321373 72.093256 -0.635117 -0.2663855 0.0058810 0.8875216 0.3759116 +VERTEX_SE3:QUAT 7156 13.050606 71.340732 0.063637 0.0221318 0.6498246 -0.0134271 0.7596432 +VERTEX_SE3:QUAT 7157 13.001428 70.476889 0.492877 0.2659677 -0.1405939 0.8139053 0.4970440 +VERTEX_SE3:QUAT 7158 12.768112 69.808814 1.199079 -0.7756951 -0.0032010 -0.1550646 0.6117531 +VERTEX_SE3:QUAT 7159 12.318477 68.999238 1.928836 -0.3492696 0.8392441 -0.1720673 0.3795694 +VERTEX_SE3:QUAT 7160 11.718430 69.861510 2.619549 -0.1908687 0.6817151 0.4360156 0.5556294 +VERTEX_SE3:QUAT 7161 11.938986 70.726137 1.846723 0.0863920 0.2719743 0.3694942 0.8843305 +VERTEX_SE3:QUAT 7162 12.184719 71.534180 1.265677 -0.5070229 -0.3251886 -0.6822799 0.4143358 +VERTEX_SE3:QUAT 7163 12.467432 72.231611 0.596654 -0.3755779 -0.1450700 0.2222584 0.8879736 +VERTEX_SE3:QUAT 7164 12.875308 72.705543 -0.272420 -0.5809942 -0.3111901 -0.4416985 0.6086944 +VERTEX_SE3:QUAT 7165 13.379286 73.427179 -1.068772 0.7030857 -0.0075382 0.6530872 0.2812309 +VERTEX_SE3:QUAT 7166 13.603714 74.062985 -1.831952 -0.3660408 0.1573555 0.3064908 0.8644749 +VERTEX_SE3:QUAT 7167 14.174872 74.894257 -2.341728 0.4985988 -0.1994691 0.6488866 0.5390338 +VERTEX_SE3:QUAT 7168 14.364901 75.513744 -3.015997 -0.1607208 -0.3863128 -0.8943832 0.1581450 +VERTEX_SE3:QUAT 7169 14.830044 76.087650 -3.709866 -0.3018033 0.2680346 0.7861469 0.4680227 +VERTEX_SE3:QUAT 7170 15.091918 76.534874 -4.408008 0.0742200 0.2276341 0.7520421 0.6140902 +VERTEX_SE3:QUAT 7171 15.408577 76.826529 -5.150030 -0.1585443 0.4722651 -0.7340649 0.4614955 +VERTEX_SE3:QUAT 7172 15.653648 77.358432 -5.948267 -0.1840188 -0.0510651 0.9781857 0.0817448 +VERTEX_SE3:QUAT 7173 15.977631 77.944175 -6.618142 0.4879681 -0.3905225 0.7671619 0.1443672 +VERTEX_SE3:QUAT 7174 16.271080 78.298332 -7.564627 -0.3439243 0.6285128 -0.2509458 0.6509331 +VERTEX_SE3:QUAT 7175 16.479412 78.672860 -8.476711 0.0783956 0.6312011 0.6601902 0.3994850 +VERTEX_SE3:QUAT 7176 16.821864 79.110071 -9.354641 -0.6119033 -0.2466241 -0.7426429 0.1150319 +VERTEX_SE3:QUAT 7177 17.112936 79.581031 -10.208577 -0.2608715 0.6250565 0.1110705 0.7272646 +VERTEX_SE3:QUAT 7178 17.539354 79.892508 -10.942425 0.1073020 0.3727304 -0.4425332 0.8085312 +VERTEX_SE3:QUAT 7179 17.981710 80.158477 -11.749561 0.0302007 0.5689671 0.2026702 0.7964227 +VERTEX_SE3:QUAT 7180 17.239652 81.168354 -11.925955 -0.2280074 -0.5138670 -0.8255188 0.0497198 +VERTEX_SE3:QUAT 7181 16.749103 80.821986 -11.101553 -0.8778480 0.2948988 -0.2118669 0.3122979 +VERTEX_SE3:QUAT 7182 16.110962 80.428632 -10.260008 -0.2626361 0.3636283 0.8547755 0.2610662 +VERTEX_SE3:QUAT 7183 15.664191 80.124363 -9.300432 0.8268450 -0.0131815 0.5618917 0.0207687 +VERTEX_SE3:QUAT 7184 15.242942 79.838403 -8.391612 0.3476753 0.7050322 0.6025127 0.1379491 +VERTEX_SE3:QUAT 7185 14.898338 79.585516 -7.563831 -0.2521637 -0.2979949 -0.9203237 0.0248341 +VERTEX_SE3:QUAT 7186 14.474426 79.153436 -6.762925 0.0931448 0.2660582 -0.1429028 0.9487444 +VERTEX_SE3:QUAT 7187 13.925899 78.695808 -6.083116 -0.0445557 0.3632991 0.9131315 0.1794980 +VERTEX_SE3:QUAT 7188 13.495078 78.345659 -5.285264 -0.1425818 -0.2466459 0.7845528 0.5507387 +VERTEX_SE3:QUAT 7189 13.017752 78.005572 -4.671675 -0.7503704 0.1109889 -0.5677527 0.3198165 +VERTEX_SE3:QUAT 7190 12.567269 77.493725 -3.687693 -0.6967393 -0.1015170 -0.3389073 0.6240116 +VERTEX_SE3:QUAT 7191 12.233562 77.137236 -2.915380 0.4352100 0.6386968 0.3291097 0.5425361 +VERTEX_SE3:QUAT 7192 11.640274 76.792479 -2.042353 -0.4638937 -0.8231195 -0.3274896 0.0052419 +VERTEX_SE3:QUAT 7193 11.085830 76.539878 -1.222875 -0.1547932 0.5670350 -0.4003246 0.7030296 +VERTEX_SE3:QUAT 7194 10.637008 76.353001 -0.395826 -0.6265228 0.1635538 -0.7150584 0.2634594 +VERTEX_SE3:QUAT 7195 10.164122 76.403000 0.508566 -0.6029352 -0.6899955 -0.2205379 0.3342728 +VERTEX_SE3:QUAT 7196 9.695782 76.200903 1.373299 0.0569973 0.0952918 0.3570825 0.9274497 +VERTEX_SE3:QUAT 7197 9.214287 76.170249 2.132592 -0.0365508 -0.6062149 -0.5265828 0.5948766 +VERTEX_SE3:QUAT 7198 8.514146 76.223169 3.097079 -0.0719416 0.3365499 0.5596294 0.7539055 +VERTEX_SE3:QUAT 7199 8.031874 75.893350 3.810506 0.1811622 -0.5881976 -0.7404755 0.2699999 +VERTEX_SE3:QUAT 7200 17.457591 79.277910 -12.623642 -0.4653426 -0.3276796 -0.7805708 0.2584406 +VERTEX_SE3:QUAT 7201 17.046164 79.175595 -11.891110 -0.2792233 0.2616554 -0.8740393 0.2993763 +VERTEX_SE3:QUAT 7202 16.500937 79.128324 -10.962150 0.0476413 -0.0743840 -0.9741146 0.2080820 +VERTEX_SE3:QUAT 7203 16.014364 79.077625 -9.898585 -0.0945842 0.1154223 0.0082962 0.9887683 +VERTEX_SE3:QUAT 7204 15.578146 78.985208 -9.094420 -0.5344128 -0.7745387 -0.3371906 0.0282002 +VERTEX_SE3:QUAT 7205 15.270450 78.949614 -8.278374 0.5793246 0.1670886 0.7968028 0.0396187 +VERTEX_SE3:QUAT 7206 14.590493 78.929535 -7.444538 0.1037981 -0.3058464 -0.5384434 0.7783076 +VERTEX_SE3:QUAT 7207 13.863886 78.930460 -6.839804 -0.3671999 0.0778230 -0.7795352 0.5014306 +VERTEX_SE3:QUAT 7208 13.110915 78.907499 -6.059646 -0.5130730 0.5724289 0.5735167 0.2831250 +VERTEX_SE3:QUAT 7209 12.324786 78.756809 -5.171311 -0.1213295 0.3685334 0.7119673 0.5852904 +VERTEX_SE3:QUAT 7210 11.582601 78.857136 -4.270291 -0.7080069 0.3347302 0.4338102 0.4455229 +VERTEX_SE3:QUAT 7211 10.805597 78.948334 -3.668525 -0.6955986 0.1688378 0.2318952 0.6586813 +VERTEX_SE3:QUAT 7212 10.211548 79.103855 -3.192369 -0.4240779 -0.4239742 -0.7904794 0.1246844 +VERTEX_SE3:QUAT 7213 9.607458 79.447305 -2.405870 0.2651066 -0.0108906 0.6382560 0.7226543 +VERTEX_SE3:QUAT 7214 8.908660 79.797063 -1.651366 0.5715847 0.3311911 -0.0206799 0.7504503 +VERTEX_SE3:QUAT 7215 8.165062 80.001383 -0.931299 0.3428693 0.4514159 -0.2384211 0.7885555 +VERTEX_SE3:QUAT 7216 7.529953 80.081529 -0.218763 0.7248167 0.0578461 0.6442444 0.2371577 +VERTEX_SE3:QUAT 7217 6.710262 80.513005 0.386967 -0.6455238 0.4084618 0.4739291 0.4380059 +VERTEX_SE3:QUAT 7218 5.924137 80.830974 1.011478 0.0913330 0.6854711 0.7005701 0.1760375 +VERTEX_SE3:QUAT 7219 5.221275 81.122409 1.497405 0.0705081 0.4882117 -0.3059627 0.8142879 +VERTEX_SE3:QUAT 7220 4.945516 80.319905 2.000730 -0.6063571 0.5455071 0.1814259 0.5493977 +VERTEX_SE3:QUAT 7221 5.664167 79.850822 1.486829 -0.2387903 -0.0974026 -0.5778899 0.7742966 +VERTEX_SE3:QUAT 7222 6.311345 79.229316 0.831349 -0.0395931 0.0730073 -0.9869810 0.1377348 +VERTEX_SE3:QUAT 7223 7.104255 78.769938 0.116092 0.2360680 0.0463677 0.3143806 0.9183065 +VERTEX_SE3:QUAT 7224 7.689624 78.341041 -0.215314 -0.5651784 0.3297724 -0.4353059 0.6183302 +VERTEX_SE3:QUAT 7225 8.377899 77.937752 -0.860982 -0.5886803 0.5605891 -0.2436106 0.5290078 +VERTEX_SE3:QUAT 7226 8.840581 77.576442 -1.496042 0.1606530 -0.3334744 0.9160943 0.1541320 +VERTEX_SE3:QUAT 7227 9.509244 77.378404 -1.942321 -0.6445872 -0.6337539 -0.4084158 0.1267279 +VERTEX_SE3:QUAT 7228 10.100777 76.826709 -2.630044 -0.1349998 -0.5568192 -0.7925496 0.2087883 +VERTEX_SE3:QUAT 7229 10.614676 76.509024 -3.273449 -0.1547209 -0.1861309 -0.2237656 0.9441110 +VERTEX_SE3:QUAT 7230 11.147901 76.142108 -4.032522 -0.1917481 0.0886321 0.8810851 0.4231620 +VERTEX_SE3:QUAT 7231 11.729142 75.965051 -4.795868 -0.1413747 0.3522394 -0.6797620 0.6275860 +VERTEX_SE3:QUAT 7232 12.171407 75.618791 -5.682520 -0.1258048 0.2828547 -0.0708460 0.9482337 +VERTEX_SE3:QUAT 7233 12.659682 75.301984 -6.275575 -0.4206585 0.1305696 0.4739940 0.7624484 +VERTEX_SE3:QUAT 7234 13.236284 75.033266 -6.850755 -0.0304799 -0.0596187 -0.6016834 0.7959231 +VERTEX_SE3:QUAT 7235 13.511913 74.640474 -7.844202 -0.4486800 0.3804032 0.2831927 0.7574837 +VERTEX_SE3:QUAT 7236 13.742138 74.438060 -8.806448 0.5270366 0.7799953 0.3290742 0.0744974 +VERTEX_SE3:QUAT 7237 14.242240 74.392835 -9.473414 0.3157121 -0.1212966 0.9330224 0.1228095 +VERTEX_SE3:QUAT 7238 14.504857 73.817521 -10.398903 -0.0499304 0.0876412 0.9409220 0.3232520 +VERTEX_SE3:QUAT 7239 14.959804 73.459196 -11.288802 0.0252386 0.0965371 0.1776702 0.9790183 +VERTEX_SE3:QUAT 7240 15.032164 72.448953 -11.205412 0.9066728 -0.1037544 0.4043997 0.0603356 +VERTEX_SE3:QUAT 7241 14.615271 72.757006 -10.123667 0.7049455 -0.2849661 0.3683761 0.5349254 +VERTEX_SE3:QUAT 7242 14.094621 73.004919 -9.131216 -0.1069345 0.1268801 0.7572845 0.6316539 +VERTEX_SE3:QUAT 7243 13.494886 73.276763 -8.284853 -0.5166175 -0.4444225 -0.7229823 0.1135412 +VERTEX_SE3:QUAT 7244 12.954808 73.532830 -7.479376 -0.3998121 0.4634796 -0.1030677 0.7840370 +VERTEX_SE3:QUAT 7245 12.411742 73.854008 -6.778147 0.1550664 -0.0644049 -0.9397933 0.2976490 +VERTEX_SE3:QUAT 7246 11.925577 74.032017 -6.036603 0.0257917 -0.1454370 -0.9474611 0.2837258 +VERTEX_SE3:QUAT 7247 11.287340 74.333797 -5.374032 -0.2444603 0.6486444 0.1035571 0.7132850 +VERTEX_SE3:QUAT 7248 10.547889 74.609625 -4.834889 0.0810532 0.1430458 0.9144884 0.3697015 +VERTEX_SE3:QUAT 7249 10.146332 74.876124 -4.258494 0.3730181 0.7742177 -0.1905005 0.4745041 +VERTEX_SE3:QUAT 7250 9.730606 75.130045 -3.515885 -0.3319837 0.0709884 0.8153232 0.4690368 +VERTEX_SE3:QUAT 7251 8.931769 75.417801 -2.689010 0.3303617 -0.4882728 0.7502671 0.2992493 +VERTEX_SE3:QUAT 7252 8.371062 75.529392 -2.020813 -0.0163406 0.3120821 -0.3110675 0.8975382 +VERTEX_SE3:QUAT 7253 7.635034 75.571837 -1.434705 -0.1546407 0.6184290 0.5188777 0.5695592 +VERTEX_SE3:QUAT 7254 7.049132 75.875239 -0.717421 0.0934749 0.3823546 -0.2925148 0.8714944 +VERTEX_SE3:QUAT 7255 6.393097 76.142399 0.035404 -0.5077527 0.7764999 -0.0951079 0.3608179 +VERTEX_SE3:QUAT 7256 5.775600 76.539161 0.726268 0.4920280 -0.2549073 0.8228474 0.1259084 +VERTEX_SE3:QUAT 7257 5.084094 77.030992 1.302370 0.1013694 0.1911589 -0.1173713 0.9692298 +VERTEX_SE3:QUAT 7258 4.397067 77.555661 1.898442 0.3908089 0.0600211 -0.4179044 0.8179375 +VERTEX_SE3:QUAT 7259 3.813201 77.959792 2.507850 -0.5548436 0.3343227 -0.7618058 0.0053722 +VERTEX_SE3:QUAT 7260 3.465616 77.147561 2.862562 -0.2772517 0.2460295 -0.3431532 0.8630451 +VERTEX_SE3:QUAT 7261 4.255946 76.670559 2.331502 0.2030414 -0.5875682 0.7685840 0.1510512 +VERTEX_SE3:QUAT 7262 4.895760 76.322695 1.687907 0.2804337 0.6616931 0.6216411 0.3115790 +VERTEX_SE3:QUAT 7263 5.419347 76.010115 0.976096 -0.1365082 0.0952891 -0.9712401 0.1702296 +VERTEX_SE3:QUAT 7264 6.013724 75.587145 0.081351 -0.0608331 -0.2610859 -0.5013850 0.8226461 +VERTEX_SE3:QUAT 7265 6.670009 75.252252 -0.814517 -0.2659201 -0.0950963 0.6936874 0.6626017 +VERTEX_SE3:QUAT 7266 7.188576 74.984680 -1.622152 -0.1393624 0.1224217 -0.9677571 0.1704032 +VERTEX_SE3:QUAT 7267 7.674656 74.628407 -2.388097 0.6673056 0.6248175 0.3085389 0.2628881 +VERTEX_SE3:QUAT 7268 8.348451 74.284701 -2.992886 0.1854982 0.6325998 -0.2697056 0.7019023 +VERTEX_SE3:QUAT 7269 9.135840 74.083682 -3.768789 0.0642440 -0.1615487 -0.5540506 0.8141269 +VERTEX_SE3:QUAT 7270 9.842966 73.873929 -4.517816 -0.4455097 0.2181434 -0.4243932 0.7575124 +VERTEX_SE3:QUAT 7271 10.457806 73.655759 -5.150771 0.2534886 -0.1140942 -0.8767222 0.3925355 +VERTEX_SE3:QUAT 7272 10.969884 73.354813 -5.834778 0.3668440 0.1658220 0.0053097 0.9153690 +VERTEX_SE3:QUAT 7273 11.586472 73.287686 -6.742486 0.5912792 0.0388683 0.7608616 0.2645143 +VERTEX_SE3:QUAT 7274 12.103535 72.997791 -7.547805 0.0221827 0.2238047 0.8948683 0.3855259 +VERTEX_SE3:QUAT 7275 12.485711 72.591620 -8.353058 -0.6629082 0.6189170 -0.0091375 0.4212019 +VERTEX_SE3:QUAT 7276 12.934050 72.457918 -9.220295 -0.1648242 -0.0968774 0.4353616 0.8797204 +VERTEX_SE3:QUAT 7277 13.476929 72.426604 -10.083304 0.1039362 0.2919619 -0.7859479 0.5350153 +VERTEX_SE3:QUAT 7278 14.096545 72.337532 -10.833632 -0.8331011 0.3496721 -0.1294481 0.4085525 +VERTEX_SE3:QUAT 7279 14.414950 72.301288 -11.687844 0.2815751 0.4147361 0.3872472 0.7737888 +VERTEX_SE3:QUAT 7280 14.585412 71.385381 -11.256389 -0.5557686 0.1765037 0.4441669 0.6802084 +VERTEX_SE3:QUAT 7281 14.066256 71.642905 -10.297657 -0.1841698 0.2873806 -0.8861459 0.3134315 +VERTEX_SE3:QUAT 7282 13.605561 71.835903 -9.480501 -0.5049045 -0.5859088 -0.4055076 0.4871816 +VERTEX_SE3:QUAT 7283 13.139262 71.975562 -8.466646 -0.2746463 0.2803812 0.8255434 0.4055044 +VERTEX_SE3:QUAT 7284 12.756946 72.176533 -7.699681 -0.4478385 0.5746738 -0.2810223 0.6246737 +VERTEX_SE3:QUAT 7285 12.395163 72.488669 -6.857302 0.1112238 0.2785908 -0.3005468 0.9053663 +VERTEX_SE3:QUAT 7286 11.844995 72.675790 -5.948344 0.1847544 0.1104349 -0.3783140 0.9003046 +VERTEX_SE3:QUAT 7287 11.342263 73.045194 -5.070016 0.6256057 0.7270217 0.2799908 0.0407684 +VERTEX_SE3:QUAT 7288 10.886722 73.163550 -4.328042 -0.8659332 -0.2452849 -0.4353196 0.0221768 +VERTEX_SE3:QUAT 7289 10.426221 73.470282 -3.444430 -0.1872514 -0.3825350 -0.8121416 0.3987856 +VERTEX_SE3:QUAT 7290 9.858265 73.773989 -2.573354 0.0125812 0.8963306 0.4282605 0.1141318 +VERTEX_SE3:QUAT 7291 9.226856 74.036031 -1.713314 -0.4523494 -0.2853201 -0.5959614 0.5990013 +VERTEX_SE3:QUAT 7292 8.447022 74.382634 -0.890990 -0.8842478 0.0750934 -0.1012807 0.4496766 +VERTEX_SE3:QUAT 7293 8.026932 74.542727 -0.027883 0.6017930 0.2966047 0.6680211 0.3218985 +VERTEX_SE3:QUAT 7294 7.551492 74.854617 0.649865 0.8703686 0.1962849 0.4509766 0.0234706 +VERTEX_SE3:QUAT 7295 7.055626 75.117860 1.491083 -0.2617984 0.1547849 0.1894434 0.9336029 +VERTEX_SE3:QUAT 7296 6.519338 75.283641 2.088747 -0.5866218 0.7358400 -0.2305441 0.2475152 +VERTEX_SE3:QUAT 7297 5.942427 75.418607 2.847774 -0.3735799 0.7909980 -0.0544894 0.4814469 +VERTEX_SE3:QUAT 7298 5.472128 75.742539 3.560658 -0.6748078 0.1695339 -0.5548427 0.4561165 +VERTEX_SE3:QUAT 7299 5.066941 76.007662 4.392786 -0.1082500 0.3273246 0.1854839 0.9201827 +VERTEX_SE3:QUAT 7300 5.624388 75.474488 4.972319 -0.3133293 -0.7004272 -0.2329825 0.5974493 +VERTEX_SE3:QUAT 7301 6.118797 75.172598 4.415472 0.0090288 -0.1813843 -0.8148437 0.5504980 +VERTEX_SE3:QUAT 7302 6.422469 75.028090 3.655607 -0.7180995 0.4229686 -0.5512382 0.0395867 +VERTEX_SE3:QUAT 7303 6.897028 74.928823 2.734759 0.1505059 -0.0735798 -0.7462450 0.6442456 +VERTEX_SE3:QUAT 7304 7.303290 74.631919 1.744432 -0.2625177 -0.5008563 -0.2968536 0.7694838 +VERTEX_SE3:QUAT 7305 7.976974 74.349470 0.841423 -0.1647732 0.5146502 0.4800483 0.6910417 +VERTEX_SE3:QUAT 7306 8.468182 74.224678 0.004286 -0.2910870 0.4101863 0.6417268 0.5789665 +VERTEX_SE3:QUAT 7307 8.881423 73.977852 -0.808504 -0.2449040 0.2653165 -0.6643765 0.6543952 +VERTEX_SE3:QUAT 7308 9.356878 73.469187 -1.647949 -0.6182224 0.1996860 -0.7515161 0.1146738 +VERTEX_SE3:QUAT 7309 9.801133 73.019645 -2.398890 0.3632296 0.8309838 0.3300293 0.2619368 +VERTEX_SE3:QUAT 7310 10.308526 72.697122 -3.165218 0.4852406 -0.5025425 0.7050322 0.1221565 +VERTEX_SE3:QUAT 7311 10.821591 72.073968 -3.914660 -0.6289033 0.6347682 -0.1035198 0.4368450 +VERTEX_SE3:QUAT 7312 11.404718 71.641450 -4.898981 -0.7491489 0.5369634 -0.3852244 0.0452591 +VERTEX_SE3:QUAT 7313 11.812217 71.286497 -5.766553 0.3197672 0.9218032 -0.0679106 0.2083650 +VERTEX_SE3:QUAT 7314 11.972573 70.792869 -6.575864 0.7586376 0.4726044 0.3691079 0.2547026 +VERTEX_SE3:QUAT 7315 12.571692 70.420797 -7.343614 -0.2569116 0.8340696 -0.3439124 0.3464803 +VERTEX_SE3:QUAT 7316 13.018883 69.963086 -8.034191 -0.4976546 0.1888741 0.5116467 0.6744510 +VERTEX_SE3:QUAT 7317 13.328709 69.261256 -8.753766 0.0319383 0.3058963 0.8126258 0.4950219 +VERTEX_SE3:QUAT 7318 13.651274 68.700937 -9.203139 0.6719884 0.6520776 0.3443799 0.0680358 +VERTEX_SE3:QUAT 7319 14.215562 68.138896 -9.645921 -0.0099891 0.0258159 0.9801783 0.1961740 +VERTEX_SE3:QUAT 7320 14.435451 67.468027 -8.860616 0.5171199 0.2888998 0.5137264 0.6206522 +VERTEX_SE3:QUAT 7321 13.923048 68.050148 -8.281378 -0.7102882 0.6348678 0.1504695 0.2641828 +VERTEX_SE3:QUAT 7322 13.480024 68.699784 -7.638823 0.3554448 0.5591872 0.2913763 0.6899772 +VERTEX_SE3:QUAT 7323 13.059882 69.324851 -6.946872 0.1453739 0.9681070 0.1494102 0.1389669 +VERTEX_SE3:QUAT 7324 12.538734 69.815880 -6.507498 0.5426485 -0.0205296 0.5903979 0.5971109 +VERTEX_SE3:QUAT 7325 11.914511 70.715721 -5.959180 0.2034752 0.5567150 -0.0129155 0.8052946 +VERTEX_SE3:QUAT 7326 11.395496 71.358977 -5.335017 0.1132854 0.5124879 -0.1716516 0.8337015 +VERTEX_SE3:QUAT 7327 10.859902 72.049837 -4.769599 -0.3191859 0.6973204 0.3537828 0.5354460 +VERTEX_SE3:QUAT 7328 10.301324 72.558803 -4.180391 -0.2369911 0.4017397 0.7005007 0.5401289 +VERTEX_SE3:QUAT 7329 9.983629 73.101778 -3.453661 0.5985147 0.2770542 0.2552419 0.7070168 +VERTEX_SE3:QUAT 7330 9.489294 73.762668 -2.788027 -0.0158481 -0.0229356 0.9211007 0.3883251 +VERTEX_SE3:QUAT 7331 9.141833 74.389330 -2.080312 -0.8410133 0.2452208 -0.4189207 0.2388910 +VERTEX_SE3:QUAT 7332 8.732489 74.951599 -1.379098 0.1964814 0.8135242 0.3923877 0.3815828 +VERTEX_SE3:QUAT 7333 8.264364 75.577032 -0.643894 -0.7406713 -0.3679590 -0.2633513 0.4966470 +VERTEX_SE3:QUAT 7334 7.683600 75.981646 -0.002367 -0.2383846 0.2795389 -0.3388648 0.8661417 +VERTEX_SE3:QUAT 7335 7.432216 76.480896 0.886787 -0.6469146 -0.7016219 -0.2981886 0.0176552 +VERTEX_SE3:QUAT 7336 7.049114 76.935482 1.776246 -0.4050634 -0.7000674 -0.5479941 0.2133816 +VERTEX_SE3:QUAT 7337 6.796777 77.423784 2.555611 -0.7178299 0.1146660 0.1724360 0.6647087 +VERTEX_SE3:QUAT 7338 6.473600 78.121552 3.382925 -0.7673413 0.5800743 -0.2731316 0.0100101 +VERTEX_SE3:QUAT 7339 6.340860 78.659362 4.152598 0.6115739 -0.3897415 0.6100294 0.3192853 +VERTEX_SE3:QUAT 7340 6.541880 77.841090 4.659316 0.3217017 -0.7984731 0.5078738 0.0318252 +VERTEX_SE3:QUAT 7341 6.808729 77.330831 3.943742 0.8502655 -0.4783467 0.2042361 0.0807507 +VERTEX_SE3:QUAT 7342 7.077338 76.812504 3.262869 0.6082477 -0.2968399 0.5626343 0.4747246 +VERTEX_SE3:QUAT 7343 7.212246 75.942878 2.439161 0.1823604 0.2701303 -0.5876320 0.7405829 +VERTEX_SE3:QUAT 7344 7.285241 75.170246 1.845415 0.4047414 0.3213186 0.7327297 0.4427708 +VERTEX_SE3:QUAT 7345 7.427788 74.547498 1.182164 -0.6934865 -0.2711352 -0.5424330 0.3890098 +VERTEX_SE3:QUAT 7346 7.579198 74.003061 0.404495 -0.6705568 -0.6595510 -0.2934955 0.1708990 +VERTEX_SE3:QUAT 7347 7.324937 73.319652 -0.282558 -0.5159829 -0.5639724 -0.5361897 0.3580466 +VERTEX_SE3:QUAT 7348 7.337543 72.839121 -0.926085 -0.1642128 0.8240295 0.5239999 0.1394046 +VERTEX_SE3:QUAT 7349 7.006724 72.221733 -1.713879 -0.4101554 0.4321761 -0.0152107 0.8029726 +VERTEX_SE3:QUAT 7350 6.865186 71.570057 -2.358679 -0.7204524 -0.4946142 -0.2706678 0.4037871 +VERTEX_SE3:QUAT 7351 6.668338 70.870948 -2.934091 0.7237039 0.0889463 0.4199019 0.5403921 +VERTEX_SE3:QUAT 7352 6.491363 70.140713 -3.707780 0.2035364 0.8764319 -0.4161153 0.1314845 +VERTEX_SE3:QUAT 7353 6.360797 69.436594 -4.370996 0.7526801 0.3605795 -0.2373484 0.4971125 +VERTEX_SE3:QUAT 7354 6.014592 68.681511 -5.113351 0.8375507 0.5299999 0.1296794 0.0281441 +VERTEX_SE3:QUAT 7355 5.590329 67.989708 -5.839519 0.6205692 0.1896904 0.7608483 0.0046133 +VERTEX_SE3:QUAT 7356 5.107898 67.510667 -6.558732 0.5931349 -0.6506023 0.4604089 0.1137156 +VERTEX_SE3:QUAT 7357 4.570394 67.051257 -7.385624 -0.6266929 0.4322633 -0.0291704 0.6477295 +VERTEX_SE3:QUAT 7358 4.331971 66.340726 -8.195024 0.6093207 -0.6727234 0.2339732 0.3484653 +VERTEX_SE3:QUAT 7359 4.026047 65.658894 -9.040136 -0.2172158 0.8312209 0.4568080 0.2306848 +VERTEX_SE3:QUAT 7360 4.391865 64.873264 -8.354216 0.3631894 0.1675604 0.8991911 0.1774044 +VERTEX_SE3:QUAT 7361 4.640541 65.684907 -7.633234 -0.4712344 0.5888735 -0.2775776 0.5950772 +VERTEX_SE3:QUAT 7362 4.895591 66.557105 -6.752894 -0.2270972 0.8228428 0.1535339 0.4977791 +VERTEX_SE3:QUAT 7363 5.041131 67.295107 -6.132415 -0.8837429 -0.3280782 -0.3277155 0.0629745 +VERTEX_SE3:QUAT 7364 5.331891 68.114112 -5.685561 -0.3185778 0.5204149 -0.3431918 0.7140699 +VERTEX_SE3:QUAT 7365 5.728122 68.756655 -5.012108 0.3705518 0.8129632 0.0503524 0.4463708 +VERTEX_SE3:QUAT 7366 6.020873 69.573619 -4.492080 0.5534579 -0.6104539 0.4680448 0.3193188 +VERTEX_SE3:QUAT 7367 6.482137 70.334817 -3.860079 -0.3854257 -0.8785366 -0.2168791 0.1805099 +VERTEX_SE3:QUAT 7368 6.804917 71.013610 -3.273244 0.2066018 0.3721897 0.8744600 0.2326161 +VERTEX_SE3:QUAT 7369 7.079416 71.735429 -2.892526 0.4162851 0.0837837 0.6087779 0.6701317 +VERTEX_SE3:QUAT 7370 7.420305 72.482132 -2.469125 0.0996703 0.7958923 -0.5436748 0.2470606 +VERTEX_SE3:QUAT 7371 7.811379 73.145102 -1.903963 0.2294178 -0.9345352 0.1716291 0.2110803 +VERTEX_SE3:QUAT 7372 8.249921 74.071451 -1.456824 0.2870400 0.9478645 -0.0070578 0.1382428 +VERTEX_SE3:QUAT 7373 8.458516 74.968054 -0.921474 0.3705531 0.2893103 -0.4484510 0.7601853 +VERTEX_SE3:QUAT 7374 8.605597 75.693097 -0.373162 0.1585978 -0.1765734 0.9035221 0.3568141 +VERTEX_SE3:QUAT 7375 8.867328 76.549003 0.241865 -0.5596383 -0.7755178 -0.2422294 0.1634075 +VERTEX_SE3:QUAT 7376 9.001329 77.162852 0.791652 -0.4632419 0.7019185 -0.1478891 0.5204289 +VERTEX_SE3:QUAT 7377 8.960192 77.776257 1.584915 0.4264279 0.8270487 -0.1529974 0.3327784 +VERTEX_SE3:QUAT 7378 9.250812 78.531898 2.255871 -0.0206715 0.5110257 -0.5944682 0.6205103 +VERTEX_SE3:QUAT 7379 9.347000 79.139289 3.086153 0.4233844 0.5192388 -0.0054651 0.7423657 +VERTEX_SE3:QUAT 7380 8.971789 78.300462 3.622812 -0.2110914 0.8567418 -0.4175369 0.2170180 +VERTEX_SE3:QUAT 7381 8.821913 77.694952 2.731037 0.5694624 0.4831554 0.0032898 0.6650283 +VERTEX_SE3:QUAT 7382 8.690614 76.987854 2.058929 0.1963073 -0.5497246 0.7200598 0.3752069 +VERTEX_SE3:QUAT 7383 8.301047 76.412650 1.279381 -0.9094495 0.4097172 -0.0254363 0.0662303 +VERTEX_SE3:QUAT 7384 8.061596 75.650958 0.513882 0.2689828 -0.6639435 0.6948953 0.0628317 +VERTEX_SE3:QUAT 7385 7.745612 75.043994 -0.263616 0.4578230 0.4273853 -0.2158644 0.7490944 +VERTEX_SE3:QUAT 7386 7.440030 74.389780 -0.889477 0.6511118 -0.0409585 0.7139549 0.2542523 +VERTEX_SE3:QUAT 7387 7.214201 74.021361 -1.772962 0.4359921 0.7793184 0.3951193 0.2155332 +VERTEX_SE3:QUAT 7388 6.903856 73.531520 -2.422563 0.7444057 -0.2972113 0.5037362 0.3221419 +VERTEX_SE3:QUAT 7389 6.532398 72.976458 -3.054145 0.4829305 -0.3542512 0.3918055 0.6984072 +VERTEX_SE3:QUAT 7390 5.974709 72.458588 -3.944445 -0.1909646 0.8327949 -0.0184320 0.5192739 +VERTEX_SE3:QUAT 7391 5.645132 71.899260 -4.769559 -0.9682328 -0.2379156 0.0295701 0.0710419 +VERTEX_SE3:QUAT 7392 5.271510 71.300511 -5.407435 -0.1752800 0.8985335 -0.2991582 0.2691073 +VERTEX_SE3:QUAT 7393 5.024341 70.861603 -6.296423 -0.4973594 -0.6097699 -0.6051499 0.1208632 +VERTEX_SE3:QUAT 7394 4.735602 70.405404 -7.275523 -0.3737556 0.5672716 -0.1635855 0.7153667 +VERTEX_SE3:QUAT 7395 4.237499 69.989628 -7.929557 0.0907145 0.7350329 -0.5059470 0.4421710 +VERTEX_SE3:QUAT 7396 3.656736 69.716679 -8.652318 0.2944718 0.8142664 0.1912766 0.4622443 +VERTEX_SE3:QUAT 7397 3.277741 69.404429 -9.638278 0.0975142 0.3626774 -0.6670731 0.6434047 +VERTEX_SE3:QUAT 7398 2.815499 69.004561 -10.275586 -0.0759468 0.9351370 -0.1520580 0.3108524 +VERTEX_SE3:QUAT 7399 2.478452 68.591905 -11.052731 0.3320091 0.6651547 0.3475242 0.5714596 +VERTEX_SE3:QUAT 7400 2.263729 67.915824 -10.536532 0.0632046 0.7579657 -0.4405647 0.4768605 +VERTEX_SE3:QUAT 7401 2.798399 68.311174 -9.671937 0.5969574 -0.1992759 0.5153624 0.5816636 +VERTEX_SE3:QUAT 7402 3.288561 68.610706 -8.729421 0.3361055 0.8173664 -0.0102819 0.4678029 +VERTEX_SE3:QUAT 7403 3.677627 69.060201 -7.941966 0.3290442 0.8144290 -0.0164908 0.4776645 +VERTEX_SE3:QUAT 7404 4.044389 69.640601 -7.082315 -0.5506849 0.2105630 -0.7539306 0.2898240 +VERTEX_SE3:QUAT 7405 4.373552 70.187373 -6.325259 -0.0708097 0.4570120 0.1051745 0.8803774 +VERTEX_SE3:QUAT 7406 4.703799 70.469635 -5.424289 0.2458760 -0.8320033 0.4972730 0.0059293 +VERTEX_SE3:QUAT 7407 5.083688 70.959803 -4.408332 -0.0856799 0.5724295 -0.1464760 0.8022021 +VERTEX_SE3:QUAT 7408 5.387423 71.455253 -3.337957 -0.6239546 0.6060127 0.0419325 0.4916003 +VERTEX_SE3:QUAT 7409 5.784195 71.728060 -2.594856 -0.4892401 -0.4788767 -0.7232505 0.0907185 +VERTEX_SE3:QUAT 7410 6.121221 72.362017 -1.883328 -0.4156596 0.1508260 -0.8868110 0.1343312 +VERTEX_SE3:QUAT 7411 6.477386 73.033115 -1.178697 -0.1015398 0.3944431 -0.5885720 0.6983461 +VERTEX_SE3:QUAT 7412 7.033950 73.514988 -0.375051 -0.0848065 0.8568889 -0.1663789 0.4804865 +VERTEX_SE3:QUAT 7413 7.473344 74.155209 0.204518 -0.9516545 -0.1984637 -0.0828332 0.2193275 +VERTEX_SE3:QUAT 7414 8.097867 74.584666 0.930428 0.5874306 0.7285633 0.2274662 0.2690351 +VERTEX_SE3:QUAT 7415 8.520827 75.372109 1.554389 -0.4733086 0.0412243 -0.8360473 0.2744165 +VERTEX_SE3:QUAT 7416 8.835236 75.776785 2.089356 -0.8587940 -0.4842206 0.0108579 0.1669892 +VERTEX_SE3:QUAT 7417 9.337105 76.496894 2.660955 0.2269298 0.6757150 0.3576864 0.6033013 +VERTEX_SE3:QUAT 7418 9.674084 77.141584 3.423250 -0.8675581 0.2021089 -0.2887119 0.3509137 +VERTEX_SE3:QUAT 7419 10.026855 77.805211 4.301325 -0.3364907 0.8668734 0.2800089 0.2385362 +VERTEX_SE3:QUAT 7420 10.228579 76.897343 4.702693 -0.3875124 0.5493898 -0.1297734 0.7288099 +VERTEX_SE3:QUAT 7421 9.789758 76.533015 3.811616 0.3969707 0.5417619 0.1085698 0.7328853 +VERTEX_SE3:QUAT 7422 9.570909 75.989179 2.709581 0.6038111 0.7329316 -0.2440010 0.1966897 +VERTEX_SE3:QUAT 7423 9.226534 75.341471 1.987883 -0.3869592 0.7538910 -0.1760650 0.5009112 +VERTEX_SE3:QUAT 7424 9.056688 74.834891 1.041938 -0.7069277 -0.0804857 -0.4445577 0.5441909 +VERTEX_SE3:QUAT 7425 8.873474 74.375747 0.130309 -0.2655834 0.8828717 0.3861575 0.0297558 +VERTEX_SE3:QUAT 7426 8.564078 73.834152 -0.726861 -0.2269035 0.3459004 0.2948148 0.8613663 +VERTEX_SE3:QUAT 7427 8.199897 73.252301 -1.467079 -0.3801612 0.5402877 0.0460709 0.7492957 +VERTEX_SE3:QUAT 7428 8.115883 72.816815 -2.235875 -0.9906671 0.0378438 -0.0736277 0.1082846 +VERTEX_SE3:QUAT 7429 8.008755 72.205613 -3.143837 0.5433012 0.6637112 -0.0650935 0.5099746 +VERTEX_SE3:QUAT 7430 7.741640 71.639228 -4.006369 0.5363243 0.5146482 0.3016577 0.5970729 +VERTEX_SE3:QUAT 7431 7.410624 70.954150 -4.913259 -0.4596169 0.3817634 -0.7988568 0.0695473 +VERTEX_SE3:QUAT 7432 7.143836 70.478098 -5.647326 0.4177056 0.1625476 0.7637293 0.4645621 +VERTEX_SE3:QUAT 7433 6.893784 70.140313 -6.709807 -0.2707890 0.6351158 -0.4163321 0.5915816 +VERTEX_SE3:QUAT 7434 6.684735 69.492853 -7.522076 -0.6233905 -0.0762825 -0.1491384 0.7637559 +VERTEX_SE3:QUAT 7435 6.524882 68.838010 -8.439215 -0.1822910 0.6599098 0.7021891 0.1954983 +VERTEX_SE3:QUAT 7436 6.244825 68.143427 -9.160779 -0.3240004 0.7347176 -0.2275982 0.5508293 +VERTEX_SE3:QUAT 7437 5.959389 67.581954 -10.022848 -0.2372996 0.6347399 -0.0982460 0.7287948 +VERTEX_SE3:QUAT 7438 5.811026 66.976094 -10.836574 -0.3421850 0.3970010 0.4554316 0.7196400 +VERTEX_SE3:QUAT 7439 5.728346 66.376878 -11.765792 0.7595290 0.0417551 0.6454863 0.0686996 +VERTEX_SE3:QUAT 7440 6.166929 65.515730 -11.251972 -0.2126783 0.4464148 -0.4677447 0.7325958 +VERTEX_SE3:QUAT 7441 6.393411 65.927449 -10.350715 0.3720264 0.2339781 0.8900273 0.1212513 +VERTEX_SE3:QUAT 7442 6.643102 66.498671 -9.453095 -0.2994448 -0.3130957 -0.7723369 0.4645424 +VERTEX_SE3:QUAT 7443 6.849337 67.062888 -8.658928 0.8123205 -0.3384550 0.2424694 0.4084021 +VERTEX_SE3:QUAT 7444 7.082463 67.767448 -8.026858 -0.4433820 -0.8819865 0.0060538 0.1596106 +VERTEX_SE3:QUAT 7445 7.371064 68.464786 -7.303751 0.6408220 0.6230536 0.0006700 0.4484985 +VERTEX_SE3:QUAT 7446 7.879436 69.277312 -6.644598 0.1608318 0.7044224 0.5897842 0.3606616 +VERTEX_SE3:QUAT 7447 8.113326 70.025672 -5.981253 0.0978584 0.7514670 0.3834647 0.5278976 +VERTEX_SE3:QUAT 7448 8.534198 70.430829 -5.415279 -0.0281861 0.9826596 0.1462614 0.1104228 +VERTEX_SE3:QUAT 7449 8.953741 71.166858 -4.625397 -0.5808193 -0.7789953 -0.2227544 0.0787134 +VERTEX_SE3:QUAT 7450 9.425228 71.694814 -3.981455 0.5565840 0.6200978 -0.4306000 0.3468092 +VERTEX_SE3:QUAT 7451 10.026299 72.367563 -3.442659 -0.9132992 0.2943487 -0.0271126 0.2801933 +VERTEX_SE3:QUAT 7452 10.679954 73.093651 -2.906533 -0.3388848 0.4725159 -0.7588107 0.2934144 +VERTEX_SE3:QUAT 7453 11.067507 73.711492 -2.387918 0.1600023 0.5075312 0.4676532 0.7057704 +VERTEX_SE3:QUAT 7454 11.732107 74.529463 -1.713061 -0.4757556 0.7283340 -0.4923839 0.0272815 +VERTEX_SE3:QUAT 7455 12.351270 75.136297 -1.255723 0.4860093 0.6489906 -0.5353536 0.2366489 +VERTEX_SE3:QUAT 7456 12.845313 75.863255 -0.755916 0.7495167 -0.4344497 0.4960586 0.0583438 +VERTEX_SE3:QUAT 7457 13.318047 76.453580 -0.266095 0.0831160 0.6506948 0.6535245 0.3776158 +VERTEX_SE3:QUAT 7458 13.763060 77.050006 0.273913 -0.7739947 -0.5291980 0.3465232 0.0283431 +VERTEX_SE3:QUAT 7459 14.410961 77.812029 0.681800 -0.7986607 0.5153671 0.0213771 0.3099692 +VERTEX_SE3:QUAT 7460 14.657637 76.995803 1.351806 -0.3306446 0.9025592 -0.2674429 0.0673450 +VERTEX_SE3:QUAT 7461 14.068579 76.395764 0.808436 0.3340019 0.4944876 0.1445299 0.7893262 +VERTEX_SE3:QUAT 7462 13.333810 75.648658 0.351199 0.2613719 0.6192309 0.7141249 0.1956104 +VERTEX_SE3:QUAT 7463 12.825936 74.818093 -0.028184 -0.7866535 -0.4472336 -0.3272756 0.2721197 +VERTEX_SE3:QUAT 7464 12.224360 74.174697 -0.529205 0.1233206 0.6169400 0.7367662 0.2476947 +VERTEX_SE3:QUAT 7465 11.568270 73.400199 -1.017652 -0.0247987 0.7758887 0.0072639 0.6303403 +VERTEX_SE3:QUAT 7466 10.847876 72.815405 -1.536592 -0.9487998 -0.0240321 -0.2376800 0.2066629 +VERTEX_SE3:QUAT 7467 10.308003 72.083909 -1.858779 0.0702613 0.7695614 -0.1376911 0.6195803 +VERTEX_SE3:QUAT 7468 9.833711 71.442572 -2.342505 0.2126362 0.9421634 -0.2321371 0.1150055 +VERTEX_SE3:QUAT 7469 9.276274 70.690504 -2.612399 0.7898980 0.3673560 -0.4779586 0.1125448 +VERTEX_SE3:QUAT 7470 8.517076 70.101980 -2.673353 0.6729845 0.0004253 0.6415718 0.3680725 +VERTEX_SE3:QUAT 7471 7.764085 69.567093 -3.051265 0.4750247 0.4422593 -0.0459840 0.7593706 +VERTEX_SE3:QUAT 7472 6.957244 68.908620 -3.362225 -0.7639847 -0.5420081 0.0541292 0.3458679 +VERTEX_SE3:QUAT 7473 6.158508 68.234033 -3.804208 0.2999887 0.7523694 -0.3206238 0.4910677 +VERTEX_SE3:QUAT 7474 5.285994 68.079165 -4.222409 0.1189097 -0.9616191 0.1090554 0.2219372 +VERTEX_SE3:QUAT 7475 4.612868 67.493423 -4.595988 0.6302773 -0.5037679 0.3994998 0.4351648 +VERTEX_SE3:QUAT 7476 3.839173 66.976767 -4.976152 0.6226359 0.6562250 0.4220208 0.0599305 +VERTEX_SE3:QUAT 7477 3.157091 66.531924 -5.583144 0.7547148 -0.1050740 0.0681544 0.6439876 +VERTEX_SE3:QUAT 7478 2.455472 65.996904 -5.768505 0.7723255 -0.2076235 0.1923684 0.5686829 +VERTEX_SE3:QUAT 7479 1.761225 65.472561 -6.166419 -0.7524831 0.2700644 -0.5949400 0.0829506 +VERTEX_SE3:QUAT 7480 2.149997 64.621975 -6.035872 0.4771049 0.5871161 -0.5114852 0.4074906 +VERTEX_SE3:QUAT 7481 2.902788 65.024797 -5.686816 0.3048162 -0.9154016 0.1922590 0.1793417 +VERTEX_SE3:QUAT 7482 3.595732 65.628249 -5.385291 -0.9618887 0.2031427 0.1723838 0.0615384 +VERTEX_SE3:QUAT 7483 4.296710 66.073396 -4.909764 0.4170917 0.8899535 -0.1439874 0.1152599 +VERTEX_SE3:QUAT 7484 5.045089 66.713803 -4.494453 0.5990083 0.7766508 0.0906815 0.1725670 +VERTEX_SE3:QUAT 7485 5.709651 67.041100 -4.065314 0.5866681 -0.4130969 0.5452866 0.4333982 +VERTEX_SE3:QUAT 7486 6.492884 67.580302 -3.755426 0.5969600 0.5014047 0.5772158 0.2430103 +VERTEX_SE3:QUAT 7487 7.252177 67.917628 -3.635912 0.5568982 -0.6767300 0.2497583 0.4117301 +VERTEX_SE3:QUAT 7488 7.912109 68.444151 -3.166301 0.0919439 0.8231146 0.4354522 0.3527181 +VERTEX_SE3:QUAT 7489 8.761254 69.031489 -2.790473 0.0663444 0.8991922 0.4324349 0.0072058 +VERTEX_SE3:QUAT 7490 9.568430 69.647549 -2.410366 0.0569400 0.8155320 -0.1128600 0.5647371 +VERTEX_SE3:QUAT 7491 10.553917 70.086799 -1.818551 -0.2371671 -0.8394578 0.4879792 0.0306385 +VERTEX_SE3:QUAT 7492 11.323534 70.574187 -1.378854 0.2749772 0.8919195 -0.1408386 0.3301994 +VERTEX_SE3:QUAT 7493 12.125894 71.142775 -1.054177 -0.5799482 0.6228995 -0.1259762 0.5096924 +VERTEX_SE3:QUAT 7494 12.894068 71.762439 -0.638188 -0.2344009 0.8817838 0.0202448 0.4087833 +VERTEX_SE3:QUAT 7495 13.663977 72.358865 -0.120692 0.1123812 -0.8921748 -0.2192755 0.3785668 +VERTEX_SE3:QUAT 7496 14.258102 72.878650 0.325477 -0.9229598 -0.3043978 -0.1575178 0.1751435 +VERTEX_SE3:QUAT 7497 14.919164 73.588247 0.447594 -0.9451332 0.0074959 -0.3265857 0.0029584 +VERTEX_SE3:QUAT 7498 15.575180 74.203635 0.545966 0.2172007 -0.5838953 0.7772617 0.0880590 +VERTEX_SE3:QUAT 7499 16.298958 75.001174 0.770408 -0.6738540 0.4092704 -0.0737612 0.6107191 +VERTEX_SE3:QUAT 7500 17.010354 74.236943 1.127977 -0.8334667 -0.2853922 -0.4189738 0.2198760 +VERTEX_SE3:QUAT 7501 16.263666 73.522952 1.023886 0.2526137 0.8192614 -0.1927096 0.4773470 +VERTEX_SE3:QUAT 7502 15.533558 72.692324 0.788761 -0.0521801 0.7123022 0.5363824 0.4496628 +VERTEX_SE3:QUAT 7503 14.693167 71.985762 0.637891 0.0346594 0.8791916 0.2221659 0.4200753 +VERTEX_SE3:QUAT 7504 13.959129 71.326390 0.400663 -0.2307947 0.6461286 -0.4475959 0.5735064 +VERTEX_SE3:QUAT 7505 13.383230 70.569808 0.316639 0.5120864 -0.7832850 0.2037604 0.2876000 +VERTEX_SE3:QUAT 7506 12.703539 69.825213 0.060075 0.8215285 0.2379634 0.4772128 0.2018224 +VERTEX_SE3:QUAT 7507 11.917567 69.180100 -0.069316 0.5715625 0.3731001 -0.0592359 0.7284255 +VERTEX_SE3:QUAT 7508 11.294438 68.465460 -0.196032 0.8816735 0.2336952 0.1616188 0.3767198 +VERTEX_SE3:QUAT 7509 10.646378 67.593537 -0.295447 -0.3702311 -0.8014345 0.4177234 0.2147994 +VERTEX_SE3:QUAT 7510 9.816079 67.058841 -0.222863 0.7659154 0.5028722 -0.3468185 0.2005246 +VERTEX_SE3:QUAT 7511 8.905038 66.400903 -0.369512 0.6013284 0.3525698 0.6701745 0.2548820 +VERTEX_SE3:QUAT 7512 8.055839 65.834882 -0.408459 0.5300892 0.7293568 -0.3981084 0.1689788 +VERTEX_SE3:QUAT 7513 7.510599 65.284220 -0.401734 0.8902265 -0.4358777 0.0584207 0.1187199 +VERTEX_SE3:QUAT 7514 6.773248 64.569276 -0.463917 0.0516184 -0.8192234 0.5178794 0.2408518 +VERTEX_SE3:QUAT 7515 5.934801 64.133444 -0.528928 0.4208758 -0.8658851 -0.0668293 0.2619930 +VERTEX_SE3:QUAT 7516 5.288880 63.601380 -0.344616 0.5342403 0.5589603 -0.5881918 0.2370256 +VERTEX_SE3:QUAT 7517 4.576350 62.937079 -0.257892 0.3046971 0.7636283 -0.5427429 0.1716437 +VERTEX_SE3:QUAT 7518 3.750334 62.553067 -0.280136 0.7856794 -0.3108644 0.3109325 0.4351920 +VERTEX_SE3:QUAT 7519 2.856156 62.052574 -0.195463 0.5316880 0.4065660 -0.7177849 0.1918249 +VERTEX_SE3:QUAT 7520 3.414889 61.495954 0.202330 -0.3323533 0.8426838 0.4121379 0.0978146 +VERTEX_SE3:QUAT 7521 4.150132 62.019311 0.212836 0.2965242 0.8206120 -0.3696193 0.3194542 +VERTEX_SE3:QUAT 7522 5.154978 62.382774 0.179332 -0.3516899 0.9065610 -0.2051253 0.1112875 +VERTEX_SE3:QUAT 7523 6.135982 62.937875 0.146051 -0.8579110 0.2373698 -0.2718632 0.3656974 +VERTEX_SE3:QUAT 7524 7.019787 63.402661 0.079656 0.2425890 0.8321288 0.4810509 0.1315380 +VERTEX_SE3:QUAT 7525 7.711128 63.804434 0.176569 0.1117083 0.7800932 0.5376238 0.2998940 +VERTEX_SE3:QUAT 7526 8.481412 64.266289 0.054480 -0.1339040 0.9438594 -0.2736710 0.1276843 +VERTEX_SE3:QUAT 7527 9.436182 64.875321 0.078294 -0.8736885 0.0903744 0.3538603 0.3213780 +VERTEX_SE3:QUAT 7528 10.328452 65.169380 -0.028029 -0.7170996 0.6631016 -0.0237057 0.2133132 +VERTEX_SE3:QUAT 7529 11.230125 65.696243 -0.291621 0.8369874 0.1946200 0.4739939 0.1921065 +VERTEX_SE3:QUAT 7530 12.148133 66.018157 -0.422349 -0.9091628 0.2422342 0.3071226 0.1429032 +VERTEX_SE3:QUAT 7531 12.908458 66.450964 -0.457393 0.6502784 -0.3503752 0.6619844 0.1270897 +VERTEX_SE3:QUAT 7532 13.718859 66.835232 -0.423691 0.7428187 0.2851654 0.1257221 0.5925328 +VERTEX_SE3:QUAT 7533 14.503478 67.433046 -0.570352 0.2771815 -0.9170763 -0.2865722 0.0042212 +VERTEX_SE3:QUAT 7534 15.368054 67.920724 -0.433633 0.5363804 0.4023519 0.2654541 0.6927793 +VERTEX_SE3:QUAT 7535 16.234596 68.338710 -0.433991 -0.0857988 -0.7602854 0.4509225 0.4596451 +VERTEX_SE3:QUAT 7536 17.112617 68.834054 -0.725615 0.6007796 -0.0049719 -0.1229173 0.7898927 +VERTEX_SE3:QUAT 7537 18.139237 69.228981 -0.755502 0.6039245 -0.3929191 0.6780145 0.1455547 +VERTEX_SE3:QUAT 7538 19.191063 69.594398 -0.947645 0.7760188 0.1990819 -0.3576692 0.4798269 +VERTEX_SE3:QUAT 7539 20.204276 69.968936 -1.064308 0.1422840 -0.7521844 -0.1510201 0.6254333 +VERTEX_SE3:QUAT 7540 20.744004 69.157280 -0.783750 0.3303271 0.6645189 0.4320108 0.5125088 +VERTEX_SE3:QUAT 7541 19.713995 68.727542 -0.374504 0.8659464 0.4637902 -0.0290704 0.1849066 +VERTEX_SE3:QUAT 7542 18.866199 68.104390 -0.286441 0.8323015 0.3700943 -0.1802636 0.3712269 +VERTEX_SE3:QUAT 7543 18.006602 67.412647 -0.287047 -0.7850515 0.5183377 0.2099230 0.2663692 +VERTEX_SE3:QUAT 7544 17.137932 66.695681 -0.171338 0.1649112 0.8491241 -0.3336247 0.3748162 +VERTEX_SE3:QUAT 7545 16.452455 66.165909 0.067759 0.5869261 0.3265330 -0.3751679 0.6388608 +VERTEX_SE3:QUAT 7546 15.681365 65.759667 0.346382 -0.9474444 -0.0172413 0.2628005 0.1816252 +VERTEX_SE3:QUAT 7547 14.930000 65.191439 0.511137 0.1916280 0.7556554 0.1929463 0.5958484 +VERTEX_SE3:QUAT 7548 14.162618 64.581849 0.791242 0.2824638 -0.7526092 -0.5902920 0.0731366 +VERTEX_SE3:QUAT 7549 13.338092 63.834099 0.851238 0.1038662 0.9401937 -0.2954459 0.1340127 +VERTEX_SE3:QUAT 7550 12.572849 63.321886 1.155723 0.7869526 -0.3985290 -0.4631174 0.0860381 +VERTEX_SE3:QUAT 7551 11.770479 62.588053 1.241526 0.7107452 -0.1459553 0.0186114 0.6878894 +VERTEX_SE3:QUAT 7552 11.136348 61.920036 1.326400 -0.8888429 0.1805017 -0.4060627 0.1117609 +VERTEX_SE3:QUAT 7553 10.565078 61.400739 1.386068 0.7912823 -0.3328673 0.0498401 0.5104778 +VERTEX_SE3:QUAT 7554 9.880894 60.758464 1.505814 0.3559308 -0.9152822 -0.1572979 0.1040626 +VERTEX_SE3:QUAT 7555 9.253073 59.724967 1.728718 -0.2717330 -0.8675141 0.3158722 0.2716711 +VERTEX_SE3:QUAT 7556 8.536180 59.157078 1.932746 -0.5148478 0.6670014 0.5097655 0.1737240 +VERTEX_SE3:QUAT 7557 7.815097 58.505813 2.098106 -0.5789375 -0.5662198 0.5077829 0.2939099 +VERTEX_SE3:QUAT 7558 7.189230 57.963434 2.254338 -0.0150036 -0.8975338 0.2479465 0.3643220 +VERTEX_SE3:QUAT 7559 6.644698 57.064170 2.544003 -0.1047664 0.8816543 0.0894138 0.4513478 +VERTEX_SE3:QUAT 7560 7.520186 56.624104 2.606739 0.8855331 -0.1913299 0.0841640 0.4148980 +VERTEX_SE3:QUAT 7561 8.154860 57.257339 2.520734 -0.7335004 -0.5241208 0.2302165 0.3664354 +VERTEX_SE3:QUAT 7562 8.622956 58.229142 2.232719 -0.3892777 0.8215266 -0.0264000 0.4157644 +VERTEX_SE3:QUAT 7563 9.346217 58.923834 2.215516 -0.1712063 -0.9772820 0.1079201 0.0629413 +VERTEX_SE3:QUAT 7564 9.784039 59.796126 2.052789 0.7426251 -0.2666784 0.2308964 0.5692780 +VERTEX_SE3:QUAT 7565 10.139831 60.576964 1.911442 -0.4381421 0.7466863 -0.4759713 0.1547330 +VERTEX_SE3:QUAT 7566 10.687103 61.278466 1.813314 -0.7480745 -0.5746798 0.2405987 0.2285604 +VERTEX_SE3:QUAT 7567 11.289346 62.038890 1.812669 0.0816801 0.8368346 -0.4865986 0.2371878 +VERTEX_SE3:QUAT 7568 11.997683 62.716842 1.675715 -0.0861223 -0.7919908 -0.4588182 0.3934710 +VERTEX_SE3:QUAT 7569 12.452645 63.512968 1.678056 0.9163856 -0.3752288 -0.0305214 0.1360483 +VERTEX_SE3:QUAT 7570 13.199640 64.267417 1.689117 0.0629956 -0.9844333 -0.0391775 0.1593353 +VERTEX_SE3:QUAT 7571 14.001150 64.927379 1.634866 0.7344214 -0.4410093 0.3924154 0.3348824 +VERTEX_SE3:QUAT 7572 14.914910 65.532400 1.508463 0.6002591 0.6214214 -0.4921576 0.1063264 +VERTEX_SE3:QUAT 7573 15.775595 66.145666 1.539131 -0.5641053 0.6220157 0.0620069 0.5394783 +VERTEX_SE3:QUAT 7574 16.544886 66.845855 1.586676 -0.5692956 -0.7679145 -0.1908344 0.2231413 +VERTEX_SE3:QUAT 7575 17.096813 67.570213 1.558998 0.4801052 -0.6174321 0.5948158 0.1856629 +VERTEX_SE3:QUAT 7576 17.744721 68.055270 1.263218 -0.3004086 -0.7866100 0.1005347 0.5299926 +VERTEX_SE3:QUAT 7577 18.501341 68.840833 1.255078 0.3054738 0.7638674 0.2694550 0.5005860 +VERTEX_SE3:QUAT 7578 19.276428 69.780387 1.040690 0.5606927 0.5332292 0.6324297 0.0363737 +VERTEX_SE3:QUAT 7579 19.839051 70.365987 0.990110 0.6913260 0.4723233 0.5202913 0.1681549 +VERTEX_SE3:QUAT 7580 20.520944 69.850500 1.045862 -0.5354165 -0.7216200 -0.2911700 0.3283502 +VERTEX_SE3:QUAT 7581 20.140939 68.949704 1.157548 -0.8187951 0.4222797 0.0436836 0.3864534 +VERTEX_SE3:QUAT 7582 19.399424 68.136260 1.159678 0.6064074 0.7311761 -0.2926530 0.1095710 +VERTEX_SE3:QUAT 7583 18.608144 67.573494 1.224327 0.5826207 -0.7968228 -0.1565913 0.0332515 +VERTEX_SE3:QUAT 7584 17.859130 66.916726 1.306100 0.2258894 0.8381719 -0.4240546 0.2581077 +VERTEX_SE3:QUAT 7585 16.999459 66.092473 1.356503 -0.8820975 -0.3867011 0.0117847 0.2687514 +VERTEX_SE3:QUAT 7586 16.417991 65.451783 1.517063 -0.0803804 -0.9284542 0.2034583 0.3001942 +VERTEX_SE3:QUAT 7587 15.962336 64.659647 1.623043 -0.4351345 -0.7316480 -0.5157773 0.0965553 +VERTEX_SE3:QUAT 7588 15.343839 63.957780 1.681797 -0.7265259 -0.3113295 0.5137765 0.3335681 +VERTEX_SE3:QUAT 7589 14.830124 62.970939 1.603917 -0.8077119 0.3344419 0.4372555 0.2110872 +VERTEX_SE3:QUAT 7590 14.378539 62.181240 1.508368 0.9079239 -0.2196375 0.0691504 0.3502167 +VERTEX_SE3:QUAT 7591 13.929033 61.295567 1.396900 0.9538426 0.0171640 -0.1628238 0.2517501 +VERTEX_SE3:QUAT 7592 13.146628 60.671197 1.218826 -0.2047824 0.7789389 -0.5087663 0.3040973 +VERTEX_SE3:QUAT 7593 12.388314 60.014927 1.201394 -0.7720153 -0.0198228 -0.3951548 0.4974455 +VERTEX_SE3:QUAT 7594 11.828263 59.150610 1.049343 -0.0075214 -0.8663253 -0.1548949 0.4747963 +VERTEX_SE3:QUAT 7595 11.208003 58.547722 1.008351 -0.7733114 0.2761168 0.2089948 0.5311028 +VERTEX_SE3:QUAT 7596 10.688648 57.717595 0.889083 -0.4942354 -0.7602053 0.0563418 0.4179054 +VERTEX_SE3:QUAT 7597 10.155230 56.956556 0.840547 0.5423779 -0.8016680 -0.1449177 0.2053131 +VERTEX_SE3:QUAT 7598 9.667436 56.176117 0.611771 0.3233567 0.8798322 -0.3464704 0.0359726 +VERTEX_SE3:QUAT 7599 8.912124 55.457524 0.609719 0.8557443 -0.2542257 -0.0134072 0.4504346 +VERTEX_SE3:QUAT 7600 21.516051 69.651852 1.806949 -0.9064208 -0.4163185 -0.0590269 0.0399503 +VERTEX_SE3:QUAT 7601 20.832226 68.881948 1.471723 -0.6866866 -0.4205925 -0.5811168 0.1177572 +VERTEX_SE3:QUAT 7602 20.004841 68.379423 1.239248 0.0718371 -0.9038796 -0.0973262 0.4103275 +VERTEX_SE3:QUAT 7603 19.317661 67.662364 1.067748 -0.8148511 -0.3222921 0.4383804 0.1999203 +VERTEX_SE3:QUAT 7604 18.585192 66.939440 0.838485 0.6723956 0.3192905 0.6614165 0.0920107 +VERTEX_SE3:QUAT 7605 18.075825 66.187844 0.892227 0.7571603 -0.6396031 -0.0749208 0.1095586 +VERTEX_SE3:QUAT 7606 17.501671 65.479093 0.865764 0.6771593 0.2159423 0.0900335 0.6976519 +VERTEX_SE3:QUAT 7607 16.945279 64.681134 0.965524 0.4478133 -0.8764652 0.0183318 0.1758862 +VERTEX_SE3:QUAT 7608 16.212784 63.736298 0.993430 -0.3993653 0.6092467 0.5763430 0.3703440 +VERTEX_SE3:QUAT 7609 15.645960 62.998250 0.798774 -0.2840261 0.8680393 0.2420898 0.3274591 +VERTEX_SE3:QUAT 7610 14.832031 62.183905 0.988265 -0.3851284 0.5602652 -0.6292541 0.3765877 +VERTEX_SE3:QUAT 7611 14.283758 61.376376 0.931032 -0.6968559 -0.0202710 -0.6760852 0.2385157 +VERTEX_SE3:QUAT 7612 13.712147 60.786502 0.943631 -0.7751619 -0.3414313 0.5078190 0.1570620 +VERTEX_SE3:QUAT 7613 13.065339 60.179420 1.150882 -0.0051232 -0.9282139 0.1351109 0.3466088 +VERTEX_SE3:QUAT 7614 12.483045 59.575637 1.252437 0.1570154 0.8688111 0.1535690 0.4437680 +VERTEX_SE3:QUAT 7615 11.893210 58.940865 1.213593 -0.5572669 0.6963510 -0.0092248 0.4521768 +VERTEX_SE3:QUAT 7616 11.199137 58.112604 1.239558 0.8929038 -0.2477480 -0.1198134 0.3563544 +VERTEX_SE3:QUAT 7617 10.573624 57.470396 1.435340 0.4939250 0.7476278 -0.4010352 0.1904245 +VERTEX_SE3:QUAT 7618 9.916978 56.912596 1.698836 -0.4981493 -0.5445745 0.3914787 0.5495729 +VERTEX_SE3:QUAT 7619 9.114546 56.244969 2.008289 -0.3434865 0.8654933 0.1711910 0.3219192 +VERTEX_SE3:QUAT 7620 8.428995 57.120996 1.956289 -0.3325352 0.8812438 0.2387382 0.2362916 +VERTEX_SE3:QUAT 7621 9.347362 57.864858 1.881123 -0.2216900 -0.9115940 -0.1278482 0.3217215 +VERTEX_SE3:QUAT 7622 10.204559 58.397598 1.661820 -0.7477713 -0.4589555 0.4791286 0.0251744 +VERTEX_SE3:QUAT 7623 10.935807 59.046704 1.722190 -0.8332434 -0.1422996 -0.3555363 0.3988111 +VERTEX_SE3:QUAT 7624 11.712542 59.511591 1.771081 -0.0261929 -0.8310738 -0.4339818 0.3468287 +VERTEX_SE3:QUAT 7625 12.606607 60.103717 1.790467 0.8087395 0.3838589 0.2123091 0.3918133 +VERTEX_SE3:QUAT 7626 13.581420 60.553059 1.883047 0.1263172 0.7578390 -0.0513629 0.6380328 +VERTEX_SE3:QUAT 7627 14.254003 61.125397 1.696186 0.0639033 0.7627378 -0.5638030 0.3102798 +VERTEX_SE3:QUAT 7628 14.975854 61.699855 1.650944 0.2277105 -0.7528022 0.6002596 0.1453448 +VERTEX_SE3:QUAT 7629 15.731423 62.119834 1.602218 0.6291627 0.6083155 -0.3912967 0.2845933 +VERTEX_SE3:QUAT 7630 16.483677 62.793820 1.480500 -0.3977075 0.6858482 -0.5175402 0.3218589 +VERTEX_SE3:QUAT 7631 17.047967 63.614195 1.465015 -0.5345268 0.7789383 0.0676353 0.3208763 +VERTEX_SE3:QUAT 7632 17.730899 64.357549 1.496900 0.5053616 0.6498027 -0.1191902 0.5551214 +VERTEX_SE3:QUAT 7633 18.335930 65.194692 1.388777 0.8491361 0.4550080 0.2422052 0.1152051 +VERTEX_SE3:QUAT 7634 18.989543 66.073337 1.465754 0.7493151 -0.4874015 -0.1113417 0.4342460 +VERTEX_SE3:QUAT 7635 19.397929 66.998221 1.420916 -0.6262273 -0.7629656 -0.1062696 0.1201234 +VERTEX_SE3:QUAT 7636 20.030560 67.698536 1.438378 -0.7920627 0.4856600 0.2260671 0.2926852 +VERTEX_SE3:QUAT 7637 20.744861 68.689717 1.457598 -0.9170965 0.1239791 -0.3657627 0.0988979 +VERTEX_SE3:QUAT 7638 21.346436 69.402531 1.709306 -0.9202639 0.2781388 0.2587179 0.0939055 +VERTEX_SE3:QUAT 7639 21.947767 70.123037 2.067928 0.5874958 -0.4658911 0.4255345 0.5066700 +VERTEX_SE3:QUAT 7640 21.372686 70.751153 1.676025 -0.1876797 -0.9631434 0.1919941 0.0164105 +VERTEX_SE3:QUAT 7641 20.787247 69.972935 1.342614 -0.8254019 0.0876672 -0.3051761 0.4667909 +VERTEX_SE3:QUAT 7642 19.991279 69.309286 0.913298 -0.8825167 0.1556611 -0.4171901 0.1512823 +VERTEX_SE3:QUAT 7643 19.351935 68.665733 0.490796 0.7148573 0.1860812 0.0971291 0.6670224 +VERTEX_SE3:QUAT 7644 18.652577 68.083989 0.275349 -0.8811950 0.3994686 -0.2487986 0.0449377 +VERTEX_SE3:QUAT 7645 17.996789 67.281988 -0.099978 -0.4097820 0.4483912 -0.4407579 0.6608756 +VERTEX_SE3:QUAT 7646 17.277252 66.850733 -0.473463 0.0244634 -0.8688731 0.4641242 0.1704398 +VERTEX_SE3:QUAT 7647 16.654913 66.267248 -0.935305 -0.5521556 -0.2946284 -0.6352239 0.4525582 +VERTEX_SE3:QUAT 7648 16.047174 65.731640 -1.475441 0.0409086 0.9697457 0.1673494 0.1729565 +VERTEX_SE3:QUAT 7649 15.386035 65.196171 -1.948633 0.2349816 0.8267607 -0.4527496 0.2372091 +VERTEX_SE3:QUAT 7650 14.787308 64.486954 -2.442291 0.5144781 -0.7330374 0.0347921 0.4435741 +VERTEX_SE3:QUAT 7651 14.069897 63.789279 -2.791559 0.5391227 0.3801258 0.0736631 0.7479471 +VERTEX_SE3:QUAT 7652 13.492845 62.981781 -3.003358 -0.4389183 -0.8827539 -0.1473014 0.0799915 +VERTEX_SE3:QUAT 7653 12.587045 62.298584 -3.277458 -0.2003805 0.8364583 -0.2622175 0.4375238 +VERTEX_SE3:QUAT 7654 11.833661 61.541746 -3.484223 0.8544517 0.2598950 -0.4443914 0.0698791 +VERTEX_SE3:QUAT 7655 11.003344 61.114042 -3.676275 0.7290983 -0.2673644 0.6280447 0.0499187 +VERTEX_SE3:QUAT 7656 10.190756 60.484829 -3.799476 0.6591019 0.1539225 -0.0796428 0.7318125 +VERTEX_SE3:QUAT 7657 9.545971 59.911421 -3.837669 0.6211827 0.7724119 -0.0926350 0.0945025 +VERTEX_SE3:QUAT 7658 8.844346 59.417525 -4.201864 0.5279221 -0.4188023 0.1416685 0.7251434 +VERTEX_SE3:QUAT 7659 8.004799 58.907204 -4.381265 0.7580209 0.2661724 -0.0067154 0.5954086 +VERTEX_SE3:QUAT 7660 7.679524 59.747704 -4.909153 -0.9092216 -0.3223354 0.0282687 0.2619482 +VERTEX_SE3:QUAT 7661 8.407946 60.462041 -4.708638 0.1290299 0.6842864 -0.6377543 0.3292003 +VERTEX_SE3:QUAT 7662 9.152865 61.023436 -4.622248 0.7378039 0.3577705 -0.5453283 0.1739616 +VERTEX_SE3:QUAT 7663 9.877791 61.832304 -4.484543 -0.0524853 0.8419042 -0.0226020 0.5365928 +VERTEX_SE3:QUAT 7664 10.592674 62.338855 -4.240852 0.0436596 -0.8796751 0.3064068 0.3610822 +VERTEX_SE3:QUAT 7665 11.463957 62.894921 -4.284250 0.4012529 0.4485286 -0.6133825 0.5114491 +VERTEX_SE3:QUAT 7666 12.494940 63.394830 -4.146912 -0.4059247 0.6855668 -0.5234098 0.3021019 +VERTEX_SE3:QUAT 7667 13.501937 63.937590 -4.024086 0.7120622 0.3691382 -0.3043249 0.5138976 +VERTEX_SE3:QUAT 7668 14.446987 64.246470 -3.968501 0.5594343 -0.7880077 -0.0774578 0.2451070 +VERTEX_SE3:QUAT 7669 15.460818 64.604871 -3.964667 0.7568308 0.5512409 -0.2871324 0.2022265 +VERTEX_SE3:QUAT 7670 16.403593 65.098882 -3.930024 -0.3094858 -0.7666697 0.5563617 0.0830531 +VERTEX_SE3:QUAT 7671 17.346915 65.668135 -3.901059 -0.1294943 0.8284491 -0.1270493 0.5298696 +VERTEX_SE3:QUAT 7672 18.093102 66.218819 -3.727770 -0.8478764 0.4892029 0.1841556 0.0887286 +VERTEX_SE3:QUAT 7673 18.825067 66.630330 -3.549899 -0.6949236 -0.4811791 -0.4210308 0.3290606 +VERTEX_SE3:QUAT 7674 19.589534 67.114418 -3.278715 0.8046247 0.1912309 -0.5369176 0.1665214 +VERTEX_SE3:QUAT 7675 20.593968 67.454515 -3.106293 -0.8047476 -0.4481619 -0.2432326 0.3039245 +VERTEX_SE3:QUAT 7676 21.379632 67.891794 -2.922834 0.7663026 0.3743991 0.4296285 0.2966901 +VERTEX_SE3:QUAT 7677 22.194593 68.409925 -2.429532 0.9888929 0.1351998 -0.0579530 0.0212897 +VERTEX_SE3:QUAT 7678 22.991893 68.917820 -2.330871 0.9301851 -0.1837936 0.2907835 0.1281425 +VERTEX_SE3:QUAT 7679 23.879747 69.305501 -1.993908 0.2827336 -0.9394756 0.0754437 0.1782009 +VERTEX_SE3:QUAT 7680 23.738274 70.071068 -2.331355 0.6760124 0.4761082 0.5166140 0.2223472 +VERTEX_SE3:QUAT 7681 22.862581 69.875648 -2.576369 -0.8257876 0.5040386 0.2512929 0.0295262 +VERTEX_SE3:QUAT 7682 22.074436 69.632003 -3.006356 0.0053400 0.7331374 0.2238722 0.6421543 +VERTEX_SE3:QUAT 7683 21.401420 69.075306 -3.681450 -0.3286516 0.3693184 -0.4314142 0.7546349 +VERTEX_SE3:QUAT 7684 20.503347 68.748843 -4.072999 0.8726290 0.3749899 0.0963788 0.2976784 +VERTEX_SE3:QUAT 7685 19.806784 68.433439 -4.588731 0.3545019 -0.4196567 0.6797575 0.4859489 +VERTEX_SE3:QUAT 7686 19.211231 67.953526 -5.139356 0.0178682 -0.9408722 -0.3373384 0.0253579 +VERTEX_SE3:QUAT 7687 18.397393 67.214679 -5.540106 0.8617712 -0.4115743 0.2610151 0.1408122 +VERTEX_SE3:QUAT 7688 17.716567 66.602719 -6.170132 0.2381390 0.9035765 -0.0568294 0.3515819 +VERTEX_SE3:QUAT 7689 17.097232 65.898962 -6.544670 0.5679687 -0.3691470 0.7082235 0.1989008 +VERTEX_SE3:QUAT 7690 16.393989 65.216547 -6.937467 0.7472218 0.6222314 -0.0162139 0.2328622 +VERTEX_SE3:QUAT 7691 15.712131 64.818779 -7.364937 0.2492844 0.6533098 0.6536439 0.2894707 +VERTEX_SE3:QUAT 7692 15.129505 64.037080 -7.904967 -0.4452125 0.7817562 0.3426661 0.2705974 +VERTEX_SE3:QUAT 7693 14.518071 63.443420 -8.244749 -0.3146401 0.7984422 0.4084610 0.3108879 +VERTEX_SE3:QUAT 7694 14.038416 62.731555 -8.767733 -0.1712779 -0.9099042 0.3701671 0.0755939 +VERTEX_SE3:QUAT 7695 13.117101 62.246735 -9.194665 -0.8867739 0.1336584 -0.3263965 0.2987185 +VERTEX_SE3:QUAT 7696 12.513231 61.454174 -9.523701 -0.2346409 -0.9093600 0.3432869 0.0127297 +VERTEX_SE3:QUAT 7697 11.925560 60.870418 -10.114809 0.7637445 -0.2038650 0.6111262 0.0407212 +VERTEX_SE3:QUAT 7698 11.140352 60.237344 -10.656507 0.3065957 0.6389296 -0.1605164 0.6870244 +VERTEX_SE3:QUAT 7699 10.463066 59.651871 -11.096951 0.5842696 -0.2011023 0.3165366 0.7197163 +VERTEX_SE3:QUAT 7700 10.284878 60.449756 -11.619402 -0.4299014 0.1463367 -0.7442303 0.4897873 +VERTEX_SE3:QUAT 7701 10.639801 60.967896 -11.023997 -0.5014679 0.0846083 -0.7963712 0.3273595 +VERTEX_SE3:QUAT 7702 11.361282 61.493209 -10.502247 0.1009518 0.4326005 0.0736499 0.8928837 +VERTEX_SE3:QUAT 7703 11.863673 62.036853 -9.991354 -0.7131813 0.0235873 -0.5671649 0.4112663 +VERTEX_SE3:QUAT 7704 12.260682 62.597469 -9.394212 0.4387630 -0.3607796 0.7250219 0.3894462 +VERTEX_SE3:QUAT 7705 12.708770 63.169112 -8.677623 0.2389762 0.9147524 -0.2697188 0.1826751 +VERTEX_SE3:QUAT 7706 13.123966 63.783887 -7.982337 0.4152652 0.4933371 -0.4817332 0.5933856 +VERTEX_SE3:QUAT 7707 13.454882 64.406524 -7.139893 0.5418188 0.3403088 0.6861946 0.3460625 +VERTEX_SE3:QUAT 7708 13.718557 64.827550 -6.243993 0.0683978 0.3439239 0.3543295 0.8668845 +VERTEX_SE3:QUAT 7709 14.157669 65.195153 -5.489508 0.3844065 0.6405201 0.6293149 0.2143092 +VERTEX_SE3:QUAT 7710 14.519192 65.755388 -4.778714 -0.5465620 0.6960067 -0.2719438 0.3780095 +VERTEX_SE3:QUAT 7711 14.746034 66.430562 -4.078258 0.9936335 -0.0395799 0.0699797 0.0789229 +VERTEX_SE3:QUAT 7712 15.040433 66.974807 -3.037530 -0.4071437 -0.1982800 -0.7047895 0.5460685 +VERTEX_SE3:QUAT 7713 15.249164 67.385298 -2.340319 -0.2352374 0.6569322 0.3207610 0.6404809 +VERTEX_SE3:QUAT 7714 15.529346 68.150876 -1.378014 0.2417570 0.3163210 0.8886868 0.2274430 +VERTEX_SE3:QUAT 7715 16.014097 68.597231 -0.670984 -0.8294671 0.3658499 -0.3668761 0.2086627 +VERTEX_SE3:QUAT 7716 16.402157 69.161107 0.120116 0.2787263 0.5838624 0.7374947 0.1936951 +VERTEX_SE3:QUAT 7717 16.717748 69.745848 0.817222 0.8529997 -0.1130299 -0.0150183 0.5093037 +VERTEX_SE3:QUAT 7718 17.143742 70.549246 1.592480 0.4993685 -0.6913795 0.5219553 0.0137207 +VERTEX_SE3:QUAT 7719 17.368142 71.226809 2.300884 0.6389902 -0.1574680 0.2194537 0.7202329 +VERTEX_SE3:QUAT 7720 17.235643 71.870868 1.772589 -0.2282710 0.9549794 0.1894703 0.0027916 +VERTEX_SE3:QUAT 7721 17.000526 71.348255 1.160874 0.6092404 -0.1403243 0.7804614 0.0039108 +VERTEX_SE3:QUAT 7722 16.500064 70.819959 0.406615 -0.9266311 -0.1704224 -0.2865371 0.1738033 +VERTEX_SE3:QUAT 7723 16.246866 70.174845 -0.334460 0.4350798 0.6327309 0.6401169 0.0246485 +VERTEX_SE3:QUAT 7724 15.779706 69.717920 -1.051667 0.8129340 0.5712274 -0.1112189 0.0216340 +VERTEX_SE3:QUAT 7725 15.198337 69.274424 -1.826364 0.1476861 0.5463650 -0.5074359 0.6497560 +VERTEX_SE3:QUAT 7726 14.775295 68.710491 -2.601940 0.8160872 -0.5678976 0.0761993 0.0754162 +VERTEX_SE3:QUAT 7727 14.382656 68.109831 -3.328654 -0.8770277 -0.3864785 -0.1904208 0.2125952 +VERTEX_SE3:QUAT 7728 14.036925 67.749582 -4.098970 -0.9565376 -0.1874918 -0.0075800 0.2232155 +VERTEX_SE3:QUAT 7729 13.664312 67.033051 -4.990452 -0.1158818 0.3251312 -0.8639514 0.3666731 +VERTEX_SE3:QUAT 7730 13.225102 66.346885 -5.679294 0.4406686 -0.3567446 0.7599545 0.3178264 +VERTEX_SE3:QUAT 7731 12.905755 65.821880 -6.427367 0.7261088 -0.2572963 0.4175398 0.4818974 +VERTEX_SE3:QUAT 7732 12.582599 65.223927 -7.204973 0.4933951 0.2428794 0.8246996 0.1320659 +VERTEX_SE3:QUAT 7733 12.379216 64.641197 -8.106078 -0.7962908 -0.5525362 -0.1523695 0.1934122 +VERTEX_SE3:QUAT 7734 11.990564 64.102456 -8.944051 -0.6812462 0.3621093 -0.5286458 0.3539973 +VERTEX_SE3:QUAT 7735 11.608845 63.746520 -9.666770 0.5251568 -0.8233970 0.1947678 0.0910674 +VERTEX_SE3:QUAT 7736 11.008926 63.309128 -10.519888 -0.7379563 0.4014899 0.1416274 0.5236105 +VERTEX_SE3:QUAT 7737 10.609116 62.981023 -11.105202 -0.3631910 -0.0212944 -0.8015096 0.4745748 +VERTEX_SE3:QUAT 7738 10.162826 62.431710 -11.815530 0.5223258 0.4009823 0.2016849 0.7250601 +VERTEX_SE3:QUAT 7739 9.766918 61.880334 -12.676723 -0.5715520 -0.4904782 -0.6536265 0.0743769 +VERTEX_SE3:QUAT 7740 9.432884 62.734619 -12.878009 0.5408472 -0.1909186 0.7953155 0.1962336 +VERTEX_SE3:QUAT 7741 9.709426 63.367873 -12.020089 -0.4687145 0.5696897 0.1286385 0.6627311 +VERTEX_SE3:QUAT 7742 10.134947 63.918628 -11.418456 0.6959609 0.2030644 0.1340776 0.6755934 +VERTEX_SE3:QUAT 7743 10.522510 64.439274 -10.559625 0.6078064 -0.7720952 -0.1854694 0.0064381 +VERTEX_SE3:QUAT 7744 10.904214 65.033957 -9.905036 -0.5272105 0.5925725 -0.2278995 0.5647732 +VERTEX_SE3:QUAT 7745 11.240091 65.500161 -9.171491 -0.6615206 0.5886812 0.2611420 0.3842523 +VERTEX_SE3:QUAT 7746 11.752332 65.981994 -8.441321 0.4071759 -0.1694511 0.8555513 0.2711570 +VERTEX_SE3:QUAT 7747 12.103613 66.314133 -7.609509 -0.8387843 -0.0957959 -0.1316049 0.5195615 +VERTEX_SE3:QUAT 7748 12.532779 66.914937 -6.901053 0.8177928 0.4533284 0.3331888 0.1212167 +VERTEX_SE3:QUAT 7749 12.915180 67.381931 -6.296522 0.3818279 0.5588821 0.5994961 0.4271566 +VERTEX_SE3:QUAT 7750 13.197222 67.729055 -5.545965 -0.7715862 0.4569285 0.1441608 0.4184359 +VERTEX_SE3:QUAT 7751 13.667100 68.274719 -4.965411 -0.1773975 0.9210225 0.1959917 0.2860681 +VERTEX_SE3:QUAT 7752 13.819601 68.743067 -4.271831 -0.8297240 0.3292997 -0.2905697 0.3445128 +VERTEX_SE3:QUAT 7753 14.337628 69.388778 -3.436544 0.5176365 -0.8199952 -0.1560485 0.1879074 +VERTEX_SE3:QUAT 7754 14.579744 69.871072 -2.884624 0.3644048 0.8425405 0.1821126 0.3523771 +VERTEX_SE3:QUAT 7755 15.037819 70.477338 -2.217404 -0.4830420 0.7210703 0.4625982 0.1809171 +VERTEX_SE3:QUAT 7756 15.370972 71.225210 -1.518711 0.5781556 -0.2224437 0.7115714 0.3315435 +VERTEX_SE3:QUAT 7757 15.815656 71.925485 -1.050148 0.4380183 0.8577793 0.2644064 0.0494350 +VERTEX_SE3:QUAT 7758 16.082674 72.751916 -0.370546 0.6091241 0.6128470 -0.1445781 0.4821655 +VERTEX_SE3:QUAT 7759 16.341379 73.424691 0.209020 -0.1501608 0.7715357 -0.4317875 0.4424297 +VERTEX_SE3:QUAT 7760 16.049707 74.014982 -0.290886 -0.2201001 0.4040209 0.2711152 0.8454700 +VERTEX_SE3:QUAT 7761 15.736607 73.348854 -0.884419 0.2650789 0.8879244 -0.1043318 0.3611625 +VERTEX_SE3:QUAT 7762 15.320968 72.604820 -1.218704 -0.4549288 -0.1509333 -0.7848867 0.3926981 +VERTEX_SE3:QUAT 7763 14.942770 71.842576 -1.743694 -0.0840442 0.9170817 -0.0616462 0.3848344 +VERTEX_SE3:QUAT 7764 14.634149 70.961283 -2.280700 -0.6160696 0.2595746 -0.4482383 0.5934321 +VERTEX_SE3:QUAT 7765 14.134449 70.200389 -2.673106 0.0020451 0.6575036 -0.4959205 0.5672281 +VERTEX_SE3:QUAT 7766 13.637243 69.456684 -3.204680 0.4323471 0.5931433 0.0550828 0.6769216 +VERTEX_SE3:QUAT 7767 13.161160 68.788502 -3.608502 0.7021058 0.4276005 0.0402441 0.5679662 +VERTEX_SE3:QUAT 7768 12.711867 67.936636 -4.218597 -0.4425526 0.4217372 -0.1817958 0.7702177 +VERTEX_SE3:QUAT 7769 12.224075 67.168525 -4.780088 0.2504228 0.6404482 0.3409108 0.6410105 +VERTEX_SE3:QUAT 7770 11.953017 66.243810 -5.501188 -0.2997754 0.7405298 -0.4805920 0.3616373 +VERTEX_SE3:QUAT 7771 11.716045 65.414342 -6.079487 0.2547794 0.4556308 0.5226289 0.6740527 +VERTEX_SE3:QUAT 7772 11.488734 64.695295 -6.790660 -0.3936182 0.8395613 -0.3465861 0.1417025 +VERTEX_SE3:QUAT 7773 11.238251 64.090641 -7.389537 -0.0909408 0.8272875 -0.5469962 0.0901123 +VERTEX_SE3:QUAT 7774 10.880561 63.442404 -7.827910 -0.6554619 0.4723879 -0.3538478 0.4711805 +VERTEX_SE3:QUAT 7775 10.397783 62.566569 -8.449063 0.2110801 0.9458762 0.1571697 0.1898977 +VERTEX_SE3:QUAT 7776 10.085566 61.916397 -8.914809 0.6835615 0.3173104 0.2901269 0.5898170 +VERTEX_SE3:QUAT 7777 9.809239 61.369797 -9.646780 0.6111417 0.5753594 0.5208215 0.1556031 +VERTEX_SE3:QUAT 7778 9.504737 60.534971 -10.082697 -0.5721979 0.4959610 -0.5783698 0.3034809 +VERTEX_SE3:QUAT 7779 8.964505 59.915507 -10.603591 0.1382189 -0.9381989 -0.3149995 0.0381259 +VERTEX_SE3:QUAT 7780 8.457744 60.413191 -11.201358 0.7210709 0.6051393 -0.3120974 0.1282902 +VERTEX_SE3:QUAT 7781 8.810210 60.982876 -10.622461 -0.1553241 0.3498817 -0.8025332 0.4575999 +VERTEX_SE3:QUAT 7782 8.961852 61.737797 -9.858326 0.5725093 0.5546728 0.4849378 0.3597311 +VERTEX_SE3:QUAT 7783 9.223245 62.324941 -9.050979 -0.2981471 0.1632311 -0.8996150 0.2741472 +VERTEX_SE3:QUAT 7784 9.527735 62.823688 -8.271473 -0.6875007 0.6713268 -0.2653832 0.0789614 +VERTEX_SE3:QUAT 7785 9.802023 63.625807 -7.524557 0.7575421 -0.1418507 0.6257144 0.1203739 +VERTEX_SE3:QUAT 7786 10.225615 64.265758 -6.744179 -0.6658741 0.2704054 -0.4400518 0.5383744 +VERTEX_SE3:QUAT 7787 10.344809 64.803152 -5.725171 0.7871091 -0.5390474 0.2692438 0.1318896 +VERTEX_SE3:QUAT 7788 10.442894 65.227244 -5.039998 0.2544024 0.4370176 0.8519691 0.1358075 +VERTEX_SE3:QUAT 7789 10.610696 65.841776 -4.192636 -0.2416829 0.7364390 0.4916540 0.3968921 +VERTEX_SE3:QUAT 7790 10.910710 66.233630 -3.421911 0.4669557 -0.7216598 0.4695555 0.2016860 +VERTEX_SE3:QUAT 7791 11.203628 66.818139 -2.553937 -0.7308486 0.6815301 -0.0354562 0.0109494 +VERTEX_SE3:QUAT 7792 11.468730 67.405344 -1.738228 0.3769202 -0.8394018 0.3477851 0.1799480 +VERTEX_SE3:QUAT 7793 12.051763 67.620000 -0.827146 0.5751177 0.5580088 0.5441570 0.2485135 +VERTEX_SE3:QUAT 7794 12.412999 67.856944 -0.036876 -0.0552739 0.7461449 0.1099465 0.6543121 +VERTEX_SE3:QUAT 7795 12.957346 68.142841 0.801524 -0.4860255 0.4854341 0.2857883 0.6681751 +VERTEX_SE3:QUAT 7796 13.607140 68.149327 1.623160 -0.7689035 0.5833741 -0.1475154 0.2161048 +VERTEX_SE3:QUAT 7797 14.132029 68.360483 2.163111 -0.9173718 0.3301856 -0.0008159 0.2222739 +VERTEX_SE3:QUAT 7798 14.792217 68.768634 2.922279 -0.3049658 0.9395442 0.1484182 0.0471658 +VERTEX_SE3:QUAT 7799 15.417215 69.061499 3.611621 0.0307871 0.4530201 -0.8088627 0.3735854 +VERTEX_SE3:QUAT 7800 15.326769 70.102002 3.335260 0.7029205 0.5154389 0.4901186 0.0030393 +VERTEX_SE3:QUAT 7801 14.556097 69.761323 2.877941 0.9297178 0.1672207 0.3178731 0.0813550 +VERTEX_SE3:QUAT 7802 13.892013 69.316890 2.078872 0.2470589 0.2913555 0.1386283 0.9137046 +VERTEX_SE3:QUAT 7803 13.209456 68.908782 1.405444 0.7348711 -0.1417452 0.1382640 0.6486569 +VERTEX_SE3:QUAT 7804 12.416210 68.708147 0.602056 -0.5807797 -0.2919343 -0.6236143 0.4342516 +VERTEX_SE3:QUAT 7805 11.904405 68.482035 0.207545 0.0266462 -0.9704756 -0.2025802 0.1281732 +VERTEX_SE3:QUAT 7806 11.101280 68.088635 -0.347624 0.5890396 0.4338105 0.4985330 0.4650867 +VERTEX_SE3:QUAT 7807 10.545651 67.848462 -0.998566 0.0779269 0.5484103 0.6548684 0.5141215 +VERTEX_SE3:QUAT 7808 9.966392 67.525909 -1.548442 0.3421998 0.1865037 0.5488924 0.7394814 +VERTEX_SE3:QUAT 7809 9.362616 66.988127 -2.255605 -0.4987478 -0.8641709 -0.0660470 0.0098520 +VERTEX_SE3:QUAT 7810 8.686809 66.432610 -2.964984 -0.6410921 0.3812053 -0.2506188 0.6171496 +VERTEX_SE3:QUAT 7811 8.080735 65.991147 -3.672574 -0.6396881 -0.6907450 -0.2678826 0.2047177 +VERTEX_SE3:QUAT 7812 7.538224 65.309193 -4.496689 -0.0642702 0.4929015 0.2574250 0.8286434 +VERTEX_SE3:QUAT 7813 6.927212 64.733225 -5.137770 -0.1342844 0.7474161 0.6341134 0.1457291 +VERTEX_SE3:QUAT 7814 6.522994 64.038435 -5.836628 0.0923016 0.9415502 -0.2904695 0.1434958 +VERTEX_SE3:QUAT 7815 5.995901 63.592121 -6.597117 0.5705948 -0.5680209 0.5478793 0.2271611 +VERTEX_SE3:QUAT 7816 5.522515 62.997002 -7.206278 -0.6769382 0.1497303 -0.2076407 0.6900875 +VERTEX_SE3:QUAT 7817 4.949698 62.297229 -7.729762 0.0703547 0.8130656 0.4696499 0.3367545 +VERTEX_SE3:QUAT 7818 4.410078 61.561581 -8.167543 -0.6875549 -0.6762881 -0.2618098 0.0368549 +VERTEX_SE3:QUAT 7819 3.901603 60.734577 -8.595529 -0.2229361 -0.9655900 -0.1333721 0.0121398 +VERTEX_SE3:QUAT 7820 3.540622 61.304226 -9.153177 0.6733661 -0.6772995 -0.2854999 0.0795825 +VERTEX_SE3:QUAT 7821 4.035558 61.863558 -8.570053 -0.5091280 0.0945366 -0.6271051 0.5818854 +VERTEX_SE3:QUAT 7822 4.706337 62.430462 -8.135421 0.6603065 -0.6543686 0.0452912 0.3657127 +VERTEX_SE3:QUAT 7823 5.266272 63.010755 -7.503234 -0.8272476 0.1674149 -0.1883426 0.5021561 +VERTEX_SE3:QUAT 7824 5.826501 63.448516 -6.988425 0.6829165 0.4572611 0.2573706 0.5082300 +VERTEX_SE3:QUAT 7825 6.193852 64.128192 -6.452546 -0.0708416 0.8839729 0.3022420 0.3496044 +VERTEX_SE3:QUAT 7826 6.755023 64.677035 -5.788705 0.6529646 0.3572220 0.0638863 0.6647919 +VERTEX_SE3:QUAT 7827 7.144671 65.478100 -5.229567 0.8880257 -0.4230468 -0.1747878 0.0434854 +VERTEX_SE3:QUAT 7828 7.472381 66.172986 -4.459602 0.8471137 0.1912698 0.2947936 0.3986364 +VERTEX_SE3:QUAT 7829 7.763567 66.688294 -3.695884 -0.4732831 0.0358843 -0.8602209 0.1863746 +VERTEX_SE3:QUAT 7830 8.129676 67.441149 -3.096197 0.8928029 0.2792761 0.1897533 0.2981636 +VERTEX_SE3:QUAT 7831 8.640397 68.016728 -2.476426 0.6583587 0.7214675 -0.2128582 0.0272015 +VERTEX_SE3:QUAT 7832 9.159022 68.538061 -1.873343 -0.5603139 -0.7820038 -0.1823144 0.2031744 +VERTEX_SE3:QUAT 7833 9.656892 69.231042 -1.139783 -0.1102847 0.5399875 -0.2626955 0.7919860 +VERTEX_SE3:QUAT 7834 10.043841 69.986958 -0.636252 0.6107963 0.0505600 0.4696622 0.6354439 +VERTEX_SE3:QUAT 7835 10.411735 70.589123 -0.232606 0.5851679 0.2548732 0.3160267 0.7019582 +VERTEX_SE3:QUAT 7836 10.993565 71.140669 0.663869 0.6628032 0.3973294 0.6306165 0.0717225 +VERTEX_SE3:QUAT 7837 11.473312 71.638326 1.326312 0.3523834 0.4928902 0.4237672 0.6732805 +VERTEX_SE3:QUAT 7838 12.129790 71.982887 2.232151 0.4192054 -0.6925739 0.3359252 0.4814172 +VERTEX_SE3:QUAT 7839 12.666192 72.474628 2.841759 -0.4899577 0.0152516 -0.8138884 0.3119206 +VERTEX_SE3:QUAT 7840 12.625939 73.469858 2.093394 0.2979593 0.5126219 -0.5729489 0.5658345 +VERTEX_SE3:QUAT 7841 11.980669 72.924551 1.515625 0.7393321 -0.6395977 0.0048520 0.2104264 +VERTEX_SE3:QUAT 7842 11.468325 72.535280 0.824451 -0.1844868 0.5683055 -0.7475012 0.2902332 +VERTEX_SE3:QUAT 7843 10.832348 72.076641 0.153758 0.3600829 -0.3261434 0.7221380 0.4924301 +VERTEX_SE3:QUAT 7844 10.211143 71.742781 -0.646935 -0.7328675 0.5699369 -0.3689496 0.0441965 +VERTEX_SE3:QUAT 7845 9.409526 71.348157 -1.370316 -0.1396025 0.6498965 -0.7450238 0.0555446 +VERTEX_SE3:QUAT 7846 8.779326 70.958340 -2.145211 0.1690406 0.7594725 -0.6166491 0.1198779 +VERTEX_SE3:QUAT 7847 8.036337 70.671954 -2.816023 0.2311164 -0.9270211 -0.0835881 0.2832492 +VERTEX_SE3:QUAT 7848 7.374641 70.480225 -3.611593 0.4957185 0.8178383 -0.2892811 0.0414735 +VERTEX_SE3:QUAT 7849 6.453704 70.100659 -4.128960 -0.4352037 0.3291661 -0.7837501 0.2966197 +VERTEX_SE3:QUAT 7850 5.759675 69.904775 -4.698850 0.6934545 -0.5502497 -0.0979826 0.4546927 +VERTEX_SE3:QUAT 7851 4.931501 69.568844 -5.259798 0.9352620 -0.0257323 0.3183787 0.1525051 +VERTEX_SE3:QUAT 7852 4.067269 69.041913 -5.534486 -0.1289562 0.4938189 -0.4835328 0.7111324 +VERTEX_SE3:QUAT 7853 3.208444 68.741804 -6.033056 0.3673590 -0.9291596 -0.0349985 0.0220188 +VERTEX_SE3:QUAT 7854 2.468861 68.316548 -6.532832 0.3042371 0.5343907 -0.4726758 0.6312241 +VERTEX_SE3:QUAT 7855 1.742824 67.864577 -6.972210 0.2917615 0.5554469 -0.4066252 0.6640858 +VERTEX_SE3:QUAT 7856 0.875450 67.479560 -7.392183 0.1385222 0.5619442 -0.4306513 0.6925098 +VERTEX_SE3:QUAT 7857 -0.057674 67.210683 -7.977905 -0.1240027 0.4559861 -0.5543368 0.6851356 +VERTEX_SE3:QUAT 7858 -0.786441 66.850657 -8.369558 0.0444697 0.8281685 0.2938398 0.4752027 +VERTEX_SE3:QUAT 7859 -1.605725 66.227988 -8.603166 -0.9626232 0.1350631 0.1562601 0.1752063 +VERTEX_SE3:QUAT 7860 -1.914086 67.004631 -9.171619 0.1512517 -0.7596198 0.5638358 0.2866878 +VERTEX_SE3:QUAT 7861 -0.897114 67.591825 -9.175503 -0.5661603 0.6589451 -0.4951369 0.0096622 +VERTEX_SE3:QUAT 7862 0.131456 67.906756 -9.055125 -0.1488811 -0.8854319 0.3525889 0.2636775 +VERTEX_SE3:QUAT 7863 1.107637 68.234357 -9.024897 0.9172152 -0.1616259 0.2289779 0.2831299 +VERTEX_SE3:QUAT 7864 2.181668 68.765541 -8.805186 -0.7685601 -0.6384977 -0.0264858 0.0305697 +VERTEX_SE3:QUAT 7865 3.211950 69.143651 -8.558118 0.6723609 0.2334255 -0.0409597 0.7012601 +VERTEX_SE3:QUAT 7866 4.021173 69.353227 -8.320964 0.4908440 0.6716900 -0.5483610 0.0848820 +VERTEX_SE3:QUAT 7867 5.081912 69.730014 -7.959535 0.4693097 0.7423803 -0.2766763 0.3899617 +VERTEX_SE3:QUAT 7868 6.080577 70.062805 -7.836407 0.9261191 0.1249800 0.2299322 0.2716884 +VERTEX_SE3:QUAT 7869 7.143460 70.527734 -7.813253 -0.2522707 0.9590633 -0.0927728 0.0891642 +VERTEX_SE3:QUAT 7870 8.077600 70.925864 -7.791560 0.6478549 0.5659871 0.4740868 0.1875750 +VERTEX_SE3:QUAT 7871 8.907773 71.515058 -7.768977 -0.5184499 0.1472207 -0.8417883 0.0304682 +VERTEX_SE3:QUAT 7872 9.699923 71.901100 -7.636927 0.8163557 0.4157462 0.3967196 0.0577240 +VERTEX_SE3:QUAT 7873 10.706569 72.260080 -7.666229 0.7826094 -0.3749454 0.4751906 0.1453700 +VERTEX_SE3:QUAT 7874 11.552488 72.454292 -7.658514 0.0325105 -0.9100261 -0.3790257 0.1647276 +VERTEX_SE3:QUAT 7875 12.664735 72.564509 -7.778682 0.8415191 0.3030589 0.3374045 0.2935288 +VERTEX_SE3:QUAT 7876 13.669234 72.533584 -7.638334 0.3416165 -0.8946174 -0.2730540 0.0916476 +VERTEX_SE3:QUAT 7877 14.644977 72.645003 -7.746735 -0.1994440 0.8947562 0.1231307 0.3800951 +VERTEX_SE3:QUAT 7878 15.512131 72.921139 -7.746084 0.3755143 0.2532724 -0.1581352 0.8774026 +VERTEX_SE3:QUAT 7879 16.487283 72.909524 -7.707441 -0.8142598 -0.3960960 -0.3853198 0.1778134 +VERTEX_SE3:QUAT 7880 16.508942 73.634792 -8.608632 0.1453328 0.8129366 -0.5151284 0.2294670 +VERTEX_SE3:QUAT 7881 15.438858 73.498870 -8.577729 0.0981653 -0.9950414 0.0098864 0.0125899 +VERTEX_SE3:QUAT 7882 14.285680 73.205358 -8.570103 0.7871884 0.4524409 0.3862831 0.1625332 +VERTEX_SE3:QUAT 7883 13.438696 72.993979 -8.770971 0.4984877 -0.6251485 0.5382071 0.2665192 +VERTEX_SE3:QUAT 7884 12.416250 72.590607 -8.925031 -0.2067942 -0.8871839 -0.0952964 0.4013223 +VERTEX_SE3:QUAT 7885 11.531704 72.394637 -8.943974 -0.7445417 0.5315602 -0.2513689 0.3160934 +VERTEX_SE3:QUAT 7886 10.504515 72.263776 -9.173149 0.3040738 0.5015301 -0.7955301 0.1521135 +VERTEX_SE3:QUAT 7887 9.464704 72.222655 -8.999006 -0.8689280 0.2975563 -0.2120858 0.3338322 +VERTEX_SE3:QUAT 7888 8.501075 72.240774 -8.720923 -0.9724093 -0.0769273 -0.1306937 0.1772612 +VERTEX_SE3:QUAT 7889 7.625786 72.215355 -8.667267 0.5781570 0.4303408 -0.6273260 0.2949633 +VERTEX_SE3:QUAT 7890 6.660761 71.927137 -8.628431 -0.3294534 0.8417128 -0.2506203 0.3466547 +VERTEX_SE3:QUAT 7891 5.573540 71.697244 -8.698188 -0.2940142 -0.8871654 0.2734951 0.2273625 +VERTEX_SE3:QUAT 7892 4.567902 71.681537 -8.747721 -0.2404105 -0.5506021 0.7714645 0.2094820 +VERTEX_SE3:QUAT 7893 3.680284 71.508204 -8.767954 0.9164244 -0.3405442 -0.1939044 0.0812220 +VERTEX_SE3:QUAT 7894 2.557890 71.351417 -9.011561 0.4204219 0.4683162 -0.7739445 0.0702513 +VERTEX_SE3:QUAT 7895 1.588585 71.263492 -9.003155 0.7174690 0.2776035 -0.4549293 0.4485686 +VERTEX_SE3:QUAT 7896 0.556641 71.260938 -9.045209 0.3284436 0.7036406 0.1305042 0.6164279 +VERTEX_SE3:QUAT 7897 -0.445232 71.235557 -9.171554 0.8194842 0.4137280 0.2793241 0.2815189 +VERTEX_SE3:QUAT 7898 -1.487943 71.052826 -9.192884 -0.4452973 -0.5829224 0.4363847 0.5210376 +VERTEX_SE3:QUAT 7899 -2.542356 70.896720 -9.108131 0.4504581 -0.3335133 0.8086607 0.1786735 +VERTEX_SE3:QUAT 7900 -2.475795 71.825505 -9.616934 -0.7427594 -0.2504691 0.6061292 0.1348373 +VERTEX_SE3:QUAT 7901 -1.456656 71.799026 -9.455902 0.4265593 0.8097339 -0.0903396 0.3927046 +VERTEX_SE3:QUAT 7902 -0.436537 71.862805 -9.510647 -0.3000295 0.9334225 0.0268717 0.1948913 +VERTEX_SE3:QUAT 7903 0.581545 71.991823 -9.480111 0.3368199 -0.9121615 0.2228627 0.0696129 +VERTEX_SE3:QUAT 7904 1.570994 72.065423 -9.556852 0.5949469 0.4236636 0.2357355 0.6410742 +VERTEX_SE3:QUAT 7905 2.513162 72.048449 -9.606288 -0.6233517 -0.6918880 -0.3485758 0.1059175 +VERTEX_SE3:QUAT 7906 3.399530 72.101438 -9.589760 -0.5937286 0.7901975 0.1004125 0.1139812 +VERTEX_SE3:QUAT 7907 4.350975 72.209202 -9.766043 -0.5764750 0.7024984 -0.0047891 0.4173124 +VERTEX_SE3:QUAT 7908 5.418506 72.289018 -9.862928 0.7192997 -0.5441978 -0.4110364 0.1323094 +VERTEX_SE3:QUAT 7909 6.388481 72.523420 -9.999092 0.3206219 0.5014953 -0.7079322 0.3801791 +VERTEX_SE3:QUAT 7910 7.406444 72.458452 -9.929817 -0.5960395 -0.5845094 0.3925253 0.3860176 +VERTEX_SE3:QUAT 7911 8.194024 72.814880 -9.939969 -0.3434189 0.9235482 0.0454491 0.1644889 +VERTEX_SE3:QUAT 7912 9.136605 73.067287 -10.009180 -0.2806248 0.5716314 -0.6693990 0.3826126 +VERTEX_SE3:QUAT 7913 9.983158 73.097701 -10.072710 -0.3496431 0.8389811 0.3055012 0.2837772 +VERTEX_SE3:QUAT 7914 10.870819 73.469158 -10.266718 0.1230666 0.8630376 -0.1387789 0.4698522 +VERTEX_SE3:QUAT 7915 11.767043 73.901593 -10.280966 -0.9801116 0.0500520 -0.0823103 0.1734965 +VERTEX_SE3:QUAT 7916 12.672189 74.151653 -10.496865 -0.1407479 0.5272027 -0.7874843 0.2865585 +VERTEX_SE3:QUAT 7917 13.635990 74.454593 -10.762023 -0.1319724 -0.7094384 0.6784600 0.1377410 +VERTEX_SE3:QUAT 7918 14.516894 74.769191 -10.714978 -0.8241760 -0.4697644 -0.2359083 0.2107193 +VERTEX_SE3:QUAT 7919 15.507373 74.991506 -10.690877 0.3591202 0.7618017 -0.0195408 0.5388033 +VERTEX_SE3:QUAT 7920 15.348807 75.772212 -11.179105 0.7297581 -0.5107290 0.4446671 0.0942346 +VERTEX_SE3:QUAT 7921 14.403917 75.590120 -11.188003 0.7036304 -0.2791902 -0.4247108 0.4965661 +VERTEX_SE3:QUAT 7922 13.497344 75.403934 -11.048869 0.5943047 -0.7824970 0.0192147 0.1847461 +VERTEX_SE3:QUAT 7923 12.580098 75.306373 -10.990565 -0.8220066 0.2365475 0.3846654 0.3469625 +VERTEX_SE3:QUAT 7924 11.558078 75.146355 -10.885178 0.7328061 0.0466469 0.3364869 0.5895726 +VERTEX_SE3:QUAT 7925 10.663433 74.904596 -10.688194 -0.5984488 -0.7907064 -0.1075836 0.0711913 +VERTEX_SE3:QUAT 7926 9.650819 74.799423 -10.725214 -0.2625098 -0.5053917 0.7506669 0.3349134 +VERTEX_SE3:QUAT 7927 8.836693 74.615373 -10.448671 0.1590753 -0.7893107 0.0758943 0.5881528 +VERTEX_SE3:QUAT 7928 7.972988 74.281229 -10.231376 0.8354207 0.4142388 -0.3177635 0.1717700 +VERTEX_SE3:QUAT 7929 6.933200 74.056244 -10.114766 0.8630847 -0.3983626 0.0522796 0.3060374 +VERTEX_SE3:QUAT 7930 5.899454 73.809934 -9.892477 -0.6009654 0.6565161 -0.2318682 0.3925104 +VERTEX_SE3:QUAT 7931 4.836152 73.641694 -9.913455 0.9171666 -0.3819924 0.0507088 0.1015669 +VERTEX_SE3:QUAT 7932 3.850199 73.494686 -9.682797 -0.3012348 0.8773869 0.0895921 0.3625231 +VERTEX_SE3:QUAT 7933 2.946792 73.202957 -9.489943 0.3441925 -0.5488274 0.4384046 0.6229938 +VERTEX_SE3:QUAT 7934 1.994709 72.894042 -9.497037 -0.8820121 -0.4301384 -0.0107940 0.1921433 +VERTEX_SE3:QUAT 7935 1.172442 72.439813 -9.370089 -0.9044215 -0.2181448 -0.3094425 0.1966722 +VERTEX_SE3:QUAT 7936 0.113142 71.809670 -9.141604 -0.7959061 0.0612849 -0.5888688 0.1265355 +VERTEX_SE3:QUAT 7937 -0.752402 71.259960 -8.871006 0.7826800 0.0844964 -0.2790853 0.5498944 +VERTEX_SE3:QUAT 7938 -1.504619 70.768832 -8.684882 0.4108358 0.8480830 0.1022702 0.3186064 +VERTEX_SE3:QUAT 7939 -2.326442 70.172557 -8.484482 -0.9352724 0.0194022 -0.2786825 0.2173137 +VERTEX_SE3:QUAT 7940 -2.772840 70.606502 -9.480345 -0.6122759 -0.0217752 -0.7865149 0.0777075 +VERTEX_SE3:QUAT 7941 -1.980901 71.137029 -9.533516 -0.0813809 0.4939761 -0.7010327 0.5078562 +VERTEX_SE3:QUAT 7942 -1.332537 72.021486 -9.612720 0.1213353 0.8585760 0.4564045 0.1995492 +VERTEX_SE3:QUAT 7943 -0.704206 72.718683 -9.624758 0.5317729 -0.3676000 0.1321793 0.7514097 +VERTEX_SE3:QUAT 7944 -0.132937 73.473246 -9.687615 0.5142410 0.4207881 -0.1623002 0.7294876 +VERTEX_SE3:QUAT 7945 0.658560 74.211791 -9.545934 0.3380607 -0.8936701 0.2777608 0.0995873 +VERTEX_SE3:QUAT 7946 1.410736 74.807831 -9.631660 0.8520718 0.3713409 -0.3677022 0.0295734 +VERTEX_SE3:QUAT 7947 2.098976 75.596749 -9.862292 0.6121168 -0.6360718 0.4524821 0.1264341 +VERTEX_SE3:QUAT 7948 2.681549 76.238397 -10.058829 0.2716142 0.2603062 0.5685659 0.7315731 +VERTEX_SE3:QUAT 7949 3.395883 76.983484 -10.285940 0.4492828 0.6813280 -0.4282471 0.3879967 +VERTEX_SE3:QUAT 7950 4.081483 77.730620 -10.471585 0.2993725 0.0404415 0.2497250 0.9199881 +VERTEX_SE3:QUAT 7951 4.642477 78.413153 -10.649616 0.6619374 0.5864723 -0.1117745 0.4532059 +VERTEX_SE3:QUAT 7952 5.323698 79.316988 -10.936974 -0.1506293 -0.9546956 0.2060923 0.1529480 +VERTEX_SE3:QUAT 7953 5.979677 80.145382 -11.021545 -0.8751524 -0.3824559 -0.2176185 0.2011912 +VERTEX_SE3:QUAT 7954 6.563103 80.603708 -11.338825 -0.7666294 0.3570972 -0.4665285 0.2590601 +VERTEX_SE3:QUAT 7955 7.280449 81.355869 -11.526879 0.9883592 -0.0427601 0.1350567 0.0554735 +VERTEX_SE3:QUAT 7956 7.949629 81.994379 -11.532448 0.3112825 0.9181713 -0.0002914 0.2450806 +VERTEX_SE3:QUAT 7957 8.735539 82.804631 -11.426793 -0.4434448 -0.8883901 0.0278372 0.1155198 +VERTEX_SE3:QUAT 7958 9.536222 83.468217 -11.522512 0.9252689 0.2749747 -0.0456637 0.2572571 +VERTEX_SE3:QUAT 7959 10.169028 84.101570 -11.714107 -0.6876286 -0.6578761 0.1029871 0.2894124 +VERTEX_SE3:QUAT 7960 9.686167 84.374385 -12.597792 0.1716621 -0.5817207 0.7935631 0.0488955 +VERTEX_SE3:QUAT 7961 9.293941 84.055874 -12.525251 -0.4394838 0.8828752 0.0061393 0.1653710 +VERTEX_SE3:QUAT 7962 8.676047 83.245072 -12.380355 0.0657411 0.5765822 -0.4905979 0.6500344 +VERTEX_SE3:QUAT 7963 8.180255 82.530476 -12.185314 0.5570688 -0.2716848 0.7419842 0.2555802 +VERTEX_SE3:QUAT 7964 7.433894 82.044859 -11.755318 -0.5318451 0.8259936 -0.0539035 0.1788011 +VERTEX_SE3:QUAT 7965 6.855913 81.297197 -11.429767 0.4721018 -0.6135298 0.2772770 0.5690506 +VERTEX_SE3:QUAT 7966 6.111957 80.603508 -11.398321 0.3393926 -0.8365335 0.4140319 0.1166275 +VERTEX_SE3:QUAT 7967 5.525860 79.960898 -11.229101 0.5968336 -0.3319257 0.5647541 0.4633225 +VERTEX_SE3:QUAT 7968 4.940729 79.202952 -10.938141 0.1582446 -0.9323431 -0.3249710 0.0094275 +VERTEX_SE3:QUAT 7969 4.405158 78.444433 -10.468595 0.3734361 0.6008464 -0.2012764 0.6775078 +VERTEX_SE3:QUAT 7970 3.902075 77.658178 -10.056012 -0.8684078 -0.1450624 -0.4360006 0.1863549 +VERTEX_SE3:QUAT 7971 3.375773 76.790884 -9.598219 0.1309459 -0.7740736 0.4166773 0.4583048 +VERTEX_SE3:QUAT 7972 2.832345 76.081264 -8.863934 0.4049677 0.0562627 0.6185798 0.6709655 +VERTEX_SE3:QUAT 7973 2.430077 75.187712 -8.404574 0.7603917 -0.0471940 0.4354843 0.4795109 +VERTEX_SE3:QUAT 7974 1.884424 74.500862 -7.837639 0.3834649 -0.6285887 0.1474563 0.6603692 +VERTEX_SE3:QUAT 7975 1.266570 73.821133 -7.304064 0.5811082 -0.2738934 -0.1753014 0.7460328 +VERTEX_SE3:QUAT 7976 0.817877 73.228192 -6.674634 0.1788622 0.9010163 0.3513985 0.1808234 +VERTEX_SE3:QUAT 7977 0.322417 72.379683 -6.135674 0.6552951 0.7445908 -0.0560494 0.1141548 +VERTEX_SE3:QUAT 7978 -0.174384 71.796016 -5.607204 0.8155504 0.3296289 0.4737825 0.0418616 +VERTEX_SE3:QUAT 7979 -0.684010 70.994715 -5.102203 0.3577946 -0.4464457 0.7981488 0.1887532 +VERTEX_SE3:QUAT 7980 -1.431044 70.929395 -5.659294 0.3136045 0.5018808 -0.2403379 0.7694190 +VERTEX_SE3:QUAT 7981 -0.997543 71.477141 -6.282237 0.5453606 -0.4659925 0.4060124 0.5662037 +VERTEX_SE3:QUAT 7982 -0.598588 72.235970 -6.823548 0.4034418 -0.6778347 0.3459757 0.5080115 +VERTEX_SE3:QUAT 7983 -0.199651 72.996795 -7.428388 -0.1658110 -0.9794813 0.1145241 0.0026917 +VERTEX_SE3:QUAT 7984 0.343812 73.619770 -7.954733 0.0455792 -0.8632838 0.1464499 0.4808492 +VERTEX_SE3:QUAT 7985 0.940922 74.320570 -8.389360 -0.2749992 -0.9282229 0.2009853 0.1496083 +VERTEX_SE3:QUAT 7986 1.374625 74.911882 -8.855274 0.8354493 0.5384689 0.1082664 0.0188166 +VERTEX_SE3:QUAT 7987 1.933650 75.612516 -9.395895 0.6964106 -0.5475923 0.4197301 0.1974378 +VERTEX_SE3:QUAT 7988 2.415653 76.344309 -9.979639 0.6034638 0.6254567 -0.0549045 0.4915495 +VERTEX_SE3:QUAT 7989 2.919307 77.091948 -10.488858 -0.0635389 0.7093547 -0.6971316 0.0823787 +VERTEX_SE3:QUAT 7990 3.241634 77.800961 -10.915211 -0.9154473 -0.2877228 -0.2727914 0.0689692 +VERTEX_SE3:QUAT 7991 3.727983 78.536960 -11.528288 0.3359358 0.8793144 0.0464617 0.3343570 +VERTEX_SE3:QUAT 7992 4.034102 79.272349 -11.824551 -0.2393266 0.6957661 -0.3755162 0.5635777 +VERTEX_SE3:QUAT 7993 4.453919 80.148594 -12.402117 0.8158059 0.1028328 0.5443527 0.1660310 +VERTEX_SE3:QUAT 7994 4.850842 80.783196 -13.072716 -0.0008228 0.7478380 -0.6004087 0.2832790 +VERTEX_SE3:QUAT 7995 5.328533 81.458170 -13.622623 0.7758196 0.1637420 -0.4730769 0.3840452 +VERTEX_SE3:QUAT 7996 5.688460 82.178956 -14.104931 0.5494181 -0.5537739 0.5447925 0.3076936 +VERTEX_SE3:QUAT 7997 6.053931 83.034854 -14.486149 0.4186600 0.5891614 -0.4767596 0.5003129 +VERTEX_SE3:QUAT 7998 6.445510 83.918401 -14.944987 0.4456790 -0.8793943 -0.1436666 0.0859988 +VERTEX_SE3:QUAT 7999 6.760109 84.790419 -15.131225 -0.0249625 0.8048791 0.2353791 0.5441903 +EDGE_SE3:QUAT 0 1 0.939375 -0.022347 -0.028831 0.1175925 -0.3414281 -0.7976288 0.4831016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1 2 -0.261677 0.621546 -0.475474 -0.3304572 0.8344976 0.3170494 0.3064171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2 3 0.552147 0.529947 0.621620 -0.7800466 0.3168744 0.5194359 0.1459601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3 4 -0.760911 -0.721534 -0.222529 0.5914394 -0.1245494 -0.2297060 0.7628381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4 5 -0.319158 -0.486346 0.982101 -0.7808770 -0.4724196 0.1032990 0.3954494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5 6 -0.366665 -0.554592 -0.880911 0.2226893 0.2540109 0.4237533 0.8404291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6 7 -0.590873 -0.318666 -0.539573 0.0686118 -0.5956480 0.2106985 0.7720764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7 8 -0.907517 -0.037948 0.415737 0.3094413 -0.0086121 -0.9100172 0.2757547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 8 9 0.461671 -0.463378 0.743302 -0.7856326 -0.0652754 -0.1409606 0.5988745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 9 10 0.588689 -0.523755 -0.593759 0.1475905 -0.5355978 -0.4413930 0.7046448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 10 11 -0.065206 -0.069040 -0.873597 0.4031964 0.6830158 0.4877760 0.3646872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 11 12 -0.207002 -0.985781 0.047962 -0.2986920 -0.4444500 -0.4920003 0.6864277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 12 13 0.407284 -0.487410 -0.817667 0.2265487 -0.3346423 -0.6784926 0.6134640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 13 14 0.264985 -0.058123 -0.710529 -0.8245061 -0.3904312 -0.3202103 0.2553793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 14 15 -0.603884 0.466872 0.547846 0.1617457 0.1559059 -0.7315929 0.6436642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 15 16 -0.665276 -0.867860 0.048951 -0.0379333 0.4966276 0.8333132 0.2398149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 16 17 0.181266 0.651467 -0.705517 0.2660948 0.8329451 -0.1683562 0.4550299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 17 18 0.668186 0.870594 -0.069964 0.3129662 -0.7295338 -0.5479134 0.2638626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 18 19 -1.063564 0.190660 -0.011200 -0.0265945 -0.0566571 -0.5925484 0.8030997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 19 20 0.843345 -0.445552 0.231598 -0.6203141 0.3183505 -0.2500883 0.6718030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 20 21 -0.125471 0.241778 0.932943 0.7070810 -0.1340922 0.2280604 0.6557776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 21 22 0.410507 0.920030 -0.375389 -0.0516033 -0.5748582 0.0405904 0.8156148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 22 23 -0.136186 0.935669 -0.242334 0.4012470 0.6871711 0.0579261 0.6028609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 23 24 0.825070 0.567687 -0.329287 -0.4779633 -0.1381770 0.2515697 0.8301632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 24 25 0.831587 0.241144 -0.320569 -0.5068102 0.2297478 -0.7811308 0.2831855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 25 26 -0.628172 0.248956 0.786418 -0.0480667 -0.0740540 0.9960104 0.0129977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 26 27 0.592578 -0.116062 0.641481 0.5416880 0.1511287 -0.7255457 0.3966328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 27 28 -0.404562 0.751304 0.122770 0.1109468 -0.7438718 -0.1874835 0.6318191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 28 29 -0.251681 0.762697 0.682741 -0.0600182 0.3038515 -0.6809320 0.6636292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 29 30 -0.761762 -0.438520 0.413388 -0.7263281 -0.0365831 -0.5864052 0.3567046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 30 31 0.194955 -0.085327 -0.834296 -0.0626217 0.2218733 0.1627370 0.9593578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 31 32 0.633034 0.013815 -0.869422 0.3998700 0.0382066 -0.1673513 0.9003542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 32 33 0.668658 -0.432739 -0.426775 0.1083296 0.1841253 0.8427334 0.4941285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 33 34 -0.904526 -0.652955 -0.278301 -0.1188067 -0.4745033 0.1432891 0.8603486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 34 35 -0.744676 -0.428979 0.403340 -0.4739013 0.4195121 -0.4666813 0.6177667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 35 36 0.127861 -0.507690 -0.764084 0.6285567 -0.2016933 -0.2661778 0.7024141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 36 37 0.472491 -0.881946 0.096362 -0.7946373 0.1169677 -0.1414195 0.5786800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 37 38 0.777577 -0.193114 -0.528272 -0.5783893 -0.0234473 -0.8058370 0.1246707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 38 39 -0.915606 0.336822 0.448479 -0.5573634 0.5601092 -0.3949150 0.4686853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 39 40 -0.880745 0.585617 0.080946 0.0847673 -0.3220310 0.1685142 0.9277465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 40 41 1.013587 0.418536 0.337336 -0.2918226 0.4348515 0.0926187 0.8468563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 41 42 0.332787 -0.204190 0.904599 0.0312414 -0.7449798 -0.2059851 0.6337185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 42 43 0.916363 0.333408 -0.357042 0.6606677 0.0341869 0.3855732 0.6431818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 43 44 0.581383 -0.811556 0.273215 0.1179071 0.0661109 -0.3110529 0.9407302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 44 45 0.716709 -0.303426 0.590233 0.1425812 0.0528742 0.9865224 0.0604034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 45 46 -0.794141 0.222554 0.586920 0.1815420 -0.0742455 -0.0696118 0.9781024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 46 47 -0.510773 0.475333 0.601130 -0.2771534 -0.4263582 0.8128047 0.2841710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 47 48 0.373604 -0.672835 0.629586 0.5979163 -0.5114638 0.5396947 0.2993836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 48 49 0.773525 -0.542506 0.597931 -0.7813612 0.3699170 0.3580983 0.3527062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 49 50 0.081064 -0.752184 -0.986192 0.2037070 -0.6043155 0.7633833 0.1027237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 50 51 -0.293943 0.830364 0.390098 0.7472950 0.4664094 0.0403764 0.4715742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 51 52 0.395298 0.054181 -0.765462 -0.5494921 -0.2173186 -0.8062884 0.0270205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 52 53 -0.977021 -0.282443 0.021840 -0.3710058 -0.0709869 -0.9141949 0.1468442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 53 54 0.923466 -0.146732 -0.586098 -0.5332076 -0.4163127 -0.7253247 0.1275829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 54 55 -0.912744 0.287036 0.241706 0.0800592 0.5687975 -0.6389191 0.5117053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 55 56 0.084116 -0.897136 -0.407063 0.6476024 0.0727154 -0.7525459 0.0948592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 56 57 0.753472 0.757335 -0.075031 0.1021650 -0.7072877 -0.0033331 0.6994965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 57 58 -0.088969 0.683536 -0.598915 0.6684204 0.5609345 0.4446883 0.2020372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 58 59 0.480861 -1.011975 0.396874 -0.7681285 -0.1888529 -0.5085364 0.3401528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 59 60 -0.450388 0.660845 0.776489 0.3574351 0.7349417 0.0998555 0.5675647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 60 61 -0.587006 -0.527921 -0.412293 -0.4170894 -0.6670104 0.0004137 0.6173600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 61 62 -0.754782 -0.593971 0.396883 0.3575105 0.2192446 -0.3320763 0.8448925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 62 63 -0.503810 -0.726509 0.529838 -0.6833612 0.2017774 0.6963798 0.0857817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 63 64 -0.535046 0.743561 0.109394 -0.7263646 0.2061950 0.6541396 0.0444926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 64 65 -0.361580 -0.500301 0.676494 -0.8750555 0.1375068 0.1054219 0.4519468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 65 66 -0.409369 -0.301104 -0.857757 0.4168650 0.2610092 -0.8693719 0.0478574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 66 67 0.953462 0.287403 -0.152546 -0.7864669 -0.0392172 -0.2763661 0.5509570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 67 68 0.552757 0.221142 0.816087 0.0023230 0.0393885 0.4508663 0.8917190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 68 69 0.485138 -0.007565 0.643834 -0.1102628 0.1285654 0.9342549 0.3138166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 69 70 -0.797258 -0.153959 0.769617 -0.6897001 -0.1679125 0.5353443 0.4577397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 70 71 -0.834056 -0.311016 0.551165 0.0230236 0.4308103 -0.9008512 0.0483679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 71 72 0.631482 -0.355125 0.487353 -0.3812624 -0.4311763 0.1734682 0.7991463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 72 73 0.564563 -0.663416 -0.789096 0.1207855 0.3998877 0.3735951 0.8282074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 73 74 0.020958 -1.044295 -0.001267 0.5358473 0.4268579 -0.7265588 0.0526526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 74 75 -0.413840 0.677687 0.494593 0.3359063 0.1615813 0.9268178 0.0454667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 75 76 0.809984 -0.427281 0.588318 0.0691623 0.2013239 0.9581077 0.1916111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 76 77 -0.697422 0.258957 0.336681 0.3893441 -0.3658777 0.8439903 0.0471700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 77 78 0.852846 -0.017202 -0.690705 0.3277549 0.2071056 0.7674624 0.5105737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 78 79 -0.618730 -0.758019 0.244445 0.1676546 0.4373916 -0.7824483 0.4103111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 79 80 0.218468 -0.840914 -0.506521 0.1761469 0.1372049 -0.6925812 0.6859142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 80 81 0.149671 -0.716967 -0.732387 0.7016251 -0.1540608 -0.0898783 0.6898619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 81 82 0.239605 -0.795751 0.726412 0.1876827 -0.5425036 -0.7894191 0.2174455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 82 83 0.246344 0.943557 -0.546451 0.1736209 0.3711946 -0.8990621 0.1541352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 83 84 -0.165045 -0.345594 -0.941266 0.1214895 0.3925617 0.0344130 0.9110167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 84 85 0.338477 -0.443622 -0.644761 0.2204060 0.4083657 0.2517149 0.8492928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 85 86 0.188336 -0.815399 -0.037231 0.1931345 0.4513850 -0.6485563 0.5816574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 86 87 0.353392 0.246668 0.785320 0.3929467 -0.4226022 0.5234917 0.6268626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 87 88 0.997963 -0.275240 -0.021695 0.4334686 -0.2259164 -0.0957169 0.8671246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 88 89 1.000013 -0.220176 -0.156917 -0.1414446 0.6371664 0.2974851 0.6967891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 89 90 -0.017266 -0.716523 0.599570 -0.5658443 0.4364847 0.6994017 0.0117724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 90 91 -0.118785 0.803185 -0.566759 0.7770493 -0.3969589 -0.1502442 0.4648060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 91 92 -0.616520 -0.574648 -0.060213 -0.3521380 0.2513220 -0.1154434 0.8941526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 92 93 -0.536627 -0.368614 -0.772333 -0.4508895 0.6141495 0.6049704 0.2313653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 93 94 1.002362 -0.131209 0.185537 0.1771948 -0.2169929 0.2365041 0.9303665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 94 95 0.643732 -0.505690 -0.426082 -0.2998032 -0.5769527 -0.5733583 0.4985016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 95 96 -0.612901 0.479400 -0.708944 0.2381266 -0.5666264 -0.7407308 0.2711975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 96 97 0.157705 -0.885168 0.344071 -0.3800796 -0.7628529 0.0010267 0.5230621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 97 98 0.086733 -0.805849 -0.412723 0.4584215 0.5091520 -0.5831891 0.4364681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 98 99 0.910092 0.128294 0.938744 0.1089823 0.8897375 0.3998039 0.1914339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 99 100 -0.125831 0.146564 1.120959 -0.5659992 0.6967992 0.2303267 0.3755868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 100 101 -0.173078 -0.752568 -0.593871 0.5616179 -0.6669464 -0.1412088 0.4688582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 101 102 0.494844 -0.775983 0.512666 -0.9522051 -0.1126027 -0.2815267 0.0369980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 102 103 0.393001 0.645301 -0.160963 0.5116404 0.5624540 -0.4116872 0.5023777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 103 104 0.396830 0.506428 -0.715179 -0.0144854 -0.2960239 -0.7695043 0.5657059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 104 105 -0.780145 -0.198502 -0.388232 -0.5811633 0.2566320 -0.0727556 0.7688276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 105 106 -0.557000 0.475122 -0.752124 -0.1365965 -0.7889749 0.4286720 0.4184499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 106 107 0.211175 0.585095 0.182497 0.1378344 -0.4946009 0.7547172 0.4083792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 107 108 0.570707 -0.567097 -0.630440 0.2490927 -0.5535919 0.7687254 0.2013705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 108 109 -0.628889 0.234390 0.419328 0.7069877 0.5103676 -0.0772686 0.4834490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 109 110 -0.487763 -0.187814 -0.607088 -0.2441893 -0.1004400 -0.9624771 0.0626192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 110 111 0.034591 0.073642 -0.874681 0.7692718 -0.3707498 0.1738787 0.4904403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 111 112 -0.811962 -0.909873 0.432307 -0.1705013 0.3146478 -0.7760782 0.5192578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 112 113 0.805992 -0.458821 0.289793 -0.5697321 0.1328097 0.5335857 0.6107808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 113 114 -0.089526 -0.531539 -0.501191 0.7212995 0.2235289 0.0082950 0.6555098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 114 115 0.031866 -0.703254 0.631840 0.2250580 -0.4719485 -0.8428000 0.1276782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 115 116 0.368242 1.114888 -0.219244 -0.0039842 0.5721686 -0.1280766 0.8100640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 116 117 0.003160 0.996257 0.106171 0.6301468 -0.4335301 0.2431935 0.5965095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 117 118 -0.084519 0.118935 -1.145914 0.8758731 0.1743612 0.4167897 0.1695018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 118 119 -0.699606 -0.723823 0.644635 0.6835321 0.2422525 0.6503240 0.2262218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 119 120 1.149190 0.250460 0.145529 0.2499899 -0.0947404 -0.5679082 0.7784662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 120 121 0.804425 0.159971 0.606689 -0.4251343 -0.7438759 0.1439447 0.4951661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 121 122 0.467960 -0.300000 -0.830565 0.0785002 -0.2625541 0.3146396 0.9087932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 122 123 -0.120788 -0.417715 -0.865864 0.0070874 -0.9199690 0.3697049 0.1300964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 123 124 -0.005992 0.441906 0.822478 0.2462167 0.1282350 0.2182735 0.9355692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 124 125 0.047022 0.840223 0.514233 0.1800202 0.4698589 -0.3432328 0.7931057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 125 126 -0.729279 0.589823 0.088296 0.3159011 0.0063280 0.6687471 0.6730110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 126 127 0.406195 0.619945 -0.720344 -0.1035483 0.4499691 0.6822994 0.5668096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 127 128 0.643823 -0.880522 0.163341 -0.4493198 -0.4149501 -0.7039422 0.3611004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 128 129 0.023623 0.905718 -0.546501 -0.1657732 0.3995989 -0.1156507 0.8941280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 129 130 0.006108 0.998958 -0.032479 0.1474232 -0.1883253 0.7318019 0.6381740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 130 131 0.899622 -0.092098 -0.707456 -0.6284085 0.0656313 -0.7751098 0.0002027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 131 132 -0.569335 -0.166627 0.680556 0.1545750 0.3302501 -0.5269099 0.7677287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 132 133 -0.712485 -0.712004 0.316074 -0.1999880 0.3410920 -0.1920232 0.8982139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 133 134 -0.445731 -0.799014 -0.456207 -0.3577849 -0.1805687 -0.4143397 0.8171337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 134 135 -0.024613 -0.275326 -0.876328 0.1069128 0.0937475 -0.9891797 0.0361183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 135 136 0.364041 0.473803 -0.880207 0.5336634 -0.2270278 -0.8108830 0.0782966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 136 137 0.354746 -0.832534 -0.539295 0.1584663 -0.2446269 0.9361016 0.1968751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 137 138 -0.828597 0.824117 -0.050148 0.3929458 0.3198537 0.3863021 0.7707515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 138 139 0.286067 0.356931 -0.859036 -0.3926024 0.2387429 -0.0467434 0.8869500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 139 140 -0.659755 0.615177 -0.271061 -0.7136931 0.1098848 0.3710685 0.5838456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 140 141 -0.545967 0.614812 -0.615844 0.3013552 0.3921089 -0.8088171 0.3181988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 141 142 0.425100 -0.669713 -0.643362 0.5318529 -0.1416555 0.1924550 0.8124206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 142 143 0.217738 -0.966249 0.398723 -0.0787621 0.0096577 0.6458817 0.7593023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 143 144 -0.865664 -0.551790 -0.008996 0.3072335 0.0080441 -0.4476709 0.8397224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 144 145 -0.322116 -0.717549 0.350531 -0.1788398 0.4106539 0.1712554 0.8775257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 145 146 -0.821865 -0.627687 -0.306880 -0.3545092 0.0289113 0.0726500 0.9317775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 146 147 -0.556769 -0.211620 -0.695635 0.3731395 -0.1381669 -0.6918308 0.6025338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 147 148 0.518581 -0.913011 0.000610 0.0367474 -0.4172749 0.5586576 0.7158442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 148 149 -0.649879 -0.791995 0.109816 0.3101431 -0.4898948 0.5449598 0.6056676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 149 150 0.039562 0.211982 0.916994 0.1687571 0.0597433 -0.7220623 0.6682647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 150 151 -0.419481 0.060340 0.903601 -0.0387372 0.3366468 0.8949122 0.2903454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 151 152 0.390650 0.646490 0.750706 0.4872379 -0.2704920 0.6239858 0.5477911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 152 153 0.884405 -0.267510 -0.357293 -0.4822264 0.7949126 -0.0392061 0.3661073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 153 154 0.359536 -0.735057 0.770061 -0.6161274 -0.4752366 -0.2846058 0.5599435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 154 155 0.506598 -0.113384 -0.797504 -0.2794733 0.8675825 -0.4088514 0.0451196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 155 156 -0.476707 0.153398 0.945553 -0.1980209 -0.9024825 0.3685892 0.1022504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 156 157 0.636367 -0.654988 -0.495597 -0.0304252 -0.3759862 0.6739645 0.6352012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 157 158 -0.877534 -0.099695 -0.263636 -0.6880825 -0.1516112 0.6859562 0.1817161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 158 159 0.319619 0.391889 0.799084 0.2200935 -0.4492072 0.6394185 0.5838799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 159 160 -0.551760 -0.644998 0.346456 -0.1441673 0.3368776 -0.9000842 0.2357493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 160 161 0.423725 -0.705219 -0.633090 0.0485004 -0.3156976 -0.1088296 0.9413495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 161 162 0.108354 -0.773946 -0.474631 0.0370058 0.9052361 -0.3754018 0.1955804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 162 163 0.397037 0.020333 1.029357 0.2128896 -0.0719857 0.2699590 0.9362789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 163 164 0.526812 0.121938 0.927156 0.4502967 -0.3053932 -0.2233068 0.8087657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 164 165 0.463675 0.795727 0.036624 -0.3071203 0.4067994 -0.0799002 0.8566255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 165 166 -0.137375 0.595971 0.711873 0.4226555 -0.3735377 0.0435764 0.8245805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 166 167 0.305670 0.687636 -0.119690 0.4165283 -0.1641705 0.8940299 0.0162107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 167 168 -0.656389 -0.673115 -0.189941 0.5509396 0.3006254 0.0900229 0.7732954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 168 169 -0.995108 -0.523482 0.385317 0.2983144 -0.1000122 -0.9244683 0.2153239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 169 170 0.850378 0.273813 0.726362 -0.4452601 -0.4851374 -0.6011377 0.4527898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 170 171 0.475120 0.766095 0.290689 -0.1361769 0.7954691 -0.4259557 0.4089577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 171 172 -0.875679 0.083737 -0.085390 0.8109700 0.0399868 -0.4599736 0.3593787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 172 173 -0.506199 -0.816714 0.564024 -0.3714125 0.1504579 0.5112644 0.7602789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 173 174 -1.014783 -0.127387 -0.075465 0.0122256 0.2135302 -0.8042995 0.5543986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 174 175 0.447254 -0.922279 -0.034351 -0.6721576 -0.6385332 0.3075432 0.2142351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 175 176 -0.806073 0.656445 -0.212558 0.8420655 -0.3278861 0.3624493 0.2281381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 176 177 -0.888864 0.036441 -0.373176 -0.6433623 -0.4170670 0.0676394 0.6384081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 177 178 -0.768006 0.207800 0.691494 -0.0735627 -0.1304018 0.5037076 0.8508011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 178 179 -0.055351 0.739836 0.745668 0.0044923 0.5235768 -0.8512402 0.0351752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 179 180 0.928270 -0.040686 0.512268 -0.2699830 -0.2495745 -0.6763990 0.6382055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 180 181 -0.574425 -0.040534 0.761932 0.2048438 -0.4635332 0.6774404 0.5331515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 181 182 0.791641 0.281867 0.521969 0.4203089 -0.0198125 -0.7988993 0.4297764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 182 183 -0.720416 0.731406 -0.115152 -0.8750146 0.1455643 0.1144921 0.4472717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 183 184 -0.996627 0.194420 0.656386 0.1013291 -0.3572425 0.8120506 0.4502045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 184 185 0.783170 0.276317 0.465179 -0.1570956 -0.5705102 0.8055345 0.0308751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 185 186 -0.977792 -0.321115 -0.154033 -0.0354206 0.1564007 -0.6845273 0.7111305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 186 187 0.489257 -0.891728 -0.450980 0.1863926 -0.0121775 0.9346592 0.3025257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 187 188 -0.808256 0.463294 -0.345034 0.6665989 -0.4932781 0.4402710 0.3442151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 188 189 -0.337883 1.012368 -0.531463 -0.3019223 0.1122944 -0.8909349 0.3201060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 189 190 -0.465856 -0.588497 -0.377544 0.1941684 -0.1541915 -0.6481548 0.7200132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 190 191 0.534377 -0.577322 0.077229 -0.0340555 -0.0715826 0.1644737 0.9831910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 191 192 0.146726 -0.965226 -0.066999 0.1824843 -0.2800428 0.8464595 0.4144658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 192 193 -0.679064 0.114114 0.321738 0.3381628 0.7880209 0.0820309 0.5078778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 193 194 -0.022679 -0.043912 -0.949170 0.2509895 -0.8742207 -0.4138313 0.0385502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 194 195 0.223971 -0.786307 0.626238 -0.5006879 0.6193313 0.1368643 0.5890744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 195 196 -0.230203 -0.719763 -0.728130 -0.6315970 0.0679089 0.6343912 0.4404786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 196 197 0.184471 0.780224 -0.252482 0.0698125 -0.8447517 -0.5299546 0.0258628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 197 198 -0.317749 -0.018184 1.111227 -0.4754461 -0.1564844 0.4510920 0.7389044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 198 199 -0.611325 -0.634407 0.617970 0.3862273 0.3066981 0.7078733 0.5056482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 199 200 0.787131 0.296407 0.554888 0.1182217 -0.6981248 0.2913494 0.6432425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 200 201 -0.254572 -0.879006 0.192647 0.3289752 0.3285073 -0.1214573 0.8769871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 201 202 -0.473674 -0.844101 0.406290 -0.2467189 0.4247924 0.3360269 0.8035963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 202 203 -0.745877 -0.531766 -0.289004 -0.4742629 0.0873921 -0.8411324 0.2448135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 203 204 0.222233 0.013002 -0.957033 -0.4175821 0.6432349 0.1827206 0.6152131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 204 205 0.879243 -0.087429 0.554717 0.3268747 -0.3481624 0.6451227 0.5964500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 205 206 0.519696 -0.860214 0.207126 -0.1433523 -0.0551208 0.8812624 0.4469769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 206 207 -0.924894 0.116221 0.223015 0.4268332 0.1629078 -0.5592055 0.6917830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 207 208 -0.372042 -0.745329 0.192504 0.0191187 -0.5217258 -0.0015682 0.8528975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 208 209 -0.143958 -0.682451 0.668731 -0.4473010 0.5091585 0.5343593 0.5051135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 209 210 -0.527126 -0.035285 -0.730323 -0.2523754 -0.2657384 -0.7438127 0.5589566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 210 211 -0.641048 -0.589449 -0.737060 0.6808235 -0.2640740 0.2247393 0.6451640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 211 212 -0.693941 -0.263985 0.535148 -0.1091960 -0.4675621 -0.8383444 0.2581483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 212 213 1.037207 0.090501 0.520098 -0.4267369 0.2875827 -0.2459247 0.8214091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 213 214 0.462216 0.087377 1.069910 -0.5685703 0.2277322 0.6224173 0.4873013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 214 215 -0.807642 -0.648504 -0.231393 -0.0939694 0.7181949 0.6343951 0.2700161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 215 216 0.468231 0.115616 -0.768291 0.2508439 -0.3012814 -0.8641519 0.3155126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 216 217 -0.374956 -0.368606 -0.960378 0.1073262 -0.5444456 -0.4589833 0.6938259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 217 218 -0.238548 -0.886969 -0.185388 0.2928562 0.4616886 -0.6337501 0.5472109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 218 219 0.816532 -0.225749 0.771737 -0.2231086 0.1733173 0.7670331 0.5760589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 219 220 0.532656 -0.699347 0.283123 -0.3666297 0.2503935 -0.7815213 0.4383037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 220 221 -0.896478 0.350263 0.347119 0.0005806 -0.1838502 0.7612424 0.6218592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 221 222 0.725858 0.510604 0.349258 -0.2561177 0.0862809 0.5503856 0.7899589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 222 223 0.576361 -0.486539 0.479401 0.1775265 -0.6186836 -0.7481673 0.1611232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 223 224 -0.471459 0.711879 -0.667963 -0.4450719 0.0394716 -0.5596011 0.6979968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 224 225 -0.876007 -0.031257 -0.273553 -0.1195786 0.0780598 0.8157503 0.5604990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 225 226 0.395452 0.760460 0.000955 -0.2202349 0.3815124 0.8225128 0.3597466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 226 227 0.031641 -0.615240 0.686474 -0.0996998 -0.0856442 0.9871383 0.0910115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 227 228 -0.626836 0.637800 0.662935 -0.1398913 -0.0977289 0.9722702 0.1599065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 228 229 0.412715 -0.702354 0.543677 -0.5135325 -0.3087572 -0.4965967 0.6279691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 229 230 0.973569 0.166142 -0.372175 -0.4694518 -0.2348296 -0.8357921 0.1610017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 230 231 -0.814154 0.242492 0.648495 0.0180684 0.2667775 -0.6341155 0.7255348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 231 232 -0.508211 -0.812060 0.317150 0.1509518 -0.7595478 -0.5513246 0.3103899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 232 233 0.897855 -0.116664 -0.337099 0.1461527 0.3883015 -0.4350248 0.7991338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 233 234 0.493329 0.785574 0.333294 0.3840622 -0.2691084 -0.8370619 0.2817875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 234 235 -1.007645 -0.073086 -0.084396 0.2714820 -0.2750475 0.7654101 0.5145812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 235 236 0.162956 1.019455 -0.121782 -0.8391148 0.2029087 -0.5038653 0.0288828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 236 237 -0.505206 -0.929513 0.062172 -0.1037932 0.6158513 -0.3694963 0.6880600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 237 238 0.555169 -0.411276 -0.146119 -0.4723231 0.3721200 -0.7796575 0.1748479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 238 239 0.376188 0.448774 0.815250 0.0241515 0.2803913 -0.5790725 0.7651617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 239 240 -0.334982 0.864760 -0.409059 0.0757299 0.0081393 -0.0260084 0.9967559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 240 241 0.762470 0.001773 -0.659949 0.0813856 -0.1264702 0.8891023 0.4322948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 241 242 -0.695314 -0.531383 -0.453108 0.6777492 0.4071398 0.4538419 0.4109996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 242 243 -0.759654 -0.436788 -0.494111 -0.7618293 0.1308112 0.1556442 0.6150442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 243 244 -0.547122 0.756545 -0.321880 0.3237781 -0.0407603 -0.7835627 0.5287115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 244 245 -0.517621 -0.839262 -0.130875 0.2608523 0.0729886 0.4931402 0.8267052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 245 246 -1.050506 -0.008448 0.066761 -0.4458223 0.4679802 -0.2580455 0.7180874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 246 247 -0.277027 0.014966 -0.915557 0.3248845 0.0817373 -0.0056717 0.9421979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 247 248 -0.262205 -0.555551 -0.693637 0.3849008 -0.4692723 -0.6294564 0.4852004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 248 249 0.802642 -0.671040 0.122413 -0.8125435 0.2777152 0.0210558 0.5120585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 249 250 0.927720 -0.373369 -0.287196 0.2045935 0.2792397 -0.3549463 0.8684352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 250 251 0.739644 0.458664 -0.052995 -0.1974211 -0.0827431 0.8304150 0.5143826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 251 252 -0.272530 -0.906800 -0.277388 0.5400396 0.2818648 -0.7871591 0.0963849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 252 253 0.197236 0.791713 0.672369 -0.2140329 -0.5300099 0.5779859 0.5824189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 253 254 0.995097 -0.415252 -0.082857 0.7001312 0.2570533 -0.5917799 0.3058374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 254 255 0.310313 0.987834 -0.223908 -0.4127534 -0.2041812 0.8837975 0.0827444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 255 256 0.087536 -0.656098 -0.556407 -0.3688155 0.7780365 -0.4456791 0.2449582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 256 257 0.463457 0.370219 0.870706 0.2754251 -0.0282661 -0.7682375 0.5771943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 257 258 -0.418962 0.635520 0.449374 -0.2363849 0.0762538 -0.8211305 0.5138601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 258 259 -0.325148 -0.809253 0.214363 -0.7627105 -0.4457039 0.4321246 0.1813533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 259 260 -0.127011 -0.042396 -0.930429 0.5848882 -0.1101738 -0.5134804 0.6181468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 260 261 0.872836 0.414994 -0.488734 0.2270297 -0.3554399 -0.8380461 0.3461196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 261 262 -0.642447 -0.258775 -0.550586 -0.6955304 -0.3513919 0.3279754 0.5340350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 262 263 -0.751243 0.553424 0.590876 -0.0875159 0.0401168 0.9370909 0.3355476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 263 264 0.627749 0.071411 0.791718 -0.7436304 -0.4783741 0.1291915 0.4488670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 264 265 0.780115 -0.118811 -0.792690 -0.3100573 -0.6238269 0.7145123 0.0646270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 265 266 -0.312491 0.810779 -0.026186 0.2887957 0.2433825 0.8649811 0.3304085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 266 267 0.738486 -0.382391 -0.045855 0.0583811 0.1027420 -0.9698811 0.2129937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 267 268 -0.390879 0.823280 0.014586 0.0151818 -0.5022229 -0.1285124 0.8550007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 268 269 -0.465802 0.640966 0.683593 0.4557658 0.2233001 0.5542804 0.6596877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 269 270 0.653143 0.672033 -0.370763 0.4441305 -0.3451959 -0.7912230 0.2399042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 270 271 -0.665053 -0.712402 -0.431218 0.2177591 -0.1366102 0.9645719 0.0593273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 271 272 0.283120 0.841876 -0.481258 -0.7194639 0.2334748 -0.0001771 0.6541110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 272 273 0.359705 0.249295 0.957345 0.1804726 0.5829179 -0.4787228 0.6312375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 273 274 -0.952881 0.221782 0.125207 0.4891211 0.3310810 -0.8069266 0.0039103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 274 275 0.644615 -0.544793 0.913032 0.4335075 0.0437813 -0.0784126 0.8966638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 275 276 0.387088 0.501655 0.733318 -0.0446704 -0.8828245 0.2044465 0.4205082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 276 277 0.642253 -0.006169 -0.952757 -0.6411381 -0.1714528 -0.5250226 0.5328200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 277 278 -0.378467 0.852117 0.359211 -0.6924503 -0.3731966 -0.5416828 0.2963386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 278 279 0.400250 -0.737523 0.320487 -0.2896230 0.3959329 -0.4387618 0.7528903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 279 280 -0.045279 -0.622296 -0.637620 -0.0107950 -0.0600275 0.9974431 0.0372488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 280 281 0.713362 -0.358788 -0.495137 -0.6212867 0.1998158 0.5203989 0.5506918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 281 282 0.522647 -0.231653 -0.840013 -0.5089047 -0.0911697 0.7428871 0.4252327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 282 283 0.390986 0.459906 -0.976499 -0.1317797 -0.0789395 0.3117425 0.9376669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 283 284 0.301646 0.165144 -0.808891 0.4128739 -0.3324707 -0.7803565 0.3317259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 284 285 0.106233 -0.710816 -0.563084 0.7800290 -0.2682035 -0.3985925 0.4009311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 285 286 0.897358 -0.064747 0.520150 -0.0468120 -0.4990906 -0.8397441 0.2086794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 286 287 -0.588455 0.952545 0.264746 0.4894003 0.5370757 0.3585177 0.5860905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 287 288 0.636111 0.195943 -0.694888 -0.0634648 -0.7052057 0.0337539 0.7053494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 288 289 -0.666059 0.429343 -0.737345 0.1716130 0.2145856 0.9385298 0.2089589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 289 290 0.590414 -0.477066 -0.837611 0.1137964 0.2730971 -0.7422433 0.6012847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 290 291 0.537052 0.846424 -0.364824 0.0148993 -0.4030921 0.8298122 0.3856246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 291 292 -0.229838 -0.601393 -0.906545 0.5324739 0.5096508 -0.2690506 0.6199511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 292 293 0.753917 -0.442352 0.307347 -0.3752477 0.3069544 0.5109771 0.7098384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 293 294 -0.562161 -0.715808 -0.039612 -0.0156078 -0.9465785 -0.3199492 0.0371230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 294 295 0.353201 -0.713288 -0.333435 -0.8485630 0.2647842 0.1538312 0.4314697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 295 296 0.805017 0.485571 -0.696777 -0.0663648 -0.3361848 0.9182017 0.1986984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 296 297 -0.475074 -0.093085 -0.702647 -0.2331289 -0.1384243 0.9512874 0.1467715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 297 298 0.660294 0.481015 -0.020216 -0.4969868 -0.2832323 -0.7441758 0.3449433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 298 299 -0.666019 0.074368 0.833137 -0.6557207 -0.0168934 0.4573698 0.6004647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 299 300 -0.412029 -0.255250 -0.747693 0.2138042 -0.4384637 0.5675232 0.6632909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 300 301 -0.387842 -0.593657 -0.783896 0.4616608 -0.5403571 0.6300586 0.3129052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 301 302 -0.645052 0.635773 0.310911 0.1760453 0.5004113 -0.5762314 0.6217347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 302 303 -0.663571 -0.515516 -0.598477 -0.7046621 -0.2830361 0.6296853 0.1638240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 303 304 -0.034713 0.615730 0.932512 0.3911090 0.1635830 0.2532197 0.8695712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 304 305 0.176159 0.884452 0.232909 -0.5968612 -0.0788026 0.7821988 0.1603494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 305 306 0.037155 -0.994090 -0.071094 0.2740301 0.2210806 -0.8280114 0.4363805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 306 307 0.717220 0.781638 0.458048 -0.4732797 -0.2639615 0.5341318 0.6488713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 307 308 0.732810 -0.553907 -0.177318 0.0325222 -0.5228829 0.5078469 0.6838328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 308 309 -0.575338 -0.677897 0.029065 0.3803847 0.3567520 -0.7885365 0.3259536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 309 310 0.850852 -0.050256 0.761580 -0.1541257 0.1138145 -0.6319740 0.7509330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 310 311 -0.017694 0.138671 1.051224 0.3397218 -0.0717883 -0.1095537 0.9313611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 311 312 0.062265 0.766236 0.447516 -0.0000353 -0.2377160 0.6522813 0.7197362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 312 313 1.042647 -0.267106 0.019939 0.4081413 0.7009534 -0.0946688 0.5771680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 313 314 -0.014055 0.701574 0.799397 0.3163870 -0.6618078 -0.6622766 0.1526414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 314 315 -0.572699 0.675796 0.890979 -0.4278804 -0.8741553 -0.1116671 0.2007520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 315 316 1.032943 -0.103384 -0.217815 0.2399824 -0.3761201 -0.8518806 0.2743020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 316 317 -0.539218 0.186594 -0.707010 0.1026421 -0.1313284 0.7296959 0.6631451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 317 318 -0.099540 0.833375 -0.646084 0.4285156 -0.4018449 -0.5462088 0.5971190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 318 319 -0.759326 -0.573477 -0.243706 -0.2348471 -0.5159790 -0.1508833 0.8098437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 319 320 -0.884439 0.769995 0.067224 0.0206913 0.0282004 -0.6694399 0.7420424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 320 321 -0.857761 0.739382 -0.318634 -0.1780876 0.4268591 -0.0240878 0.8862821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 321 322 -0.504066 0.648159 -0.325064 -0.4718208 -0.3620583 -0.3465309 0.7254069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 322 323 -0.843194 0.159920 0.775889 0.7591572 -0.2433441 0.1032006 0.5948223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 323 324 -0.486777 0.700074 -0.406293 -0.0396485 0.4838623 -0.8608648 0.1523715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 324 325 0.207985 -0.180391 -0.912536 0.4666031 0.5352347 -0.1001187 0.6969803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 325 326 0.806523 -0.501946 0.536433 0.2896414 0.1531753 -0.5988748 0.7307490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 326 327 0.338660 0.703236 0.633834 0.1648444 0.4147301 -0.7159467 0.5368851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 327 328 -1.112976 -0.131371 -0.136764 -0.2566947 -0.3511711 0.5273628 0.7298460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 328 329 -0.214559 0.695310 0.722098 -0.3664728 0.1646500 0.8627106 0.3071132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 329 330 -0.218141 -0.256458 1.240733 -0.3236786 -0.5943021 -0.7223572 0.1422577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 330 331 0.504641 0.865964 -0.056014 -0.1936010 0.2116722 0.3130834 0.9053686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 331 332 0.756645 0.240026 0.372660 0.0833903 0.1179976 -0.6289370 0.7639115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 332 333 -0.089956 0.936601 0.364183 0.1178057 -0.2265584 0.9205101 0.2957266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 333 334 0.682393 -0.582305 -0.131320 0.6242287 -0.5124707 0.5715207 0.1451772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 334 335 0.096775 -0.086554 0.989333 -0.4979259 0.7518231 0.2306501 0.3655577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 335 336 -0.617574 -0.247110 -0.553740 -0.3235607 -0.2212381 -0.2834232 0.8752334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 336 337 -0.937116 -0.417391 -0.336290 0.4071739 0.1966455 0.8911436 0.0374579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 337 338 0.099491 0.080708 -0.872118 -0.5608931 0.5239955 0.4233553 0.4812462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 338 339 1.162929 -0.029031 0.182810 0.2185505 -0.1223961 -0.5487502 0.7975764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 339 340 -0.857750 0.495068 -0.119204 -0.8104518 0.0920781 0.4154178 0.4026383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 340 341 -0.658518 0.686951 -0.447106 0.9177234 0.1478329 -0.0853538 0.3586698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 341 342 -0.457438 -1.067570 -0.127727 -0.5257593 0.4086324 0.3749699 0.6449762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 342 343 -0.007168 0.242380 -0.952986 -0.0725128 -0.5100723 -0.5998014 0.6122143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 343 344 -0.875426 -0.719641 -0.361074 0.4401849 -0.2742301 -0.8398423 0.1603120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 344 345 0.884376 0.179416 0.446054 -0.2655212 0.5866924 0.5088948 0.5712413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 345 346 -0.703286 -0.663088 0.565377 -0.2302125 -0.7513211 -0.2661517 0.5582850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 346 347 0.696870 -0.429566 -0.224767 -0.7515298 -0.2335411 -0.1489898 0.5987183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 347 348 0.573878 0.729708 -0.675378 0.2204291 0.1905532 0.9564615 0.0167886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 348 349 -0.580378 -0.953308 -0.013033 -0.2041147 0.0188665 -0.9548919 0.2148552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 349 350 0.792316 0.365316 -0.242882 0.7339900 -0.1680860 0.6544091 0.0689528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 350 351 -0.493798 -0.810721 0.571385 -0.4336217 0.2789341 -0.2142713 0.8296119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 351 352 -0.009768 -0.914451 -0.372304 -0.4623991 -0.2967045 -0.0668382 0.8328782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 352 353 -0.207540 -0.099430 -1.082853 -0.8525390 -0.3113691 -0.4106055 0.0873483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 353 354 -0.756760 -0.137627 0.172017 -0.5302666 -0.1633198 -0.5118781 0.6558390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 354 355 -0.345699 -1.002207 -0.412863 0.2891938 0.2923050 0.8739309 0.2591706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 355 356 -0.580829 0.552071 -0.752306 -0.7456951 0.4852794 -0.4197737 0.1795350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 356 357 -0.915759 0.497883 -0.120450 0.7625023 0.0906583 -0.3059727 0.5628073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 357 358 -0.720023 -0.743233 0.068883 0.4350189 0.0077289 -0.6875112 0.5814010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 358 359 0.779792 -0.251059 0.642816 -0.2535032 0.1905575 -0.2998731 0.8997222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 359 360 0.423463 -0.567004 -0.776566 0.3231069 0.1220395 -0.7981978 0.4935469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 360 361 0.247871 -0.958137 -0.738494 0.5467990 0.4132655 0.6111044 0.3959469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 361 362 -0.789660 -0.274170 0.080603 -0.1897917 0.1955594 0.6198595 0.7358735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 362 363 -0.380735 1.091325 0.032592 0.5471220 -0.1417165 0.1527822 0.8106982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 363 364 -0.244765 0.542636 -0.697953 -0.8697924 -0.1208420 -0.2272538 0.4209682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 364 365 -0.666544 0.133797 0.562886 -0.4285750 0.5940484 -0.3552773 0.5806961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 365 366 -0.377699 -0.757237 -0.477461 0.0950352 -0.5825948 0.5799962 0.5613875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 366 367 -0.722982 0.401772 0.649644 -0.0502771 0.1977382 0.1755732 0.9630918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 367 368 -0.648806 0.740099 0.428978 0.1194906 0.6870343 -0.5888346 0.4086315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 368 369 -0.024105 -0.272895 -0.868242 0.2262881 -0.5971455 0.5395450 0.5487278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 369 370 -0.892509 0.214192 0.197676 -0.1651536 0.4881013 -0.8562260 0.0368570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 370 371 0.880493 -0.231565 -0.426094 -0.0614011 0.4968940 -0.3358808 0.7978160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 371 372 0.693432 0.297027 0.735140 0.5501867 -0.4858808 -0.4915798 0.4685763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 372 373 -0.245904 0.275859 -0.806142 0.5509087 0.7041145 0.3092496 0.3241715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 373 374 0.733498 -0.785202 0.095007 -0.6104842 0.3636624 -0.0595698 0.7010779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 374 375 0.932974 -0.526857 -0.304981 0.0338843 0.3948840 0.9174218 0.0354378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 375 376 -0.732774 0.266659 -0.516972 -0.1204396 -0.7680341 -0.6245866 0.0742259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 376 377 0.635693 -0.663425 0.362185 -0.5672997 -0.4253692 -0.1208419 0.6947153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 377 378 0.510967 0.008965 -0.691545 -0.7794619 0.5252310 -0.3413837 0.0053471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 378 379 -0.477992 -0.120198 0.909239 0.5203147 0.0088404 0.3660097 0.7715123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 379 380 -1.063719 0.068922 0.391174 -0.0353514 -0.3270125 0.1669852 0.9294778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 380 381 -0.673337 -0.819437 -0.059808 -0.4968737 0.2778645 -0.1752716 0.8032358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 381 382 -0.072536 -0.341014 -0.966340 0.6808070 -0.5571999 0.0384521 0.4738687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 382 383 -0.450847 -0.565852 0.831748 -0.1032646 0.3676513 0.5996495 0.7032705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 383 384 -0.763875 0.513742 0.160708 0.3758420 0.1208653 0.6161566 0.6815317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 384 385 0.381390 0.681302 -0.511725 0.1601225 -0.1739531 0.3099170 0.9208977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 385 386 0.353461 0.204947 -0.999392 -0.5762056 -0.3196787 0.5314549 0.5323048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 386 387 0.356086 0.819847 -0.495626 0.8132122 -0.0964445 0.4770161 0.3191238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 387 388 -0.034976 -0.932440 0.068351 0.3370782 0.7736650 0.0530802 0.5338570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 388 389 -0.696913 -0.660479 0.317812 -0.3070326 -0.5194971 0.2214971 0.7660240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 389 390 -0.448733 -0.766488 0.507261 -0.4909262 0.4618796 -0.4954183 0.5479228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 390 391 0.592049 -0.580543 -0.467793 0.5845026 -0.4386528 0.6758669 0.0956254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 391 392 -0.554867 0.068454 0.901636 0.2784362 0.4628605 0.2405836 0.8064446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 392 393 -0.629488 1.135862 -0.003504 0.2076426 0.1481767 0.9074016 0.3339917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 393 394 1.005871 -0.265740 -0.133240 -0.5064046 0.4064114 -0.4693246 0.5984302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 394 395 0.303677 0.227519 0.745025 0.5531437 -0.4636221 0.2610085 0.6410625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 395 396 0.820817 0.163365 -0.503651 -0.0428517 0.2539743 -0.6431281 0.7211429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 396 397 -0.124541 0.941556 -0.016844 -0.4760117 0.3806785 0.7796308 0.1437798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 397 398 -0.283198 -0.747696 0.795260 0.3862985 -0.8645468 -0.3151462 0.0633647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 398 399 0.376122 0.424309 -0.660055 -0.9086012 -0.2095290 -0.1078710 0.3448266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 399 400 -4.272761 -9.376798 -16.130739 0.1486894 0.5730937 -0.5499201 0.5891035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 400 401 -0.932965 0.013001 0.154487 0.2269143 0.3193611 0.9042755 0.1697183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 401 402 0.794716 0.020344 -0.359489 0.2187717 -0.1628220 -0.6881933 0.6723227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 402 403 -0.246126 0.609808 -0.607150 -0.2935221 -0.1827443 0.8760848 0.3360429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 403 404 0.799256 0.229380 -0.654128 0.0657167 0.1033619 0.6875985 0.7156857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 404 405 0.270602 -0.908145 -0.320584 0.4259798 0.6681654 -0.3825189 0.4751583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 405 406 0.092199 -0.063908 0.997548 0.3966311 0.4296621 -0.6443363 0.4928539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 406 407 -1.013752 -0.020937 0.308535 0.1988074 0.2967960 -0.4059664 0.8411772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 407 408 -0.788764 -0.631934 0.072599 0.2421582 -0.4409076 -0.8502838 0.1548459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 408 409 0.941431 0.346821 -0.152590 -0.2242205 -0.6816389 0.3208936 0.6181592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 409 410 -0.110613 0.269231 -1.018211 -0.2180572 0.0903198 0.0739479 0.9689299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 410 411 0.314196 0.718395 -0.733756 -0.8152647 0.1478566 -0.1088309 0.5492156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 411 412 0.073062 0.607372 0.794051 -0.5657974 0.4348900 -0.2414081 0.6576215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 412 413 -0.667132 -0.756759 0.324737 0.1687350 0.7148189 -0.2822697 0.6171598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 413 414 0.199883 -0.984684 -0.113186 -0.6451628 -0.3824408 0.5078123 0.4238285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 414 415 -0.644226 0.417098 -0.215757 0.7185061 0.3531115 -0.3420334 0.4920106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 415 416 -0.480887 -0.871573 -0.077772 -0.2235745 -0.7400422 0.6324426 0.0486656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 416 417 -0.139070 0.043859 0.940877 0.1576479 0.2394828 -0.5030502 0.8153132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 417 418 -0.627889 0.049664 0.966713 0.6032157 0.6572391 0.4516854 0.0121601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 418 419 0.467364 -0.060632 -0.792337 0.0306510 0.5758944 0.3224496 0.7506214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 419 420 0.691675 0.185015 -0.753933 0.3591713 -0.1501896 0.7597667 0.5207625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 420 421 0.276685 0.284066 -0.809447 0.1634925 0.8465800 -0.4466621 0.2388838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 421 422 0.403318 0.859559 0.255726 0.0858720 -0.4833550 0.3755550 0.7860995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 422 423 0.657413 0.367146 -0.760117 0.6849308 -0.1277882 0.7170667 0.0188486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 423 424 -0.817874 -0.259755 0.552105 0.5605964 0.3465744 0.3962283 0.6392347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 424 425 -0.686459 0.560295 -0.456789 0.4393724 -0.6348010 -0.3902066 0.5017154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 425 426 -0.466200 -0.104950 0.719747 -0.3399871 -0.0672654 -0.7216664 0.5992343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 426 427 0.454783 -0.705180 -0.039552 -0.3538554 -0.4024725 0.7734675 0.3384528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 427 428 -1.090745 -0.116502 -0.111608 -0.1593475 -0.4956630 -0.0477034 0.8524382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 428 429 -0.522959 -0.452003 0.813963 -0.1082958 0.0016650 0.7651603 0.6346645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 429 430 -0.248890 0.673143 0.859404 0.2365874 0.0385237 -0.9587253 0.1529316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 430 431 -0.171699 -0.422139 0.789190 0.2066997 -0.1785515 0.4747119 0.8366858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 431 432 -0.466690 0.121592 0.934865 0.0056291 0.8324250 -0.1602204 0.5304398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 432 433 -0.774942 -0.119430 -0.819942 -0.1208578 -0.2054177 -0.8122562 0.5323879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 433 434 0.082284 -0.749137 -0.510157 -0.2158210 0.7751125 0.3893634 0.4483504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 434 435 0.367269 -0.859044 -0.303942 -0.4301577 0.2385430 0.8236479 0.2822514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 435 436 -0.142229 0.102363 -1.085039 -0.9286609 -0.0582625 -0.2651857 0.2527270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 436 437 -0.696664 0.136014 0.532558 0.2018615 -0.4996064 -0.1213280 0.8336215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 437 438 0.118418 0.373951 0.964806 0.3832678 -0.5393291 0.7085052 0.2454595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 438 439 0.472761 -0.759910 -0.274759 0.6542946 -0.0278220 0.2569818 0.7106932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 439 440 -1.011511 -0.115868 0.088712 -0.2616925 0.1612306 -0.8631296 0.4006608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 440 441 -0.813277 -0.180647 -0.649763 0.2808492 -0.1017851 0.7136536 0.6336104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 441 442 -0.693048 0.256351 -0.811693 -0.5914632 0.4437523 0.3822137 0.5542272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 442 443 0.525208 0.734576 0.458537 -0.0330891 -0.2173052 -0.9689754 0.1130052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 443 444 -0.820786 -0.153820 0.579631 0.5564664 0.3016793 0.3067160 0.7108165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 444 445 -0.585945 0.767309 -0.128058 0.0025106 -0.1454727 0.9826486 0.1150351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 445 446 0.698151 -0.680337 -0.496677 -0.4236970 -0.7714734 0.4700263 0.0662179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 446 447 -0.720210 0.700036 0.288886 0.9086969 0.1255246 0.0944729 0.3867667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 447 448 -0.431508 -0.364128 -1.005078 -0.4930416 -0.7260742 -0.3973591 0.2680149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 448 449 -0.748537 -0.906288 0.266737 -0.3169440 -0.1787500 -0.9098332 0.1994955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 449 450 0.763386 0.318559 -0.294674 -0.3103662 -0.3152109 0.7568805 0.4810891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 450 451 0.073524 -0.367326 -0.920372 0.4202114 0.2520232 0.6361053 0.5960509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 451 452 -0.477297 -0.746577 -0.479646 -0.2867889 0.1216280 0.9196976 0.2389874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 452 453 0.237210 1.003728 -0.417616 0.0630998 0.1678812 -0.0275528 0.9833998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 453 454 0.379313 0.848840 -0.543872 -0.5225766 0.3910138 0.7539608 0.0745988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 454 455 -0.085363 -0.995274 0.325793 0.0346949 -0.1427707 0.0847428 0.9855108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 455 456 -0.112173 -0.766064 0.492057 -0.6234688 0.0981226 -0.7740783 0.0496121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 456 457 0.581665 0.822956 -0.055248 0.8643330 -0.3486446 0.3589550 0.0502675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 457 458 -0.114905 -1.008004 -0.003386 -0.7008426 0.3579648 -0.0238101 0.6165338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 458 459 0.354433 -0.128200 -0.858897 0.4087007 0.1382647 0.4403532 0.7873599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 459 460 0.713620 -0.080562 0.581741 0.2691868 -0.4763483 0.1124232 0.8294527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 460 461 0.120431 1.017528 -0.316811 -0.4525779 -0.3989792 -0.6868906 0.4051791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 461 462 -0.386608 -0.436093 0.789935 0.4975597 0.7869654 0.3251632 0.1654954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 462 463 -0.090947 -0.030405 -0.883701 -0.5892399 -0.3955895 0.1143140 0.6951529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 463 464 -0.274903 0.893873 0.264866 0.1485519 0.0253414 -0.8728583 0.4641213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 464 465 -0.589124 -0.707436 0.091594 0.5464493 0.0538419 -0.6389082 0.5387862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 465 466 0.328877 -0.147837 1.039405 -0.0140915 -0.2493337 0.9014375 0.3536164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 466 467 -0.181148 -0.623912 0.920242 -0.6342367 0.3158047 0.6938117 0.1289826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 467 468 -0.633592 0.743158 -0.366873 -0.0061917 -0.2198975 -0.2272062 0.9486749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 468 469 -0.925968 0.168933 0.064065 -0.1816400 -0.3123963 0.4203730 0.8322872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 469 470 -0.301496 0.744653 0.773134 0.4491012 0.7629456 -0.4418270 0.1449516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 470 471 -0.102710 -0.507887 -0.907006 -0.2007352 -0.3240273 0.8851384 0.2669113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 471 472 -0.089363 0.898097 -0.249040 0.4035687 -0.1892200 -0.1885185 0.8750936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 472 473 -0.683989 0.465378 -0.723405 -0.0173637 0.0218924 0.0842763 0.9960506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 473 474 -0.669126 0.464096 -0.759705 0.4758703 -0.3640536 -0.7981861 0.0625403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 474 475 0.696533 -0.623698 0.253509 0.3709576 0.1452387 -0.8091442 0.4319511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 475 476 -0.162372 0.909224 0.586505 -0.1215836 0.5834788 0.7018204 0.3901512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 476 477 0.387632 0.255958 1.131695 -0.1641416 0.1673020 0.9681948 0.0875577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 477 478 -0.670806 -0.062288 0.893237 0.7224291 0.2310077 -0.2115501 0.6164237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 478 479 -0.766784 0.282394 -0.063233 0.3160447 0.1574132 0.8651610 0.3561366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 479 480 -0.201782 -0.661600 -0.587375 0.8713385 0.3309152 -0.1502475 0.3296818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 480 481 -0.920648 -0.149225 -0.219154 0.0661880 -0.4564520 -0.7402133 0.4892393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 481 482 0.494154 -0.909044 0.254945 0.3605142 -0.3423105 -0.5367499 0.6817277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 482 483 1.004680 0.121401 -0.115908 -0.4287609 0.1385646 0.8659911 0.2168486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 483 484 -0.482103 -0.854548 -0.532865 0.0500249 0.3241914 0.9413125 0.0795506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 484 485 0.267917 0.292161 -0.891789 -0.2477497 0.7531786 0.3406259 0.5052880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 485 486 0.708063 -0.115112 0.483217 0.0998294 -0.2872565 -0.2270602 0.9251818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 486 487 0.944982 0.517291 0.031431 0.4629465 -0.0862832 0.2124074 0.8562236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 487 488 0.982310 -0.220022 -0.321284 0.3094223 -0.0769648 0.7783824 0.5407912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 488 489 -0.685505 -0.653922 0.138446 0.6637293 -0.5560938 0.4415489 0.2350695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 489 490 0.690860 0.547270 0.245588 0.2237955 0.0736386 -0.1879752 0.9534979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 490 491 0.227715 0.941706 -0.060152 0.3885933 0.4884698 0.7342048 0.2670877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 491 492 0.607554 -0.474574 0.685012 -0.5497239 -0.3007809 -0.2890627 0.7237246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 492 493 0.968884 0.151229 -0.409672 0.0816327 0.4312452 0.5249446 0.7292440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 493 494 0.163558 -0.937610 0.582825 -0.4380903 0.5254502 0.6955788 0.2194289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 494 495 -0.409265 0.484423 -0.846908 0.4112985 -0.4577978 -0.7602724 0.2079439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 495 496 0.431536 -0.784554 0.244451 -0.0143667 -0.6934591 -0.2504429 0.6754157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 496 497 0.449805 -0.426945 -0.693713 -0.0506716 0.6138682 0.5769132 0.5364415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 497 498 0.143708 -0.922048 -0.149903 -0.0743099 -0.3841279 0.3332979 0.8578090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 498 499 -0.642417 -0.742940 -0.348431 -0.5095469 -0.4562874 0.6318594 0.3645784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 499 500 -0.737540 -0.035855 -0.595970 0.4110074 -0.5873472 0.4452436 0.5365205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 500 501 -0.851568 -0.537554 0.390318 0.2971453 -0.0469313 0.4008489 0.8653452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 501 502 -0.739567 0.546162 0.545860 0.3315110 0.6473363 0.6479268 0.2263781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 502 503 0.854983 0.426763 -0.253026 -0.2174928 -0.1569291 0.0076081 0.9633339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 503 504 0.856928 0.543151 -0.238758 -0.0668760 0.2003712 -0.8869471 0.4107357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 504 505 -0.936392 0.549413 -0.264425 0.2432788 0.2317300 -0.1842654 0.9236682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 505 506 -0.816683 0.121260 -0.477153 -0.1812633 -0.6992844 0.4659374 0.5109279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 506 507 -0.046194 0.526827 0.686238 0.5958531 0.1682686 0.5117744 0.5955936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 507 508 0.791057 0.680428 -0.223397 0.2953298 -0.0842941 -0.8520810 0.4238310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 508 509 -0.643821 0.195493 -0.675846 0.3691061 0.0094396 0.6909607 0.6214860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 509 510 -0.156262 -0.161257 -1.060448 0.1907152 0.4123657 0.8900358 0.0376628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 510 511 0.025985 -0.776724 -0.511819 0.3789358 0.6798688 -0.3469462 0.5232729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 511 512 0.572937 -0.460364 0.594333 0.0646856 0.1414282 -0.7768742 0.6101478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 512 513 0.221765 0.446744 1.006455 0.1913473 0.1165594 -0.8731322 0.4329438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 513 514 -0.658617 -0.247962 0.693514 0.0439783 0.1743816 -0.0395630 0.9828996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 514 515 -0.929745 -0.564150 0.455624 -0.5081094 0.5588790 0.5909015 0.2833981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 515 516 0.080440 1.101191 -0.339716 0.2067132 -0.4104870 0.6898610 0.5593406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 516 517 0.530774 -0.044534 -0.882611 -0.5435860 -0.0590084 0.3085834 0.7783370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 517 518 0.608052 0.535611 -0.548408 -0.4225682 0.3054475 -0.2771570 0.8070452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 518 519 0.062685 0.933572 0.283621 -0.0215740 -0.2166304 -0.5199461 0.8259914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 519 520 -0.077008 0.688299 -0.940614 0.1312574 0.7434306 0.6258481 0.1959506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 520 521 -0.734309 -0.747852 -0.082940 0.3711709 -0.0243491 0.7822039 0.4997963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 521 522 -0.425659 0.594514 -0.195630 -0.1754222 0.5447094 -0.3954966 0.7184019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 522 523 -0.466686 0.529258 -0.532304 0.1017473 -0.7902093 -0.5913927 0.1243844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 523 524 0.485607 -0.374252 0.853733 0.3044799 0.6660416 0.4184397 0.5372047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 524 525 -0.873746 0.594368 -0.058899 -0.9199605 -0.0215945 -0.3909126 0.0198434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 525 526 -0.438247 -0.667579 -0.577532 0.7032677 0.1284245 -0.2313338 0.6598532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 526 527 -0.057587 -0.597754 0.558785 -0.6975853 -0.1896534 -0.5037437 0.4729151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 527 528 0.797611 0.070801 -0.422245 0.7488537 0.0239742 0.5185422 0.4120162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 528 529 -0.051822 -0.938393 0.579044 -0.0591661 0.0488408 -0.8673531 0.4917445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 529 530 0.696968 0.041338 0.646124 -0.2040273 0.2534390 -0.5716008 0.7532689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 530 531 -0.160691 0.329232 0.992385 0.4249971 -0.3370527 0.4682931 0.6974772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 531 532 0.984721 0.268890 0.168810 0.1582009 0.0086660 0.6344391 0.7565609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 532 533 0.659930 -1.110720 0.138347 -0.5171309 0.5583278 -0.4931048 0.4215369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 533 534 0.854523 -0.214812 0.419096 -0.0168384 0.0180001 -0.9692361 0.2448956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 534 535 -0.724492 0.599085 0.477768 0.2543591 0.0037700 0.4198655 0.8712062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 535 536 0.186092 0.963638 -0.017879 0.2916968 -0.1356629 0.4561969 0.8296945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 536 537 0.817159 0.086475 -0.669345 0.1633028 0.8151340 -0.4484154 0.3283480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 537 538 -0.275406 0.976790 0.304508 -0.1238587 -0.5190377 0.1433911 0.8334854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 538 539 0.557126 0.833878 0.310083 0.3839889 -0.6049788 0.6451659 0.2651680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 539 540 0.592822 0.694667 -0.666884 0.5065469 0.1536595 0.3827669 0.7571582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 540 541 0.760630 0.633983 -0.103384 0.5918101 -0.1391651 -0.4561944 0.6498312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 541 542 0.031985 0.142730 -0.980658 -0.5524643 -0.4219327 -0.1922794 0.6926649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 542 543 -0.699152 0.569855 0.235226 0.4098440 0.0179304 0.8333333 0.3704889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 543 544 0.617410 0.063022 -0.493064 -0.5530666 -0.2146067 -0.7204654 0.3591530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 544 545 -0.666836 0.478319 0.374696 -0.3800421 0.4348972 -0.2996547 0.7593679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 545 546 -0.820032 -0.242896 -0.194280 0.7498821 -0.2218929 -0.5135754 0.3531016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 546 547 -0.081857 -0.215204 0.895517 -0.2002617 0.6504386 0.5504519 0.4835572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 547 548 -0.958566 0.415104 -0.288133 -0.2709335 0.5373818 0.7747838 0.1937161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 548 549 0.671859 0.243446 0.565998 -0.5739441 -0.5548444 0.3388166 0.4979350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 549 550 0.403151 -0.366098 -0.932203 0.4735874 -0.0410822 0.8797629 0.0066654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 550 551 -0.908299 0.410550 -0.074721 0.4334386 0.1533117 0.8853181 0.0695586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 551 552 0.376467 -0.527550 -0.756355 0.5370092 0.3851067 -0.3500173 0.6639291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 552 553 0.984670 -0.296858 0.228506 0.3050298 -0.3167083 -0.5295437 0.7254214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 553 554 0.250106 0.917207 -0.303538 -0.5574386 -0.5947948 -0.1594765 0.5568202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 554 555 -0.006764 0.622558 0.603944 0.4343532 0.0472913 0.8994549 0.0090395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 555 556 0.478181 -0.548386 0.461427 0.4999082 -0.0862014 0.8606622 0.0438376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 556 557 0.305363 0.618201 0.731501 -0.0180173 0.0076795 -0.6885229 0.7249501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 557 558 -0.715509 0.144604 1.032294 -0.6614331 0.3647689 0.6222324 0.2056131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 558 559 -0.847534 0.407092 0.366705 0.7763912 -0.0362467 -0.4104944 0.4768618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 559 560 -0.451354 0.884381 -0.146874 0.3221165 0.4810231 0.8026558 0.1435320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 560 561 -0.620000 -0.459637 0.647930 0.2287863 0.6394299 -0.1890766 0.7092505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 561 562 -0.484150 -0.679130 -0.396484 0.0445713 0.4876317 0.6785783 0.5475037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 562 563 -0.260027 0.093390 -0.916807 0.5854203 0.4070985 0.4456098 0.5412815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 563 564 0.243971 -0.813381 -0.427804 0.5489516 -0.3795792 0.6475789 0.3677137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 564 565 -0.216438 0.437321 0.799139 0.1558627 0.7929989 0.2209269 0.5459404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 565 566 -0.522138 0.931526 -0.522259 0.0261229 -0.1552059 -0.0094187 0.9874918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 566 567 -0.714500 0.565759 -0.353292 -0.5177788 -0.5719652 0.3858167 0.5058719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 567 568 0.757397 0.292806 0.873255 0.0789903 -0.6243573 0.0014361 0.7771335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 568 569 0.827730 0.198886 -0.429424 0.3304974 0.4522426 -0.8079143 0.1830917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 569 570 -0.428156 0.555766 -0.777061 0.4176482 -0.4316100 -0.7986889 0.0371324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 570 571 0.496911 -0.754670 0.263833 0.1075874 -0.3833347 -0.9170352 0.0229305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 571 572 -0.271480 0.683972 -0.415884 -0.5834738 0.2584817 0.7547942 0.1517608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 572 573 0.468925 -0.770934 0.704788 -0.3904605 -0.7817901 -0.0647246 0.4818252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 573 574 0.295062 -0.296483 -0.999059 0.0274857 0.2838233 -0.3122293 0.9062018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 574 575 0.591006 0.024808 -0.656830 0.4932653 -0.0552566 0.8678707 0.0208942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 575 576 -0.919300 -0.118264 0.329537 0.0810983 -0.3022748 -0.0024790 0.9497615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 576 577 -0.757464 0.254445 0.572366 0.4173829 0.1338676 0.7314569 0.5223426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 577 578 0.342387 0.786221 -0.210736 0.5565225 -0.1067001 0.8154166 0.1182940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 578 579 -0.303247 -0.932619 0.157842 0.2040789 0.4405102 -0.0941870 0.8691555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 579 580 1.122021 -0.185651 0.206322 0.1415103 -0.5076412 -0.3980709 0.7508760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 580 581 -0.993890 0.435671 0.007162 -0.4181813 0.2185234 -0.1420473 0.8701692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 581 582 -0.905401 0.304372 0.153057 -0.1593120 -0.0492211 0.8431340 0.5111967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 582 583 0.456411 0.747183 0.260082 -0.1823214 0.5037474 -0.4910778 0.6869062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 583 584 -0.691268 0.564537 0.398770 -0.0654822 0.2268100 -0.7687316 0.5944081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 584 585 -0.407780 -0.965572 -0.127454 -0.1750215 -0.1045492 -0.6360936 0.7441921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 585 586 0.632144 -0.495200 -0.495042 0.6350302 0.0631304 0.5750714 0.5119025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 586 587 -0.640021 -0.407161 0.820640 0.8138268 -0.3721492 0.4388107 0.0814629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 587 588 0.703255 0.569641 -0.533196 -0.5305996 0.0036545 -0.6934932 0.4873580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 588 589 -0.809167 0.529243 0.550580 0.0948469 -0.0843289 0.9022685 0.4120730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 589 590 0.916450 0.217035 0.070499 0.1289202 0.3936417 -0.8492063 0.3275277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 590 591 -0.930569 0.411880 0.141251 0.1272350 -0.3117053 0.8108072 0.4787929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 591 592 0.655301 0.919938 -0.261005 0.1188500 0.0410427 -0.3421198 0.9312058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 592 593 0.186392 1.001181 -0.183101 0.5426126 -0.0718206 0.2576976 0.7962445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 593 594 0.429320 -0.015396 -0.962418 -0.0527095 -0.2973054 -0.3781709 0.8751103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 594 595 -0.443791 0.365632 -0.759068 -0.6230072 0.6274721 0.4419733 0.1509976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 595 596 0.778357 -0.290921 0.766323 0.2093014 -0.3623790 -0.0193901 0.9080190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 596 597 0.942677 0.150420 0.141300 0.6017967 0.0548399 0.4446729 0.6611349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 597 598 0.816155 -0.647422 0.608342 -0.6118386 -0.3004622 -0.3864004 0.6213459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 598 599 0.741631 0.470128 -0.580386 0.0498586 0.2763900 -0.3609799 0.8892785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 599 600 0.879095 -0.302495 0.690748 -0.2957935 0.3894042 -0.4389075 0.7538108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 600 601 0.478088 -0.589700 -0.339434 0.2356642 -0.7684565 0.4895776 0.3380101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 601 602 -0.588027 -0.389589 0.731747 0.2367542 0.5558696 0.1430935 0.7838882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 602 603 -0.782469 -0.043919 -0.243702 0.0167940 0.0180048 0.7886838 0.6143058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 603 604 0.108904 0.796382 -0.371285 -0.2088373 0.7051512 0.0186213 0.6773492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 604 605 0.051738 1.079732 0.330503 0.2492427 -0.8101754 -0.4760029 0.2343398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 605 606 -0.754708 0.597021 0.289334 0.2702299 0.7679156 0.5713357 0.1041965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 606 607 0.906887 0.071991 0.031927 0.0767996 0.5536632 0.1382964 0.8175775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 607 608 0.292776 -0.005706 1.039143 -0.5362042 -0.0624751 -0.3823861 0.7499085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 608 609 0.269769 -0.541489 0.447185 0.4334793 -0.7708701 -0.3796562 0.2715074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 609 610 0.305716 -0.051579 -1.126822 -0.2715460 0.1757960 -0.7475476 0.5801130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 610 611 -0.085811 0.744813 -0.721759 0.6009431 -0.0416190 -0.6839463 0.4115250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 611 612 -0.224436 -0.888543 -0.234030 -0.6836061 -0.0881760 0.2443150 0.6820688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 612 613 -0.480435 0.379728 -0.984416 0.4397381 0.5449878 -0.4568927 0.5485142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 613 614 0.829777 -0.227322 -0.475267 0.3036384 0.6275149 -0.1483758 0.7014367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 614 615 0.519900 -0.063597 0.772054 0.8093617 0.1223289 0.1455457 0.5556849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 615 616 0.554103 0.711078 -0.097529 0.1951388 -0.6431761 -0.0256444 0.7399917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 616 617 -0.231996 0.654871 -0.680896 0.1441891 0.7987478 0.3108264 0.4945689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 617 618 0.881306 0.216647 0.252718 0.2001043 -0.4163273 -0.7159828 0.5234487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 618 619 -0.248409 0.715533 -0.441990 -0.2137169 0.2772188 0.4284344 0.8330179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 619 620 -0.100735 -0.009340 -1.024646 -0.1619403 -0.5432418 -0.0372013 0.8229701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 620 621 -0.417291 -0.875864 0.196166 -0.0250617 -0.1438735 -0.9891488 0.0160318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 621 622 0.466964 0.866101 0.052152 0.3304839 0.1359539 -0.4610651 0.8122290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 622 623 -0.374357 0.572422 -0.742314 0.1774685 -0.6932016 -0.6985530 0.0004180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 623 624 0.456521 -0.560437 0.765406 -0.9208130 -0.1255259 -0.2947587 0.2224050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 624 625 0.622976 0.411346 -0.636451 0.6720014 0.5525110 -0.2446255 0.4281403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 625 626 0.793524 0.411831 0.040569 0.3986488 -0.2239525 -0.2133479 0.8633696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 626 627 0.499648 0.419156 -0.608018 -0.1322917 0.2539316 0.6820490 0.6729241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 627 628 0.892612 -0.687911 -0.267921 -0.1933173 -0.4416745 -0.6677821 0.5671147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 628 629 0.037899 0.634894 -0.827509 -0.5409366 -0.2326047 0.3543918 0.7264222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 629 630 0.574901 0.688780 0.147719 0.3341618 0.4023730 -0.8015982 0.2896069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 630 631 -0.641734 -0.175640 -0.766860 0.2564893 -0.7118363 0.4057528 0.5127055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 631 632 -0.624643 0.669021 0.645542 0.5315657 0.4209995 0.7123863 0.1808397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 632 633 0.972623 -0.132947 -0.228352 -0.0095113 0.3140074 -0.6162704 0.7221632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 633 634 0.251964 1.141118 0.280842 0.1819595 -0.2254199 0.8851256 0.3641830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 634 635 0.511708 -0.759307 -0.263092 -0.1312280 0.4696996 0.8694993 0.0783101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 635 636 -0.501940 0.118368 -0.918452 -0.8691156 -0.0102920 0.0477959 0.4921866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 636 637 -0.336580 0.722524 0.784639 0.5905748 -0.4454383 -0.5895185 0.3244597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 637 638 -0.752985 0.498411 0.411192 -0.3675873 0.3144470 -0.7261075 0.4886416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 638 639 0.222414 -0.832761 -0.364046 -0.2608680 0.4773430 -0.7450567 0.3859819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 639 640 0.204648 0.064608 -0.796407 0.3881724 -0.1974184 0.1167976 0.8925841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 640 641 -0.749817 -0.430590 0.716655 -0.4688908 0.4863655 -0.5923301 0.4390161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 641 642 0.454738 -0.702343 -0.619899 0.7016317 0.3167108 -0.2599821 0.5829379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 642 643 0.713982 0.343833 0.792048 -0.4129250 -0.7682045 -0.4788441 0.1003151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 643 644 -0.001525 1.079067 -0.012215 0.6780576 -0.2151502 0.6965061 0.0939550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 644 645 -0.283638 -0.927150 -0.396548 -0.2696865 0.8753455 -0.1887753 0.3541234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 645 646 0.951500 -0.315092 0.231755 -0.0405613 -0.7511884 0.3103590 0.5811609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 646 647 -0.417770 -0.529407 -0.843919 0.7447765 -0.3276542 0.0156582 0.5811243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 647 648 -0.338670 -0.375109 0.746564 0.1974508 0.1380271 -0.5974307 0.7648780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 648 649 -0.051988 -0.173601 0.918072 0.2751627 -0.4598956 -0.6491109 0.5398486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 649 650 0.262149 0.902116 0.496164 0.6267278 -0.3617730 -0.6838038 0.0935138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 650 651 -0.789176 -0.243461 -0.057044 0.7739943 -0.1629170 -0.5315906 0.3029890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 651 652 -0.069447 0.134698 1.025880 0.9736018 -0.2087797 -0.0920369 0.0063070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 652 653 -0.414282 -0.110825 -0.982829 -0.1919168 -0.2851252 0.5503005 0.7609474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 653 654 -0.248332 0.668894 -0.616903 0.1469598 0.0476809 -0.1939215 0.9687744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 654 655 -0.482541 0.328670 -0.786130 -0.0206611 -0.0234817 0.8627809 0.5046096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 655 656 0.494688 0.318702 -0.779906 0.5177143 0.2797092 -0.1812700 0.7879567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 656 657 0.813046 -0.170210 -0.426462 -0.3241500 0.5216993 -0.7129936 0.3382260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 657 658 -0.624516 0.585444 0.643424 0.2801878 -0.7662548 0.5254961 0.2412514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 658 659 0.738616 0.116725 -0.624761 0.1054323 -0.1048317 -0.8062536 0.5725814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 659 660 -0.972523 0.063543 0.391729 0.3788225 0.6414509 0.6515028 0.1434519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 660 661 -0.285738 1.018241 0.010936 0.1296294 -0.1676523 -0.9705331 0.1146930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 661 662 -0.057968 -0.827048 0.376404 0.4249275 0.3089470 -0.6248913 0.5774939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 662 663 0.075549 -0.002642 0.872866 -0.5076683 -0.1278062 0.6180747 0.5864487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 663 664 -0.581963 -0.701800 0.281812 -0.2450700 -0.1996245 -0.6656342 0.6760340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 664 665 0.787885 -0.309607 -0.193455 0.2794092 -0.5175251 0.8080204 0.0346588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 665 666 -0.607625 0.257019 0.585140 0.3731868 0.5679943 0.7332694 0.0207399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 666 667 0.870580 0.188948 -0.268543 -0.1817887 0.0349974 -0.8615225 0.4727652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 667 668 -0.696482 0.713225 0.023777 -0.2713713 0.3784699 -0.8802600 0.0908869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 668 669 0.404295 -0.540443 -0.809279 0.1811510 0.6520440 0.7150433 0.1753167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 669 670 -0.794778 -0.686463 -0.240023 0.6599801 -0.0413251 -0.6414489 0.3889238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 670 671 0.480597 0.341656 1.074091 -0.0933584 0.2478974 -0.8259282 0.4976682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 671 672 -0.367567 -0.130322 0.985894 0.0727646 0.5892644 -0.7257932 0.3474146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 672 673 -0.122883 -1.070532 0.220243 0.5075487 -0.7119346 -0.4707040 0.1182417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 673 674 0.638615 0.214697 -0.855481 -0.5898507 0.2252892 0.5819015 0.5125540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 674 675 0.961860 -0.432585 -0.326793 -0.2837966 -0.4740704 -0.8255805 0.1146020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 675 676 -0.940459 0.395106 -0.186257 0.2087239 0.6223387 0.3580513 0.6640242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 676 677 0.278663 0.516453 -0.818624 -0.4805678 0.1025129 -0.3249538 0.8080537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 677 678 -0.150634 0.861067 0.267003 0.4493033 0.0453194 -0.7717271 0.4477835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 678 679 -0.702042 -0.698427 -0.238969 -0.5654752 -0.0800504 -0.7345452 0.3664328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 679 680 -0.692265 -0.426412 -0.170134 0.2554712 -0.0915559 0.4530639 0.8491673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 680 681 0.435480 0.397072 0.885412 -0.1794561 0.1655927 -0.0888752 0.9656478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 681 682 -0.221319 0.230116 0.887151 -0.3027101 -0.9160067 0.1569020 0.2113765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 682 683 0.322704 -0.229406 -0.728152 0.0970443 -0.9496986 -0.0267914 0.2965422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 683 684 -0.636647 -0.393299 0.331875 0.8227474 -0.4301873 0.3619587 0.0837346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 684 685 0.282762 0.855216 -0.577792 0.2324178 0.5441583 0.8047923 0.0467227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 685 686 -0.202969 -0.809935 0.672274 -0.6633109 -0.6791032 0.0417670 0.3115974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 686 687 -0.257693 -0.585402 -0.633792 0.6720082 0.1431215 0.3555742 0.6336310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 687 688 -0.752221 -0.680284 0.023495 0.1393297 0.2042449 0.6803254 0.6899482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 688 689 -0.594005 0.715156 -0.431210 0.2771164 -0.4225107 -0.3247612 0.7995132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 689 690 -0.998991 -0.118900 0.400667 0.1022566 0.1248981 0.4970947 0.8525497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 690 691 -0.429355 0.848622 0.046848 0.1133864 0.5431367 0.2581108 0.7909013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 691 692 0.415219 0.812692 -0.124368 -0.2208277 -0.0896316 -0.5473218 0.8022718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 692 693 -0.783092 0.673746 0.213095 -0.5708585 0.1467105 -0.3697761 0.7182356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 693 694 -1.152691 -0.177282 -0.025048 0.8801270 -0.2797098 -0.2307486 0.3064214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 694 695 -0.488961 0.556732 0.629076 0.7361169 -0.2202476 0.6116603 0.1883998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 695 696 0.730806 -0.121882 -1.075471 0.5626476 0.2821738 -0.5933521 0.5017359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 696 697 1.085443 0.246373 -0.184046 -0.1536610 0.6888709 0.4678961 0.5319008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 697 698 -0.189069 -0.608336 0.868291 0.0189744 0.6440801 0.5766314 0.5022917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 698 699 -0.609057 0.616706 -0.501418 0.0517729 -0.1200134 -0.6361918 0.7603791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 699 700 -0.177131 -0.304758 0.940825 0.1728322 -0.6876554 -0.6531416 0.2658291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 700 701 -0.676504 0.305117 0.109321 0.0309719 0.1138989 -0.8125232 0.5708536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 701 702 0.141831 -0.962094 -0.134479 -0.3340045 0.3045055 -0.4925733 0.7436995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 702 703 0.853333 -0.223242 -0.178084 -0.0393038 -0.2849874 -0.1143564 0.9508733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 703 704 0.526382 -0.215841 -0.717386 -0.2417287 0.3822659 -0.7307624 0.5112987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 704 705 0.048259 1.062527 -0.038892 -0.3023678 0.5344740 -0.5970913 0.5161331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 705 706 -0.888207 0.129248 -0.161764 0.1357539 -0.0161041 0.9634071 0.2305609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 706 707 0.958333 0.446863 -0.529787 -0.2104175 0.5958394 0.7739682 0.0409036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 707 708 -0.596410 -1.009363 0.055321 -0.1923327 0.6495836 0.6152841 0.4030817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 708 709 0.266404 0.355619 -0.982331 -0.3266972 -0.3915591 -0.1208043 0.8516787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 709 710 -0.513790 0.658305 -0.347242 -0.2820348 0.1528537 -0.2152437 0.9223678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 710 711 -0.745605 0.605634 -0.146133 -0.2373785 0.1401699 -0.5158555 0.8111084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 711 712 -0.939486 -0.323296 -0.415171 -0.2440885 -0.1780319 -0.9531727 0.0136808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 712 713 0.763112 0.071449 -0.823085 0.0111139 -0.4519845 -0.8287060 0.3298983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 713 714 -0.614698 -0.316119 -0.711958 -0.2831211 -0.5096906 0.1597369 0.7965815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 714 715 -0.983140 0.194274 0.381822 -0.1123905 -0.3007814 -0.3111887 0.8944610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 715 716 -0.421850 -0.301951 0.828384 -0.6434029 0.2728724 -0.6370698 0.3251391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 716 717 0.887102 -0.408915 -0.531839 0.2730888 0.1052533 0.0026673 0.9562098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 717 718 0.835204 -0.601240 -0.016878 0.2610272 0.2316570 -0.9323537 0.0944268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 718 719 -0.660568 0.841065 -0.137433 0.4462495 -0.4074728 -0.6261429 0.4927193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 719 720 -0.688578 0.633629 -0.410193 -0.7028023 0.0115370 -0.0445905 0.7098926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 720 721 0.581646 0.709455 0.537841 -0.2632200 -0.5944800 0.4945303 0.5768435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 721 722 0.556604 -0.404762 -0.633418 -0.2711590 -0.6999027 0.6598551 0.0346450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 722 723 -0.415731 0.829086 -0.155496 0.4592727 -0.1274913 -0.8783335 0.0366719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 723 724 0.201658 -0.822084 0.390385 -0.5007990 0.3592206 0.7163056 0.3272112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 724 725 -0.738225 0.449911 -0.578074 0.2999815 0.5158793 0.7138733 0.3664213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 725 726 0.436656 -0.550395 -0.448067 -0.2229873 0.2676298 -0.6859907 0.6388017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 726 727 0.547975 0.960950 0.138644 -0.4596961 0.3844933 0.3728683 0.7083880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 727 728 0.338905 -0.361772 0.859516 -0.6486480 -0.4481766 -0.4196358 0.4497770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 728 729 0.771351 0.173050 -0.572792 -0.2039786 0.5716697 0.0539352 0.7928919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 729 730 0.820825 -0.039800 0.706888 0.2230539 -0.1482044 0.1982852 0.9428496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 730 731 0.852094 0.064338 0.365275 0.1299594 0.4923581 -0.1043479 0.8542866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 731 732 0.150213 0.325167 0.866613 -0.0388766 -0.5153993 0.2691717 0.8126492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 732 733 0.954422 -0.221196 0.254644 -0.1681136 0.1705970 -0.9531929 0.1845476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 733 734 -0.586671 0.277900 0.652888 0.5325041 -0.3688136 0.7427119 0.1696907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 734 735 0.820205 -0.010161 -0.391953 0.0639101 0.3483355 0.5546360 0.7529654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 735 736 0.409308 -0.975271 0.139865 -0.6151872 -0.0172409 0.7191983 0.3224923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 736 737 -0.635651 0.552554 -0.653102 -0.5302424 0.5769192 0.6051367 0.1407724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 737 738 0.591793 -0.097626 0.933580 0.1956845 -0.2697531 -0.0447044 0.9417762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 738 739 1.100203 0.473679 0.385057 0.5376235 -0.4786127 -0.6271812 0.2975476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 739 740 0.165095 -0.981284 -0.241592 0.2523146 -0.6159735 0.2667723 0.6969552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 740 741 0.816062 -0.495824 -0.303665 0.0047437 -0.1898752 0.9797728 0.0630097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 741 742 -1.046438 0.478038 0.044920 0.3059073 0.3646074 -0.7145432 0.5127477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 742 743 0.075163 -0.901000 -0.519765 -0.0005864 -0.1127606 0.9813609 0.1556132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 743 744 -0.521588 0.952182 -0.052443 0.2761009 0.5621546 0.7588054 0.1787871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 744 745 1.016993 -0.549104 0.222466 -0.8093275 0.3090363 -0.3419782 0.3640557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 745 746 1.021468 -0.023405 0.342925 0.2368380 -0.5773828 0.0823549 0.7770164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 746 747 0.603362 -0.236910 -0.646462 -0.3736732 0.3073593 0.0940202 0.8700913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 747 748 0.983623 -0.040691 -0.124910 0.0332344 -0.1348515 -0.2810828 0.9495804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 748 749 0.608321 0.332916 -0.751541 0.2976364 0.5215950 -0.3389911 0.7241797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 749 750 0.676176 0.750429 -0.271956 -0.3696430 0.0395965 0.8975324 0.2371323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 750 751 0.052970 -1.015756 -0.318853 -0.4988847 -0.0834756 0.3986361 0.7650066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 751 752 -0.424596 -0.225783 -0.862592 0.0825227 -0.1464595 0.9585154 0.2301908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 752 753 0.217498 0.492887 -0.834122 -0.4441609 0.6360183 -0.0588909 0.6282784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 753 754 0.331343 0.692836 0.397114 0.2757524 -0.6063545 0.5084096 0.5457238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 754 755 0.600964 -0.103790 -0.861241 -0.6780554 0.2787001 0.0100556 0.6800486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 755 756 0.886643 0.318883 0.129438 0.4369265 0.6830757 -0.3048364 0.4995774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 756 757 -0.013502 0.974117 -0.173557 0.8424153 -0.3620800 -0.3091190 0.2523487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 757 758 -0.767042 -0.675972 0.034048 -0.0950561 0.3689631 0.8903879 0.2490781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 758 759 0.413849 0.767783 -0.463545 -0.1335392 0.2304838 -0.4549612 0.8497381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 759 760 1.008313 0.178422 -0.476702 0.2424797 -0.2254439 -0.3606642 0.8719518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 760 761 0.888186 -0.307168 0.212030 0.3901430 0.5235517 0.3674860 0.6622961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 761 762 -0.207240 0.124842 0.928247 -0.1655243 0.6635462 0.6650414 0.3000468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 762 763 -0.635877 0.904450 0.293361 0.0153980 0.6221097 -0.3654412 0.6922392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 763 764 -0.515083 0.346578 -0.684301 0.0657182 0.1143376 0.9830333 0.1274896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 764 765 0.462010 -0.146334 -0.722768 -0.3298090 0.8289736 0.2131438 0.3982443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 765 766 0.405424 -0.729291 0.816047 -0.7804426 0.0194520 0.4907746 0.3868737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 766 767 -0.491843 -0.155202 -0.811388 -0.1314564 -0.1173835 -0.4664279 0.8668249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 767 768 -0.593932 -0.415141 -0.802342 0.4257462 0.0726045 -0.5157525 0.7399109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 768 769 0.339797 -0.847668 -0.172072 0.2912122 0.0735383 -0.2500795 0.9204607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 769 770 0.708695 -0.377796 0.353871 -0.3750635 0.2527883 -0.7467376 0.4876561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 770 771 0.292462 0.201590 0.902685 0.5125487 0.1957822 -0.0637821 0.8336037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 771 772 0.058494 0.880183 0.134477 0.8083917 0.2338116 -0.5355060 0.0711921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 772 773 -0.098557 -1.031237 -0.386215 0.1668245 0.1317021 -0.7088289 0.6725962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 773 774 1.004510 0.164217 -0.123827 0.5692100 0.2800786 0.7585007 0.1491061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 774 775 -0.336424 0.183810 0.903300 -0.7565805 0.1829710 0.1169554 0.6167893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 775 776 -0.601939 -0.576801 -0.326419 -0.1353389 -0.6381125 0.5772757 0.4911706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 776 777 -0.312387 -0.060325 0.863279 0.0122493 0.8550582 -0.2049479 0.4761530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 777 778 -0.688942 -0.452813 -0.515956 0.3521742 -0.6564125 0.0226572 0.6667703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 778 779 -0.595701 -0.057931 0.706788 0.4745614 0.4598563 0.0873698 0.7454463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 779 780 -0.589346 -0.942073 0.564849 0.0123302 -0.1361316 -0.8405761 0.5241641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 780 781 -0.026592 0.935241 0.122769 0.2503008 0.5532172 -0.7938063 0.0342332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 781 782 0.338375 -0.439095 -0.674508 0.5296677 0.0493000 -0.8224732 0.2013940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 782 783 0.874870 0.442404 -0.333609 0.3040034 0.1616910 0.9376293 0.0478459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 783 784 -0.653209 -0.565527 0.174366 -0.7427708 0.3818813 -0.5283759 0.1525682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 784 785 0.430008 0.551278 -0.537169 0.2073083 0.1087307 -0.9452018 0.2275840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 785 786 -0.158021 -0.062002 -1.014519 -0.6090114 0.2026537 0.5754517 0.5068451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 786 787 0.512432 0.832777 -0.013625 -0.3950761 -0.0160635 0.5860815 0.7072237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 787 788 0.838336 -0.626103 -0.132079 0.2293761 -0.7233040 0.5577313 0.3363833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 788 789 -0.702420 -0.773168 0.383974 -0.3406462 0.6546785 -0.1463371 0.6587425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 789 790 0.288796 -0.670896 -0.784356 -0.1752201 -0.1864580 0.8772064 0.4062515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 790 791 -0.438751 0.433771 -0.604494 0.2570680 -0.1147647 -0.8673821 0.4103575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 791 792 0.082562 -0.918764 -0.317713 -0.3644247 0.5467244 -0.5701710 0.4931451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 792 793 0.915402 0.251081 0.074190 0.0874077 0.4347931 -0.7258393 0.5258062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 793 794 -0.758712 0.404284 0.268536 0.2879811 0.3533648 0.5324405 0.7132372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 794 795 0.442025 0.799348 -0.545808 -0.2019571 0.1906537 -0.8756091 0.3951875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 795 796 -0.948555 0.036679 -0.225864 0.0425060 -0.2395266 0.6917419 0.6799363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 796 797 -0.278474 0.784124 -0.106969 0.1738054 0.3242139 0.3968697 0.8409349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 797 798 0.657868 0.661302 0.101820 0.4239615 -0.8795699 -0.0734062 0.2030395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 798 799 -0.925476 -0.111662 -0.310819 -0.9571207 -0.1121399 -0.0281733 0.2656143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 799 800 18.100066 -2.224979 -5.809110 0.1487564 -0.4593943 0.8594072 0.1680705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 800 801 1.052783 0.153313 -0.181050 -0.4867242 -0.3255930 0.7810666 0.2168493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 801 802 -0.305521 -0.281399 -1.082530 0.2374527 -0.1338266 0.1983247 0.9414744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 802 803 -0.570508 0.019682 -0.875859 0.7726985 -0.3019484 -0.2308670 0.5083941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 803 804 -0.236445 -0.527338 0.907166 -0.5042469 0.6487918 0.2601092 0.5070971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 804 805 -0.554920 0.041761 -0.843263 -0.2983555 -0.3231025 -0.7874479 0.4318733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 805 806 -0.208765 -0.682210 -0.614154 0.1348960 -0.1117930 -0.6544814 0.7354995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 806 807 0.651529 -0.666143 -0.381252 -0.1024264 0.6476163 -0.0429584 0.7538280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 807 808 0.497990 -0.481312 0.501041 0.2997815 -0.8204691 -0.4494074 0.1870679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 808 809 -0.177746 0.042648 -0.983449 -0.5277971 -0.5227794 0.0556106 0.6671127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 809 810 -0.709058 0.629559 0.133640 0.4502358 0.2243473 0.1931166 0.8424144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 810 811 -0.306942 0.767177 -0.590695 -0.1143407 0.7194216 -0.2239376 0.6474649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 811 812 0.685825 0.686173 -0.229952 -0.7243454 -0.0563411 0.6355137 0.2612886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 812 813 0.734463 -0.708903 -0.218114 0.3617940 0.1706741 -0.8684012 0.2930101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 813 814 0.232206 1.026609 -0.219835 -0.0261974 -0.2436746 -0.9413665 0.2318739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 814 815 -0.581554 -0.755571 0.362257 -0.4963291 -0.3055596 0.4925809 0.6462622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 815 816 -1.118160 -0.259529 0.334644 0.4434344 -0.0183316 0.1484914 0.8837308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 816 817 -0.724575 0.363665 0.269725 -0.2317323 -0.3556759 0.8813024 0.2076077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 817 818 0.949442 -0.217865 0.325169 0.1817622 -0.1287664 0.1197082 0.9674976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 818 819 0.826643 -0.443740 0.366321 0.2835151 -0.3933786 0.8633977 0.1393446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 819 820 -0.430609 -0.695063 -0.790335 0.5277334 0.6504759 -0.5137233 0.1856527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 820 821 0.543312 1.030065 -0.209014 -0.5747904 -0.6551170 -0.3399713 0.3533514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 821 822 0.294253 0.580702 0.595730 0.2281536 0.6122706 -0.6536665 0.3818255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 822 823 -0.679178 -0.501124 -0.423515 0.2097951 0.3183173 0.8473033 0.3697800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 823 824 0.201662 0.423479 -0.840633 -0.1462355 0.1398896 0.5859547 0.7846676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 824 825 0.804142 -0.003374 -0.681935 0.5510746 0.5574913 -0.4826614 0.3905869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 825 826 0.762576 0.702296 0.157420 -0.5807699 0.4802395 0.5066387 0.4188001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 826 827 -0.262272 -0.797642 0.504719 0.0181477 -0.2241098 0.8861225 0.4052559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 827 828 -0.118583 0.425682 0.808961 0.3126705 0.7759698 0.2714046 0.4758650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 828 829 -0.191369 0.853617 -0.465994 -0.2826889 -0.7532297 0.5724586 0.1581872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 829 830 0.714682 0.832429 -0.537620 0.0799151 -0.4651528 0.6988573 0.5374430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 830 831 0.242345 -0.252537 -1.016088 0.4975602 -0.3144356 0.6428435 0.4902207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 831 832 -1.070630 0.306369 -0.029850 0.1471221 -0.8662778 -0.1539743 0.4518958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 832 833 0.530920 0.009873 0.904145 -0.6765265 0.5847802 0.1615639 0.4174219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 833 834 -0.378584 -0.803159 -0.465694 0.6214624 0.2389160 -0.5813112 0.4677403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 834 835 0.464667 -0.039020 0.837795 -0.8245719 -0.0392942 0.5240249 0.2096067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 835 836 -0.584854 -0.260373 -0.766510 -0.1071538 -0.7391642 0.0034102 0.6649381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 836 837 -0.590127 -0.210550 0.546901 0.1416031 0.0536614 0.9864356 0.0633549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 837 838 0.766101 0.610118 0.402637 -0.0102500 0.4417230 -0.8137526 0.3776008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 838 839 -0.899839 -0.128594 0.207111 0.8293167 0.2245774 -0.4950389 0.1293646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 839 840 -0.711072 -0.240316 -0.686026 -0.4638717 -0.0922714 0.4347659 0.7663470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 840 841 0.906028 0.093246 -0.272091 0.1407918 0.1242907 -0.7999380 0.5699374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 841 842 -0.558428 0.752325 -0.410071 -0.6900429 -0.3225551 0.6474408 0.0248878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 842 843 0.749030 -0.408124 0.181520 0.0048818 -0.0474947 0.5112678 0.8580942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 843 844 -0.253231 -1.057756 0.091060 0.4838110 -0.0010157 -0.6536521 0.5819492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 844 845 0.617055 0.301659 0.702751 0.0320801 -0.3929297 0.3613056 0.8450061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 845 846 0.871563 -0.419585 -0.245714 0.2467740 0.4736970 -0.7426812 0.4039040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 846 847 -0.368605 0.883981 0.467284 -0.0374792 0.4895268 -0.8222969 0.2877266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 847 848 -0.234821 -0.749558 -0.554186 -0.0080746 -0.1732785 -0.6463167 0.7430909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 848 849 0.647144 -0.631925 -0.627592 -0.3832439 -0.3713598 -0.4629286 0.7077522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 849 850 -0.204308 0.332720 -1.000430 -0.3171532 0.8253096 0.3427923 0.3174450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 850 851 0.720225 -0.121108 0.893430 -0.3060035 -0.4812645 0.5827296 0.5789409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 851 852 0.063765 -1.077655 -0.348893 -0.4666870 0.0455520 -0.8826275 0.0331207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 852 853 0.092460 1.142653 0.075795 -0.2706504 -0.4623839 -0.5161854 0.6682081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 853 854 -0.573234 0.451469 0.827140 0.0152510 0.7996667 0.5806206 0.1522507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 854 855 0.335732 0.889050 -0.124041 -0.1242497 -0.7806222 -0.0804190 0.6072262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 855 856 -0.158361 1.066540 -0.266690 -0.5298907 0.0287951 0.0373954 0.8467516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 856 857 -0.171058 0.361116 0.813249 -0.1654500 -0.2300668 0.9589857 0.0064759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 857 858 0.135118 -0.916464 0.473126 0.7849381 -0.3309286 -0.4887417 0.1883877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 858 859 0.045173 1.061334 -0.259287 0.7234253 -0.1812778 -0.6352958 0.2004829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 859 860 0.721690 -0.346489 0.580987 -0.0542558 -0.6218656 0.7331948 0.2697496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 860 861 0.072195 -0.337069 -0.927705 -0.4132749 0.8195907 -0.1961221 0.3449799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 861 862 0.600881 0.075324 0.618943 0.0099197 -0.1646442 0.7495617 0.6410547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 862 863 0.215363 -0.945603 0.371702 -0.4025028 -0.2616358 0.8303371 0.2829816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 863 864 -0.938723 0.182971 0.153556 0.5275609 0.1406957 0.8356938 0.0591611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 864 865 0.531335 -0.474884 -0.728989 -0.1911457 -0.0724305 0.8931742 0.4005707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 865 866 -0.455252 -0.147502 -0.873263 0.9157632 -0.3928746 0.0529493 0.0649906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 866 867 -0.660764 0.163628 0.826616 -0.1534247 0.1982234 -0.7401555 0.6239697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 867 868 -0.161996 -0.862581 0.622463 -0.3527700 -0.2812704 -0.6608112 0.5998073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 868 869 0.907642 -0.135714 -0.203665 0.7448028 0.4301331 -0.2896034 0.4199811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 869 870 0.544258 0.711644 0.170345 -0.7407869 0.0397420 0.6705492 0.0043751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 870 871 -0.240728 -0.806688 -0.681203 0.0456961 -0.4738673 -0.4702005 0.7431508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 871 872 0.117154 -0.790665 -0.436198 -0.1891227 0.7251539 -0.0453807 0.6605491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 872 873 0.665138 -0.649108 0.113570 -0.1441530 -0.0947057 0.5615619 0.8092583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 873 874 -0.353599 -0.896622 -0.365794 -0.0292334 -0.2415797 -0.9341355 0.2611045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 874 875 0.789464 0.313774 -0.619284 -0.7695026 0.3496130 -0.5340820 0.0198232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 875 876 -0.650468 -0.538372 0.618505 -0.7812558 0.5381537 -0.1681516 0.2678712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 876 877 0.133461 0.133693 -1.083286 0.1261460 0.5341314 -0.6376700 0.5405255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 877 878 0.548709 0.655074 -0.505260 0.2818093 -0.3557864 -0.6408394 0.6191320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 878 879 -0.775168 0.284306 -0.716201 -0.7818732 -0.3594101 -0.3193300 0.3968968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 879 880 0.005609 0.472543 0.723571 0.4973472 0.2544990 0.7328667 0.3883070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 880 881 0.055745 -0.706049 0.677692 0.6828904 -0.4228060 -0.4331013 0.4090466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 881 882 0.572829 0.740302 -0.358667 -0.9293153 -0.0932414 0.3246722 0.1492213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 882 883 0.884795 -0.613345 -0.119252 0.0840541 -0.1979061 -0.3213236 0.9222360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 883 884 1.120519 -0.222216 -0.306589 0.5812240 0.0554693 0.6375738 0.5025947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 884 885 -0.027660 -0.792516 0.655768 -0.2536717 -0.2753614 0.3962279 0.8383497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 885 886 -0.379146 -0.524188 0.517590 0.1446622 0.7642964 -0.0439965 0.6268877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 886 887 -0.417071 -0.791744 -0.491704 0.2752670 0.0460014 -0.2930888 0.9144457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 887 888 0.060881 -0.939559 0.264169 0.3127761 -0.8754401 0.1285824 0.3453149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 888 889 0.681281 -0.764584 0.182413 -0.7011408 0.2722480 0.2631016 0.6042020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 889 890 0.341164 -0.529820 -0.844740 0.5137368 -0.1029068 -0.7820494 0.3374661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 890 891 0.894446 0.241844 -0.553163 -0.8155876 0.2460072 0.3050936 0.4256938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 891 892 0.957151 -0.272959 0.050650 -0.1922372 0.5058207 -0.8082099 0.2323512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 892 893 -0.632876 0.314520 0.617229 0.2075814 -0.7122955 0.5066581 0.4391385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 893 894 0.913754 0.195122 -0.074274 -0.1075573 0.3633840 -0.8503338 0.3651246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 894 895 -0.847052 0.651663 0.215404 0.5732886 0.3264723 0.6960402 0.2833444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 895 896 0.682630 -0.072904 -0.692710 0.5560913 -0.1362540 0.7829734 0.2432074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 896 897 -0.961242 -0.522498 0.437704 0.3591455 0.0320781 0.5005936 0.7870143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 897 898 -0.569199 0.915014 0.388948 0.5184539 -0.2076956 0.8199728 0.1253505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 898 899 0.354233 -0.432456 -0.736915 -0.4745988 -0.2142536 -0.8001542 0.2976654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 899 900 -0.602932 -0.608282 0.137540 0.4605288 -0.0544987 0.8854358 0.0307666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 900 901 -0.280975 0.657259 0.896658 0.0998553 -0.4361419 0.8692187 0.2103995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 901 902 0.597057 -0.574402 0.030865 -0.5485604 0.4374969 0.7124178 0.0117810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 902 903 0.227350 0.125356 -0.839131 -0.7149696 0.2106144 0.4290907 0.5102365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 903 904 0.793346 0.361424 0.284129 0.1758551 -0.0785340 0.2861611 0.9386262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 904 905 0.814060 -0.040447 -0.223511 -0.2542140 -0.5955960 -0.7472093 0.1493951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 905 906 -0.778046 0.416395 0.061731 -0.2681444 0.1810918 -0.7793550 0.5365725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 906 907 -0.254905 -0.878714 -0.398658 -0.0382614 -0.7224296 -0.1949697 0.6622827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 907 908 -0.411087 -0.952764 -0.025454 -0.3966339 0.7403494 -0.4726880 0.2667028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 908 909 0.843752 -0.024224 0.356524 0.6516452 0.1193191 0.0856737 0.7441650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 909 910 0.952632 0.153245 0.270876 0.7083663 -0.1948077 -0.6180256 0.2798419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 910 911 -0.440386 0.291058 -0.996601 -0.4337511 -0.8288661 -0.0276404 0.3522456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 911 912 -0.514019 0.151729 0.660546 0.0303442 0.1730959 -0.8544906 0.4888383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 912 913 -0.411411 -0.486049 0.812001 -0.1572916 -0.6312214 -0.7556947 0.0757917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 913 914 0.235910 0.846713 -0.547831 -0.0839661 -0.7114102 -0.6609732 0.2235164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 914 915 -0.475245 -0.158407 0.900047 -0.1691500 -0.1937622 -0.9414386 0.2180319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 915 916 1.040555 0.136185 0.447358 -0.3559771 -0.4941789 0.5239153 0.5954664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 916 917 0.092951 -0.659524 -0.515156 0.2473019 -0.3942502 -0.1408666 0.8738221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 917 918 -0.153103 -0.860674 -0.344309 -0.2637348 0.0784850 -0.9173178 0.2877711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 918 919 0.297837 0.774328 -0.474921 -0.5280378 0.0211080 -0.7569593 0.3843736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 919 920 -0.023477 1.052685 0.324629 -0.4364466 0.2456837 -0.4021425 0.7664433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 920 921 0.234766 0.787240 0.755139 -0.0829609 -0.0350535 -0.7930840 0.6024172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 921 922 -0.795278 0.068122 0.706652 -0.3113563 0.6261897 -0.5901214 0.4033615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 922 923 0.160744 -0.574397 -0.588049 0.3698997 0.4982860 -0.3116581 0.7195516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 923 924 0.597029 -0.613749 0.442628 0.9483983 0.0629029 0.0734209 0.3019824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 924 925 0.652909 0.687660 -0.206922 -0.3668145 -0.7388850 -0.0571992 0.5623382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 925 926 0.283531 0.997733 -0.206139 -0.5207057 0.0607844 -0.7811830 0.3390045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 926 927 -0.806538 -0.636605 0.404536 0.6738908 0.2317317 -0.0703147 0.6980168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 927 928 -0.926021 0.219273 0.309719 0.4761044 0.7828853 0.2462207 0.3158964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 928 929 0.206850 -0.254357 -0.815394 -0.0042375 -0.8073323 -0.5856720 0.0720062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 929 930 -0.639488 -0.968051 0.061931 0.0990346 -0.2067722 0.0001106 0.9733640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 930 931 -0.490471 -0.886587 0.342360 -0.1121609 -0.6462049 0.4469698 0.6083232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 931 932 -0.184826 -0.644993 0.807567 0.3983117 0.0431152 0.0552408 0.9145695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 932 933 -0.389469 0.099131 0.983139 0.2569646 0.6915620 0.6008082 0.3077998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 933 934 0.325383 0.770088 -0.080781 0.4310550 -0.4393505 -0.1827549 0.7666573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 934 935 -0.418019 0.485221 -0.715723 -0.4374765 0.3218589 0.7947314 0.2709672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 935 936 1.006513 -0.237561 0.168883 0.0572930 -0.3171803 -0.9452744 0.0507007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 936 937 -0.951310 0.412112 -0.161090 -0.4334572 0.2005588 0.6546959 0.5858877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 937 938 0.227123 0.971722 0.623708 -0.3765729 0.4335356 -0.2191742 0.7887981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 938 939 -0.615294 0.186095 0.802213 -0.3623426 0.5784985 -0.2952171 0.6685014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 939 940 0.631053 0.303652 -0.735326 0.1191632 0.7618631 0.1628484 0.6155040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 940 941 -0.740017 0.548385 0.439237 -0.7323857 -0.1708238 0.6494402 0.1125075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 941 942 -0.274395 -1.148336 0.513627 0.6850260 -0.3361171 -0.4706787 0.4429744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 942 943 0.401039 1.004567 0.362355 -0.0849855 0.4681529 0.8135370 0.3343171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 943 944 0.036866 -0.250030 1.113333 0.0899547 0.7662513 -0.0472147 0.6344587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 944 945 -0.812572 -0.282796 -0.250525 -0.5083281 0.0759452 0.0621966 0.8555504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 945 946 -0.823857 0.096920 -0.408112 -0.4018119 0.2994692 -0.6184784 0.6052684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 946 947 -0.282899 -0.092701 -1.165452 -0.1859233 -0.5972522 0.7406840 0.2451724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 947 948 -0.033773 0.904092 -0.076756 -0.3671593 0.4890895 0.7758639 0.1549862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 948 949 -0.035555 -0.668149 0.880512 -0.6197305 0.2171152 -0.5418877 0.5245502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 949 950 0.908792 -0.468539 -0.162973 -0.0715134 0.6824123 -0.5211316 0.5075639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 950 951 0.021135 0.373452 0.875641 -0.4308239 0.8130727 -0.2369295 0.3117177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 951 952 -0.762233 -0.340099 -0.532435 -0.0355328 0.4680681 -0.8136401 0.3429861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 952 953 1.002742 0.411855 -0.365044 -0.4597824 -0.4165702 0.4294170 0.6562548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 953 954 0.736572 0.112593 -0.739955 0.6785628 -0.5767095 0.1491980 0.4297659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 954 955 -0.438289 -0.850991 0.180928 -0.3000678 -0.1968127 -0.6967351 0.6211154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 955 956 0.854549 -0.354501 -0.613256 -0.1522000 0.0683524 0.7987437 0.5780758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 956 957 -0.195070 -0.581147 -0.752074 -0.3657919 0.8320350 -0.2601687 0.3259237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 957 958 0.859388 0.437448 0.214035 0.5509386 -0.1788194 0.7006925 0.4165576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 958 959 0.237293 -0.784834 0.346128 0.0731840 0.1699756 -0.1596362 0.9696745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 959 960 -0.689756 -0.679341 -0.367095 0.1865447 0.0948800 -0.0389292 0.9770790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 960 961 -0.352867 0.229133 -0.730836 0.4556582 -0.2757053 0.1937747 0.8239014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 961 962 -0.618763 -0.046263 -0.701271 0.4959542 -0.7494007 -0.4304375 0.0845672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 962 963 0.759975 0.199412 0.744916 0.4610837 -0.6591288 -0.5894536 0.0741319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 963 964 -0.827563 0.233127 -0.953665 -0.5527664 0.2408294 -0.3576134 0.7131362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 964 965 -0.538682 0.441467 -0.673647 -0.4783134 0.2740985 0.8075098 0.2097956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 965 966 0.784047 -0.043093 0.406531 0.3458829 0.3842579 0.4985053 0.6958473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 966 967 -0.153846 -0.060872 0.835520 0.0301115 0.6777848 -0.3102944 0.6658967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 967 968 -1.003707 -0.304523 -0.057627 -0.6858136 -0.1569591 -0.4550234 0.5458729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 968 969 -0.334855 -0.444465 -0.911023 -0.0241590 0.0668023 -0.6579381 0.7497141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 969 970 0.567054 -0.418979 -0.699346 -0.5709909 -0.2123064 -0.7840029 0.1193098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 970 971 -0.984258 0.529024 -0.059269 -0.4881450 0.1573315 -0.1081590 0.8516237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 971 972 -0.863876 0.068425 0.029209 -0.2820133 0.3763348 -0.0128737 0.8824256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 972 973 -0.644963 0.297123 -0.799184 0.4150345 0.0256678 0.6159473 0.6691012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 973 974 -0.340914 0.059216 -0.957854 -0.1478709 0.0529149 0.1062738 0.9818554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 974 975 0.161276 0.299743 -0.843737 -0.7032066 -0.0736081 -0.1483724 0.6914246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 975 976 -0.277504 0.714030 0.383811 -0.1682125 -0.2677492 0.3162646 0.8944225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 976 977 0.633627 0.711023 0.563158 0.4957608 0.4161507 -0.3921568 0.6536459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 977 978 -0.268205 0.804245 -0.457343 -0.0283530 0.4074203 -0.7754973 0.4814652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 978 979 -0.380575 -0.446356 -0.978052 -0.0124768 0.4005912 -0.9160317 0.0160265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 979 980 -1.114483 0.277077 -0.499112 0.0359127 0.1186378 -0.6469323 0.7524054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 980 981 0.641286 -0.661559 0.561747 -0.7122764 0.2098320 0.6078273 0.2813873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 981 982 -0.372827 0.103813 -0.992313 -0.7735894 0.1619029 0.5870928 0.1751256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 982 983 0.755158 0.469120 0.572208 0.2756618 -0.5824085 -0.4908652 0.5863977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 983 984 -0.141372 0.884275 -0.318332 0.1066982 -0.2206624 -0.0218272 0.9692508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 984 985 -0.310410 0.926946 -0.665982 -0.8439803 -0.2624712 -0.3896904 0.2587421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 985 986 -0.313947 -0.457329 0.555184 0.1958839 0.0081355 0.8071117 0.5568968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 986 987 -0.631981 0.874779 0.318660 0.5690737 0.4550161 -0.6156149 0.3002228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 987 988 -0.376350 -0.636682 -0.473846 0.0313872 -0.7359602 -0.1887193 0.6494324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 988 989 -0.204039 -0.976887 0.201953 0.1166475 0.6564050 -0.0615180 0.7427930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 989 990 -0.226173 -0.971400 -0.025657 -0.6754969 0.0676039 0.3845554 0.6255004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 990 991 -0.448537 0.221515 -0.740472 0.4487534 -0.4522784 -0.7633881 0.1063169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 991 992 0.581890 -0.884975 0.437604 -0.6503646 0.3523911 -0.2289238 0.6328035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 992 993 0.886359 -0.426432 0.015523 -0.1415110 -0.4047951 -0.4580557 0.7786530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 993 994 0.411268 0.703129 -0.703260 0.6659151 0.1087246 0.5165715 0.5271527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 994 995 0.245541 -1.177544 -0.093923 0.6796937 -0.2497739 -0.1212912 0.6789094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 995 996 0.763053 -0.197794 0.630313 -0.4392392 0.2976382 0.2381041 0.8135028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 996 997 0.101588 -0.856001 0.304916 -0.1190182 0.1496025 0.9020915 0.3868911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 997 998 -0.892714 0.766579 -0.027383 -0.5047784 0.2176964 -0.7534101 0.3608050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 998 999 -0.485314 -0.806885 -0.523740 0.8594520 0.1183313 0.4857467 0.1067248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 999 1000 0.516863 0.675799 -0.890045 0.0259190 0.0528339 0.8548721 0.5154906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1000 1001 -0.655561 -0.488120 0.058439 0.4600166 0.0177790 -0.7078609 0.5357253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1001 1002 0.293000 -0.492272 0.823644 -0.4429692 0.1221748 -0.6949056 0.5531346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1002 1003 0.556295 -0.185395 0.831556 0.0019385 -0.1616800 0.0895247 0.9827722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1003 1004 0.704504 -0.338224 0.666108 0.6815257 0.4922704 -0.3425414 0.4193542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1004 1005 -0.292971 0.871755 0.220640 0.1829006 -0.2995649 -0.1819945 0.9185240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1005 1006 -0.591242 0.764991 -0.137951 0.1690512 -0.5394756 -0.2310002 0.7918502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1006 1007 -0.631676 0.332220 0.632347 -0.0234655 -0.0712652 0.8628330 0.4998899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1007 1008 0.602212 0.324616 0.542547 -0.1161977 0.2715120 0.0958006 0.9505796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1008 1009 0.431640 -0.112761 1.125701 0.5216002 -0.6730291 0.5218486 0.0513724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1009 1010 0.546602 -0.849456 -0.273747 -0.7022504 0.3757784 -0.5703694 0.2007829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1010 1011 0.623241 0.721228 0.418749 -0.1211826 -0.0666391 0.0465320 0.9892971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1011 1012 0.664510 0.639530 0.615598 0.7529970 -0.2813256 -0.2177857 0.5535529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1012 1013 0.415500 0.302011 -0.830386 -0.6557407 0.3761421 -0.4168050 0.5047721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1013 1014 -0.566345 0.729073 0.486415 0.4321143 0.3632607 0.0156809 0.8252715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1014 1015 -0.067133 0.881920 -0.509767 -0.6037467 -0.5279222 0.5971175 0.0154537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1015 1016 0.937133 -0.099073 -0.074113 0.6557075 -0.4869091 0.1565387 0.5553943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1016 1017 0.292754 -0.757913 -0.269515 0.5834725 0.1697834 0.0005827 0.7941871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1017 1018 0.533453 -0.658664 0.624677 -0.1184992 0.8059976 0.2826625 0.5063869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1018 1019 -1.025159 -0.330473 -0.167174 0.1274631 0.0977560 -0.8992658 0.4068389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1019 1020 0.250836 0.536897 0.720284 -0.0286176 -0.0813725 -0.9935830 0.0731604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1020 1021 0.736156 -0.349482 0.065971 -0.4969252 -0.1894434 0.1301934 0.8367952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1021 1022 0.582529 -0.532702 -0.934494 0.7267786 0.2479495 0.1920358 0.6110942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1022 1023 0.158898 -0.500557 0.778983 -0.8395394 0.4362348 0.0317978 0.3222759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1023 1024 0.306052 -0.124975 -0.874765 0.4426142 0.0277070 0.7289059 0.5215565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1024 1025 -0.696339 -0.867878 -0.269229 -0.2195747 0.4858660 0.4520696 0.7150904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1025 1026 -0.147620 0.149989 -0.949868 -0.2245030 0.2035240 -0.9042980 0.3007017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1026 1027 -0.193486 0.158419 -1.126575 0.6273057 -0.2986936 -0.6550397 0.2969726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1027 1028 0.393849 -0.849665 0.167863 0.3230220 0.0054128 -0.2893276 0.9010644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1028 1029 0.996342 -0.323783 0.530429 -0.8279649 0.3334281 0.4481724 0.0494098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1029 1030 0.169671 -0.116169 -1.032419 0.4944096 0.8000501 -0.2957878 0.1672977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1030 1031 0.484936 0.392908 0.865978 0.1412810 -0.9466355 0.2570487 0.1335919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1031 1032 -0.215667 -0.300865 -0.843219 0.6115103 -0.5666792 0.1410769 0.5338794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1032 1033 -0.591091 -0.351500 0.713312 0.1299458 0.0498877 -0.5737147 0.8071411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1033 1034 -0.312758 -0.530772 0.861600 0.2434091 0.5063994 0.8130268 0.1526403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1034 1035 0.339706 0.978440 -0.054507 -0.2519824 0.3315996 -0.4761064 0.7745123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1035 1036 -0.731985 0.652735 0.250865 0.3500759 -0.2430202 -0.1811538 0.8863246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1036 1037 -0.772219 0.416881 0.316147 -0.4223769 0.4263173 -0.0544603 0.7980510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1037 1038 -0.836865 0.668960 -0.621926 0.1207492 -0.3590582 0.1797225 0.9078528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1038 1039 -0.690373 0.768144 0.327787 0.4506340 -0.3740978 0.7804557 0.2187892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1039 1040 0.331866 -0.955800 0.325918 0.4256934 0.3512957 0.0105431 0.8338257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1040 1041 -0.901105 0.588288 0.007336 0.8829884 0.1419504 0.4444197 0.0516988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1041 1042 -0.248522 -0.748809 -0.443862 0.2369687 0.2244684 0.8196071 0.4708545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1042 1043 -0.699601 0.223616 -0.638791 0.3126832 0.0851418 0.1963227 0.9254391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1043 1044 -0.681932 -0.180588 -0.895260 0.3070945 -0.1256133 -0.6739430 0.6600872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1044 1045 0.170645 -0.888735 -0.186424 0.3992121 -0.2701235 0.7267085 0.4894464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1045 1046 -0.545398 -0.083866 0.628390 -0.4812947 0.4063594 -0.6936455 0.3494044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1046 1047 0.490488 -0.808872 -0.457476 0.3063652 -0.1827398 -0.6554599 0.6656717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1047 1048 0.824787 -0.024487 -0.604303 -0.2218944 0.0408604 0.7931039 0.5657557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1048 1049 0.062917 -0.759343 -0.696125 -0.0655425 0.6373659 -0.7282256 0.2432210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1049 1050 0.592880 0.541671 0.690332 -0.4269182 0.5836177 -0.4515027 0.5227585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1050 1051 -0.738967 -0.490016 0.547664 0.0382008 0.3791920 -0.9083625 0.1721389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1051 1052 0.741607 -0.158509 0.462256 -0.6880840 -0.5145202 0.4078687 0.3089540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1052 1053 -0.360634 -0.169554 -0.976811 0.0804300 0.2092690 -0.9323004 0.2838193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1053 1054 0.694799 0.236784 -0.728771 0.0094802 0.4641162 0.5336534 0.7069090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1054 1055 0.840815 -0.652224 0.009275 0.3139697 0.5038459 0.7440810 0.3064404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1055 1056 -0.915252 0.197782 0.124025 -0.6237919 0.0501922 0.0882738 0.7749659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1056 1057 -1.022094 0.045549 0.198067 -0.1584905 -0.3922856 0.5715910 0.7030479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1057 1058 -0.136390 0.435120 0.865652 -0.1169757 -0.8867131 0.4371326 0.0947191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1058 1059 0.143006 -0.320826 -0.989554 0.0950002 0.1986010 -0.8252561 0.5200816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1059 1060 -0.164808 0.610569 0.614561 -0.4852027 -0.3693178 -0.7474560 0.2636138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1060 1061 0.574146 0.185840 -0.583448 -0.6250988 0.3781272 0.5699837 0.3760184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1061 1062 0.622190 -0.801806 -0.151718 0.5007468 0.2696696 -0.4169925 0.7089769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1062 1063 0.476064 0.271702 0.678964 0.1948884 -0.5080684 -0.0488854 0.8375531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1063 1064 0.796002 0.536754 -0.409107 -0.3662430 0.2701921 0.8467608 0.2754241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1064 1065 -0.043180 -0.889470 -0.198055 -0.6829934 0.2021757 0.6737846 0.1966195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1065 1066 0.150838 0.779209 -0.561431 0.0338841 0.0272379 0.2571195 0.9654012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1066 1067 0.568317 0.621231 -0.529965 -0.3249341 0.5868872 0.7410351 0.0291225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1067 1068 -0.372809 -0.970405 0.222097 0.4309072 0.3167305 0.0109124 0.8449152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1068 1069 -0.666043 -0.551141 0.640638 -0.5747973 -0.6593644 -0.3380327 0.3472471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1069 1070 0.070118 -0.626862 -0.621094 -0.0451369 -0.3243569 0.7190677 0.6129412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1070 1071 -0.893061 0.228096 -0.236814 0.6010197 -0.1019195 0.1044101 0.7858029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1071 1072 -0.986313 0.042105 -0.228829 -0.0894376 -0.4981944 -0.5603217 0.6556240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1072 1073 0.082300 -0.910679 0.344765 -0.2892461 -0.2765239 -0.8919463 0.2104828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1073 1074 0.427056 0.824798 -0.189632 0.3780824 -0.0780746 -0.4420555 0.8096574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1074 1075 -0.258297 0.273572 -0.946401 -0.1578394 0.3308452 0.9285221 0.0589491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1075 1076 0.567204 -0.832602 -0.208767 0.2925951 0.4004778 -0.4790676 0.7242236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1076 1077 0.790533 0.235019 0.654389 -0.8019864 -0.2698206 0.5288410 0.0658924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1077 1078 -0.303542 -0.119823 -0.898079 -0.4768792 -0.5661151 -0.1080016 0.6636532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1078 1079 -1.067570 0.075654 0.107215 0.3544531 0.4056869 0.0743425 0.8391986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1079 1080 -0.502227 0.670709 0.327942 0.2537878 0.4930698 -0.0852686 0.8277700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1080 1081 -0.363563 0.506517 0.922126 -0.0996215 0.0211326 0.7942732 0.5989650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1081 1082 0.614947 0.094825 0.932288 -0.1707984 0.0104324 0.9390019 0.2983193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1082 1083 -0.644415 -0.432755 0.732949 -0.4217646 0.2283877 0.2657455 0.8362613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1083 1084 -0.938603 -0.393725 -0.004878 -0.3396883 0.7599670 -0.5417128 0.1166586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1084 1085 0.875293 0.391636 -0.302962 -0.5758204 0.5380983 -0.2780998 0.5491280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1085 1086 0.248846 -0.140002 1.148807 0.2802282 -0.4610103 0.8345568 0.1116090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1086 1087 0.584800 -0.836149 0.244842 -0.3631119 -0.4457701 0.0146890 0.8180605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1087 1088 0.346670 -0.480564 -0.660332 0.2358081 0.1924792 -0.4884382 0.8177863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1088 1089 0.856169 -0.278740 -0.334854 -0.3389169 0.4530272 -0.4031974 0.7192590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1089 1090 0.532586 0.404570 0.675231 -0.2790374 -0.4379547 0.2482170 0.8177543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1090 1091 0.988583 -0.280851 0.018350 -0.0546156 0.2114019 -0.1226158 0.9681383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1091 1092 0.696863 -0.188437 0.642605 0.1611825 -0.7984142 0.0560951 0.5774152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1092 1093 0.417539 -0.213162 -0.733096 0.7876765 -0.3531241 0.4412590 0.2452748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1093 1094 -0.537909 -0.192518 0.875400 0.6064697 0.5950864 0.0632038 0.5235188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1094 1095 -0.573097 0.318712 -0.683413 -0.2433729 -0.5773102 -0.6923747 0.3579104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1095 1096 -0.095444 -0.881443 0.344468 -0.3967562 0.0810963 -0.8901153 0.2090517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1096 1097 0.731213 0.601649 0.257285 -0.4523241 -0.0178707 -0.5413605 0.7085283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1097 1098 -0.415487 0.460006 0.921245 0.3756613 0.2222745 0.8898784 0.1326238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1098 1099 0.710282 -0.009023 0.676066 0.3140855 0.3941507 0.8179890 0.2772896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1099 1100 0.434166 -0.726396 0.488544 -0.7766309 -0.2154859 -0.3409609 0.4838966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1100 1101 -0.399351 0.907110 0.315581 0.3904476 0.2096457 -0.1252416 0.8876452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1101 1102 -0.412456 0.430049 -0.585046 -0.5687490 -0.3684327 0.0438911 0.7340677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1102 1103 -0.603392 0.933595 0.539089 -0.2311224 -0.2619491 -0.8695113 0.3491637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1103 1104 0.278042 -0.591277 0.819524 0.0171135 -0.1982875 -0.6276117 0.7526571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1104 1105 0.852292 0.294032 0.502255 0.3364516 0.2229510 0.5585777 0.7246269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1105 1106 0.524824 0.000393 0.767272 -0.1566455 0.9524167 0.1264951 0.2288311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1106 1107 -1.096573 -0.190557 -0.519906 -0.2458530 -0.3917063 -0.8072856 0.3666230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1107 1108 0.176785 -0.605181 -0.454794 0.4025906 -0.1135793 0.8682790 0.2666686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1108 1109 -0.831256 0.298963 0.381435 0.1610350 -0.5481472 -0.6138645 0.5447685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1109 1110 -0.067753 -0.108802 0.955954 -0.2684215 -0.0200576 0.8621281 0.4292816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1110 1111 -0.425719 -0.134484 0.695948 0.4786284 0.0350582 -0.5270810 0.7013355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1111 1112 -0.471403 -0.012464 0.750204 -0.3971275 -0.1726525 -0.6006923 0.6720488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1112 1113 0.411544 -0.729816 0.485544 -0.4024431 0.3534823 0.4904553 0.6874179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1113 1114 -0.507433 -0.809613 -0.482360 0.5526915 0.3086516 -0.7132800 0.3008286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1114 1115 0.732683 0.128181 0.717861 -0.1412493 -0.1300582 0.5143829 0.8357893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1115 1116 0.381580 -0.802055 0.424925 0.5999668 0.0839182 0.0748893 0.7920790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1116 1117 0.392286 0.258443 0.912909 -0.1423413 -0.3200085 -0.3967648 0.8484758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1117 1118 0.414038 0.437826 0.566146 -0.5857969 -0.2668493 0.2148524 0.7344875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1118 1119 0.948607 -0.492096 -0.131236 0.2732542 0.1341521 0.1592267 0.9391391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1119 1120 -0.022967 -0.508431 -0.822935 0.2487855 -0.0813774 0.6426092 0.7200951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1120 1121 0.190966 0.351888 -0.939320 -0.6817282 0.0541695 -0.0478897 0.7280240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1121 1122 0.035531 1.066836 0.419225 -0.0715988 -0.6638004 0.2258613 0.7093865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1122 1123 0.503887 0.622244 -0.249332 -0.0956225 0.2161381 -0.7732463 0.5884139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1123 1124 -0.735867 0.820534 -0.163046 -0.5186341 -0.0278808 0.7565044 0.3974197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1124 1125 0.532387 -0.119994 0.869146 0.8199893 -0.4004971 0.2630592 0.3130806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1125 1126 0.983184 -0.268537 -0.359021 -0.3535377 0.6959526 0.0505867 0.6229783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1126 1127 0.350110 -0.378375 0.676432 -0.3565581 -0.7408299 -0.0588513 0.5661925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1127 1128 0.502715 -0.576377 -0.795680 -0.2205279 0.3311649 0.4638960 0.7915161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1128 1129 0.607472 -0.500498 -0.485744 0.1203089 0.0851879 0.6409078 0.7533299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1129 1130 -0.430783 -0.818104 -0.395623 0.0103894 0.3790975 -0.9247271 0.0325112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1130 1131 0.671553 0.867868 0.175079 -0.5196492 -0.1046503 -0.8191439 0.2191263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1131 1132 -0.196926 -0.673854 0.806544 -0.5838768 -0.5710457 0.0301551 0.5762685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1132 1133 0.147541 -0.919166 -0.638089 0.6905461 -0.2622524 0.6601168 0.1364389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1133 1134 -0.262949 0.541507 0.661028 -0.2171771 -0.0127182 -0.0324930 0.9755084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1134 1135 -0.332847 0.651742 0.989196 0.1363212 -0.8530095 0.4787754 0.1567338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1135 1136 0.576037 -0.234204 -0.833252 0.2117969 -0.3015522 -0.2671600 0.8904122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1136 1137 0.164121 -0.461638 -0.867812 0.3465829 0.4799912 0.4720775 0.6531704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1137 1138 -0.354790 -0.906202 -0.175781 -0.0468240 0.2723066 0.6557422 0.7026086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1138 1139 -0.995593 0.075742 -0.553129 -0.3284229 0.2283202 0.4353006 0.8065493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1139 1140 -0.871036 -0.076534 -0.082411 -0.7638960 -0.0084211 -0.0014097 0.6452828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1140 1141 -0.078675 -0.360859 -0.955868 0.6605860 0.4666470 -0.5827366 0.0792762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1141 1142 0.658035 0.511322 0.538852 0.0018888 -0.1125700 -0.8541326 0.5077223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1142 1143 -0.885750 0.339108 0.747596 0.0081511 0.3728793 -0.9021523 0.2168314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1143 1144 0.153030 -0.962099 0.058473 -0.7297000 0.0839606 -0.2054737 0.6467373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1144 1145 0.555047 0.212534 -0.775871 -0.0850485 0.6117903 -0.7782340 0.1132753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1145 1146 -0.851396 0.826097 -0.277050 0.3553238 -0.4212814 -0.0341274 0.8337279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1146 1147 -0.792149 0.558537 0.036275 0.4834405 0.3635300 0.6290132 0.4883376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1147 1148 0.724107 0.134145 -0.595154 -0.0559014 0.7589900 0.2575964 0.5953598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1148 1149 0.722503 -0.377226 0.722246 0.7483075 0.2397796 -0.4073239 0.4654341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1149 1150 -0.313911 0.866760 -0.205610 -0.0736489 -0.7983342 0.1791979 0.5701986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1150 1151 0.238787 0.920014 0.322383 0.0629198 0.6566407 -0.7475037 0.0781173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1151 1152 -0.388845 -0.232624 -0.975399 -0.5275060 0.2420435 0.7827415 0.2246513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1152 1153 0.978887 0.482171 -0.049171 0.2000859 0.5730202 0.6794188 0.4123149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1153 1154 -0.106933 -0.521394 0.921946 0.1727941 0.1937417 -0.5320098 0.8059603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1154 1155 -0.036800 -0.197937 0.934210 -0.4053811 -0.2675147 0.5134055 0.7074722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1155 1156 -0.389279 -0.916855 0.358929 -0.6213973 0.3609747 -0.0305910 0.6947135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1156 1157 -0.047905 -0.608906 -0.767594 0.8436041 -0.3578094 0.3647304 0.1651555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1157 1158 -0.392926 0.429809 0.795144 -0.8248449 0.2607472 -0.1931512 0.4629626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1158 1159 -0.628610 -0.780838 -0.556928 -0.1867977 0.8952093 -0.3545582 0.1949242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1159 1160 0.386285 -0.026101 -0.794630 0.7091895 0.5950016 -0.1278450 0.3559199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1160 1161 0.096958 -1.188125 -0.067871 -0.1205294 -0.0397854 0.9348026 0.3317134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1161 1162 -0.712708 0.714092 0.078239 -0.0383576 -0.5535289 -0.4230281 0.7163670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1162 1163 -0.453353 0.081426 0.850885 -0.7782541 0.5784683 0.1295557 0.2071479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1163 1164 -0.498454 0.091163 -0.937144 -0.6119283 -0.1555699 0.6022393 0.4885178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1164 1165 0.571475 0.741502 0.479325 -0.0963677 -0.0704609 -0.9240875 0.3630575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1165 1166 -0.670697 0.066954 0.898149 -0.0216199 0.5893427 -0.2140228 0.7787181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1166 1167 -0.744656 -0.519251 -0.514150 0.0322652 0.0543331 -0.9474902 0.3134791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1167 1168 0.969985 0.022537 -0.490887 -0.0384239 0.6408950 0.6613436 0.3878167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1168 1169 -0.428702 -0.904827 0.604928 -0.2844575 0.1006454 -0.8762970 0.3755768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1169 1170 1.004782 0.316518 0.081493 0.4531941 0.7584303 -0.2822471 0.3738115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1170 1171 -0.246573 0.993733 0.144410 -0.7062195 0.4013748 0.5557748 0.1768239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1171 1172 -0.574428 -0.324504 0.989568 -0.4395606 -0.6861017 0.2345368 0.5301352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1172 1173 0.146401 -0.957428 -0.023028 -0.3282639 -0.5301995 -0.7778388 0.0780910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1173 1174 -0.396643 0.604548 -0.875707 -0.4751785 0.1256030 -0.0749449 0.8676477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1174 1175 -0.416681 1.095612 0.053404 0.5191985 -0.0551818 -0.5352665 0.6639861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1175 1176 -0.888558 -0.348901 -0.397869 -0.1990535 -0.1308869 -0.9520016 0.1921960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1176 1177 0.778480 -0.257117 -0.663203 -0.0590898 0.1083847 -0.9889119 0.0825495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1177 1178 -0.549961 0.626455 -0.600373 -0.4632508 0.1144022 0.3604198 0.8015038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1178 1179 -0.014899 1.061851 0.227982 0.0373819 -0.1680603 0.9850674 0.0007574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1179 1180 0.666897 -0.142839 -0.567959 0.2212452 -0.0106668 -0.5121236 0.8298592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1180 1181 -0.651225 0.364920 -0.402893 -0.3596588 0.0233012 -0.0522833 0.9313265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1181 1182 -0.959256 0.495212 -0.038903 -0.3689961 -0.0057271 -0.8311006 0.4160298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1182 1183 -0.124863 -0.862842 -0.595083 -0.1322994 -0.5331923 0.6686168 0.5011531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1183 1184 -1.031438 0.226332 0.647134 0.5314191 -0.0176069 0.7671037 0.3589367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1184 1185 0.437127 0.357799 -0.799427 0.0416704 0.0812305 0.2975063 0.9503448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1185 1186 0.979471 -0.200470 -0.497278 0.2389562 -0.1118184 0.9593342 0.1003718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1186 1187 -0.821313 0.016591 -0.050621 0.3461870 -0.1845130 0.2821780 0.8754913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1187 1188 -0.619666 0.637183 0.130244 -0.0577766 -0.5024816 0.6123826 0.6075868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1188 1189 0.687138 0.390713 0.378588 0.0425230 -0.2681948 0.3553823 0.8944086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1189 1190 0.835756 0.078979 -0.185669 -0.0320842 -0.7964070 0.5760242 0.1813908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1190 1191 -0.852465 -0.071280 -0.252436 0.5281467 0.8032107 -0.2223493 0.1627095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1191 1192 0.443550 -0.909049 0.220500 0.7991409 -0.1837278 -0.5097991 0.2602359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1192 1193 0.703515 0.562972 -0.359603 -0.2184283 0.6995200 0.6798858 0.0267611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1193 1194 -0.513315 -0.670530 0.416631 -0.6986602 -0.2370325 0.4639219 0.4903734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1194 1195 -0.890842 -0.054030 0.100312 0.6461675 0.1687495 -0.4788143 0.5698492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1195 1196 -0.564793 -0.516942 0.420567 0.2481947 0.0003348 -0.2978890 0.9217708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1196 1197 -0.188725 -0.773960 0.873531 -0.1548797 0.4450976 0.6829577 0.5580942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1197 1198 -1.102088 0.550371 -0.041130 -0.2552172 0.6578369 0.6191301 0.3446632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1198 1199 0.758891 0.957409 0.312960 -0.5141215 -0.4654393 -0.2179618 0.6866863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1199 1200 -12.468752 -12.164084 -7.450674 -0.0123884 0.5294898 -0.7581546 0.3803797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1200 1201 -0.907770 -0.045529 0.151543 0.1217838 -0.1056960 0.6584982 0.7351035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1201 1202 -0.126760 0.989711 -0.151484 0.2272849 0.2080377 0.3635624 0.8791383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1202 1203 0.656373 0.643430 -0.191997 -0.0348002 -0.5948548 -0.6803790 0.4266392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1203 1204 -0.843655 0.374555 0.229238 -0.8774488 -0.1524270 -0.4299506 0.1482975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1204 1205 -0.221844 -0.643430 -0.687147 0.6114019 0.0803773 0.3467220 0.7067610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1205 1206 -0.912210 -0.664822 0.008084 -0.3680964 0.0735447 0.8789313 0.2942379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1206 1207 0.372577 0.848580 0.166363 -0.1545206 0.2344324 0.4720837 0.8356445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1207 1208 0.270906 0.204508 0.983392 0.1729818 -0.1017997 0.2587781 0.9448534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1208 1209 0.760672 0.183593 0.758532 -0.1439766 -0.9677306 0.0554328 0.1992373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1209 1210 -0.592402 0.102411 -0.740205 0.3155157 0.9192379 0.1982744 0.1270386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1210 1211 0.638725 -0.506771 0.608148 -0.9693590 0.0162413 0.0418040 0.2415196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1211 1212 0.485256 -0.052222 -0.762189 0.3273219 -0.2466728 -0.2452720 0.8785525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1212 1213 0.469796 -0.487161 -0.845878 0.3281519 0.5103067 0.7628247 0.2236110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1213 1214 -0.707617 -0.653211 -0.232892 -0.1492488 -0.5461040 0.1740480 0.8057310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1214 1215 -0.525681 -0.433574 0.476162 0.3906435 0.0969985 -0.6869637 0.6050370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1215 1216 -0.016643 -0.251628 1.053779 -0.0225729 -0.5707367 -0.5830163 0.5777906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1216 1217 0.673770 0.480441 0.118989 0.3864794 0.5468177 0.2795455 0.6880976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1217 1218 0.607822 0.572708 0.585511 -0.2189505 -0.2053728 -0.2305513 0.9255964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1218 1219 0.608765 0.559422 0.772714 0.3107744 0.2735592 0.8785624 0.2381444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1219 1220 0.686503 -0.854691 -0.164476 -0.0448219 0.6383092 -0.1150032 0.7598201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1220 1221 0.946545 0.362633 -0.366697 0.0323328 0.3309090 0.9243897 0.1869694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1221 1222 -0.495241 -0.777345 0.425951 -0.5341837 -0.1033430 -0.4023808 0.7362457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1222 1223 0.177086 -0.967721 -0.719292 0.2168122 -0.0371659 0.0148242 0.9753930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1223 1224 0.112830 -0.905956 -0.631995 0.2601764 0.0403402 -0.8137554 0.5181535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1224 1225 1.062549 0.321431 -0.085388 0.0470761 0.3808670 0.4910720 0.7820310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1225 1226 0.458813 -0.366083 0.790875 -0.7157088 0.4535802 0.1457398 0.5106719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1226 1227 0.011467 -0.720440 -0.598431 -0.4748085 -0.1105167 0.5153244 0.7048289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1227 1228 -0.534129 0.358853 -0.879765 -0.4370530 -0.5522329 -0.0900033 0.7042179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1228 1229 -0.839734 0.535778 0.467865 -0.3802753 -0.8709519 0.2953146 0.0980960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1229 1230 0.631312 -0.612361 -0.177209 0.6110254 -0.1698244 0.7575842 0.1545115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1230 1231 -0.427723 0.247804 0.814922 -0.5252995 0.6888482 -0.0150308 0.4993222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1231 1232 -0.679936 0.132866 -0.691349 0.2921115 -0.6978299 0.3636053 0.5435949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1232 1233 -0.491680 0.699831 0.479917 0.7417192 0.3070840 0.4560844 0.3841082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1233 1234 0.449563 -0.164545 -0.870766 0.3023347 0.3787293 -0.2114580 0.8487894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1234 1235 0.830505 -0.126895 0.024805 0.4599809 0.5042105 0.7303408 0.0281382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1235 1236 -0.926512 0.263660 0.522948 0.0019418 0.4835352 0.8634736 0.1435382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1236 1237 0.853021 0.403273 0.504790 -0.1256991 -0.5404339 0.0486419 0.8305209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1237 1238 0.838893 0.267931 -0.613573 -0.0980461 0.4094045 -0.1914003 0.8866458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1238 1239 0.696371 0.599079 0.059039 0.0926896 -0.1157839 0.9487781 0.2789675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1239 1240 -0.673305 0.207924 0.657348 -0.6472705 -0.0081474 -0.6968909 0.3087354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1240 1241 -0.186319 -0.699814 0.523807 -0.3496594 0.6888300 -0.1144018 0.6246308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1241 1242 0.113844 -0.865915 -0.670384 0.2534067 -0.0078033 0.9283262 0.2719091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1242 1243 -0.665356 0.651516 -0.489107 -0.2693458 0.2320909 -0.9342451 0.0277992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1243 1244 0.115007 -0.101672 -0.875339 0.4953980 -0.4327817 0.7393876 0.1434812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1244 1245 -0.770350 0.507061 0.015118 0.4176522 0.3645810 0.2384253 0.7973711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1245 1246 -0.120310 0.451715 -0.779322 -0.3756961 -0.1829665 0.2192602 0.8816465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1246 1247 -0.095583 1.157317 -0.294196 -0.4726560 -0.1370756 -0.6520880 0.5767043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1247 1248 -0.872231 -0.219754 0.656973 -0.4354074 -0.3293604 0.2714814 0.7926159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1248 1249 -0.766760 -0.655966 0.455254 -0.1783279 0.4818588 -0.1216907 0.8492365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1249 1250 -0.484388 -0.788188 -0.364075 -0.0038481 0.3731772 0.4762952 0.7961575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1250 1251 -0.485576 -0.400669 -0.810931 0.1002005 -0.1873527 0.9654169 0.1510926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1251 1252 0.267112 0.442789 -0.785300 0.4504806 0.3529417 0.4162013 0.7065945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1252 1253 0.652497 -0.751763 -0.365291 -0.5059491 0.3976603 -0.6358893 0.4260594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1253 1254 0.510881 0.793675 0.598980 0.0909378 -0.5417624 -0.0174747 0.8354151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1254 1255 0.435908 0.614034 -0.190841 -0.1103613 -0.2466247 -0.7740657 0.5725547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1255 1256 -1.113512 0.343322 -0.057246 -0.7861907 -0.1840250 0.0844256 0.5838760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1256 1257 -0.824863 -0.232088 0.847902 0.6667637 -0.0184767 0.7046993 0.2418339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1257 1258 0.618501 0.610267 -0.502855 -0.8514528 0.0887365 -0.3772657 0.3533051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1258 1259 -0.292194 0.046261 1.170983 -0.0187001 -0.9259489 0.3186219 0.2018639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1259 1260 0.445529 -0.235967 0.864992 0.5235956 -0.7825660 0.0942154 0.3233599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1260 1261 0.082350 0.864573 -0.552916 -0.5768369 0.5629140 -0.3483000 0.4786168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1261 1262 -0.625792 0.697456 0.232705 -0.6407062 -0.5320277 0.3469230 0.4313776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1262 1263 0.675198 -0.367346 0.304497 0.0610244 -0.9609040 0.2244045 0.1502735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1263 1264 -0.426446 -0.932977 -0.483752 0.2829575 -0.0227674 -0.7886514 0.5453859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1264 1265 0.928628 -0.138959 0.002154 -0.3134714 -0.3878048 -0.8168747 0.2899289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1265 1266 -0.579872 0.939253 0.277717 -0.4481860 -0.1186044 0.6064811 0.6459435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1266 1267 0.594546 -0.052129 1.083105 -0.7871880 -0.4038600 0.4656228 0.0206797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1267 1268 -0.680328 -0.280273 -0.851878 -0.5633889 0.0021057 0.6538478 0.5050461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1268 1269 0.396197 0.828584 -0.023289 -0.0549497 0.1357313 -0.6636443 0.7335761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1269 1270 -0.920382 0.685368 0.053223 0.5039221 -0.1555053 0.6820662 0.5066225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1270 1271 0.240562 0.434259 -0.827778 -0.6310774 -0.2446195 -0.6737580 0.2965683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1271 1272 -0.915138 -0.147435 0.267093 0.1897022 -0.3868596 0.2105302 0.8775134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1272 1273 -0.154775 0.560338 0.838249 0.3591405 0.2818558 0.7762904 0.4346823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1273 1274 0.754126 0.410998 0.439840 0.2119043 -0.8433150 0.1271237 0.4772379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1274 1275 -0.120664 0.131608 -0.871364 -0.6245717 0.1788824 -0.7579652 0.0583101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1275 1276 -0.924182 0.317331 -0.154287 -0.3319836 -0.5508652 0.2586794 0.7207076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1276 1277 -0.255022 0.342688 0.926188 -0.0979315 -0.2059021 0.0432423 0.9726993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1277 1278 0.352782 -0.077914 0.903414 0.2427674 -0.2677698 -0.4005965 0.8419536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1278 1279 0.322259 0.537705 0.415880 -0.1096538 0.5013348 0.4987301 0.6985039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1279 1280 0.823609 -0.644961 0.420021 0.5585630 -0.5203289 0.4009574 0.5064567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1280 1281 -0.897250 -0.218440 0.328663 0.4736020 -0.2113313 0.8537640 0.0461223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1281 1282 0.846659 0.315298 -0.727033 0.2905429 0.0171464 -0.1653891 0.9423042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1282 1283 0.796214 0.194946 -0.565725 -0.5198148 0.5340471 -0.2832910 0.6035996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1283 1284 0.105510 0.496403 0.817960 0.2074979 0.2534295 -0.2560953 0.9094687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1284 1285 -0.441312 0.464221 0.585402 -0.2421018 0.2849084 -0.8625093 0.3410156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1285 1286 0.318129 -0.788921 0.061851 -0.2604174 0.4792576 -0.7715886 0.3273316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1286 1287 0.543932 0.449531 0.682607 0.5411611 -0.3570189 0.3232304 0.6893506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1287 1288 0.790895 0.052158 -0.475450 0.1315280 -0.6795784 -0.6497405 0.3141827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1288 1289 -0.682012 -0.186326 -0.776063 -0.6747517 -0.1178157 -0.5967238 0.4180316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1289 1290 -0.703758 -0.024604 -0.625217 0.3027213 0.3311739 -0.0180511 0.8935087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1290 1291 -0.352196 -0.792076 -0.834523 -0.6832373 -0.5441446 0.4807467 0.0773052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1291 1292 -0.143114 0.422266 0.730728 0.2663732 -0.2756570 0.0954766 0.9186636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1292 1293 0.317683 0.773893 0.667287 0.4510276 0.2512150 -0.2844165 0.8078195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1293 1294 -0.375850 0.898434 -0.329740 0.3852107 -0.2873306 0.7139300 0.5092718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1294 1295 0.158543 0.011991 -0.894473 0.0047775 0.2396598 0.7206637 0.6505261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1295 1296 0.400768 -0.486632 -0.952219 0.4750673 0.6100510 0.5039060 0.3850033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1296 1297 -0.651999 -0.724395 0.405528 -0.4769703 -0.5108162 0.5426429 0.4659451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1297 1298 -0.565058 -0.359493 0.671638 0.5947148 0.1967107 0.6291543 0.4602001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1298 1299 0.040241 0.856842 -0.401890 0.1148794 0.4084110 -0.1037335 0.8995791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1299 1300 -0.657686 -0.248539 -0.733237 0.8921591 -0.1362870 -0.4268131 0.0575198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1300 1301 -0.237763 0.959884 -0.110478 -0.0070326 -0.5630292 0.7747880 0.2874930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1301 1302 0.630996 -0.245945 -0.598416 0.4167398 0.6799700 0.3530483 0.4892091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1302 1303 0.154722 -0.488014 0.893324 -0.0714225 0.3140980 0.9358178 0.1431305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1303 1304 -0.442326 0.976314 0.441190 0.3957457 -0.5366381 0.5280393 0.5259081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1304 1305 0.496533 0.558959 -0.798649 0.1974190 -0.3969061 0.5759578 0.6868507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1305 1306 -0.074955 -0.040362 -0.894349 -0.1801329 -0.8955533 0.3900140 0.1158687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1306 1307 0.078406 0.512058 0.885869 0.1209598 0.6188796 -0.2429333 0.7371161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1307 1308 -1.011032 0.307854 0.167101 0.6074658 0.0598495 -0.4973598 0.6164711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1308 1309 -0.555807 -0.667777 0.258749 -0.1543566 0.3038924 0.9401044 0.0052056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1309 1310 0.665978 0.650182 -0.139168 -0.6824240 0.0188917 0.7267480 0.0760120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1310 1311 0.138018 -0.996298 -0.622278 0.0708974 -0.2808108 -0.4400882 0.8499654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1311 1312 0.381098 -0.508814 -0.710511 0.3279809 0.4424768 -0.2084510 0.8082023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1312 1313 1.004455 -0.293304 0.274870 -0.4887043 0.1346644 -0.0903287 0.8572481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1313 1314 0.867265 -0.420303 0.178866 -0.2006562 -0.4774306 0.5232370 0.6767719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1314 1315 -0.307789 -0.895613 -0.609126 -0.4593853 0.2608794 0.8487854 0.0216894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1315 1316 0.730416 0.445978 -0.419099 -0.0215021 0.5732412 0.0980299 0.8132173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1316 1317 0.850397 0.335556 0.602286 -0.2329367 0.0141434 -0.6885350 0.6866294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1317 1318 -0.048796 0.150912 0.800051 -0.2526348 -0.8992095 0.3434762 0.0980921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1318 1319 0.211506 -0.535883 -0.734075 0.1033777 0.9091290 -0.2314414 0.3305032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1319 1320 0.811490 -0.559644 -0.125096 0.0769901 0.2325938 -0.0501099 0.9682260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1320 1321 0.304180 -0.355432 -1.000179 0.5049159 -0.7541214 0.1050257 0.4066085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1321 1322 -0.526099 -0.526763 0.687681 0.4408310 0.1817728 0.8367245 0.2692931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1322 1323 0.173761 1.100766 -0.289614 0.3817536 0.0121760 0.5370125 0.7521526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1323 1324 0.694512 -0.056159 -0.669307 -0.2242905 -0.2090185 -0.9205753 0.2419632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1324 1325 -0.664940 0.454349 -0.165173 0.3694049 0.1413244 -0.9178713 0.0328599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1325 1326 0.932930 -0.598614 0.140612 -0.3478076 -0.0919211 0.8025920 0.4758430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1326 1327 -0.819630 -0.502218 -0.418853 0.2765307 -0.2307204 0.7936416 0.4903385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1327 1328 -0.336935 0.813690 -0.356995 0.3695076 -0.2767386 0.8837136 0.0770070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1328 1329 -0.048325 -0.569954 -0.655421 -0.1005256 0.1374973 -0.8711482 0.4605322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1329 1330 0.381350 0.678927 -0.769740 0.1131713 -0.2486155 -0.5993636 0.7524266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1330 1331 -0.730886 0.334032 -0.637883 -0.4651927 -0.1572134 -0.2511428 0.8341504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1331 1332 -1.097399 0.154962 0.023273 0.5039435 -0.0982323 -0.3351076 0.7899964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1332 1333 -0.886353 -0.611377 0.194274 -0.3306795 -0.6614176 -0.5781670 0.3448200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1333 1334 0.585892 -0.634181 -0.667273 0.1241970 -0.1937551 0.1939408 0.9536357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1334 1335 0.268155 -0.715516 -0.680702 -0.1573575 0.3615220 0.1353239 0.9089708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1335 1336 0.500600 -0.796040 -0.785100 -0.0104685 0.4784878 -0.7480823 0.4596876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1336 1337 0.618105 0.657965 0.265833 0.0483081 0.1302631 0.9488039 0.2836707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1337 1338 0.079607 -0.879642 0.576737 0.1919820 -0.5896627 -0.7799985 0.0839236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1338 1339 0.198184 0.969572 -0.522638 0.4257560 -0.1811450 -0.8761230 0.1353766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1339 1340 0.677108 -0.367101 0.682285 0.4920987 0.0418146 -0.0901321 0.8648506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1340 1341 -0.013117 0.941393 -0.561215 -0.4344969 0.5912883 0.5823730 0.3499031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1341 1342 0.505860 -0.214825 0.817293 -0.0269710 0.8522078 0.5192222 0.0585047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1342 1343 -0.637601 0.656932 -0.452802 0.2702352 -0.0041817 0.1386248 0.9527532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1343 1344 -0.278164 0.416432 -0.810501 -0.2883531 0.2435749 -0.9243939 0.0549513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1344 1345 0.106865 -0.021287 -0.935348 -0.4655923 -0.5673493 0.2829521 0.6174760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1345 1346 -0.271043 0.783394 0.351943 0.0963815 0.1025414 0.6725694 0.7265303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1346 1347 0.950134 0.379698 0.421857 0.3280825 -0.4113523 -0.7143239 0.4614027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1347 1348 -0.898695 0.527892 -0.387978 0.5737868 0.0610281 0.0074731 0.8166936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1348 1349 -0.667765 -0.155874 -0.627341 -0.1876377 -0.6968865 0.2414958 0.6487073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1349 1350 -0.803907 0.257464 0.848493 0.0171987 0.6167633 0.4866811 0.6184245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1350 1351 -0.311232 1.086384 -0.116408 -0.1074031 0.6081391 -0.4656513 0.6338772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1351 1352 -0.584846 0.343165 -0.919076 0.9027421 0.1039650 -0.2862004 0.3038706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1352 1353 -0.085832 -0.902456 0.316641 -0.3587809 0.4079696 0.2791585 0.7917749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1353 1354 -0.640324 -0.560283 -0.503006 0.1552688 0.4039366 0.8309747 0.3495824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1354 1355 0.085315 0.194930 -1.062034 -0.4070211 -0.2276685 -0.6789673 0.5670135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1355 1356 -0.873258 0.146678 -0.481728 -0.5185647 0.3546964 0.3782097 0.6798813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1356 1357 0.167638 0.977854 -0.105042 -0.5727269 -0.3839709 -0.4971133 0.5267149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1357 1358 -0.136494 -0.131290 0.896446 0.2136703 0.1276444 -0.6476836 0.7201096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1358 1359 -0.392811 0.030173 0.752495 -0.6146990 -0.6770911 -0.3448259 0.2116315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1359 1360 0.339567 -0.712825 0.598053 0.5261502 0.6132916 0.2623136 0.5274760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1360 1361 -0.151697 0.403903 -0.970842 -0.1695671 0.3634396 0.9014039 0.1631863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1361 1362 0.549685 -0.724042 -0.376558 0.9302853 -0.0460481 -0.1168048 0.3446818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1362 1363 0.620170 0.261332 0.579900 -0.2548036 0.1806213 0.7340195 0.6030476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1363 1364 -0.142036 -0.938428 0.564896 0.5000291 0.1936704 -0.4361516 0.7226579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1364 1365 -0.142636 -0.097817 1.092257 -0.3100304 0.1243971 0.0342467 0.9419308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1365 1366 -0.342611 -0.544275 0.744644 0.0622204 -0.9707131 -0.2264546 0.0506253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1366 1367 0.584095 -0.181343 -1.028950 -0.8062355 -0.0700345 -0.4059228 0.4246247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1367 1368 -0.518304 0.870959 0.414841 -0.0500605 0.4676993 -0.8810606 0.0498349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1368 1369 0.308150 -0.748934 -0.478495 -0.0126357 0.1463649 0.9686765 0.2002088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1369 1370 -0.443093 0.463445 -0.681012 -0.1296366 -0.1451284 -0.8577079 0.4758879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1370 1371 -0.316428 -0.694972 -0.407188 -0.3292299 0.0964369 -0.9315121 0.1208006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1371 1372 0.044617 0.762116 -0.384456 -0.6961876 0.5590750 -0.1549321 0.4227931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1372 1373 -0.703227 0.201787 0.851970 0.2038294 0.8636877 -0.3795426 0.2616191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1373 1374 0.067439 -0.550385 -0.878093 0.2185838 0.3158860 0.0409494 0.9223667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1374 1375 0.319905 -0.803294 -0.217277 -0.1737317 -0.8499458 0.4530552 0.2053058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1375 1376 -0.827379 -0.299592 0.648211 0.8673903 -0.2387986 0.1475536 0.4108980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1376 1377 -0.329199 0.743271 -0.118194 0.1140812 -0.3649778 -0.8798784 0.2821181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1377 1378 -0.227455 -0.846509 0.408655 0.2129748 -0.6049639 -0.3743533 0.6697164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1378 1379 1.029175 -0.177266 0.100714 -0.0176452 -0.1693813 0.4149190 0.8937790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1379 1380 0.588404 0.512406 -0.448621 0.0204809 -0.2547942 0.0131191 0.9666894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1380 1381 -0.425150 0.867541 0.550771 0.1942788 0.4778242 0.6694042 0.5346381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1381 1382 0.952194 0.424271 0.452038 0.5593864 -0.3933287 0.5173585 0.5145090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1382 1383 0.641866 -0.992622 -0.317886 -0.4689256 -0.0222183 -0.1509767 0.8699547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1383 1384 0.579976 0.057845 -0.767051 0.0743617 0.0416769 -0.1505039 0.9849274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1384 1385 0.479746 0.177854 -0.768866 -0.6583253 0.4184619 -0.1447973 0.6087127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1385 1386 0.635123 0.544554 0.797095 -0.2318064 -0.5882257 0.7731145 0.0504997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1386 1387 -0.452183 -0.731657 -0.364424 0.5642858 0.4365369 -0.2967402 0.6347931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1387 1388 0.121541 -0.846372 0.602646 0.6382571 -0.7076104 -0.2768699 0.1235250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1388 1389 0.665436 0.045039 -0.696370 -0.8740618 0.1421556 -0.0641511 0.4601004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1389 1390 0.374469 0.420248 0.753062 -0.6333915 -0.2453029 0.4080841 0.6100075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1390 1391 0.502034 -0.785924 -0.043408 -0.0568748 0.0667781 0.5853175 0.8060455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1391 1392 -0.337228 -0.828108 -0.182302 -0.3215266 -0.2641938 0.4308988 0.8007175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1392 1393 -0.925409 0.231681 0.053880 0.2109714 0.2718578 0.8390915 0.4213191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1393 1394 0.649638 0.467620 -0.646349 0.4687560 0.3241046 0.7979274 0.1963057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1394 1395 -0.353708 -0.802222 0.433904 -0.6435119 -0.4006314 -0.6503822 0.0488870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1395 1396 0.042588 0.359659 -0.787666 -0.1775843 -0.1033549 0.5401074 0.8161284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1396 1397 0.694098 0.390581 -0.888657 0.7210023 -0.5418594 0.3569059 0.2432328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1397 1398 -0.730643 -0.585912 0.332672 -0.5651475 0.0161303 -0.6852936 0.4590433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1398 1399 0.934119 -0.477711 -0.676427 0.1470562 0.8187579 -0.1811291 0.5245972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1399 1400 -0.645532 -0.730988 0.482631 -0.5161083 -0.1240380 -0.6805692 0.5050469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1400 1401 -0.658303 0.157228 -0.614851 0.4016093 0.8742739 -0.0420745 0.2694158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1401 1402 0.904155 -0.318823 0.147505 -0.0996740 -0.1814097 0.4042577 0.8909160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1402 1403 0.428239 -0.965261 0.054562 0.0409072 0.2117120 0.9654548 0.1462933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1403 1404 -0.474757 0.694184 -0.320804 -0.7844258 -0.3372890 -0.4186217 0.3093025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1404 1405 -0.305817 -0.750634 0.590436 -0.6094724 0.4599272 -0.0514390 0.6437114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1405 1406 -0.106218 -0.543659 -0.890776 -0.1738428 0.0424516 0.8750344 0.4497680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1406 1407 0.190134 0.371445 -0.986964 -0.3943585 -0.7392376 -0.5226796 0.1575283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1407 1408 -0.277970 -0.386223 0.519379 -0.8004430 0.5236084 -0.2917604 0.0010147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1408 1409 0.754132 0.470426 -0.680997 0.2285641 -0.3230319 0.8974258 0.1950274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1409 1410 -0.718908 -0.198845 -0.518814 0.3425388 0.0417738 -0.4525817 0.8222481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1410 1411 -0.188936 -1.085426 -0.005767 0.0170608 0.1239882 -0.8158015 0.5646271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1411 1412 0.958844 0.198105 0.059450 0.0585840 0.3754358 0.8011436 0.4623687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1412 1413 -0.465978 -0.623702 0.731294 -0.6088278 -0.5572661 0.4557965 0.3332158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1413 1414 -0.621287 -0.575872 0.222801 0.0679933 -0.5171498 0.8496907 0.0771921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1414 1415 0.738807 0.312593 0.626052 0.7565439 -0.0840583 -0.2789465 0.5854609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1415 1416 0.433789 0.856211 -0.711302 0.3028125 0.2408286 0.9097536 0.1505144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1416 1417 -0.299095 -0.931910 -0.305407 -0.7699707 -0.4500805 -0.4378619 0.1133562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1417 1418 -0.803100 0.296898 -0.491660 -0.3399380 0.5215750 -0.0931649 0.7769955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1418 1419 0.152985 0.693905 -0.588775 0.2326516 0.1069341 -0.1315764 0.9576669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1419 1420 -0.837128 -0.389145 0.152379 0.1137824 0.0397691 0.9759424 0.1816822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1420 1421 0.069152 0.276078 0.956250 -0.5501702 -0.0136622 -0.8349393 0.0015899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1421 1422 0.966600 -0.383146 0.255015 -0.1541419 -0.3734272 0.4035102 0.8209579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1422 1423 0.124707 -0.779090 -0.198585 0.4372485 0.7672027 0.3957620 0.2521631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1423 1424 -0.840229 -0.415662 -0.094497 -0.6375071 -0.0538583 -0.3128266 0.7020139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1424 1425 -0.660002 -0.439310 -0.730791 -0.0704628 -0.2365617 0.7027329 0.6672631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1425 1426 -0.717273 0.938558 -0.320952 -0.0812002 -0.3513605 0.5022051 0.7859659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1426 1427 0.232269 0.848191 -0.237943 0.8118214 0.2639483 0.4733383 0.2173203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1427 1428 0.599506 -0.858321 0.074146 -0.1497633 0.8871182 0.2294016 0.3714394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1428 1429 -0.251369 -0.894670 -0.120569 0.5359360 -0.1272040 -0.0260368 0.8342145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1429 1430 -0.375298 -0.355106 0.676632 -0.7334769 0.6055045 0.2896058 0.1072586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1430 1431 -0.070990 0.468618 -0.806863 -0.3388366 0.3180169 0.2467522 0.8503930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1431 1432 0.560266 0.612314 -0.206001 0.0574984 -0.3322461 -0.4681687 0.8167769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1432 1433 -0.404798 0.975986 -0.311438 0.2046435 -0.1559308 -0.1439121 0.9555605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1433 1434 -0.553730 0.418834 -0.367666 -0.6385151 -0.0178689 0.7644020 0.0875712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1434 1435 0.726736 -0.067657 0.915384 -0.4948273 0.1030090 0.0495908 0.8614382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1435 1436 0.609209 -0.816858 0.291757 -0.3237887 -0.4023299 0.5820427 0.6281066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1436 1437 -0.548433 -0.597364 -0.454014 -0.2221527 0.1571736 0.8652258 0.4211045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1437 1438 -0.071807 1.052345 -0.126242 -0.4318129 0.1952515 -0.8503338 0.2287943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1438 1439 -0.668877 -0.587705 -0.434299 -0.0466670 -0.3651964 0.9258959 0.0846785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1439 1440 0.457058 -0.702350 0.497281 0.1584772 0.2885977 -0.4403640 0.8352700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1440 1441 0.426547 -0.859762 -0.007083 -0.1912271 -0.0325663 0.9394256 0.2825797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1441 1442 -0.649138 0.687516 -0.269059 0.2219069 0.1064094 -0.3233750 0.9137084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1442 1443 -0.664992 -0.005786 -0.596116 -0.4453318 -0.3301967 -0.7700566 0.3156938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1443 1444 -0.310686 -0.751473 -0.775739 0.0608740 -0.3080874 0.6933539 0.6485652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1444 1445 -0.783059 0.426366 -0.109370 0.5701408 -0.3151667 0.1059319 0.7512575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1445 1446 -0.836729 0.529894 -0.057692 0.2471460 0.4822310 0.8246004 0.1625000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1446 1447 1.000526 -0.394265 -0.147620 0.0739345 0.0310897 -0.3280069 0.9412644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1447 1448 0.879766 0.458124 -0.097769 -0.2533854 0.1813627 0.9235468 0.2235280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1448 1449 -0.581093 -0.602888 -0.235233 0.0776536 0.5988547 -0.4612218 0.6500903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1449 1450 0.611365 -0.712036 0.091707 -0.3513503 -0.6627428 0.3429141 0.5654510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1450 1451 -0.495541 -0.280294 -0.871528 -0.1415582 -0.6454723 0.7503032 0.0192847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1451 1452 0.710660 0.626240 0.226665 0.0221572 -0.2527001 -0.8617971 0.4392693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1452 1453 -0.837495 0.369980 0.216956 -0.2036670 0.6792598 0.6867700 0.1596021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1453 1454 0.442068 0.751671 0.431556 0.2322940 -0.3758460 -0.3821140 0.8116453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1454 1455 -0.184726 0.891962 -0.271105 -0.0912335 -0.6993579 -0.3413312 0.6213437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1455 1456 -0.643580 0.616982 0.583133 -0.8134537 0.1380207 0.1047276 0.5552257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1456 1457 -0.647091 -0.448933 0.251618 0.0385216 -0.1614974 0.9860605 0.0109291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1457 1458 0.784070 0.365334 0.291016 -0.1603568 -0.6539713 -0.1926411 0.7137904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1458 1459 0.277534 0.829074 -0.713299 -0.1914198 0.5969513 -0.0825883 0.7747172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1459 1460 -0.656637 0.619817 -0.439645 0.2108056 -0.1284138 -0.9176014 0.3115742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1460 1461 0.920473 0.250265 -0.444884 0.3591416 -0.4209922 0.5478883 0.6273765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1461 1462 -0.113762 -0.830662 -0.657146 -0.4867896 -0.1722181 -0.8562564 0.0142077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1462 1463 -0.329904 0.550241 -0.792344 -0.1421402 -0.4044305 0.8988395 0.0912122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1463 1464 0.576630 0.178648 -0.601605 -0.1362504 -0.7264491 0.5637961 0.3685667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1464 1465 -0.315731 0.508218 -0.711205 -0.3045559 0.1706767 0.6003492 0.7195109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1465 1466 0.711621 0.947984 0.005064 0.2431541 0.0431070 -0.6798390 0.6905337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1466 1467 -0.733269 0.546484 -0.433344 -0.4847358 -0.6477581 0.0931597 0.5803119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1467 1468 -0.075267 0.046776 0.952562 0.7170867 -0.4127637 -0.2060754 0.5224421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1468 1469 0.036302 0.977913 -0.430509 -0.2673521 0.3464820 0.8931302 0.1038823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1469 1470 0.372937 -0.790061 0.391140 0.0148580 0.2146859 0.9628844 0.1629196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1470 1471 -0.521196 0.853952 -0.103262 -0.4459100 0.5350497 -0.2405466 0.6760351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1471 1472 -0.732611 0.706790 -0.444684 0.3463249 0.3014738 0.0417093 0.8873742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1472 1473 -0.022964 0.170121 -0.884517 0.6543788 -0.2602366 -0.5953430 0.3868230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1473 1474 0.458674 -0.678363 0.057859 0.6478910 -0.4971853 -0.5692194 0.0950441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1474 1475 0.578891 0.291846 -0.570366 -0.2854635 0.3466319 0.4327684 0.7817087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1475 1476 0.942476 -0.144283 -0.156796 -0.2272645 0.7134596 0.4576001 0.4795085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1476 1477 -0.348463 -0.933039 0.267584 -0.1136614 0.0943990 -0.9101548 0.3870247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1477 1478 0.848210 0.474818 0.246103 0.7118537 0.2416799 -0.5942526 0.2858653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1478 1479 -0.210868 0.598126 -0.795284 -0.8997940 -0.1387689 -0.3332459 0.2450735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1479 1480 0.714521 0.386768 0.469089 0.4601437 0.7923306 -0.3806003 0.1249936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1480 1481 0.133745 0.893254 0.281128 0.4951689 -0.1333895 -0.6960109 0.5025771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1481 1482 -0.902894 -0.056054 -0.409142 -0.6006837 -0.2154899 0.0146942 0.7697579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1482 1483 -0.968260 0.213415 -0.063460 -0.5008032 -0.7822843 0.3504218 0.1201332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1483 1484 0.471399 -0.728967 0.452820 0.9119750 -0.2851698 0.0978677 0.2782115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1484 1485 0.957430 0.247014 0.036965 -0.4952793 0.2346216 -0.1150143 0.8285064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1485 1486 0.456465 -0.018667 0.781225 -0.9010416 -0.1340149 0.1940131 0.3640370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1486 1487 0.128201 -0.388995 -0.903401 0.5377924 -0.5386214 0.5889567 0.2716547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1487 1488 -0.604680 0.261023 0.724024 -0.3968427 0.2334220 -0.8872500 0.0285923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1488 1489 0.848215 -0.393731 -0.262221 0.3357098 -0.5491447 0.6884600 0.3343079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1489 1490 -0.809217 -0.439871 0.321286 -0.5825104 0.0246153 -0.4043526 0.7046806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1490 1491 0.056273 -0.720793 -0.729697 0.2421255 0.6680390 -0.5824944 0.3947143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1491 1492 0.804094 0.164180 0.852926 -0.2305526 -0.6333442 0.6234092 0.3963353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1492 1493 -0.196064 -0.833104 -0.594384 -0.5080996 0.3956306 -0.3356146 0.6875130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1493 1494 0.677532 0.363295 -0.544437 0.9373787 0.2897713 0.0394682 0.1891981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1494 1495 1.010130 -0.099556 0.404853 0.1906007 0.8989048 0.3095620 0.2445669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1495 1496 -0.823088 0.335572 0.162050 -0.8150710 -0.2932820 -0.4660470 0.1801252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1496 1497 -0.501452 -0.972701 -0.553958 -0.0044019 -0.5535752 0.7997261 0.2323216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1497 1498 -0.239659 0.940727 0.615541 0.1655239 -0.3017686 0.5629536 0.7514125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1498 1499 0.859825 0.203045 0.252638 0.2659727 0.6376355 0.6574179 0.3008009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1499 1500 0.690384 -0.762713 0.385541 0.2225310 0.6206554 0.7246563 0.2003501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1500 1501 -0.336620 -0.718450 -0.039675 -0.1048704 -0.5197359 -0.5952746 0.6037590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1501 1502 0.654629 -0.533459 -0.455230 -0.5405329 0.0913680 0.1862302 0.8153492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1502 1503 0.702765 -0.063264 -0.719947 0.1006348 -0.1335623 -0.1213885 0.9784164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1503 1504 0.523696 -0.207577 -0.798538 0.1923688 -0.6707630 0.6364305 0.3286752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1504 1505 -0.906968 0.373896 0.106902 0.1966460 0.8516799 -0.3074500 0.3760933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1505 1506 0.452065 -0.308345 -0.944850 0.9457522 0.1443317 0.1436717 0.2531393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1506 1507 0.170560 -0.020514 0.899161 -0.2501249 -0.7842016 0.1569594 0.5457371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1507 1508 0.725790 -0.604570 -0.312075 -0.3218608 -0.3570690 -0.4795247 0.7341413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1508 1509 0.297529 0.472428 -0.876136 0.4286085 0.3851849 0.5409547 0.6126136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1509 1510 0.381786 -0.750170 -0.352798 -0.2800452 0.1399646 -0.2586229 0.9138374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1510 1511 0.841274 -0.287569 -0.413892 -0.3840737 0.6794000 -0.3051958 0.5456725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1511 1512 0.038639 0.156717 1.088078 0.0548330 -0.1189802 0.8792384 0.4580141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1512 1513 0.103307 -0.348028 0.925931 -0.5261815 0.2959630 -0.5715640 0.5557459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1513 1514 0.620561 -0.936591 0.349056 0.5426446 0.1530326 -0.8228728 0.0706986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1514 1515 -0.378411 1.039962 -0.331518 -0.5783055 -0.3336640 0.3903597 0.6339167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1515 1516 0.568761 0.131674 0.672787 0.5238900 -0.0291578 -0.6939496 0.4930752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1516 1517 -0.422659 0.950681 -0.092260 0.6985135 0.4812458 0.5208656 0.0958144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1517 1518 0.751560 -0.780897 -0.042997 -0.6365262 -0.5708090 -0.3035384 0.4205663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1518 1519 -0.082531 0.615760 -0.668328 -0.5052095 0.6013394 0.5338504 0.3133019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1519 1520 0.634560 -0.744849 -0.433741 -0.3372272 -0.5442544 0.7471165 0.1785548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1520 1521 0.855545 0.567343 0.304708 -0.1269763 0.3442917 0.0511927 0.9288270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1521 1522 0.309094 0.309512 0.990664 0.1159730 0.1536484 -0.9000052 0.3910666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1522 1523 -0.938537 -0.176655 0.501661 -0.1745762 0.3289836 0.5010450 0.7811830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1523 1524 -0.667489 0.619681 0.118450 0.1064064 0.1669863 0.9748656 0.1021291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1524 1525 0.818260 -0.662217 0.139250 -0.6751308 0.6795582 0.1770756 0.2259275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1525 1526 0.468119 -0.893078 -0.225667 0.4687948 -0.7055177 0.2171781 0.4850875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1526 1527 -0.195663 -0.704477 0.587172 0.4823785 -0.2733281 0.7591121 0.3411034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1527 1528 0.218978 0.399005 0.834389 0.3894217 -0.2547097 0.2757549 0.8410903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1528 1529 0.868694 0.381452 -0.110855 -0.2568344 -0.3685418 0.8348327 0.3182254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1529 1530 -0.363284 -0.545415 -0.744163 -0.6298872 -0.6148107 0.3662011 0.3019050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1530 1531 -0.476554 0.557959 0.742609 0.7751645 -0.0497581 0.1381941 0.6144481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1531 1532 0.193632 0.696799 -0.758179 -0.2595559 -0.1548403 0.9366539 0.1770162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1532 1533 0.469517 -0.357053 -0.834873 0.5605915 -0.0509970 -0.6382140 0.5251851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1533 1534 0.965836 -0.019327 -0.578562 -0.3700761 0.7126103 0.5407292 0.2506833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1534 1535 0.042248 -1.057981 0.166666 0.2507183 0.1643456 0.9004049 0.3152806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1535 1536 -0.561733 0.733355 -0.116519 -0.1229352 0.1537293 0.1478283 0.9692270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1536 1537 -0.195760 0.990611 0.043201 0.0361081 -0.0306408 -0.8672898 0.4955459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1537 1538 -0.471549 -0.877618 0.084463 -0.3741690 -0.7711536 -0.0661732 0.5108237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1538 1539 0.033684 -0.900074 0.170908 -0.3133057 0.2050107 -0.9220703 0.0979618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1539 1540 -0.887448 0.339969 -0.302932 0.1761396 -0.4146553 0.0953370 0.8876636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1540 1541 -0.291088 -0.496484 0.606412 0.2310253 0.4988329 0.2318198 0.8025289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1541 1542 -0.957370 0.072976 -0.184295 -0.4143258 0.7826401 0.3904914 0.2516448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1542 1543 0.617310 0.628684 -0.214271 -0.1373223 0.4724770 0.8003105 0.3426532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1543 1544 0.076081 -0.838782 0.463623 -0.1498460 -0.4953702 -0.7358009 0.4367511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1544 1545 0.931692 0.260591 -0.443371 -0.1755364 -0.3607537 0.4207141 0.8136605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1545 1546 0.464319 0.097935 -0.710325 -0.2309570 0.3393096 0.4426318 0.7972484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1546 1547 0.946181 -0.000645 -0.207216 0.0929427 0.4990107 0.7014557 0.5003097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1547 1548 -0.364656 -0.930363 0.429388 -0.7864909 0.3947466 0.3982981 0.2587776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1548 1549 -0.171833 0.701724 -0.599065 0.0679844 -0.3820916 -0.4931090 0.7786062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1549 1550 -1.101171 0.049579 -0.137802 -0.3089484 0.2281904 0.2664754 0.8840084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1550 1551 -0.693730 0.697173 -0.147839 0.3922742 -0.7258001 0.2295008 0.5163958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1551 1552 -0.294332 1.017074 0.068443 -0.8945086 0.2229576 -0.3364893 0.1921440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1552 1553 -0.752164 -0.692893 0.034492 -0.0595617 0.2887613 -0.8050417 0.5147594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1553 1554 0.885655 -0.372520 0.003795 -0.3923455 0.5673993 0.1444202 0.7094123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1554 1555 0.542963 -0.906474 0.326094 -0.2727286 -0.4547473 -0.1013403 0.8417566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1555 1556 0.367752 -0.663957 -0.685151 0.3628658 0.4634259 0.4888168 0.6439123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1556 1557 -0.518202 -0.741781 0.262146 0.2519955 -0.6599666 -0.0319484 0.7070514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1557 1558 0.353058 -0.639839 0.700396 -0.1619391 0.3123933 0.7270182 0.5896021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1558 1559 -0.951621 0.070378 0.457338 -0.5808534 0.1180335 0.5661013 0.5728933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1559 1560 0.272244 -0.235596 0.974218 0.4433504 -0.2295794 -0.6652421 0.5551456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1560 1561 0.757030 0.062564 -0.543355 0.3712289 -0.0555788 -0.4892947 0.7872044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1561 1562 0.661487 0.089138 -0.820693 0.2314720 -0.6168129 -0.6021592 0.4509621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1562 1563 -0.607812 -0.886509 -0.469860 -0.0305063 -0.6990597 -0.6278875 0.3407964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1563 1564 0.399170 -0.772917 -0.322637 0.0491160 0.6888429 -0.1092849 0.7149405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1564 1565 0.260782 -0.639561 0.575933 -0.4786571 -0.7682189 0.0829807 0.4169428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1565 1566 -0.442457 -0.419713 -0.933300 0.6020425 0.4710622 -0.2296724 0.6024084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1566 1567 0.560477 -0.945699 0.512528 -0.4633474 -0.4106273 -0.2423690 0.7469617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1567 1568 0.424337 -0.301689 -1.031019 0.0718967 0.7486631 0.0845660 0.6535924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1568 1569 0.541680 -0.532157 0.698646 0.0942848 -0.1908143 0.6487593 0.7306241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1569 1570 -0.408077 -0.645929 0.768037 -0.2307615 -0.2708517 -0.9304171 0.0878210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1570 1571 0.656889 0.936363 0.026775 -0.4125911 0.2887748 0.0994651 0.8581867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1571 1572 0.416166 0.214411 0.874365 0.1356262 -0.4878472 0.7343318 0.4520701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1572 1573 0.452905 -0.892487 0.118859 -0.1417644 -0.6518653 -0.5464955 0.5062778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1573 1574 0.208337 0.061674 -1.092755 -0.4847898 -0.6878485 -0.5292950 0.1081205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1574 1575 -0.629414 -0.426665 0.660718 -0.0574755 -0.2816148 0.8610801 0.4194410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1575 1576 0.253843 0.469421 0.884899 0.3818854 -0.5278714 0.3778993 0.6578050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1576 1577 1.072435 -0.071407 -0.305526 0.6309382 -0.3306002 0.5268934 0.4636850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1577 1578 -0.020805 -0.875710 0.406865 0.1389436 -0.0973833 0.3998001 0.9007614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1578 1579 -0.451679 -0.544643 0.591313 0.2437896 0.3776701 -0.7139418 0.5368604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1579 1580 0.745233 0.843097 0.307366 -0.4766595 0.1618780 0.2966436 0.8115379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1580 1581 0.715603 0.799877 -0.142324 0.2010374 0.1561786 -0.6637507 0.7032974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1581 1582 -0.333974 0.735865 -0.344318 0.2479907 -0.2505948 0.7312813 0.5838926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1582 1583 0.290226 0.317088 -0.724794 -0.5269812 0.2486528 0.5773958 0.5719062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1583 1584 0.993726 -0.133030 -0.100479 -0.4519743 0.3848288 0.1999706 0.7795112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1584 1585 0.474625 -0.732134 0.399521 0.8416828 -0.3499142 -0.4108771 0.0176091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1585 1586 0.341647 0.484092 -0.788841 -0.4744996 0.7367216 0.4365016 0.2038573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1586 1587 0.315897 -0.506925 0.666152 -0.1369314 -0.5032317 0.8026611 0.2893834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1587 1588 -0.379284 -0.562776 0.639527 0.7177642 0.5154134 -0.1960257 0.4251322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1588 1589 -0.979548 -0.037497 -0.009102 -0.4011896 0.7404140 0.4156775 0.3435786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1589 1590 0.685856 0.756005 -0.209697 0.1332718 -0.7508265 -0.6371824 0.1117887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1590 1591 -0.683030 -0.082080 0.589282 -0.6809881 0.0646460 0.0712058 0.7259517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1591 1592 -0.965531 -0.428118 -0.020818 0.6144848 0.1483989 -0.2592838 0.7301767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1592 1593 -0.567097 -0.451364 0.544694 0.4737946 -0.5354084 -0.4454163 0.5389442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1593 1594 0.513255 0.573896 0.766341 -0.3727213 0.5079509 0.4080622 0.6607193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1594 1595 -0.452209 -0.311365 0.882744 -0.9158772 -0.0995664 -0.0985355 0.3762263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1595 1596 -0.353830 -0.325076 -0.923786 0.6047090 0.4316068 0.5683526 0.3535788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1596 1597 -0.673994 -0.729872 0.009028 0.0836623 -0.4243423 -0.2728700 0.8593464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1597 1598 0.034423 -0.901195 0.576230 0.3415410 -0.7166775 0.0614935 0.6049311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1598 1599 0.612297 -0.554382 0.330629 -0.4587460 0.1700049 0.7719243 0.4059352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1599 1600 13.967509 4.502858 12.283158 0.1898782 0.4947912 -0.7910609 0.3055334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1600 1601 0.974336 -0.110454 0.137103 0.3980884 -0.2345198 -0.6954326 0.5503632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1601 1602 -0.054642 0.526464 -0.773229 -0.2526647 -0.1466152 -0.5774371 0.7623850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1602 1603 -0.910380 -0.014471 -0.475706 -0.4161440 -0.2044092 0.7474210 0.4758182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1603 1604 0.560112 0.751994 0.305731 0.2091679 -0.6092785 0.4829094 0.5931500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1604 1605 0.363230 -0.515860 -0.781420 0.1010396 0.7407184 -0.3824370 0.5430186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1605 1606 0.394837 0.194481 0.687101 -0.0596554 -0.0514276 -0.5506914 0.8309846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1606 1607 0.159272 0.581690 0.868764 0.5590771 -0.3449308 -0.0865488 0.7489758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1607 1608 0.051211 1.094368 -0.330212 -0.7666070 0.3234890 -0.2030380 0.5161822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1608 1609 -0.644088 0.087910 0.869703 0.6756406 -0.3218472 -0.2139644 0.6278084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1609 1610 -0.202772 0.753543 0.091984 -0.0923105 -0.0589517 -0.5679972 0.8157099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1610 1611 -0.683239 -0.402159 0.631245 0.2789686 -0.3667682 -0.8594713 0.2212842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1611 1612 0.554422 0.366824 0.739812 0.3128149 -0.8266968 -0.4674758 0.0136233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1612 1613 -0.759972 0.444040 -0.359844 0.6746509 0.2887786 0.6747471 0.0785451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1613 1614 0.043590 -0.864783 -0.624081 0.6753294 -0.0462722 0.5654211 0.4712622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1614 1615 -0.892616 0.219413 0.606253 -0.2899923 -0.0686198 -0.7358824 0.6080074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1615 1616 0.510073 -0.767409 0.130692 0.5195268 0.2477594 0.3099593 0.7567248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1616 1617 -0.392253 -0.098006 0.998321 0.3152148 -0.4595102 -0.7592271 0.3362501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1617 1618 0.306307 0.605435 0.689349 0.2388019 -0.3644028 0.2062191 0.8761609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1618 1619 0.740449 0.507406 -0.103845 0.1936033 -0.3876842 -0.8187587 0.3766337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1619 1620 -0.201659 -0.898656 0.544795 -0.1098536 -0.1974279 -0.7122006 0.6646238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1620 1621 -0.032590 1.094373 0.034798 -0.5692878 0.0649083 -0.7085684 0.4118605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1621 1622 -0.462837 -0.598745 0.384195 0.3965886 0.5466847 -0.7209129 0.1553636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1622 1623 -0.005018 -0.194656 0.990351 -0.4812041 -0.8191734 -0.0869730 0.2997220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1623 1624 0.183231 -0.420693 -0.849943 -0.1485749 0.9633154 -0.0721554 0.2115244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1624 1625 0.549165 -0.218939 0.902960 0.1890490 0.5643697 -0.6089987 0.5242784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1625 1626 -0.669387 -0.023403 0.792467 0.6603278 0.5079902 -0.5125250 0.2079213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1626 1627 -0.725044 -0.726687 0.260718 0.1682995 -0.4619622 -0.2424357 0.8363558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1627 1628 0.362807 -0.705180 0.625895 -0.0541278 0.7351441 0.5606300 0.3772629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1628 1629 -0.686565 0.102716 -0.582297 -0.5249735 0.0360343 -0.6502117 0.5480230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1629 1630 -0.674735 -0.478851 -0.731816 -0.4914510 -0.6574117 0.4614696 0.3366476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1630 1631 -0.093034 0.459244 0.938656 0.0084946 -0.4830721 0.0559234 0.8737515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1631 1632 0.601567 0.418634 0.641205 0.1799189 0.4367130 0.3418123 0.8124502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1632 1633 0.201419 0.428640 0.802854 0.6333132 -0.1900508 -0.7288060 0.1778674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1633 1634 -0.827029 0.000939 -0.068007 0.1081932 -0.6791017 -0.6273899 0.3653725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1634 1635 0.662838 -0.457983 0.531517 0.3695224 -0.5574823 -0.5376678 0.5134005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1635 1636 0.202119 0.729281 -0.559408 -0.1410503 -0.1336821 -0.3818379 0.9035672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1636 1637 -0.333916 0.707547 -0.191725 -0.6118906 -0.0246272 0.7178392 0.3311952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1637 1638 0.523996 -0.567343 0.662005 0.1072809 -0.6239061 -0.1524681 0.7589371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1638 1639 0.935179 -0.231610 -0.553232 0.0678085 -0.5030771 -0.8600889 0.0506210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1639 1640 0.009171 0.709361 -0.769291 -0.6142754 -0.3210904 0.0644120 0.7179261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1640 1641 0.990469 -0.181104 -0.189342 -0.1698330 0.1377714 0.9700859 0.1054004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1641 1642 -0.960936 -0.133608 -0.461484 0.5502897 -0.2598763 -0.7696678 0.1930208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1642 1643 0.549652 -0.355026 0.728826 -0.0637692 0.3665810 -0.8482285 0.3769089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1643 1644 -0.532661 -0.198473 1.035056 0.3008392 -0.7800269 0.5328788 0.1307439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1644 1645 0.734149 -0.465358 -0.556453 0.4170363 0.4370964 0.2821781 0.7452536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1645 1646 0.044401 -0.538068 0.702058 0.1528010 -0.3758181 0.1214471 0.9059046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1646 1647 0.592892 -0.310213 0.551717 -0.6489293 0.4085229 0.5862563 0.2613492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1647 1648 -0.327076 -0.066554 -0.776600 0.3465501 -0.7368169 -0.5658779 0.1295611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1648 1649 0.589127 -0.621504 0.394061 0.0491592 0.2777841 0.7812794 0.5567961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1649 1650 -0.750416 -0.344799 0.205095 0.6832097 0.3061592 0.6287294 0.2102151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1650 1651 0.053766 0.341283 -1.040718 0.5078536 0.5082403 0.4392986 0.5392524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1651 1652 0.489341 -0.947541 0.000076 -0.1922631 -0.1866471 -0.1599483 0.9500601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1652 1653 0.655304 -0.571564 -0.551042 -0.7083423 -0.6605678 -0.1900900 0.1605213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1653 1654 -0.747311 0.773985 0.287297 -0.0327885 0.0363627 0.9861018 0.1587640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1654 1655 0.836460 -0.437071 0.229658 0.1271351 0.1729774 -0.1389763 0.9667477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1655 1656 0.703748 -0.210304 0.878418 -0.3906417 -0.2286845 0.8904900 0.0461517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1656 1657 -0.928966 -0.010504 -0.098456 -0.8116219 0.0159442 0.4896932 0.3181451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1657 1658 -0.428371 0.488478 0.694786 0.2743507 0.9117645 -0.2860138 0.1077651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1658 1659 0.310516 -0.017227 -1.038215 0.9001978 -0.4162392 0.1073047 0.0698186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1659 1660 0.637941 -0.743298 -0.165181 -0.3360358 0.7339508 0.1785414 0.5626003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1660 1661 0.883500 0.339139 0.353531 -0.3347905 -0.2007899 -0.1571891 0.9071330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1661 1662 0.917168 0.209681 0.000503 -0.4244702 -0.1008969 -0.2604096 0.8612965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1662 1663 0.811135 0.591580 0.464443 0.1355130 0.9124690 -0.3159431 0.2218481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1663 1664 -0.868113 0.400785 -0.511037 0.0998520 0.4062243 -0.4455874 0.7914943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1664 1665 0.013429 -0.184775 -0.893936 0.6047995 -0.6013648 0.0968300 0.5130321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1665 1666 -0.506327 -0.499571 0.643727 0.1659901 -0.1464755 0.6068584 0.7633578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1666 1667 -0.109357 0.432760 0.914838 0.2180984 -0.1865879 0.9541519 0.0849245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1667 1668 0.553238 -0.537766 0.429201 -0.1869277 -0.7176312 -0.6518290 0.1586900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1668 1669 -0.183146 0.714967 -0.544414 0.1526213 0.9083592 0.0582489 0.3849640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1669 1670 0.859856 0.499894 0.166339 0.3773063 -0.2388490 -0.8677623 0.2181279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1670 1671 -0.895196 -0.126908 -0.439827 0.0516529 0.2761264 -0.8485318 0.4484195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1671 1672 0.765227 -0.428369 -0.200870 -0.4682318 -0.2130355 0.7088899 0.4825453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1672 1673 -0.533307 -0.022885 -0.860734 -0.0089680 -0.6877772 0.6229003 0.3726625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1673 1674 -0.110578 0.938709 0.108363 -0.4870653 0.3348536 0.2475160 0.7677085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1674 1675 -0.130370 0.526884 0.806708 0.5515439 -0.3869288 0.7190747 0.1703437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1675 1676 0.561557 -0.762712 -0.175966 -0.9592427 -0.0962436 -0.1139974 0.2399899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1676 1677 0.420872 0.869905 0.155456 0.2178066 -0.0127999 -0.3181653 0.9225873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1677 1678 -0.230181 0.857278 -0.332842 0.0549060 0.7576452 -0.1773769 0.6256968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1678 1679 0.202121 0.706529 -0.354579 -0.2250331 -0.2329761 0.4409163 0.8370634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1679 1680 0.756795 -0.727624 0.154088 0.3598750 0.1993063 0.4582742 0.7878780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1680 1681 -0.994664 0.494364 0.162139 -0.3392924 -0.5261690 -0.1617821 0.7627931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1681 1682 -0.260048 -0.102803 1.227305 -0.6484177 -0.0581864 0.4686331 0.5971196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1682 1683 -0.859306 -0.792507 0.227576 -0.1261938 -0.7288917 0.6688683 0.0735335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1683 1684 0.728307 -0.323491 0.641233 0.7911573 -0.3338453 -0.0944387 0.5036852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1684 1685 0.881325 0.581619 -0.446222 0.1299682 -0.4634526 -0.7273308 0.4891930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1685 1686 -0.930303 0.033526 -0.524591 -0.0181586 -0.5250210 -0.1932716 0.8286551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1686 1687 -0.719024 -0.425580 0.523722 -0.5362489 -0.2705168 -0.7789467 0.1802772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1687 1688 0.723632 -0.079672 -0.767172 0.2352531 0.1335018 0.8591477 0.4343943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1688 1689 -0.551737 -0.730616 0.154915 -0.1212457 0.8213360 -0.1181877 0.5447370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1689 1690 0.608144 -0.720587 -0.455227 0.0534243 -0.4970830 -0.4989315 0.7078995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1690 1691 0.170445 -0.208720 -1.121961 -0.0858597 -0.1081820 -0.8005399 0.5831471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1691 1692 -0.281806 0.126100 -0.981098 0.0682635 0.5345185 0.3434749 0.7691911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1692 1693 0.699298 -0.074673 -0.605512 -0.2983614 -0.1072349 -0.9182682 0.2372018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1693 1694 -0.806551 0.559594 -0.138759 0.4794543 0.2369718 0.6009433 0.5939992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1694 1695 0.294525 0.119884 -0.891645 -0.5338750 0.2209949 -0.3021681 0.7581776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1695 1696 0.041207 0.976958 0.021775 0.7764307 -0.3285509 -0.3671063 0.3929919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1696 1697 -0.786367 -0.625920 -0.257200 -0.5839317 -0.1779460 -0.6791174 0.4076254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1697 1698 -0.133721 -0.185605 -0.923908 0.1163607 -0.4527116 0.7226195 0.5092478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1698 1699 -0.704991 0.831008 -0.323195 -0.1583404 -0.6143098 0.5734834 0.5183325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1699 1700 -0.298283 0.539954 0.670716 0.0147130 0.8549167 0.0777995 0.5126872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1700 1701 0.354829 -0.639003 -0.613856 0.0706800 -0.3195805 0.7000743 0.6346405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1701 1702 -1.139315 -0.222772 -0.228030 -0.4209599 -0.0266416 0.8870346 0.1877568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1702 1703 0.572376 0.549906 0.638152 0.3666027 0.2387995 0.5960415 0.6732844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1703 1704 0.883261 0.267947 0.633057 0.1437263 0.7346294 0.6294977 0.2083146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1704 1705 -0.537809 0.717897 0.359559 -0.2663446 0.8246473 0.4369521 0.2410191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1705 1706 0.224000 1.038846 0.287244 -0.0381140 0.1982828 -0.4864526 0.8500559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1706 1707 -0.736821 0.404478 0.160256 0.3821875 -0.3426653 0.7261139 0.4574625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1707 1708 0.637844 0.440662 -0.789184 -0.3788844 0.3684059 0.0642195 0.8465220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1708 1709 0.682213 0.617424 0.296098 -0.7283335 -0.3092629 0.5548767 0.2569021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1709 1710 0.457124 -0.603457 -0.653374 0.0532535 -0.5447965 0.5517170 0.6292608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1710 1711 -1.057943 -0.147009 -0.100781 -0.1160693 0.0532532 -0.2489618 0.9600573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1711 1712 -0.634256 -0.550101 -0.329283 -0.3244593 -0.1213261 0.3941926 0.8512452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1712 1713 -0.757397 0.408415 -0.141447 0.1921598 -0.6152209 0.2782562 0.7121455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1713 1714 -0.476785 0.880354 0.441595 -0.3758450 0.2065175 0.9014858 0.0584328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1714 1715 -0.171832 -0.619408 0.806365 0.3289881 0.6260399 -0.7069937 0.0009451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1715 1716 -0.580346 -0.453226 0.580174 0.3546051 0.4824311 -0.7715757 0.2149104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1716 1717 0.011392 -0.320277 0.909925 -0.3293907 0.5845032 0.5784810 0.4639154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1717 1718 -0.758584 0.300489 -0.254132 0.3174461 -0.0027608 0.1327050 0.9389408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1718 1719 -0.543274 0.203673 -0.563328 -0.0023236 -0.4003791 -0.8642333 0.3046178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1719 1720 -0.573427 -0.236721 -0.707320 -0.0291053 -0.3885510 0.1336704 0.9112152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1720 1721 -0.004429 0.990505 0.185351 -0.3566878 0.0154690 -0.5344390 0.7661002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1721 1722 -0.616327 0.201720 0.657823 -0.3276418 0.4414058 0.3448283 0.7608582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1722 1723 -0.813702 0.806721 0.295964 0.8709762 -0.3263410 0.2571282 0.2622729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1723 1724 -0.663894 0.256487 -0.775847 -0.0347380 0.4453305 0.7270739 0.5213805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1724 1725 0.824583 0.021422 -0.590714 -0.0147770 0.7154174 0.4194100 0.5586186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1725 1726 0.232426 -0.677095 0.642469 -0.3535930 -0.0260307 -0.9128127 0.2026508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1726 1727 0.246063 0.818548 0.636786 0.4696507 0.7861386 -0.3765103 0.1401936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1727 1728 -0.257774 0.427665 -0.955792 -0.3027223 0.1574785 0.6762107 0.6529156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1728 1729 0.658138 0.448407 -0.778153 -0.4362680 -0.7380945 -0.5133866 0.0363454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1729 1730 -0.475001 0.328953 0.722373 0.1298814 -0.1869835 -0.8397855 0.4928775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1730 1731 0.147296 -0.200747 1.038093 -0.4795136 0.1388864 0.3356469 0.7988231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1731 1732 -0.558556 -0.779709 0.434540 -0.1809251 -0.0096292 -0.8984552 0.3999395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1732 1733 1.099319 0.057573 0.088964 -0.2521197 -0.5471680 0.6914969 0.3985911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1733 1734 -0.650200 -0.533681 -0.785432 0.5129747 0.7215090 -0.3923793 0.2496402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1734 1735 0.475052 -0.431595 0.911852 0.3433776 -0.2342128 0.8245494 0.3838678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1735 1736 0.187141 -0.267965 1.005729 -0.0172060 0.8945805 0.4423517 0.0612751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1736 1737 -0.259416 0.664951 -0.862436 0.0279182 0.1587455 0.4992752 0.8513194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1737 1738 0.593974 0.330126 -0.745124 -0.5755801 -0.6752220 -0.4604508 0.0277095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1738 1739 -0.288841 0.016460 1.086985 -0.0754687 0.9058717 0.2340475 0.3448517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1739 1740 -0.684170 -0.574584 -0.146989 -0.2387005 0.6606952 0.6779018 0.2166866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1740 1741 -0.748911 0.506001 -0.445719 -0.4668047 -0.5595971 -0.6669396 0.1553575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1741 1742 0.181418 -1.164345 0.218531 0.1506702 0.4960028 -0.6035859 0.6057754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1742 1743 0.553351 -0.140863 1.009169 -0.4668987 -0.7563869 0.1937497 0.4151451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1743 1744 0.275060 -0.384637 -0.893940 0.1482900 -0.4413910 0.5626634 0.6830769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1744 1745 -0.853692 -0.051736 -0.437337 -0.4224434 -0.6437846 0.3448444 0.5368103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1745 1746 -0.321994 0.248350 0.908555 0.0826662 -0.1208637 0.0247762 0.9889107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1746 1747 -0.009459 0.352228 1.094592 0.4800175 -0.1353459 0.5325270 0.6838710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1747 1748 0.761289 0.499040 0.297023 -0.0379254 0.1642127 0.9735871 0.1540259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1748 1749 -0.713962 -0.711191 0.229510 0.3944302 -0.6658545 0.4938827 0.3964121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1749 1750 0.623851 0.462106 0.672182 0.3684774 -0.6489471 0.6265449 0.2247965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1750 1751 0.137108 -0.908028 -0.213299 0.2111167 -0.4041833 0.7762635 0.4352936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1751 1752 -0.540109 0.406254 0.417328 0.2518797 0.5574521 0.6962724 0.3755110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1752 1753 0.681180 0.764299 -0.189330 0.6750083 -0.3470057 -0.5755810 0.3043967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1753 1754 -0.370254 -0.365651 -0.651578 -0.6742555 -0.2535822 0.2047840 0.6626757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1754 1755 -0.535667 0.568493 -0.311778 -0.4081816 -0.2938240 -0.1055201 0.8578582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1755 1756 -0.692122 0.127810 0.690671 0.2364436 -0.8590959 0.4516443 0.0454546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1756 1757 0.614466 -0.222879 -0.880684 -0.4860744 0.3928141 0.1469611 0.7667015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1757 1758 1.031947 -0.023402 -0.002004 -0.2942558 0.4959799 -0.8015148 0.1580867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1758 1759 -0.807214 0.076131 0.774093 -0.1587425 0.5095397 -0.7855383 0.3132086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1759 1760 -0.446595 -0.097453 -0.921829 -0.0200079 -0.8945627 0.2452474 0.3731098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1760 1761 0.818364 0.659807 -0.162991 0.1793707 0.4773830 0.7721811 0.3790355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1761 1762 -0.055460 -0.592989 0.893042 0.7125053 -0.6101872 -0.3405373 0.0635784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1762 1763 0.085122 0.810825 -0.777207 0.1317712 -0.1925928 0.6378911 0.7339205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1763 1764 0.021632 0.280238 -0.992866 -0.7366131 -0.5524721 -0.3781264 0.0958968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1764 1765 -0.733962 -0.241236 0.776629 -0.4392249 -0.2794173 -0.1762800 0.8354238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1765 1766 0.203319 -0.946162 0.504265 0.1961742 0.0303231 0.4875971 0.8502031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1766 1767 -0.580255 -0.222595 0.584239 0.2281459 0.3791646 0.2472304 0.8620098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1767 1768 -1.040365 0.352216 0.049628 -0.1740943 -0.3010855 0.9008424 0.2598492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1768 1769 0.993041 0.044611 0.233110 -0.1999799 0.2692854 -0.9330288 0.1301950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1769 1770 -0.791132 -0.128376 0.605126 -0.2514283 0.0526386 -0.9440750 0.2067254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1770 1771 0.936565 -0.527922 0.110582 -0.1568158 -0.5119443 -0.6016911 0.5926969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1771 1772 0.009275 0.820515 -0.521310 0.8161372 0.4129962 0.4035331 0.0226987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1772 1773 0.064660 -0.634116 0.539931 -0.5273760 -0.3082055 -0.6882845 0.3913418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1773 1774 0.767605 0.355618 -0.167464 -0.5592379 -0.1297441 -0.3483564 0.7409908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1774 1775 0.365616 0.769937 0.557096 -0.0863999 0.3929666 0.0294689 0.9150103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1775 1776 -0.206151 0.659230 0.636099 -0.1096545 0.0125807 0.9929143 0.0440322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1776 1777 -0.012657 -0.813189 0.727185 -0.1712641 -0.4350167 -0.0800286 0.8803548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1777 1778 0.567231 -0.801889 0.041135 -0.5553531 0.5646513 0.5562760 0.2516125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1778 1779 0.156778 -0.545339 -0.963126 0.6844409 0.1057661 -0.2413838 0.6797706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1779 1780 0.333043 0.809411 0.790307 0.3297408 0.1023199 0.8756571 0.3376778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1780 1781 0.577702 -0.245674 -0.793943 -0.7794434 -0.0996350 0.1102663 0.6085903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1781 1782 0.712807 0.661797 -0.361814 0.1905563 0.0125521 -0.9473743 0.2569293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1782 1783 -0.663757 -0.448681 -0.756814 -0.3395237 -0.4606444 -0.7998881 0.1808572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1783 1784 0.063032 -0.613137 -0.806610 0.5608862 0.6013436 -0.2498048 0.5112632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1784 1785 0.436248 -0.442719 0.732887 -0.6083370 0.2102545 0.6087868 0.4637864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1785 1786 -0.626897 -0.619198 -0.605143 0.0382658 -0.1495475 -0.8361576 0.5263190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1786 1787 0.619603 -0.683346 -0.432254 -0.3968127 0.3404123 -0.4018018 0.7518075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1787 1788 0.716858 0.434314 0.088116 0.7115620 0.5713443 -0.2474533 0.3255949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1788 1789 0.620514 0.715449 -0.486686 -0.3001643 -0.2903156 -0.0256555 0.9082731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1789 1790 0.013330 0.933072 -0.035982 -0.4798889 -0.1154540 0.1529552 0.8561435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1790 1791 0.499755 0.755750 0.719921 -0.2596654 -0.0265091 -0.0030273 0.9653300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1791 1792 0.710862 0.060941 0.943522 -0.2495417 -0.7100635 0.5413020 0.3748744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1792 1793 0.010375 -0.854185 -0.708073 0.3470099 -0.6058510 -0.4461986 0.5598531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1793 1794 0.653488 -0.829412 -0.021644 -0.7226260 0.5382995 -0.4072096 0.1490827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1794 1795 0.775879 -0.012692 0.708091 0.4588614 -0.3483613 0.1716837 0.7991341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1795 1796 0.936549 0.050979 -0.150667 -0.4476352 -0.2941936 -0.1758333 0.8259270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1796 1797 0.841003 0.509180 -0.285521 -0.2227270 0.0729105 -0.6998453 0.6747543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1797 1798 -0.590497 0.732570 0.066129 -0.2379019 0.3378180 -0.3044073 0.8582645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1798 1799 -0.923677 0.364086 -0.348063 -0.4674674 0.0140573 -0.6993718 0.5405143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1799 1800 -0.767428 0.031907 0.450451 -0.0187352 -0.2777087 -0.0208885 0.9602554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1800 1801 0.399222 0.682490 0.132995 -0.7548595 0.5150152 -0.3887604 0.1175236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1801 1802 -0.199515 -0.904895 0.304236 -0.4448561 -0.0502217 -0.8614205 0.2398657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1802 1803 0.749884 0.666216 -0.521912 -0.5186589 -0.0171941 -0.8157655 0.2553896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1803 1804 -0.795857 -0.154143 0.444215 0.2839111 0.4655038 0.5634129 0.6206985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1804 1805 -0.211705 0.746963 -0.547476 0.7255175 -0.3073637 -0.1286082 0.6021726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1805 1806 -0.892222 -0.478219 -0.518277 -0.6040899 0.1566085 0.6805441 0.3839386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1806 1807 0.107316 1.040638 0.013319 -0.3338386 -0.2716202 -0.4222051 0.7978202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1807 1808 -0.456806 0.595553 0.511515 0.4395506 0.3562320 -0.7623634 0.3141593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1808 1809 -0.581018 -0.687350 0.489890 0.0387012 -0.4816135 0.1786097 0.8571168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1809 1810 -0.273626 -0.591532 0.737017 -0.3098153 -0.7462101 -0.5647159 0.1681691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1810 1811 0.823708 0.211451 -1.072841 -0.4316183 -0.3746682 -0.6591213 0.4887621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1811 1812 -0.904895 0.316272 0.320158 -0.6922330 0.0409002 0.2689543 0.6684342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1812 1813 -0.861673 0.077842 0.327769 0.0190463 -0.2968133 0.6089980 0.7352963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1813 1814 0.447896 0.707332 0.602091 0.4498627 0.6064125 -0.6446454 0.1196651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1814 1815 -0.348735 -0.290367 -0.949641 0.4840665 -0.4124185 -0.6154752 0.4655973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1815 1816 0.513433 -0.764285 0.274477 -0.3385898 0.3267695 0.7385825 0.4827780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1816 1817 -0.668821 -0.125374 -0.712851 0.4247956 -0.7360061 0.4551834 0.2658041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1817 1818 -0.034552 0.865426 0.383041 0.4423697 0.3277191 0.0518883 0.8331968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1818 1819 0.016384 0.852221 -0.554760 0.3041172 -0.1233574 0.6762753 0.6595054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1819 1820 -0.048605 0.978079 -0.286535 0.5533309 0.0669607 0.4000409 0.7275359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1820 1821 0.235070 0.927832 -0.097266 0.1643940 0.6701468 0.0366262 0.7228668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1821 1822 0.432782 0.870161 0.115138 0.4780498 -0.6861559 -0.5476985 0.0261693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1822 1823 -0.786724 -0.438372 0.506327 0.1000569 0.1521606 0.0355588 0.9826349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1823 1824 -0.781337 -0.305203 0.132535 -0.7900513 -0.4035471 -0.4458973 0.1189301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1824 1825 -0.116929 -0.356266 -1.035343 -0.0590075 0.0066578 0.2966604 0.9531350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1825 1826 -0.296086 -0.176618 -0.973070 0.2230785 0.4829154 -0.3465968 0.7725926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1826 1827 0.804659 -0.272511 -0.583696 0.0371446 0.2602054 -0.8042105 0.5330655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1827 1828 -0.090368 1.021178 -0.212920 -0.0271769 -0.2265267 0.1427304 0.9631070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1828 1829 0.208905 0.688314 -0.304988 -0.1665371 -0.0916756 -0.8890661 0.4164401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1829 1830 -0.946842 -0.449141 0.184582 -0.1442838 0.0585998 -0.6209625 0.7682147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1830 1831 0.119851 -1.052709 -0.296284 0.2468829 -0.6157900 -0.5577255 0.4987923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1831 1832 0.550671 -0.741080 -0.499021 -0.2392612 0.3684945 -0.6703094 0.5980394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1832 1833 0.393258 0.857417 0.190615 -0.3999930 -0.1367824 0.4523318 0.7852975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1833 1834 0.734355 -0.353091 0.309639 0.2263201 0.2325545 -0.0387004 0.9450925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1834 1835 0.613305 0.019405 0.940190 -0.1445174 0.3354443 0.5392428 0.7588208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1835 1836 -0.413268 -0.223192 0.845262 -0.8659616 0.1679134 0.2032530 0.4249750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1836 1837 -0.793299 -0.128822 -0.597122 0.6608320 0.4737779 -0.5737702 0.0980983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1837 1838 0.454868 -0.169455 0.840300 -0.5414546 0.1400615 0.4588831 0.6903882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1838 1839 -0.413010 -1.032727 -0.169536 0.3559971 -0.7338790 -0.5265478 0.2396563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1839 1840 -0.106450 -0.931518 0.752428 -0.2709168 -0.3887611 -0.8078456 0.3505058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1840 1841 0.514578 -0.768975 0.145709 -0.1304603 -0.2938339 0.1695512 0.9316084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1841 1842 0.199915 -0.945145 -0.619188 -0.2556485 0.1548678 -0.9310586 0.2092600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1842 1843 0.049426 0.987561 -0.359366 -0.1414572 -0.4454600 0.3680450 0.8038023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1843 1844 0.410630 0.848996 -0.210652 -0.7823204 0.2875336 -0.3542764 0.4240135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1844 1845 -0.368241 -0.202715 0.872428 0.0648706 0.6350645 0.4264892 0.6407744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1845 1846 -0.942926 0.361538 -0.373333 -0.4580939 0.1308671 0.8766245 0.0674788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1846 1847 0.761267 -0.242133 0.554719 -0.3706872 -0.4347446 -0.7666044 0.2930970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1847 1848 0.152316 0.997433 0.140614 0.5736759 0.4223645 -0.0391467 0.7006938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1848 1849 0.397151 0.478036 -0.689485 0.6585583 -0.6374220 -0.3102976 0.2524073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1849 1850 -0.418106 -0.811371 0.000706 0.6427831 0.4056461 -0.6141169 0.2124654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1850 1851 -0.180642 0.213613 1.119612 -0.0287453 -0.5478536 0.5073367 0.6645597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1851 1852 0.942536 -0.343057 0.547225 0.2314624 0.0712500 -0.4819558 0.8420613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1852 1853 0.571075 0.618020 0.319517 -0.2556005 0.2637962 -0.1305362 0.9208910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1853 1854 0.261106 0.259845 0.824263 -0.7169262 -0.4820669 0.5018544 0.0420783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1854 1855 -0.370059 -0.570144 -0.915190 0.3668252 -0.8363396 -0.1062723 0.3932958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1855 1856 0.188725 -0.574328 1.096841 0.7584267 0.0454337 0.6143817 0.2127436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1856 1857 0.736725 0.790246 0.179449 -0.6161317 0.6864140 -0.2471365 0.2968856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1857 1858 -0.831569 -0.491937 0.327815 0.1968700 0.5058505 -0.0814850 0.8358933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1858 1859 -0.524417 -0.652686 -0.307551 0.1149190 -0.3855510 0.6646069 0.6296362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1859 1860 -0.903156 -0.594132 -0.068438 -0.2729178 -0.1478511 0.6768167 0.6675141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1860 1861 -0.696540 -0.163593 -0.780765 -0.4100290 -0.3813249 0.2799136 0.7798179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1861 1862 -0.679767 0.747937 0.151951 -0.2108684 -0.6513321 0.5568745 0.4703102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1862 1863 0.977910 0.257761 0.158524 -0.0088933 0.2905528 -0.8080397 0.5124176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1863 1864 -0.625086 0.633368 0.255406 0.6120838 -0.1241795 0.6119571 0.4852230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1864 1865 0.232958 0.114591 -1.115287 0.1367041 0.2638631 -0.6621019 0.6879748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1865 1866 0.278910 0.616352 -0.912349 -0.5339390 -0.0113644 0.8205270 0.2037533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1866 1867 0.564570 -0.589956 -0.387390 -0.1789196 -0.1089575 0.9541279 0.2139063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1867 1868 -0.611827 0.458739 -0.841269 -0.4024963 0.2135210 0.5481966 0.7013458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1868 1869 0.653880 0.840118 -0.235367 0.1833724 -0.3031577 -0.0291055 0.9346779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1869 1870 0.189477 0.639650 -0.713089 0.2328481 -0.2876415 -0.2986281 0.8796962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1870 1871 -0.507610 0.283976 -0.934955 -0.4585157 -0.3651756 -0.6388423 0.4982878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1871 1872 -1.004247 -0.532796 -0.269962 0.3368017 0.1315184 -0.9307883 0.0538585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1872 1873 0.772345 0.526383 0.545543 0.4392518 -0.2325613 -0.2783176 0.8218956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1873 1874 0.422428 0.891122 -0.307519 -0.6358452 0.0619805 -0.3427481 0.6887547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1874 1875 -0.399261 0.655839 0.733336 0.6826377 0.4611766 -0.3850403 0.4160118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1875 1876 -0.703808 -0.200796 -0.621688 -0.1260574 0.3566275 0.7921625 0.4789624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1876 1877 0.410588 0.273027 -0.742671 -0.4779296 0.2535752 0.7594608 0.3612509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1877 1878 0.988449 -0.453752 -0.279720 -0.4907854 0.0220243 -0.1955811 0.8487595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1878 1879 0.933729 0.255530 -0.300513 0.1795586 -0.1138126 -0.9606878 0.1785620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1879 1880 0.540121 0.099764 -0.900171 -0.5000826 0.7587939 0.4018380 0.1125854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1880 1881 -0.879247 -0.317949 -0.627262 0.3075894 0.0046332 -0.9391062 0.1531234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1881 1882 0.949534 -0.149892 -0.131914 -0.2556082 0.1431371 -0.8321846 0.4707918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1882 1883 -0.415083 1.035420 0.612265 0.2558673 0.0000215 0.5493779 0.7954344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1883 1884 0.648212 0.598048 0.277191 -0.3219126 -0.2688113 0.8709610 0.2560072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1884 1885 0.033183 -0.968800 -0.666769 -0.6431571 -0.5669665 0.2396371 0.4554910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1885 1886 -0.670608 0.369678 -0.144789 0.5687186 -0.0445696 -0.4308368 0.6992513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1886 1887 -1.012816 -0.454989 0.181265 0.0931405 0.5336733 -0.6981507 0.4680846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1887 1888 0.651969 -0.708614 0.086862 0.0617336 0.3764162 -0.8880745 0.2565608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1888 1889 -0.216914 0.673590 0.746569 -0.3145275 -0.0135315 -0.9470059 0.0637893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1889 1890 0.364036 -0.603219 0.403640 0.3527211 -0.5369863 -0.6832797 0.3469329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1890 1891 0.430947 0.635290 -0.478912 -0.8767606 0.0731106 0.4501843 0.1525771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1891 1892 0.838196 -0.708503 0.337750 0.0877602 0.1895269 0.0033367 0.9779400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1892 1893 0.498587 -0.726274 0.560460 0.0767875 -0.2548948 0.6422457 0.7187857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1893 1894 -0.258786 -0.853929 0.502667 -0.3467645 -0.4653496 -0.6709089 0.4616116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1894 1895 0.846884 0.036801 -0.531677 -0.2292485 0.4056667 0.5497402 0.6933004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1895 1896 0.683875 -0.814656 -0.293773 -0.6787371 0.2944128 0.6482898 0.1798818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1896 1897 0.237576 0.083348 -0.897956 0.2524976 -0.0338699 0.9487888 0.1868093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1897 1898 -0.552801 -0.436097 -0.745559 0.1247046 0.9386313 -0.1109593 0.3018411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1898 1899 0.758458 -0.367563 0.540048 0.3924452 -0.4976668 0.6220207 0.4597877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1899 1900 0.892005 -0.129934 -0.337988 -0.4698367 -0.0334818 -0.8454883 0.2515590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1900 1901 -0.767933 -0.688185 -0.206128 -0.3246548 -0.0646021 -0.5234035 0.7851590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1901 1902 0.138049 -0.685391 -0.486618 0.2648740 0.4982104 -0.2421415 0.7893007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1902 1903 0.776385 -0.367300 0.350333 -0.0007804 0.0066120 -0.9996043 0.0273309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1903 1904 -0.585124 0.604754 0.313705 -0.0039872 -0.0522297 -0.1074557 0.9928290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1904 1905 -0.619594 0.350822 0.546200 0.1577357 0.6426479 0.6043136 0.4437659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1905 1906 0.295865 0.739740 -0.271609 -0.2904676 0.0852621 0.9407499 0.1528026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1906 1907 -0.101141 -0.993799 -0.216316 -0.5121342 -0.2877519 -0.7604099 0.2769373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1907 1908 -0.200538 0.719630 -0.567837 -0.3331108 0.1968896 0.8508148 0.3555080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1908 1909 0.915459 -0.161272 -0.112698 0.0737585 -0.3487772 -0.8203690 0.4471117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1909 1910 -0.380045 0.610338 -0.669754 0.1177006 0.8818270 -0.0582324 0.4529203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1910 1911 0.639204 0.570047 0.050738 0.0094860 -0.0952826 -0.4030251 0.9101659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1911 1912 0.068956 0.913991 -0.060057 -0.4306114 -0.2206091 -0.0385189 0.8743121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1912 1913 0.243789 0.710503 0.726173 0.0174853 -0.7264526 -0.0034250 0.6869856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1913 1914 0.609342 0.747896 -0.379973 0.1021980 0.3797045 0.2056698 0.8961473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1914 1915 0.909101 0.217560 0.417122 -0.0897098 0.3823807 0.2348969 0.8891348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1915 1916 0.569555 -0.316641 0.879072 -0.8339327 -0.4060996 0.1479485 0.3431481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1916 1917 0.061759 -0.175137 -0.919919 0.1167066 -0.2647121 -0.0005999 0.9572391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1917 1918 -0.452498 -0.406405 -0.693812 0.3943592 -0.6304806 0.4121332 0.5264231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1918 1919 -0.614345 0.353263 0.448808 -0.3860716 0.0503802 -0.5885333 0.7085472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1919 1920 -0.783306 0.504017 -0.157884 0.0507302 -0.0701923 0.9934557 0.0744667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1920 1921 -0.324506 -0.975425 -0.334956 -0.1402781 0.5485378 0.7003590 0.4346558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1921 1922 0.010371 0.111852 -1.021104 -0.5994451 0.3994261 0.0646651 0.6906105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1922 1923 0.721653 0.437510 -0.027167 0.1249909 -0.8238937 0.2433297 0.4963538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1923 1924 -0.250985 0.431483 -1.064430 0.0220125 0.1718471 -0.6465295 0.7429560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1924 1925 0.066179 -0.154684 -1.110134 -0.5685031 -0.1970402 0.7498348 0.2751859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1925 1926 0.690497 0.810289 -0.138051 0.3861583 0.3562043 0.1341521 0.8402401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1926 1927 0.843394 0.179766 0.243902 -0.2793870 -0.0523571 -0.4854639 0.8267566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1927 1928 0.524598 0.777079 0.499674 -0.2897528 0.1930430 -0.0105550 0.9373720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1928 1929 0.079359 0.470458 0.724637 0.1001961 -0.7549498 0.5020711 0.4098001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1929 1930 0.671350 -0.317514 -0.345026 -0.3406251 -0.1844674 -0.7873064 0.4796821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1930 1931 -0.116084 0.984160 -0.527539 0.4638794 0.0044639 0.8133820 0.3510066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1931 1932 0.367665 -0.614982 -0.786036 0.2089616 -0.2855269 0.5801446 0.7336495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1932 1933 -0.940508 -0.442131 0.012864 0.0227294 -0.0915288 -0.3695394 0.9244169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1933 1934 -0.346012 -1.103674 -0.230356 0.4215834 -0.4217911 0.7842696 0.1711169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1934 1935 0.199733 0.755282 0.466666 0.1363013 0.0195328 0.1955487 0.9709795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1935 1936 0.549736 0.820616 0.058477 0.6225716 0.1124837 -0.1578896 0.7581708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1936 1937 0.490763 0.411127 -0.416505 0.0088648 0.6935772 0.7082048 0.1315983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1937 1938 -0.290846 -0.383844 0.816517 -0.0668442 -0.1286271 -0.6794461 0.7192634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1938 1939 0.878772 -0.410917 0.663137 -0.4092033 0.2480988 0.7108745 0.5154194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1939 1940 0.676317 -0.495156 0.462353 0.0466158 -0.1036181 -0.4618502 0.8796503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1940 1941 0.037183 1.098746 0.145142 -0.2644798 -0.1294307 0.6926885 0.6583926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1941 1942 0.786392 -0.042980 0.305658 0.2273430 -0.6996208 -0.3915166 0.5527755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1942 1943 -0.141093 0.307297 -0.960702 -0.2556966 0.7796329 0.0489977 0.5695534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1943 1944 0.785386 0.292100 0.368078 0.6177389 -0.2015095 0.3119638 0.6931602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1944 1945 0.779903 -0.084700 -0.338426 -0.1683025 0.6294946 0.7584222 0.0143738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1945 1946 -0.644048 -0.472876 -0.482141 0.6759025 0.1685687 -0.5794851 0.4230099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1946 1947 0.473475 -0.628372 0.757404 0.7100344 0.3358446 -0.4735296 0.3985340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1947 1948 -0.707614 0.749437 0.170154 0.4976633 -0.4053998 -0.1876629 0.7434816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1948 1949 -0.930745 0.618416 0.207232 0.0285995 -0.1182718 0.3368126 0.9336761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1949 1950 -0.186752 0.878048 0.154473 -0.4241916 -0.2928568 0.0396719 0.8559921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1950 1951 0.056191 0.513477 0.761122 -0.0001145 -0.2553665 -0.6993975 0.6675560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1951 1952 -0.480165 0.238877 0.944897 0.6833302 0.6223253 0.2808847 0.2586015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1952 1953 0.585351 0.368352 -0.876273 0.7089991 0.1286846 0.6917710 0.0470478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1953 1954 -0.724026 -0.510625 0.214132 0.4660990 0.5982532 0.5808406 0.2957517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1954 1955 -0.268174 0.142476 -0.879665 0.3312455 -0.2123567 -0.7954933 0.4608378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1955 1956 0.394616 -0.915014 -0.471245 -0.4415300 -0.5973667 0.0974128 0.6623556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1956 1957 -0.774545 -0.115198 -0.684348 0.4132456 0.0673109 -0.1647867 0.8930524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1957 1958 -0.576296 -0.911114 -0.099349 0.1609110 -0.6828349 -0.4629145 0.5418065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1958 1959 0.528922 -0.825264 0.190946 0.9412004 -0.0795445 0.3224532 0.0619554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1959 1960 0.394523 0.020094 -0.834565 0.3139955 -0.2998627 -0.0265357 0.9004360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1960 1961 -0.682165 -0.677807 0.545723 0.5853004 0.4254706 0.6508756 0.2296936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1961 1962 -0.172999 0.385929 -0.722423 -0.1338993 -0.8977004 -0.0223729 0.4191711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1962 1963 -0.331628 0.688153 0.810018 -0.6355162 -0.4004376 -0.5266909 0.3979518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1963 1964 0.788314 -0.716639 0.206492 -0.4055679 -0.2424747 0.5559766 0.6838207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1964 1965 -0.674596 -0.753405 -0.561010 -0.4714589 0.5641935 -0.3856631 0.5573833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1965 1966 0.750450 0.618479 -0.446576 -0.0081021 -0.2534530 0.7387609 0.6244423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1966 1967 0.155300 -0.406274 -0.702407 0.3466590 0.4532508 -0.5260984 0.6305646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1967 1968 0.797870 0.026527 0.192320 0.6527952 -0.0771135 -0.7171375 0.2315723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1968 1969 -0.347512 0.311484 -0.957023 -0.5342314 0.6306327 0.2830283 0.4866151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1969 1970 0.733532 0.527150 0.604289 -0.3888754 -0.5817619 0.3714335 0.6102182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1970 1971 0.755778 -0.366198 -0.688439 0.4430035 0.3433060 -0.5549197 0.6147788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1971 1972 0.815034 0.636156 -0.042131 -0.6237133 -0.4772616 -0.3350929 0.5204958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1972 1973 0.369355 0.641772 0.769758 0.0445871 -0.2701091 -0.7868985 0.5530315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1973 1974 -0.601091 0.483694 0.626112 0.9212407 0.1141339 0.3538546 0.1143504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1974 1975 0.181552 -0.362935 -1.103690 -0.3974119 0.3832302 -0.0781472 0.8301153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1975 1976 0.732530 0.424859 -0.365443 -0.4748580 0.0446067 -0.7046834 0.5253013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1976 1977 -0.661431 0.801249 0.328962 0.0571245 -0.0497072 0.7835766 0.6166633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1977 1978 1.003365 0.323872 0.418234 0.2086852 -0.3081727 0.9180426 0.1366670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1978 1979 -0.483527 -0.729438 0.100866 0.4850667 0.4048773 0.7237397 0.2774627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1979 1980 -0.382963 0.501603 0.695339 -0.7650414 0.4618791 -0.2560435 0.3685392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1980 1981 0.742346 -0.640358 -0.266304 -0.3121093 0.2821301 -0.8613742 0.2846487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1981 1982 -0.112554 0.709127 0.556522 0.5926064 -0.2904463 0.3828473 0.6464415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1982 1983 0.544768 0.497189 -0.849090 -0.4017115 0.1497215 0.2029358 0.8803570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1983 1984 0.783618 0.425887 -0.014696 0.3962784 0.2529687 -0.3620817 0.8049019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1984 1985 0.477937 0.645204 -0.353671 -0.1651259 0.3079867 -0.8982858 0.2663835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1985 1986 -0.930726 -0.166670 -0.551987 -0.0153263 -0.4278888 -0.4925015 0.7577061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1986 1987 -0.308186 -0.876489 0.419995 -0.5335563 -0.4156383 -0.6805550 0.2817932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1987 1988 0.262366 0.364795 -0.865482 -0.4149866 0.3338686 0.5637852 0.6312401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1988 1989 0.818112 -0.262209 -0.211748 0.3749578 0.5292187 -0.7606547 0.0271778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1989 1990 -0.639752 0.595254 -0.164809 0.3727884 -0.1367310 0.7490086 0.5303956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1990 1991 0.250575 0.365863 -0.856639 -0.2686564 -0.4557986 -0.8482703 0.0225590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1991 1992 -0.576233 -0.828211 -0.114236 -0.3556379 0.0138463 -0.6519740 0.6695221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1992 1993 0.565907 -0.422967 -0.805701 0.7425238 -0.2865959 0.5478014 0.2577495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1993 1994 -0.581047 -0.262916 0.869177 0.7257178 0.1876432 0.3596363 0.5556846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1994 1995 -0.292087 0.833804 -0.320774 -0.7232840 0.2822149 0.2608424 0.5737388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1995 1996 0.001598 0.095726 0.956586 0.0289372 -0.5846880 0.4994248 0.6386528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1996 1997 0.891262 -0.385645 0.105969 0.7523812 -0.2757876 0.2089237 0.5605485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1997 1998 0.842610 -0.342518 0.549039 -0.2147954 0.4913289 0.8435480 0.0297575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1998 1999 -0.824185 0.216955 -0.494509 0.2721491 0.6967610 -0.4012278 0.5286541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1999 2000 -12.223180 7.565274 12.617703 0.0816710 -0.6553138 0.6374737 0.3968891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2000 2001 -0.871895 0.171251 -0.173236 -0.1166731 0.6275752 -0.2490409 0.7283648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2001 2002 -0.173136 -0.162079 -0.879416 0.5464626 -0.1721706 0.5385680 0.6178029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2002 2003 -0.970756 -0.084330 -0.344625 -0.5684954 -0.5655641 0.0707781 0.5932459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2003 2004 -0.626720 -0.404543 0.577461 -0.1038914 0.4263653 0.4632549 0.7699442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2004 2005 -1.053196 0.432497 -0.135803 0.3703218 0.5188982 -0.7201014 0.2739715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2005 2006 0.742715 -0.679157 -0.221313 0.1791896 0.2347214 0.9504341 0.0973246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2006 2007 -0.803851 0.462861 -0.416344 -0.2162100 0.5219664 -0.4012166 0.7209920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2007 2008 -0.289857 0.201625 -0.988142 0.2101867 -0.2945534 -0.0096909 0.9321834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2008 2009 -0.713306 -0.196132 -0.516868 -0.0852736 -0.8678950 -0.0107119 0.4892566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2009 2010 -0.257829 -0.258316 0.694356 -0.4006551 0.3535880 -0.8256079 0.1811701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2010 2011 0.893465 -0.365343 0.415055 0.1729040 -0.1732131 -0.7303664 0.6377040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2011 2012 0.271916 1.152315 0.103255 0.0974141 0.5481484 -0.0184120 0.8304847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2012 2013 0.136236 0.898633 0.154406 0.0681867 0.0631987 0.8776743 0.4701535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2013 2014 0.896337 -0.746250 0.214164 -0.4469875 0.3608311 0.5739520 0.5835942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2014 2015 -0.186065 -0.740712 -0.519729 0.4934830 0.2888710 -0.3719996 0.7311938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2015 2016 0.735059 -0.837523 0.516585 0.3619452 -0.2047533 -0.8989748 0.1375357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2016 2017 -0.432472 0.888201 -0.296430 0.0486925 -0.2664980 -0.0052158 0.9625906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2017 2018 -0.468169 0.969453 -0.029371 0.3100825 0.7369163 0.2305016 0.5546821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2018 2019 0.698441 0.332671 -0.417775 0.3882768 -0.1299231 0.8634157 0.2947448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2019 2020 0.156201 -0.169723 -1.062966 0.3821907 -0.1385627 0.8364419 0.3675536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2020 2021 0.223207 -0.744827 0.008887 -0.1886223 -0.5698156 0.7534004 0.2685511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2021 2022 -0.793954 0.291701 0.553085 -0.0171023 -0.0607758 0.9803910 0.1866745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2022 2023 0.840442 0.041227 0.644491 -0.2281313 -0.5887329 -0.6289036 0.4536848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2023 2024 0.060566 1.025714 -0.188837 0.6607218 0.0240265 0.5472815 0.5131787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2024 2025 0.639782 -0.691645 -0.796094 -0.5341975 0.7621034 0.0161608 0.3654727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2025 2026 0.697680 -0.127084 0.667273 0.5047396 0.4133004 -0.7317622 0.1973441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2026 2027 -0.900980 0.216132 -0.081374 0.3187227 -0.1783272 0.0563072 0.9292173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2027 2028 -0.805260 0.434452 0.034476 -0.1995721 -0.2210773 -0.3250187 0.8975849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2028 2029 -1.041050 -0.123772 0.278048 0.1043507 0.2082546 0.8561389 0.4612669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2029 2030 0.348876 0.936289 -0.147048 0.5452987 0.3277027 0.2561487 0.7277693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2030 2031 0.947015 0.153783 -0.032372 0.1919490 -0.1929701 0.9576299 0.0941441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2031 2032 -0.719277 -0.412016 -0.098186 0.0529367 0.7555527 0.2965180 0.5817345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2032 2033 0.062619 -0.093878 -1.151205 0.8475600 -0.2711634 -0.4552992 0.0285503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2033 2034 0.806603 -0.220336 0.568385 -0.4515156 0.0651338 0.4049916 0.7923844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2034 2035 0.154069 -0.855206 -0.147533 0.5391397 -0.1919183 -0.1423423 0.8076103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2035 2036 0.731371 -0.529570 0.437124 -0.0435480 -0.4614392 -0.8835342 0.0674143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2036 2037 -0.114635 1.239529 -0.119337 -0.3775010 0.3850392 0.5915061 0.5994650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2037 2038 0.496263 0.493392 0.852315 0.0171802 0.0761984 -0.8592630 0.5055352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2038 2039 -0.502115 0.245382 0.708790 0.5423901 0.1220778 -0.6557864 0.5107388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2039 2040 -0.448972 0.803585 -0.273778 -0.6188004 0.3226256 -0.0779405 0.7119860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2040 2041 0.728048 0.116308 0.632709 -0.0217783 -0.4082979 0.6990584 0.5866309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2041 2042 0.360411 -1.036408 0.149189 -0.5016084 -0.5105034 0.6670537 0.2069171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2042 2043 -0.790959 0.470942 0.194511 0.0906595 -0.3023690 -0.6222503 0.7163508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2043 2044 -0.703108 -0.748573 0.670775 0.1376989 0.1086086 -0.4954948 0.8507221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2044 2045 0.040046 -0.415501 0.936446 -0.5152269 -0.3959560 -0.6396418 0.4106318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2045 2046 0.887178 0.125220 -0.386485 -0.3368285 0.2743012 0.6231302 0.6503954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2046 2047 0.668586 -0.922526 -0.146643 0.0815527 -0.0486651 0.9719533 0.2151459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2047 2048 -0.762629 0.765843 -0.021001 0.0268800 0.5042639 -0.1231614 0.8542989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2048 2049 -0.390343 0.460226 -0.737845 0.0247056 -0.1723112 -0.5819991 0.7943396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2049 2050 -0.782029 -0.595675 -0.388273 -0.2389589 -0.4783977 -0.8265854 0.1754730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2050 2051 0.254841 -0.323366 -0.965873 -0.3317048 0.1536352 -0.8663532 0.3402944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2051 2052 -0.202483 1.048457 -0.546132 -0.1900141 -0.1480065 -0.9009414 0.3609618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2052 2053 -0.488101 -0.773494 -0.203317 0.1228035 -0.3675388 0.5502925 0.7396031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2053 2054 -0.917070 -0.025785 0.407130 0.2148934 0.5714656 -0.1932151 0.7680597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2054 2055 -0.629201 -0.408078 -0.589471 0.1123872 0.0785260 0.9885705 0.0626992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2055 2056 0.429772 0.391835 -0.884045 -0.6979816 -0.3475047 0.1750632 0.6011780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2056 2057 0.265056 1.011207 -0.068209 0.2521075 0.7437528 0.3130402 0.5341156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2057 2058 0.516659 0.597852 0.496281 -0.2273223 0.0020229 -0.2798405 0.9327431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2058 2059 0.146734 0.534556 0.901206 0.0489872 -0.7502521 -0.0445371 0.6578286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2059 2060 -0.346734 0.591882 0.863632 0.1564077 0.4160772 0.6780688 0.5853538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2060 2061 -0.485124 0.751458 -0.704784 0.1698256 -0.0821507 -0.1139685 0.9754085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2061 2062 -0.773323 0.173055 -0.943169 -0.6255361 0.1211439 0.1080366 0.7631231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2062 2063 -0.258000 0.695872 0.135792 0.7799509 -0.0931902 -0.0089860 0.6187984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2063 2064 -0.600352 -0.121204 -0.816933 -0.1133999 -0.0186918 -0.6889532 0.7156358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2064 2065 0.104757 -0.484924 -0.922900 0.4468319 0.1833776 -0.8136366 0.3235882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2065 2066 0.900498 0.316667 -0.233045 0.3821910 -0.0796278 0.6207622 0.6798850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2066 2067 0.038930 -0.853267 -0.036856 -0.0674210 -0.3187532 -0.8521662 0.4094674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2067 2068 0.450341 0.480453 -0.515125 0.0474067 0.1302949 0.9845001 0.1074026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2068 2069 -0.393693 -1.009755 -0.480134 0.4744693 -0.3927621 0.6428255 0.4554033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2069 2070 -0.535608 0.575629 0.489964 0.1386637 0.4014882 -0.6198752 0.6597987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2070 2071 -0.877371 -0.209954 -0.225928 -0.2476147 -0.4192615 0.4125573 0.7698722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2071 2072 -0.770882 0.202476 0.671170 -0.3770810 -0.0980730 -0.2038297 0.8981342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2072 2073 -0.601499 -0.656588 0.659291 -0.8464927 0.4636006 -0.2593007 0.0358839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2073 2074 0.450167 0.456720 -0.644207 -0.0879294 -0.2072254 -0.9684325 0.1070729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2074 2075 -0.699734 -0.565690 -0.191434 -0.4898749 -0.2066170 -0.8402987 0.1059724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2075 2076 0.245909 0.235169 -0.921941 0.5692691 -0.6047789 0.1665779 0.5314386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2076 2077 -0.863401 -0.410505 0.177002 -0.3822827 0.1606333 -0.8830496 0.2197280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2077 2078 0.898860 0.122812 -0.485763 -0.3219611 0.7526437 0.4143407 0.3977314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2078 2079 0.094232 -0.823242 0.589088 -0.4660443 -0.7669930 -0.2140488 0.3856262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2079 2080 -0.362850 -0.715861 0.385454 -0.4391930 0.2670172 -0.8492216 0.1209709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2080 2081 0.588579 -0.490772 0.334919 0.3751706 -0.2864449 -0.6614002 0.5828774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2081 2082 0.756463 0.550761 -0.143575 0.2675949 -0.2324148 -0.6728406 0.6493550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2082 2083 -0.679160 0.497518 -0.604615 0.1250252 -0.6562524 0.5088628 0.5429182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2083 2084 0.047367 0.848237 0.152777 0.6683757 0.6511363 0.2739942 0.2328577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2084 2085 0.882327 -0.247633 -0.109787 -0.3107615 -0.5009269 -0.2208789 0.7769891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2085 2086 0.327689 0.300632 -0.983329 0.2675953 0.3534198 0.0001121 0.8963745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2086 2087 0.838665 0.107284 -0.570768 -0.8944410 -0.0218118 0.4466536 0.0002976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2087 2088 0.923332 -0.304978 -0.277177 0.3390741 0.3340843 -0.2109980 0.8537542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2088 2089 0.775759 0.469914 0.086065 0.7628518 0.1197614 -0.4593113 0.4390302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2089 2090 0.337992 0.428905 -0.876481 -0.6999563 -0.0310925 0.5947570 0.3941555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2090 2091 0.934149 0.191441 0.147008 -0.1571534 0.0082068 -0.9762923 0.1486230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2091 2092 -0.928920 0.166769 0.279433 -0.3555341 0.3827894 0.8413611 0.1384889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2092 2093 0.501939 0.640023 0.884497 0.7181677 0.3008109 -0.6129607 0.1342653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2093 2094 -0.568836 -0.303860 -0.653818 0.4024802 -0.1046989 0.2846266 0.8637335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2094 2095 -0.970268 -0.252929 -0.296405 -0.0727063 -0.2483087 0.8342613 0.4868928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2095 2096 0.297700 0.895311 -0.030386 0.1163348 -0.1041384 -0.2808671 0.9469610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2096 2097 -0.353919 1.151031 -0.064219 -0.1992740 -0.4033339 -0.3829392 0.8068266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2097 2098 -0.659176 0.062982 0.704355 -0.3557331 -0.0868157 -0.5602263 0.7430098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2098 2099 -0.088179 -0.866998 0.436141 -0.3685677 -0.0061352 0.9105867 0.1869545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2099 2100 -0.895654 -0.625172 -0.427199 0.2830111 -0.2928329 0.7723170 0.4875244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2100 2101 -0.943549 -0.026005 0.409160 0.2007572 0.3937868 -0.1038508 0.8909789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2101 2102 -1.030529 -0.286974 -0.143427 -0.0969385 -0.2941805 -0.4577224 0.8333973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2102 2103 -0.191562 -0.819526 0.198756 0.4924408 -0.1652920 -0.4259291 0.7407868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2103 2104 0.712868 -0.234571 0.769149 -0.7529306 -0.0828412 -0.3534070 0.5489411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2104 2105 0.882956 -0.112922 0.105689 -0.4921626 -0.0565836 0.7892435 0.3628621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2105 2106 -0.452177 -0.195480 -0.618683 -0.3461337 0.0988305 0.4699968 0.8059323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2106 2107 -0.020087 0.580069 -0.800736 -0.2052404 -0.1895904 0.9305060 0.2368342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2107 2108 0.597886 -0.272732 -0.749145 0.5670186 -0.1545992 -0.6392371 0.4959485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2108 2109 0.636552 -0.213764 -0.779696 0.7387044 0.3562188 0.5721340 0.0093106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2109 2110 -0.874264 0.322269 0.623846 0.6918141 0.5459860 -0.2282923 0.4137332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2110 2111 -0.669852 -0.352069 -0.669954 0.1555631 -0.0453569 -0.8261298 0.5396780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2111 2112 0.455359 -0.762650 -0.540999 -0.6988879 -0.2266210 0.6051527 0.3065758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2112 2113 0.120612 0.627147 -0.688116 -0.6597794 -0.2600446 0.3726500 0.5984981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2113 2114 0.806486 0.495128 0.298061 0.4096276 -0.0898643 0.8769166 0.2348337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2114 2115 0.024147 -0.869885 0.765142 0.2527161 0.1681970 0.3330080 0.8927206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2115 2116 -0.732936 -0.104401 0.784841 -0.2515657 0.1366290 0.9186563 0.2722459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2116 2117 -0.033774 0.512795 0.867732 0.4596748 -0.5830552 0.4930316 0.4535036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2117 2118 0.786799 -0.084299 -0.635890 -0.0871462 0.4561302 0.4619321 0.7556253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2118 2119 0.593712 -0.662923 -0.164167 -0.5375654 -0.5473687 -0.0995421 0.6336420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2119 2120 -0.609515 -0.949452 -0.068655 0.7635265 0.4244040 0.3763730 0.3086291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2120 2121 0.324496 0.778478 -0.438288 -0.6424853 0.1350953 -0.6152985 0.4363136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2121 2122 -0.865610 0.000317 0.464508 0.6785501 0.5415426 -0.2167082 0.4464738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2122 2123 -0.530680 -0.502232 -0.323091 0.4321781 -0.0832579 -0.3353900 0.8329489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2123 2124 -0.054958 -0.788830 0.595564 -0.5258935 -0.1496084 0.6665359 0.5067380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2124 2125 -0.934489 0.161165 0.133579 0.6869291 -0.2854868 0.1881719 0.6412621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2125 2126 -0.797774 0.800646 -0.058143 -0.7780183 0.4760093 0.1470929 0.3827093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2126 2127 -0.713852 0.562569 0.280456 -0.2065833 -0.3896251 -0.1198988 0.8894605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2127 2128 -0.256627 0.154983 1.063439 -0.0375803 -0.2271828 0.2967100 0.9267896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2128 2129 0.137672 -0.102515 1.013821 0.8638652 0.0520755 0.5004922 0.0230780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2129 2130 1.011077 -0.065487 -0.267136 -0.2631806 -0.3489054 -0.4526146 0.7772651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2130 2131 0.097530 1.033278 -0.407378 -0.1775645 -0.0312825 -0.9776915 0.1077574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2131 2132 -0.036666 -0.955803 -0.442602 0.1072931 -0.1872736 0.7819684 0.5847583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2132 2133 -0.759528 0.551966 0.044678 0.3893098 -0.1308778 0.8118818 0.4149180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2133 2134 0.604256 0.305417 -0.770485 -0.5408394 0.0329776 -0.0659955 0.8378841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2134 2135 0.627333 0.896501 -0.008129 -0.3446532 -0.1151096 -0.1211539 0.9237346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2135 2136 0.369624 0.710167 0.374209 -0.2760733 -0.5228562 0.7942804 0.1397268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2136 2137 0.107860 -0.777862 -0.591161 -0.8599107 0.2012839 0.4593379 0.0951161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2137 2138 0.530134 0.478413 -0.001119 -0.9063879 -0.2208944 -0.1252297 0.3376155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2138 2139 0.890136 -0.220407 0.460261 0.2756223 0.2204471 0.1683078 0.9203846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2139 2140 -0.281157 0.940871 0.456026 0.6308121 -0.3440426 -0.6643436 0.2058116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2140 2141 0.609900 -0.238786 0.654380 -0.8053615 0.3181167 0.3920146 0.3106754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2141 2142 0.033619 -0.308279 -0.925632 0.3307784 0.8465792 -0.3912516 0.1442617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2142 2143 0.288096 0.342282 0.733262 0.7521377 -0.0759356 0.3917169 0.5244812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2143 2144 1.093714 0.041853 -0.129678 -0.4605425 0.3809420 -0.4162343 0.6852246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2144 2145 0.230287 0.562715 0.768184 -0.4191571 -0.1946976 0.8716456 0.1631998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2145 2146 -0.517769 -0.685000 0.256294 -0.4567335 -0.0850979 0.6697677 0.5792789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2146 2147 -0.778771 0.292290 0.164927 -0.2615129 -0.1998569 -0.4854642 0.8099338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2147 2148 -0.600240 -0.638146 0.314339 0.4144517 0.0788869 -0.1407386 0.8956558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2148 2149 -0.373187 -0.329149 0.605472 -0.8009967 0.3536947 -0.0308047 0.4820326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2149 2150 -0.495987 -0.319612 -0.765112 0.3378588 0.3295636 -0.4286288 0.7704003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2150 2151 0.549011 -0.861464 -0.567007 0.4568687 0.6132764 -0.1165485 0.6337030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2151 2152 0.089759 -0.168470 0.866673 -0.7527356 0.2129814 0.4003556 0.4772248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2152 2153 -0.623954 -0.565647 -0.476313 0.1576886 0.3413078 0.9266251 0.0030456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2153 2154 0.537432 0.140137 -1.062332 -0.7217271 0.4958175 0.2994162 0.3789788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2154 2155 0.854381 -0.368460 0.549267 0.7979787 -0.5541476 0.1709086 0.1641361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2155 2156 0.691423 -0.425044 -0.381069 -0.7833610 0.0382502 -0.6098260 0.1139944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2156 2157 -0.019672 0.632954 0.579531 0.1756039 -0.5042928 0.6644468 0.5228408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2157 2158 0.951134 -0.350361 -0.395579 0.8421444 -0.1824822 0.5010516 0.0802513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2158 2159 0.199975 0.166146 0.966896 -0.0242233 -0.7517911 -0.6520984 0.0948218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2159 2160 0.528879 0.107911 0.746618 -0.6268705 -0.1160064 0.1016764 0.7637001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2160 2161 -0.535749 -0.490872 -0.716072 -0.1376743 0.3365233 -0.1084786 0.9252190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2161 2162 0.395046 -0.162115 -0.996800 0.7608250 0.1794488 -0.5670848 0.2595346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2162 2163 1.090504 0.112868 0.438669 0.3055320 -0.1027723 -0.9463233 0.0236694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2163 2164 -0.936339 -0.026346 -0.486039 0.4222301 -0.0599101 0.3731936 0.8239290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2164 2165 -0.833750 0.468729 -0.372479 0.0444284 -0.1435759 -0.1433759 0.9781899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2165 2166 -1.133829 0.189670 -0.053850 0.2206192 -0.9139143 -0.3271878 0.0950578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2166 2167 0.925993 0.476918 0.253633 -0.1187773 0.4724704 0.7249555 0.4869325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2167 2168 -0.553039 -0.548065 0.897451 -0.4981070 -0.6576271 -0.5393972 0.1687209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2168 2169 0.705001 0.020083 -0.841015 -0.6034477 -0.3774111 -0.6689801 0.2141902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2169 2170 -0.955415 0.352336 0.503492 -0.3221131 0.5663125 -0.7457608 0.1391908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2170 2171 0.676276 -0.389413 -0.618531 -0.0540727 0.0604882 -0.5821402 0.8090304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2171 2172 0.758787 0.480734 -0.508510 0.6308595 -0.6069831 0.3818905 0.2962220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2172 2173 -0.744135 -0.744055 0.015982 0.3292552 -0.2084745 0.8211013 0.4170397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2173 2174 -0.047925 0.920403 0.107014 -0.2022830 0.0610745 0.7387236 0.6400304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2174 2175 0.831255 -0.106230 0.449704 -0.0606377 0.1282021 -0.7177077 0.6817499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2175 2176 -0.036249 0.697273 0.481205 -0.2078991 0.0995348 0.8372039 0.4959440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2176 2177 0.555677 -0.355259 0.820330 -0.6674285 -0.1442150 -0.5276694 0.5052784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2177 2178 1.084263 0.013111 -0.229457 0.0484014 -0.0772877 -0.9074493 0.4101460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2178 2179 -0.735181 0.493162 -0.306063 -0.6059283 0.7220304 0.1641883 0.2908009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2179 2180 -0.530285 0.326867 -0.805271 0.5935495 -0.4457043 0.5834143 0.3296580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2180 2181 -0.490588 0.402113 0.869326 -0.5750787 0.0864832 0.5544245 0.5953307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2181 2182 -0.676891 -0.368068 0.490400 0.0859660 0.3654479 -0.3144858 0.8718695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2182 2183 -0.624784 -0.585667 0.239400 0.6234896 0.4789752 0.2429478 0.5681724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2183 2184 -0.931992 -0.058860 -0.158164 -0.3862753 -0.8529216 -0.3491806 0.0372702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2184 2185 0.374117 -0.977206 -0.172983 0.2269462 0.8769846 0.3971995 0.1470581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2185 2186 -0.906414 -0.425555 -0.152656 -0.0585690 -0.7684304 -0.5702449 0.2844383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2186 2187 0.726244 -0.787121 0.087140 -0.2606612 -0.0783467 0.2558093 0.9276201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2187 2188 0.014336 -0.732864 -0.552811 -0.7670256 0.0343791 -0.6159595 0.1763058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2188 2189 -0.203501 0.956266 -0.089945 -0.0861044 0.0520017 -0.4987357 0.8608975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2189 2190 -0.962234 0.393556 -0.061799 0.3640593 -0.3301865 -0.6448858 0.5852863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2190 2191 -0.369463 -0.389228 0.820207 -0.0758139 0.7900011 0.5939777 0.1316853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2191 2192 0.124782 0.799202 -0.487639 -0.0662239 -0.1806042 0.8644052 0.4645430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2192 2193 0.499118 -0.374748 -0.804325 0.4855886 0.5462474 -0.2843851 0.6204375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2193 2194 0.919409 0.349930 0.540702 0.1301448 -0.1897963 0.9131221 0.3365229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2194 2195 0.011921 -0.989722 0.316414 -0.0421513 0.7573118 0.5356415 0.3712012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2195 2196 -0.539193 0.156415 -0.828857 0.3438859 -0.6801242 0.0349511 0.6464921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2196 2197 -0.890704 0.079262 0.551307 0.2937680 -0.6161401 -0.6996256 0.2111768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2197 2198 0.386638 0.666241 0.566616 -0.2499326 0.2274179 0.9038231 0.2625234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2198 2199 -0.450141 -0.437036 0.631304 -0.0242195 0.4890655 0.8470067 0.2069010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2199 2200 0.777159 0.173316 0.183802 0.2484036 -0.6559128 -0.7127431 0.0084453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2200 2201 0.237214 0.286315 -0.838861 -0.5592317 -0.0311514 -0.3664451 0.7429721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2201 2202 -0.396371 0.834523 0.177709 -0.0249833 -0.2695164 0.7707095 0.5768394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2202 2203 1.017341 0.379872 -0.039987 0.3562595 -0.1209237 -0.3520679 0.8570325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2203 2204 0.627778 0.667588 -0.619712 -0.0137976 0.2163243 -0.2616698 0.9405011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2204 2205 0.328265 0.945244 -0.376400 -0.2252602 -0.0459771 0.9133147 0.3361549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2205 2206 0.422245 -0.823694 -0.608436 0.5354214 0.0315651 -0.6894481 0.4868149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2206 2207 1.122816 0.343139 -0.001943 0.1151655 0.2351115 0.9466264 0.1880370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2207 2208 -0.742748 -0.462988 0.577988 0.4022907 0.1511541 -0.8422972 0.3253460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2208 2209 0.178397 0.093280 0.964266 0.4682016 -0.7709941 -0.2564144 0.3472853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2209 2210 0.358102 0.464471 -0.808144 0.3662212 -0.5065788 -0.1219192 0.7709706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2210 2211 -0.784027 -0.069166 -0.626632 -0.6540225 0.0393603 0.1949587 0.7298606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2211 2212 -0.543220 0.826184 -0.087499 -0.6819149 0.3541234 0.6035709 0.2128164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2212 2213 -0.081044 -0.282622 0.830562 -0.8513951 -0.4059766 0.1727566 0.2836626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2213 2214 -0.209704 -0.475634 -0.648423 -0.2600049 -0.7458846 0.6084224 0.0766543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2214 2215 -0.025176 0.679362 0.742618 0.7473641 -0.2770204 -0.3300167 0.5057625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2215 2216 -0.649570 0.563052 -0.680275 -0.1436270 -0.2309076 0.9333097 0.2344908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2216 2217 0.733156 0.117178 -0.840483 0.0456252 0.5012683 0.2571657 0.8249329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2217 2218 0.770154 -0.333793 0.505879 0.0189655 -0.6771840 -0.2292065 0.6989468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2218 2219 0.537164 0.062117 -0.883683 0.5694930 0.5979255 -0.4448029 0.3468620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2219 2220 -0.231024 0.587984 -0.626427 -0.7460463 0.0406437 -0.2434714 0.6184535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2220 2221 -0.590926 0.264112 -1.119716 0.3909445 0.0536970 -0.2895080 0.8720460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2221 2222 -0.006619 -0.525049 -0.815187 -0.2043212 -0.8276637 0.4627091 0.2431585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2222 2223 -0.452335 0.356622 0.920688 0.1180562 0.0042283 0.7935976 0.5968649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2223 2224 0.383808 0.404632 0.629538 -0.6939515 -0.3213475 -0.3172288 0.5608324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2224 2225 1.216151 -0.194331 0.361253 0.2753603 -0.4580108 0.5882394 0.6069409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2225 2226 -0.153910 -1.073219 -0.048266 -0.0425286 -0.4661348 -0.3142401 0.8259315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2226 2227 0.395095 -0.842442 -0.379177 -0.2764649 0.2555120 -0.6437785 0.6662056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2227 2228 0.911623 0.430352 -0.089584 -0.2844510 0.4440798 0.0987779 0.8438742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2228 2229 0.599696 -0.026267 0.995166 0.8087607 0.0983917 -0.2855406 0.5046700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2229 2230 -0.009411 0.877711 -0.303044 0.6065306 -0.5852279 -0.5025481 0.1925471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2230 2231 -0.913504 -0.369325 0.489354 -0.5108850 0.6880683 0.2639441 0.4425970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2231 2232 0.007223 0.179389 -0.958130 0.4082760 -0.3435764 -0.2142150 0.8181552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2232 2233 -0.698732 -0.368095 -0.368939 -0.2358929 0.4138043 0.2974729 0.8274240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2233 2234 -0.232353 0.242580 -0.904453 0.0393172 -0.7304051 -0.1184356 0.6715174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2234 2235 -0.936503 -0.313150 0.314887 0.2483329 0.4328040 0.5831450 0.6410564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2235 2236 -0.260999 0.669499 -0.826706 -0.3855019 0.0966635 -0.6469426 0.6507763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2236 2237 -0.896799 0.195376 -0.437287 0.0030666 -0.0859403 -0.2329600 0.9686767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2237 2238 -1.083549 -0.137615 -0.377329 -0.3236124 -0.2686741 -0.8979961 0.1291984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2238 2239 0.534383 -0.354337 -0.759502 -0.4526050 -0.7963344 -0.3728877 0.1481722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2239 2240 -0.410786 0.003002 -0.902598 0.2705351 0.9315816 0.2233776 0.0952313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2240 2241 -0.879187 0.282986 0.482547 0.4846180 0.7935003 0.3315048 0.1600225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2241 2242 0.649285 -0.108577 -0.676196 0.2677107 -0.6985986 -0.4948237 0.4420866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2242 2243 -0.445784 -0.492255 -0.590880 -0.7333191 -0.5977157 0.0180620 0.3235009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2243 2244 -1.063700 -0.124682 0.402628 -0.0952653 0.0918078 0.9148979 0.3813892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2244 2245 0.697036 0.922659 0.544702 -0.2264793 -0.3446744 0.8463337 0.3370845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2245 2246 0.271952 -1.072633 -0.208686 -0.5560666 -0.0205701 -0.7975937 0.2328328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2246 2247 0.110627 0.993496 -0.222485 0.2459664 -0.5072186 -0.8206008 0.0940434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2247 2248 -0.446017 -0.669472 0.563124 -0.4891964 -0.6147998 -0.4358149 0.4390598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2248 2249 0.272205 -0.459567 -0.661148 0.5447816 -0.7081424 0.3677149 0.2579400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2249 2250 -0.634028 -0.509351 1.026309 -0.0261752 0.7729781 -0.4127646 0.4810874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2250 2251 -0.188635 -0.933864 -0.178881 0.1273352 0.4167540 0.8861420 0.1576520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2251 2252 -0.241164 0.372734 -0.778439 0.0208617 -0.0865893 -0.2996233 0.9498910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2252 2253 -0.605805 0.169857 -0.797126 -0.7031471 -0.5543091 -0.0970060 0.4346439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2253 2254 -0.776404 -0.006252 0.726599 0.1130702 0.3503846 0.7024925 0.6090567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2254 2255 -0.027026 0.903512 0.062697 0.5764181 -0.6770609 -0.0166467 0.4572238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2255 2256 -0.552464 0.471556 -0.692456 -0.5055714 0.2462707 0.3299965 0.7581890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2256 2257 0.220762 1.044468 0.244950 -0.2685397 0.4291516 -0.2547622 0.8239002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2257 2258 -0.679034 0.692780 0.526687 0.7773498 0.1784134 0.2857405 0.5312704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2258 2259 0.021583 0.165826 -1.027251 0.0941801 -0.5707696 -0.5907502 0.5624645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2259 2260 0.521814 -0.728953 0.538648 -0.5334599 -0.4598704 -0.0675380 0.7066671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2260 2261 0.563717 0.669680 0.161983 0.3404476 0.1346830 0.8207354 0.4385764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2261 2262 0.315645 -0.880778 0.653160 -0.6672218 0.4988166 0.4681560 0.2946642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2262 2263 -0.195313 0.119902 -1.070920 0.2331876 -0.3765883 -0.1246567 0.8878432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2263 2264 -0.803804 -0.273681 -0.263789 -0.1251442 -0.2438943 -0.9343407 0.2277321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2264 2265 0.704305 -0.306506 -0.795750 0.6068703 0.6029739 0.2049066 0.4755462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2265 2266 0.076095 -0.399747 0.855893 0.5611759 -0.5666086 -0.5519883 0.2436088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2266 2267 -0.206507 0.859120 -0.385033 -0.7049161 -0.5361983 0.0916233 0.4551811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2267 2268 0.523052 0.088908 0.973718 0.2413581 0.9541970 -0.1039358 0.1430098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2268 2269 -0.651056 0.259759 -0.683024 0.0018664 -0.5157511 0.3916146 0.7619943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2269 2270 -0.602542 0.855953 0.340292 0.7429547 0.0413855 0.1786234 0.6437385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2270 2271 -0.361384 -0.026605 -0.956919 -0.7976059 -0.0392386 -0.2516978 0.5467480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2271 2272 -0.739601 0.585515 0.248531 0.1753548 0.0685190 0.6179120 0.7633745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2272 2273 0.418610 0.810603 0.007779 0.1343031 -0.4214533 -0.4652380 0.7667421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2273 2274 -0.661506 0.773260 -0.451807 0.1510439 0.1416072 -0.5619117 0.8008673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2274 2275 -0.700600 -0.477701 -0.820017 -0.0553477 -0.7517099 -0.0132021 0.6570347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2275 2276 -0.670316 -0.275105 0.686721 -0.3026909 0.1324475 0.3726792 0.8671483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2276 2277 -0.900316 0.031738 0.239158 -0.0713783 0.9667215 -0.1741361 0.1732956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2277 2278 0.854493 -0.079814 -0.395755 -0.1696822 0.1787421 -0.8697857 0.4274717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2278 2279 -0.420884 0.741297 -0.137484 -0.5454002 -0.2977452 -0.4220652 0.6601116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2279 2280 -0.653381 0.930187 -0.112331 0.1949426 0.4076781 0.4831374 0.7499161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2280 2281 0.701802 -0.713407 -0.249597 0.4260113 -0.0473976 0.6841559 0.5900835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2281 2282 -0.407029 -0.346724 0.544743 -0.2523260 0.8584903 0.0413006 0.4445449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2282 2283 -0.127536 -0.211102 -0.968939 0.9507071 0.0051605 -0.1434442 0.2748693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2283 2284 0.137875 -0.384027 0.767583 -0.6909972 -0.5173273 0.0783078 0.4987617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2284 2285 0.121781 -0.574655 -0.984841 0.7750297 -0.0479387 0.0955355 0.6228192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2285 2286 0.067921 -0.666301 0.601812 -0.2660970 -0.6153610 -0.4439242 0.5945204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2286 2287 0.832911 -0.009808 -0.323403 -0.5908054 -0.2303188 0.4699067 0.6140765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2287 2288 0.407118 -0.023866 -0.954346 0.7894970 -0.4090849 0.4569745 0.0227665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2288 2289 -0.586572 -0.119120 0.975709 0.3454550 -0.2582683 0.6037771 0.6703816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2289 2290 0.596897 0.607924 0.396687 0.2792235 -0.0968588 -0.6068985 0.7377851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2290 2291 -0.730501 0.712447 -0.060295 -0.1284667 -0.3193635 -0.4320673 0.8335593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2291 2292 -0.678103 -0.219758 0.751865 -0.1976432 0.5228498 -0.0364812 0.8283926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2292 2293 -0.812265 -0.406526 -0.445302 0.0528854 -0.8909035 0.1369852 0.4298012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2293 2294 0.056023 -0.288716 1.039382 -0.9103773 0.0145202 -0.1255104 0.3940170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2294 2295 0.294484 -0.507647 -0.693955 0.8209875 -0.0113278 0.0953899 0.5628073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2295 2296 0.304009 -0.410020 0.673643 -0.1153495 -0.5059660 -0.6217943 0.5865703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2296 2297 0.895624 0.491052 0.017628 -0.3885903 0.8574083 0.0805116 0.3276681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2297 2298 -0.735567 -0.231791 0.691620 -0.1947806 0.6183639 0.7367980 0.1918730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2298 2299 0.156255 0.895030 -0.119679 -0.5607976 0.3749832 0.4724449 0.5671767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2299 2300 -0.729236 0.673932 0.179044 0.8711469 -0.1008855 -0.1331177 0.4617411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2300 2301 -0.238403 -0.861649 0.405426 -0.1457956 0.0517932 -0.2859051 0.9456846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2301 2302 0.357678 -1.010495 0.321206 -0.2491320 0.0829855 0.1789899 0.9481610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2302 2303 0.007878 -0.953100 -0.187771 -0.0250089 -0.1728191 0.9653001 0.1941747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2303 2304 -0.299015 1.187392 0.227116 0.2813102 0.3403734 -0.4954396 0.7480309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2304 2305 -0.738413 0.085905 -0.624527 0.0416218 -0.3853172 -0.8867825 0.2518236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2305 2306 0.680122 -0.717406 -0.088943 -0.1439379 0.0613584 -0.3568086 0.9209803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2306 2307 0.893193 -0.342103 -0.128144 0.1899954 -0.3887366 -0.5772015 0.6925490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2307 2308 0.115572 0.511003 -0.852532 0.3263477 -0.0708928 0.8736819 0.3537674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2308 2309 -0.532967 -0.414186 -0.751559 0.6549453 0.3790071 0.3372853 0.5600348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2309 2310 -0.624649 -0.803476 -0.046111 -0.3619665 0.2980877 0.8141661 0.3424288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2310 2311 0.122228 1.074068 -0.383120 -0.2145299 0.2413665 -0.0169878 0.9462719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2311 2312 0.097253 0.925599 0.140045 0.2463633 0.5852870 -0.5271594 0.5646657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2312 2313 -0.523728 0.327741 -0.852326 0.3619467 0.0496025 -0.7971788 0.4806663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2313 2314 0.445437 -0.729719 -0.496134 0.1772291 0.4199759 0.7699498 0.4465282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2314 2315 -0.998721 -0.529063 -0.569839 -0.3511333 -0.0143753 -0.2823192 0.8926335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2315 2316 -0.715497 -0.352040 -0.573250 0.4574026 -0.3107299 -0.1309668 0.8228472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2316 2317 -0.643068 -0.768020 0.279368 -0.3760122 0.5497204 -0.0626832 0.7432988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2317 2318 -0.035905 -0.661054 -0.400660 -0.2128588 -0.7508679 0.1073266 0.6159298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2318 2319 -0.883082 -0.311162 0.366922 0.7621058 -0.0826846 0.3164982 0.5587368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2319 2320 0.625886 0.400940 -0.797211 0.1158262 -0.5640433 -0.7319259 0.3643129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2320 2321 0.446208 0.363301 -0.792131 -0.9739229 -0.0575953 0.2061853 0.0751308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2321 2322 0.752670 -0.411544 0.687343 0.1573920 -0.1762883 -0.9492682 0.2074608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2322 2323 -0.594516 0.633535 0.290035 -0.5916737 -0.0615344 -0.3791415 0.7087930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2323 2324 -0.589784 -0.544027 0.388719 -0.7418777 0.1735258 -0.0456842 0.6460799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2324 2325 -0.403187 -0.092553 -1.011099 0.3023682 0.6655731 0.0670041 0.6790408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2325 2326 0.715393 -0.803534 -0.117542 0.2021426 -0.6108101 0.7537866 0.1336233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2326 2327 -0.795086 0.053653 0.855426 0.0576047 0.5002287 0.6405341 0.5798009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2327 2328 -0.193315 0.847595 -0.095328 -0.4860575 -0.0902263 0.1017133 0.8632854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2328 2329 0.247007 0.646566 0.777276 -0.4762878 -0.6772107 0.2802304 0.4858050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2329 2330 0.493325 -0.605781 -0.626945 0.1827019 0.7307290 -0.6206062 0.2179520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2330 2331 -0.246427 0.837738 0.697222 0.0519607 -0.3328009 -0.4764867 0.8120986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2331 2332 -0.387644 0.595036 0.618562 -0.1799067 0.0687561 -0.5452894 0.8158221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2332 2333 -0.585986 -0.575380 0.593171 -0.1624105 -0.5892998 -0.7867426 0.0859337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2333 2334 0.816312 0.471760 -0.544460 0.4373528 -0.4223540 0.6774359 0.4140291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2334 2335 -0.494412 -0.692532 -0.459218 0.0442946 0.9290829 -0.2093639 0.3016780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2335 2336 0.648376 -0.535883 0.324809 0.2813441 -0.1398080 -0.8111654 0.4932646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2336 2337 0.181592 0.898359 -0.122875 0.0776439 -0.6413094 0.7622438 0.0409645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2337 2338 -0.338132 0.102161 -0.991668 0.6688658 -0.5207646 0.2378626 0.4741773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2338 2339 -1.017204 -0.083278 0.538192 0.6356914 0.6120897 0.4485920 0.1414489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2339 2340 -0.779811 0.572479 -0.264062 0.2032084 -0.4374625 -0.8674642 0.1218148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2340 2341 -0.015851 0.712004 0.702869 0.7912576 0.0415125 -0.6069470 0.0616719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2341 2342 -0.681693 -0.710697 -0.184669 -0.2161781 -0.4733688 -0.6196906 0.5875140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2342 2343 0.301552 -0.954498 -0.324771 0.1853006 0.5104947 0.5819105 0.6053421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2343 2344 -0.559920 -0.754151 -0.074257 0.3856110 -0.5585361 -0.0834715 0.7296397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2344 2345 0.024732 -0.536075 0.821400 -0.2211112 0.3024724 0.3210616 0.8697929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2345 2346 -0.830068 -0.587736 0.260408 0.0898003 -0.0055061 -0.8643700 0.4947425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2346 2347 0.914303 -0.345158 0.342666 0.7266875 -0.1336802 -0.1467021 0.6576727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2347 2348 0.853716 0.347906 -0.088723 -0.0849748 -0.1687454 0.6304576 0.7528795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2348 2349 0.743027 -0.814449 -0.316476 0.2136477 0.3525297 0.3610074 0.8365113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2349 2350 0.072322 -0.835151 0.047925 0.2145002 -0.1530787 -0.1374750 0.9548074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2350 2351 0.305535 -0.753694 0.719580 -0.5447638 0.2892656 0.4877905 0.6177526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2351 2352 -0.559097 -0.635074 -0.584196 0.3584595 -0.0951009 -0.9258799 0.0721731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2352 2353 0.974217 0.356892 -0.265417 -0.5654698 -0.5737122 0.0272016 0.5919108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2353 2354 0.390484 0.874709 -0.372320 0.4436575 -0.1263986 0.0504871 0.8858004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2354 2355 0.525241 -0.155449 -0.948888 0.1943031 0.6302023 -0.3255991 0.6775519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2355 2356 1.013132 0.521819 0.039825 -0.4076172 -0.3587895 -0.8364201 0.0742947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2356 2357 -0.497834 0.199127 0.964297 0.0324280 -0.3412878 0.3178897 0.8839781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2357 2358 0.471238 0.233487 0.824581 0.1573358 -0.8645048 0.3197170 0.3544826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2358 2359 0.536390 -0.391771 -0.772699 0.6425400 0.0341049 0.3536698 0.6788939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2359 2360 -1.004001 0.225436 -0.291114 -0.5883920 0.2809202 -0.6065661 0.4549244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2360 2361 -0.724823 0.072436 0.496554 0.1000505 -0.7033984 0.6879581 0.1481020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2361 2362 1.035016 -0.055643 0.015800 -0.3301269 0.5899462 -0.3865000 0.6273735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2362 2363 -0.014484 0.091651 1.092912 0.1536951 -0.4918395 0.6471979 0.5617887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2363 2364 0.779836 -0.575340 0.300756 -0.4988460 0.2555209 0.5691138 0.6016405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2364 2365 -0.321572 -0.692716 -0.611023 0.7835479 0.4122980 -0.4600223 0.0666521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2365 2366 0.081979 0.356701 0.880109 0.3951716 -0.3090036 0.7256419 0.4709565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2366 2367 1.124316 -0.064947 0.077047 -0.4099841 -0.0456563 -0.6515073 0.6366842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2367 2368 0.376617 0.832980 0.374668 -0.0501341 0.5695950 0.8202153 0.0171759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2368 2369 -0.613436 0.079167 0.929650 -0.0182902 -0.4365652 -0.7272535 0.5293190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2369 2370 0.306220 0.190053 0.767103 -0.2762176 -0.7264838 0.3662816 0.5116278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2370 2371 0.362563 -0.578970 -0.746528 0.3143336 0.1297887 0.9402804 0.0149003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2371 2372 -0.938396 0.600394 -0.567521 0.4021426 -0.3253190 -0.4130479 0.7495601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2372 2373 -0.770514 -0.627152 0.208932 -0.0793265 0.1330728 0.9452056 0.2873766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2373 2374 0.392380 0.971176 0.083231 -0.2467407 0.2557017 0.4268213 0.8316004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2374 2375 0.561028 0.109280 0.858040 0.6775224 0.0996129 -0.0179871 0.7285033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2375 2376 0.456162 0.742200 0.091619 -0.1302389 0.6580311 0.7131115 0.2037273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2376 2377 -0.170559 -0.124996 0.956784 -0.0214496 -0.1843370 0.2442960 0.9517769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2377 2378 0.012798 -0.024561 1.129560 0.8693149 0.0215739 0.3938052 0.2978987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2378 2379 0.715852 0.639795 -0.314532 -0.0933097 0.8445610 0.2413125 0.4688053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2379 2380 -0.706690 0.650607 -0.014251 0.0978682 -0.8523517 0.1350370 0.4956646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2380 2381 -0.633339 -0.070502 0.429892 0.5374699 -0.0049090 0.6737595 0.5070997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2381 2382 0.010874 0.962959 -0.307830 -0.0312560 0.6762372 0.5134508 0.5273467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2382 2383 0.692812 0.189717 0.892147 -0.0896895 -0.9017427 0.1367290 0.4001513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2383 2384 0.271288 -0.153452 -1.137155 -0.7249826 -0.6224827 -0.1275868 0.2657766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2384 2385 -0.479948 0.264010 0.779637 -0.2222438 0.3401270 -0.1556356 0.9003882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2385 2386 -1.032526 -0.159546 0.250307 -0.4763207 -0.0318303 0.8133668 0.3324754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2386 2387 -0.171905 0.662558 0.836071 -0.3709252 0.3717735 -0.8508009 0.0183506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2387 2388 0.777862 -0.817869 -0.091043 -0.2885621 0.7031798 0.3536354 0.5451717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2388 2389 -0.119802 -0.904301 -0.497636 0.4406295 -0.2871333 -0.0582113 0.8485350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2389 2390 0.092605 -0.730226 0.391573 -0.1394100 -0.1505033 0.8802819 0.4278053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2390 2391 -0.805500 0.441148 0.662033 -0.0674394 -0.5903344 0.8040896 0.0199273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2391 2392 0.673180 -0.755886 -0.128203 0.3448337 -0.0185657 0.4435993 0.8270216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2392 2393 -0.262438 -0.722280 0.689378 0.4270625 -0.6198193 -0.6371827 0.1656502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2393 2394 0.464009 0.911574 -0.276372 0.5127476 0.1969730 -0.8012258 0.2373367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2394 2395 -0.052961 -0.686464 -0.940097 0.1276036 -0.9558001 0.1563120 0.2138458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2395 2396 -0.238134 -0.234003 0.853143 -0.1800858 0.5886460 -0.1543032 0.7728231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2396 2397 -0.717904 -0.574932 -0.315390 -0.0520173 -0.1500430 0.9819789 0.1024632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2397 2398 0.673857 0.965730 0.088971 0.4238359 0.1522379 0.2869864 0.8454736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2398 2399 0.948571 0.150611 -0.031279 -0.8512057 0.0340931 0.4227722 0.3091120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2399 2400 -14.580151 5.851332 10.828847 0.4297491 0.1436402 -0.3025804 0.8385275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2400 2401 0.909529 0.071621 -0.100542 -0.0419831 -0.2933276 -0.7639812 0.5731746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2401 2402 -0.157733 1.022873 -0.258514 -0.4258631 0.5480613 -0.5774898 0.4298546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2402 2403 -0.774038 0.110980 -0.517519 0.6482986 -0.0846146 0.3481714 0.6718080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2403 2404 -0.719815 0.097099 -0.674109 -0.0740769 0.0623540 -0.7132975 0.6941407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2404 2405 -0.094887 -0.511617 -0.881694 -0.4097673 0.1924026 0.8008297 0.3921018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2405 2406 0.391225 0.526219 -0.826846 0.0231321 0.7369095 0.6632374 0.1286290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2406 2407 -0.254369 -0.858457 0.715027 -0.8347034 -0.1062290 -0.5277330 0.1161181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2407 2408 0.499996 0.617250 -0.513635 -0.1040954 0.4166025 -0.3474457 0.8335995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2408 2409 -0.083810 1.002079 0.061991 0.0653623 -0.0624702 -0.8250387 0.5577961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2409 2410 -1.008539 -0.422421 0.039606 -0.4235101 0.0115181 0.4178986 0.8036587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2410 2411 -0.861601 0.441725 -0.008085 -0.0823525 0.0281178 0.2834888 0.9550191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2411 2412 -0.331819 0.940849 0.176112 0.1843127 -0.4208510 -0.8536774 0.2452513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2412 2413 -0.075206 -0.420061 1.001496 -0.3495905 0.5152509 -0.0496637 0.7809203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2413 2414 -0.715331 -0.711352 -0.144868 -0.4101570 0.2425763 0.2197879 0.8512469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2414 2415 -0.549649 0.050675 -0.968363 0.6066475 -0.7490420 -0.1619090 0.2114246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2415 2416 0.006390 -0.018596 0.847155 -0.0127883 -0.3175243 -0.4092566 0.8552916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2416 2417 0.772723 0.000873 0.545654 0.4719338 0.5445854 0.6879096 0.0865193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2417 2418 -0.095072 0.831170 0.593126 -0.0926740 0.7414010 -0.1499171 0.6475036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2418 2419 -0.896225 0.512737 -0.298382 0.0153601 -0.3866124 0.5187955 0.7623294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2419 2420 -1.009567 0.027090 0.339684 -0.3008081 0.2905411 0.0517519 0.9068749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2420 2421 0.081449 -0.763690 -1.001687 0.2787227 0.0396823 0.7468931 0.6024033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2421 2422 -0.890626 -0.309294 -0.362358 -0.6827061 0.1663516 0.1060627 0.7035554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2422 2423 -0.549226 0.712690 -0.270429 -0.6109482 0.1275391 0.7252360 0.2907040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2423 2424 0.547032 -0.393391 0.704972 -0.6879036 0.2056524 0.5897610 0.3696995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2424 2425 -0.516142 -0.436222 -0.698268 -0.2840414 -0.5108272 -0.2545695 0.7704352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2425 2426 -0.573463 -0.710894 -0.013092 0.0878714 -0.1282807 -0.1854659 0.9702706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2426 2427 -0.476357 -0.806473 0.001551 -0.1118509 0.5525169 -0.2357568 0.7916016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2427 2428 0.081681 -0.950524 -0.252456 0.0706113 -0.3135967 -0.6874728 0.6511929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2428 2429 0.610638 0.030010 -0.463628 -0.1894981 -0.1171643 -0.9335606 0.2807626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2429 2430 -1.044661 0.388023 -0.118004 0.3700507 0.0100758 0.6609961 0.6527214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2430 2431 0.188114 0.515294 -0.731035 0.1950125 0.2599298 0.3288939 0.8866992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2431 2432 0.755543 -0.188259 -0.761780 -0.3598215 -0.2788254 -0.6632505 0.5940402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2432 2433 -0.511636 0.648913 -0.594441 -0.6730391 -0.1565105 -0.5393931 0.4812255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2433 2434 -0.693581 -0.718605 0.193545 0.1363382 0.1006574 0.5261292 0.8333475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2434 2435 -0.572083 0.606417 -0.009452 0.2576448 -0.1727700 0.6031258 0.7348530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2435 2436 0.293791 0.979928 -0.180370 0.3533675 0.0511390 -0.7533162 0.5522960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2436 2437 -0.671161 0.018718 -0.784519 -0.1787913 -0.7203802 0.0954877 0.6633009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2437 2438 -0.753829 0.232267 0.640040 0.6427691 -0.1945995 0.7328390 0.1092061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2438 2439 0.874401 0.072710 -0.689738 0.1547242 0.0151481 0.4513960 0.8786766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2439 2440 -0.929379 -0.561131 -0.224576 -0.3434756 -0.5422878 0.6013177 0.4757788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2440 2441 0.887520 -0.162917 0.281678 0.0208105 0.5213960 -0.7524379 0.4019332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2441 2442 -0.566206 0.442960 0.601182 0.1157385 -0.1468212 -0.6707034 0.7177779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2442 2443 -0.409991 -0.410527 0.836325 -0.4708537 0.2867521 -0.4120301 0.7254662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2443 2444 0.074910 -1.205194 -0.088344 0.6198548 0.3343072 -0.6568416 0.2694027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2444 2445 0.059514 0.655892 0.913164 0.7184693 -0.4449012 -0.4666327 0.2609955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2445 2446 -0.938712 0.209016 -0.249054 -0.8396801 -0.1078607 0.4653910 0.2582917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2446 2447 0.018029 0.122453 1.081650 0.5747589 0.3419683 0.4050655 0.6234035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2447 2448 0.034218 0.800676 0.084630 -0.4302270 -0.5763930 0.1465666 0.6791128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2448 2449 0.674628 0.562169 0.402714 -0.1103361 -0.7359671 0.6075032 0.2777018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2449 2450 -0.165470 -0.336860 -0.875372 0.3450060 0.4511651 -0.7196870 0.3993389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2450 2451 1.033196 0.263789 0.103709 -0.4456609 -0.1124943 -0.8561480 0.2360974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2451 2452 -0.619846 0.240848 0.681266 0.2275682 0.5577856 -0.6310292 0.4887639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2452 2453 -0.687417 -0.793710 -0.066342 -0.6610006 0.5904989 0.2615505 0.3820741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2453 2454 0.444408 0.702730 -0.697888 -0.3294628 -0.1123167 -0.0978968 0.9323387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2454 2455 0.308687 0.946125 -0.102890 0.6925342 0.0514733 -0.6575613 0.2921645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2455 2456 -0.094654 -0.616042 -0.680776 -0.2131058 -0.8493489 -0.1003186 0.4723649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2456 2457 -0.688902 -0.607661 0.225855 0.4545067 -0.5315756 0.2051112 0.6846754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2457 2458 0.260308 0.422372 0.881964 0.6683209 0.1932133 -0.5903951 0.4092059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2458 2459 -0.734620 0.338855 -0.265148 -0.1560775 0.5527745 -0.3829232 0.7234984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2459 2460 -0.496555 -0.704841 0.006184 -0.6991209 0.5028676 0.3899608 0.3260134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2460 2461 -0.736096 -0.183634 -0.532021 0.3321277 -0.4576119 -0.7745542 0.2834578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2461 2462 0.882148 -0.445175 0.266461 -0.4749529 -0.1758186 0.0322228 0.8616665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2462 2463 0.556435 -0.506128 -0.487503 0.2581571 0.8275246 -0.4940552 0.0668388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2463 2464 -0.471573 0.556901 0.731489 0.3679387 -0.6107026 0.3024235 0.6326163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2464 2465 0.618514 0.807627 -0.314068 -0.1477285 -0.1580234 -0.6790938 0.7014531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2465 2466 -0.546560 0.792802 0.171844 -0.4585156 -0.2034023 -0.8297368 0.2448014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2466 2467 0.308414 -0.971616 0.020890 0.3832422 -0.0937587 0.4761865 0.7858633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2467 2468 -0.392235 -0.528401 0.652348 -0.1516023 0.5614878 -0.6962286 0.4207303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2468 2469 0.602491 -0.867517 0.212909 -0.0579248 -0.1796404 0.8492572 0.4930884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2469 2470 -0.926507 -0.111526 0.205123 -0.2865146 0.1024296 0.8890798 0.3419864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2470 2471 0.178350 0.795921 0.492489 0.1020307 -0.7854591 0.5397610 0.2851349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2471 2472 0.134347 -0.428141 -1.031525 0.3455528 0.0883157 -0.3678418 0.8587701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2472 2473 0.652790 -0.433812 -0.639171 -0.6703527 0.4483651 -0.5909695 0.0187349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2473 2474 -0.280073 0.238309 0.981226 0.2837625 -0.4073092 0.4240897 0.7574470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2474 2475 0.966170 0.504772 0.397660 -0.3236920 0.0200958 -0.8719585 0.3667533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2475 2476 -0.329132 0.118795 0.775967 0.0394813 -0.4487101 0.8549897 0.2570858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2476 2477 0.744476 -0.420737 0.739832 -0.9919986 -0.0226988 0.1219423 0.0235272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2477 2478 0.553236 0.534809 -0.803476 -0.7867926 0.4068642 0.4211148 0.1951443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2478 2479 0.663835 -0.673360 0.499223 0.5697940 -0.1636753 -0.7645087 0.2531237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2479 2480 0.933006 0.166590 0.430187 0.0747869 0.3969828 -0.8943633 0.1921612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2480 2481 0.028941 0.476018 0.868270 0.1959985 -0.8501740 0.3420144 0.3490200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2481 2482 0.418517 0.001121 -0.642800 0.0985126 0.2765720 0.4722443 0.8311369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2482 2483 0.321584 -0.684301 -0.410905 0.7733580 -0.2780487 -0.4377521 0.3646634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2483 2484 1.072378 -0.129009 0.053102 -0.2551675 0.5310001 0.7537857 0.2910937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2484 2485 -0.555675 -0.721609 -0.098135 0.2454220 -0.5410818 -0.5487485 0.5881101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2485 2486 0.788277 -0.701943 0.155720 0.2178801 0.0024736 -0.6053992 0.7655155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2486 2487 0.581395 0.627143 0.146012 -0.0936860 0.1650470 -0.5873402 0.7867744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2487 2488 -0.627942 0.880191 0.263776 0.5200043 -0.6122828 -0.5388384 0.2536898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2488 2489 -0.675458 0.614191 0.498799 -0.6553132 0.3263518 0.2611069 0.6291918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2489 2490 -0.929678 0.116211 0.402954 0.6427037 0.5120525 -0.1103673 0.5590646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2490 2491 -0.488402 -0.323340 -0.702381 0.1948971 0.1034970 -0.9753192 0.0074784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2491 2492 0.916283 0.507801 -0.516907 0.2490287 0.3407688 -0.8459739 0.3258673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2492 2493 -0.324187 0.515135 -0.667475 -0.2827872 -0.5305601 0.7188799 0.3489256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2493 2494 0.611117 0.742318 -0.015975 0.3821425 0.6281536 0.4370806 0.5180258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2494 2495 0.653508 0.094914 0.939272 0.0596533 -0.0717375 -0.9944688 0.0482382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2495 2496 -0.607555 0.183111 0.858209 -0.0562501 0.6374296 0.4184410 0.6445360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2496 2497 -0.381555 0.784846 -0.178352 -0.2526844 -0.4383743 0.6882880 0.5198444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2497 2498 1.087181 0.315373 0.023876 0.4344916 0.1884220 -0.7005114 0.5338519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2498 2499 -0.425344 0.717294 -0.589632 0.7604742 -0.2439360 -0.6004518 0.0403952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2499 2500 0.886534 0.687171 0.393821 -0.6413117 0.4864711 0.5282333 0.2702496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2500 2501 0.323757 -0.334336 0.739847 -0.3330454 -0.1512824 0.5985918 0.7126586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2501 2502 -0.360654 -0.839090 0.385809 -0.5676306 0.1225912 -0.5406908 0.6086217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2502 2503 0.615485 -0.349154 -0.685706 0.4096539 -0.3270494 -0.3943085 0.7548133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2503 2504 0.516272 -0.389680 -0.831550 0.5524275 0.1973771 0.7691483 0.2535294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2504 2505 -0.920194 -0.206717 0.150713 0.3807677 -0.2075532 -0.2839500 0.8551667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2505 2506 -0.427251 -0.126126 0.921224 0.4724173 0.5841133 0.5326672 0.3897424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2506 2507 -0.019591 0.733489 -0.550225 -0.2888783 -0.4842414 -0.8204244 0.0946748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2507 2508 -0.339783 -0.805717 0.466774 0.3819098 0.0768395 -0.5446046 0.7427291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2508 2509 0.398996 0.147582 0.990650 0.1515887 0.1496703 -0.6376115 0.7403183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2509 2510 -0.448560 0.351595 0.807632 0.6493967 -0.2230492 0.2180329 0.6935378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2510 2511 0.212515 0.837684 -0.431364 -0.1025788 -0.0920519 0.3791133 0.9150285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2511 2512 0.506747 0.566360 -0.230034 -0.0741303 0.0085339 0.2211217 0.9723873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2512 2513 0.963893 0.198575 -0.443606 0.0864155 -0.4154438 -0.9029135 0.0684548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2513 2514 -0.857553 -0.644404 -0.135807 -0.4988434 -0.3948202 0.6056910 0.4779233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2514 2515 -0.383429 0.489981 0.669533 0.6392587 0.5493240 0.3253117 0.4286767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2515 2516 0.225367 0.625025 -0.824681 -0.0162278 -0.7483759 -0.3585168 0.5577956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2516 2517 -1.065772 0.162874 0.144832 -0.4995343 0.2805805 -0.7096116 0.4101114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2517 2518 0.143638 -0.455438 -0.954650 -0.0715107 0.4272116 0.0028352 0.9013148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2518 2519 1.009901 -0.252283 -0.596647 0.7084613 0.2790716 0.0265933 0.6476839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2519 2520 -0.321477 -0.908493 -0.166169 -0.1361900 -0.3094929 -0.5597362 0.7565459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2520 2521 -0.599316 -0.538136 -0.361606 0.1016525 0.3284974 0.8462445 0.4069723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2521 2522 0.050252 0.461694 -0.661096 -0.0635706 -0.6328331 -0.5556171 0.5355097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2522 2523 -1.141973 -0.175664 0.063255 0.4190927 -0.2947560 0.1508211 0.8454189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2523 2524 -0.505951 0.571882 0.716444 -0.4494880 0.1262435 -0.7277758 0.5023599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2524 2525 0.087975 -0.952806 0.068583 -0.6149423 -0.1387481 0.5518636 0.5459318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2525 2526 -0.890529 0.398046 -0.411903 -0.4074878 0.2081656 0.8843903 0.0920575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2526 2527 0.898759 -0.167611 0.435929 0.1299327 -0.8373943 -0.5233372 0.0894787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2527 2528 -0.746970 0.211519 -0.560088 0.3521203 -0.4013878 -0.1164209 0.8374636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2528 2529 -1.046563 -0.124277 0.419456 0.0675418 0.7910470 0.3491535 0.4977696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2529 2530 -0.159841 0.252497 -0.991347 0.1322845 0.1338468 0.3207613 0.9282769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2530 2531 0.326567 -0.176227 -0.879133 -0.2405270 0.1845643 -0.1200053 0.9453473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2531 2532 0.716706 0.326984 -0.805640 -0.3069845 -0.4378708 -0.7401821 0.4076276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2532 2533 -0.918766 0.096673 0.121548 0.2845761 -0.0872642 0.2063328 0.9321095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2533 2534 -0.750003 0.760067 0.318451 -0.1861537 0.6455829 0.3053307 0.6747909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2534 2535 -0.152389 1.148649 -0.338102 0.2171287 -0.7219147 -0.1912121 0.6285954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2535 2536 -0.631037 0.679374 -0.070383 -0.3613987 0.7999840 0.3488326 0.3282260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2536 2537 0.133039 0.861444 0.486988 0.3081494 0.6669863 -0.6757298 0.0596858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2537 2538 -0.205342 -0.408531 -0.878782 0.6979737 -0.3732201 0.5050909 0.3441260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2538 2539 -1.061023 0.189984 0.387034 0.4538779 0.3422907 0.7992106 0.1951776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2539 2540 -0.478928 0.796250 -0.359334 0.1719737 -0.3470063 0.0603134 0.9199858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2540 2541 -0.297856 0.108803 0.879554 0.6767382 -0.0849966 0.7146695 0.1550757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2541 2542 1.115790 0.080378 -0.248352 0.0530222 0.4107153 -0.8308547 0.3717284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2542 2543 -0.565283 0.888317 -0.069220 -0.6372961 -0.0426415 -0.6445596 0.4202123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2543 2544 -0.433156 -0.880089 -0.167579 0.0467173 0.0530415 0.1157171 0.9907642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2544 2545 -0.587996 -0.893512 0.119970 -0.4038576 0.5811334 -0.5966387 0.3784248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2545 2546 0.702832 0.023946 -0.457625 0.6856271 0.3548960 0.6141254 0.1637506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2546 2547 -0.231904 0.120943 0.965822 -0.4645502 -0.1714900 -0.5504764 0.6721310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2547 2548 0.649487 -0.612293 0.308356 -0.5481695 -0.4612281 0.0024883 0.6976909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2548 2549 0.420417 -0.553816 -0.753815 0.3875221 -0.5209158 0.1022514 0.7536697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2549 2550 -0.460607 -0.946601 -0.160608 0.1560946 -0.0094634 0.9259765 0.3436749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2550 2551 -0.393495 1.151500 -0.312766 -0.0265435 -0.1859385 -0.1136239 0.9756085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2551 2552 -0.455978 0.792352 0.154405 -0.1133792 -0.4230223 -0.8961136 0.0719568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2552 2553 0.414109 -0.645010 0.602711 -0.0222041 0.6543916 0.7246307 0.2149161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2553 2554 -0.784583 0.680351 -0.341452 0.0035918 -0.2432943 0.9652557 0.0952699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2554 2555 0.708603 0.103789 -0.677566 0.6206749 0.3752239 0.0404747 0.6872638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2555 2556 0.807565 -0.171970 0.631751 -0.7003014 -0.1074384 0.5659573 0.4215771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2556 2557 -0.382674 -0.343749 -0.821006 -0.0003296 -0.2432575 0.7141934 0.6563182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2557 2558 -0.437957 0.663550 -0.544456 0.0837973 -0.2432628 0.9657136 0.0346178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2558 2559 0.492397 -0.315784 -0.853272 0.3813200 0.3548651 0.7025241 0.4848977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2559 2560 -0.803155 0.531169 -0.107078 -0.2938583 -0.3948935 0.5108096 0.7048262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2560 2561 0.814774 0.052912 -0.305600 -0.3592497 0.0984682 -0.2016249 0.9058648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2561 2562 0.721228 0.534545 -0.267508 0.1224299 0.9374735 -0.3103813 0.0990853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2562 2563 -0.590706 0.770546 -0.123882 -0.3042635 0.1375028 0.9212099 0.1997224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2563 2564 0.565898 -0.581998 0.579348 -0.3292730 -0.3652755 -0.3299549 0.8057809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2564 2565 0.753050 -0.007073 -0.262896 0.0961889 -0.4703249 0.8577026 0.1840881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2565 2566 -0.957560 -0.497055 -0.410071 0.2306281 0.6432797 0.2881538 0.6707975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2566 2567 0.132534 -0.382894 -1.081642 0.3467264 0.0760446 -0.9322184 0.0704760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2567 2568 0.616546 0.240061 -0.804483 -0.2550181 0.3678446 0.8072923 0.3846236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2568 2569 0.443436 -0.950439 -0.289608 0.4161975 0.1362626 -0.7418978 0.5077398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2569 2570 0.544463 0.698660 0.335555 -0.4242775 0.0966491 0.7181596 0.5430418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2570 2571 0.425065 -0.909293 0.237563 0.0479631 -0.3143971 0.9103680 0.2647340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2571 2572 -0.573650 0.175791 0.804684 -0.4477360 0.2154831 -0.1014753 0.8618598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2572 2573 -0.775259 -0.377640 0.377944 0.0870838 -0.0511944 0.4655585 0.8792331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2573 2574 -0.671671 0.758014 0.197432 -0.3113560 -0.4628901 0.0464392 0.8286336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2574 2575 0.048138 0.165637 0.887976 0.4098938 -0.7601652 0.1529603 0.4803530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2575 2576 0.744540 0.026697 -0.821151 0.4447121 0.0427534 -0.7217872 0.5286081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2576 2577 0.335306 0.636876 -1.024678 0.2360108 -0.6719502 -0.6541063 0.2548073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2577 2578 -0.664699 -0.796801 0.155768 0.2640275 -0.6328966 -0.7212840 0.0973688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2578 2579 0.619515 0.490007 -0.588712 -0.6535951 0.2720286 -0.5653808 0.4232712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2579 2580 -0.877711 -0.324389 -0.324588 -0.1957444 -0.5148899 0.7233136 0.4164012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2580 2581 -0.595430 0.713308 -0.453574 -0.1242227 -0.4830953 0.2934953 0.8155048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2581 2582 -0.337578 0.909021 0.214390 -0.1139647 -0.5318633 -0.0355684 0.8383725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2582 2583 0.064256 0.695185 0.583189 0.5079093 -0.2512792 0.7261566 0.3893373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2583 2584 0.868194 -0.498705 -0.364369 -0.5004130 0.2589257 -0.7983646 0.2125047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2584 2585 -0.277170 0.768350 0.822214 -0.4683091 0.4787510 0.2082045 0.7128359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2585 2586 -0.807833 0.176338 0.441591 0.4991448 -0.4939657 -0.2161431 0.6783321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2586 2587 -0.334857 0.712827 0.747606 0.2682677 0.6264034 0.7297905 0.0552913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2587 2588 0.712361 0.623505 0.523303 -0.7135406 -0.5743902 0.0807526 0.3929564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2588 2589 0.693799 0.232711 -0.432971 0.4944379 0.1922452 0.6737833 0.5143821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2589 2590 0.115205 -0.949491 0.234634 -0.1283861 0.3152463 -0.3484170 0.8733512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2590 2591 0.519784 -0.813034 0.253458 -0.1208019 -0.8865544 0.3102392 0.3212163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2591 2592 -0.388573 -0.835232 -0.020930 0.3957030 0.1547913 0.3914360 0.8162332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2592 2593 -0.997913 0.125377 0.135505 -0.1100650 0.2750232 -0.6976399 0.6523393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2593 2594 0.384839 -0.644978 -0.306674 -0.0009400 0.7150612 -0.3776206 0.5882935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2594 2595 0.450159 -0.309658 0.658253 0.9550091 -0.0579449 -0.1823939 0.2265668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2595 2596 0.391287 0.601086 -0.638583 -0.2365319 0.6538057 0.3541716 0.6254225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2596 2597 0.745825 0.212096 0.720239 -0.6509823 -0.6363896 -0.3729099 0.1793558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2597 2598 0.655115 0.653524 -0.228849 0.5468117 -0.3647872 0.3704742 0.6562592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2598 2599 0.063864 -0.402696 -0.861075 -0.0683446 0.3878864 -0.9177920 0.0503088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2599 2600 0.527584 0.311401 0.619245 -0.3869580 -0.3467086 -0.2557384 0.8152635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2600 2601 0.484879 -0.553323 -0.735168 -0.0957631 -0.0770064 0.4615095 0.8785832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2601 2602 -0.223339 -0.563235 -0.697061 -0.5381797 -0.5065771 0.3439962 0.5791450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2602 2603 -0.858878 0.524978 0.284296 0.1695070 -0.0538061 -0.9629800 0.2025878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2603 2604 0.282543 -0.863610 0.304996 -0.2081935 -0.2591432 -0.8153295 0.4740654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2604 2605 0.605425 0.604680 0.126162 -0.0975529 -0.6142235 -0.2644911 0.7370599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2605 2606 0.014125 0.872066 -0.274795 -0.6569957 0.0479931 0.2530374 0.7085375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2606 2607 0.305819 0.242564 0.800216 0.1389841 0.9634873 -0.2215521 0.0573619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2607 2608 -0.279154 0.111315 -0.883480 -0.8296491 -0.1969350 0.5058792 0.1303272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2608 2609 0.601027 0.201266 0.758810 -0.1096020 -0.3265964 0.1258243 0.9303174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2609 2610 0.904754 -0.116668 0.181573 -0.3807480 -0.1502841 -0.7342949 0.5415318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2610 2611 0.151304 0.868480 0.380144 0.1860337 -0.4028552 0.1919415 0.8753614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2611 2612 0.753355 0.574001 -0.135249 -0.7110927 0.3446909 -0.6033648 0.1071738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2612 2613 -0.741444 -0.518983 0.413323 0.3808390 0.0140685 -0.8594481 0.3407532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2613 2614 0.184892 0.322302 0.849205 -0.6168337 0.1074271 0.6808992 0.3799366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2614 2615 -0.643100 -0.711669 0.030577 -0.4404249 0.2130863 -0.8419141 0.2275978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2615 2616 0.678621 0.434629 -0.367931 0.1906586 -0.2420554 -0.7370201 0.6015479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2616 2617 -0.202765 0.411352 -0.774887 -0.3215952 0.2709523 0.5957714 0.6842644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2617 2618 0.928151 0.512531 -0.033603 -0.5377236 0.2580110 0.0360812 0.8018615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2618 2619 0.860228 0.090892 0.556592 -0.2727897 0.3284006 -0.8779776 0.2165507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2619 2620 0.836515 -0.511162 0.018343 -0.4206055 -0.3159692 -0.8077166 0.2661735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2620 2621 -0.876221 -0.331944 0.167265 0.4785254 -0.2198911 -0.6318302 0.5687284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2621 2622 0.105655 -0.092593 1.155506 -0.5343709 -0.2612077 0.6457434 0.4787837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2622 2623 -0.839540 -0.740196 0.048418 -0.0116733 0.5574153 0.0040357 0.8301419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2623 2624 -0.302605 -0.701419 -0.581439 -0.0295557 0.1030051 -0.6234397 0.7744930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2624 2625 0.679204 -0.309170 -0.567154 0.0619101 0.4455212 0.4229253 0.7866462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2625 2626 0.450006 -1.143302 -0.003422 0.3904303 -0.8290996 -0.1122688 0.3841273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2626 2627 0.638184 -0.833826 -0.195659 -0.0398614 0.9129834 0.3173506 0.2533002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2627 2628 -0.535602 -0.822926 0.042357 -0.0547524 -0.7772510 0.1822543 0.5997220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2628 2629 -0.192541 -0.695271 0.594979 0.1469201 -0.3420176 0.9102738 0.1812180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2629 2630 0.385369 0.441905 0.985522 0.8066265 0.3487308 0.2205042 0.4232238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2630 2631 0.655921 0.881275 -0.601810 -0.8870473 -0.0548511 0.2822896 0.3611802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2631 2632 0.848759 -0.259187 0.507067 -0.2369094 0.2333749 -0.9430124 0.0117362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2632 2633 -0.586778 -0.253827 0.933611 -0.3337257 0.7504257 -0.4684407 0.3256559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2633 2634 0.243961 -0.740752 -0.529289 -0.4270393 -0.6505056 0.5815267 0.2372902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2634 2635 -0.869307 0.843403 0.256481 0.7036733 0.0511743 -0.6751672 0.2153472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2635 2636 -0.510837 -0.885285 0.279095 -0.5433988 -0.5812717 0.5904653 0.1348765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2636 2637 -0.723250 -0.057276 0.610972 0.3619721 0.7874197 -0.4112806 0.2824797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2637 2638 -0.065895 -0.815037 -0.077715 0.2713217 -0.3194510 0.5501737 0.7222496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2638 2639 -0.806409 -0.041536 0.569911 -0.0044608 0.8225232 0.3142609 0.4739998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2639 2640 0.715542 0.310267 0.409642 -0.2707446 -0.7680071 -0.2455975 0.5258749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2640 2641 0.735222 -0.416934 -0.459512 0.0047746 0.1921609 0.8784486 0.4374694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2641 2642 -0.857776 -0.440855 -0.593651 0.5901047 -0.5366940 -0.1005030 0.5946723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2642 2643 -0.245286 -0.173160 0.927301 0.0089174 0.4084336 -0.2555198 0.8762489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2643 2644 -0.874517 -0.392636 0.681782 -0.7738637 0.1109570 0.5932098 0.1921602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2644 2645 -0.875035 0.484639 0.343010 0.1663228 0.7316694 -0.6570277 0.0728777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2645 2646 0.607973 -0.397403 -0.710192 -0.0507740 -0.5071801 -0.1864832 0.8398895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2646 2647 -0.170132 -0.273458 -0.803638 -0.4131028 0.4662354 -0.7820564 0.0189309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2647 2648 -0.579688 0.870134 0.052422 0.2654954 -0.0684641 -0.8169334 0.5073901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2648 2649 -0.528899 -0.879085 0.319531 0.5126030 -0.0815568 -0.7568892 0.3971214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2649 2650 0.607976 0.351206 0.710844 -0.7404136 -0.2066887 0.5378990 0.3460233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2650 2651 0.001719 -0.940214 -0.504705 0.2151302 -0.4654925 0.6265216 0.5869467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2651 2652 -1.047332 0.090507 0.506327 -0.7293537 -0.4977816 -0.4692472 0.0079814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2652 2653 0.662195 -0.306366 -0.862770 0.7162916 0.5739418 0.3716410 0.1392841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2653 2654 -0.764708 -0.144346 0.595958 -0.2576908 0.4089620 0.3833980 0.7869889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2654 2655 -0.752016 0.318812 0.053316 0.2499969 -0.2222309 -0.3304529 0.8825621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2655 2656 -1.096754 -0.017107 0.537359 0.0551740 -0.1629522 0.1561480 0.9726357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2656 2657 -0.652424 0.157755 0.798878 0.1341219 0.3078295 -0.6954815 0.6352620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2657 2658 -0.482418 -0.889213 0.339434 0.0272236 -0.2942887 0.0908603 0.9509981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2658 2659 -0.236660 -0.801134 0.648200 -0.7825144 -0.1822821 0.2750801 0.5279919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2659 2660 0.678401 -0.356664 -0.684961 0.5568835 -0.5235641 0.6308137 0.1335495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2660 2661 0.340806 -1.034530 0.097432 0.5527219 0.3135317 0.2939349 0.7140019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2661 2662 -0.687818 0.002969 0.866668 -0.0966693 0.2347230 -0.3860297 0.8868716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2662 2663 -0.623128 -0.706973 0.158588 0.0654689 0.0311492 0.8877476 0.4545853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2663 2664 -0.106804 0.994206 0.131019 -0.2517360 0.7920477 -0.3098115 0.4618509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2664 2665 -0.615251 0.511275 -0.521992 -0.8888632 -0.2626795 0.3745778 0.0247624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2665 2666 0.371647 -0.676569 0.562296 0.2521017 -0.6694824 0.4922878 0.4958737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2666 2667 0.785110 -0.750957 0.384971 -0.0105007 0.3835371 -0.2878205 0.8774670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2667 2668 0.525631 -0.707199 0.684662 -0.7348153 0.3368818 -0.2050066 0.5518419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2668 2669 0.675266 -0.698560 -0.213456 0.0198151 -0.5850183 -0.2552643 0.7695460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2669 2670 0.169415 -0.431198 -0.863172 0.8172932 -0.1471715 0.5496199 0.0910518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2670 2671 -1.005659 0.214251 0.770356 -0.4662577 0.5705543 0.4069565 0.5398684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2671 2672 -0.939346 0.678590 0.124449 -0.4947725 -0.5848386 0.4566684 0.4523472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2672 2673 0.875005 0.084454 0.474692 0.6667560 0.6438143 -0.3690600 0.0688066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2673 2674 -0.395861 0.616706 -0.721939 -0.4540551 0.0640104 0.6395396 0.6170298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2674 2675 0.793533 0.854019 0.114130 0.6268475 -0.2181486 -0.6587843 0.3542268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2675 2676 -0.584175 -0.101557 -0.870152 0.3900549 -0.0966207 -0.5867310 0.7030422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2676 2677 -0.113614 -1.090131 -0.044899 -0.2836767 0.0822170 -0.5504985 0.7808453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2677 2678 0.775873 -0.180901 -0.338040 0.4060889 -0.2174862 -0.8758607 0.1437346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2678 2679 -0.295227 -0.069298 -1.002807 0.6552564 -0.3031022 -0.5978787 0.3482946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2679 2680 -0.148945 -0.409994 -0.954435 0.1226603 0.0258193 -0.1059720 0.9864369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2680 2681 -0.434971 0.453778 -0.562377 0.4288308 -0.3908079 -0.7956125 0.1742817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2681 2682 0.279305 -0.686141 0.486159 0.4277764 0.0979167 0.1674457 0.8828259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2682 2683 0.148684 0.027200 0.884452 -0.3306622 0.4491104 0.5326791 0.6365653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2683 2684 -0.941758 -0.048865 0.240511 -0.0426667 -0.0854564 -0.7444888 0.6607671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2684 2685 0.072951 -0.764193 0.325161 0.0069552 0.1001900 -0.9881438 0.1161267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2685 2686 0.030025 0.955867 0.642851 -0.1867642 -0.1181242 -0.3325771 0.9168196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2686 2687 -0.244218 0.332617 0.879243 0.1293453 -0.0109899 0.9902627 0.0502872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2687 2688 0.469916 -0.335207 0.748631 -0.5729694 0.2335895 0.7824444 0.0701631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2688 2689 -0.945964 0.257128 -0.608412 -0.0748709 0.0406435 -0.5438700 0.8348340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2689 2690 -0.529307 -0.697568 -0.397573 0.2177225 0.1183567 -0.5046093 0.8270175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2690 2691 0.413337 -0.923753 -0.060955 0.7423936 -0.0746364 0.6396561 0.1847195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2691 2692 -0.232858 0.703014 0.591976 -0.7064350 0.4020445 -0.2279464 0.5360506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2692 2693 -0.756341 -0.781559 0.054796 0.0911878 0.5994268 -0.0510400 0.7935787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2693 2694 -0.214691 -0.835894 -0.518387 0.7402223 0.0987887 -0.6181097 0.2454632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2694 2695 0.660238 0.320978 0.319468 -0.2213212 -0.2735607 -0.8836934 0.3086541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2695 2696 -0.303420 0.433012 0.811802 0.4948468 -0.2496116 0.3353656 0.7618075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2696 2697 0.419527 0.935543 -0.161739 0.4334321 0.3584286 -0.8204349 0.1027238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2697 2698 -0.375671 -0.546357 -0.809399 0.1421196 -0.5846439 -0.0664983 0.7959721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2698 2699 -0.735287 -0.612736 -0.033858 0.4448916 -0.2996305 0.8286707 0.1599932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2699 2700 -0.748589 0.151436 0.762980 0.2690896 0.5369399 -0.6505289 0.4648639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2700 2701 0.309835 -0.272104 0.998898 -0.2921661 0.0239506 0.5612334 0.7740041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2701 2702 -0.290900 -0.727119 0.416788 -0.1435189 -0.0258129 -0.9678908 0.2047522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2702 2703 0.679602 0.454983 0.052621 0.0663242 -0.4344365 0.8516809 0.2854921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2703 2704 -0.432974 -0.596963 -0.408535 -0.1802540 0.0405190 -0.7180951 0.6709740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2704 2705 0.838791 -0.119129 -0.807329 0.5089549 -0.1509752 -0.0513633 0.8458920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2705 2706 0.451742 -0.703403 -0.559726 -0.0624945 0.1307881 0.8712144 0.4690142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2706 2707 -0.650765 -0.059303 -0.707383 -0.0464570 -0.4248078 -0.4063005 0.8076509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2707 2708 -0.449693 -0.695602 0.154894 0.9062057 0.0087211 0.2161384 0.3633171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2708 2709 -0.696558 0.570374 0.472333 0.0721285 -0.5253316 -0.8175606 0.2245415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2709 2710 0.582996 -0.296012 0.888779 -0.2249621 -0.5984025 0.3922586 0.6613922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2710 2711 0.424325 -1.101401 -0.173886 0.0929868 -0.1310990 0.9868949 0.0143182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2711 2712 -0.121133 0.944184 0.174238 -0.2613717 0.4129635 -0.8351467 0.2523409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2712 2713 -0.241725 -0.731492 -0.499492 0.4703903 -0.2688732 0.7798252 0.3135487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2713 2714 -0.544931 0.825704 0.008996 -0.0881031 0.2573906 0.8710063 0.4090672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2714 2715 1.024441 -0.267887 0.268921 0.1745226 -0.4372699 0.3186225 0.8226886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2715 2716 0.749830 -0.569385 -0.288939 -0.3268705 -0.5851812 -0.6761728 0.3057924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2716 2717 -0.687029 0.623584 -0.455580 -0.3238647 -0.5600099 -0.5288115 0.5494169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2717 2718 -0.420476 -0.626896 0.697040 -0.3201838 0.0278841 -0.0872659 0.9429154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2718 2719 -0.218427 -1.039495 0.190634 -0.5593547 0.0301846 -0.7715585 0.3015107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2719 2720 0.724198 -0.715659 0.055324 -0.5725497 0.0799513 0.7779046 0.2462905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2720 2721 -0.421214 0.647008 0.605687 0.7539704 -0.0110927 -0.5798030 0.3086002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2721 2722 -1.006072 -0.627865 0.158667 0.6078566 -0.2682030 -0.6933722 0.2789489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2722 2723 0.511601 0.283242 0.857086 -0.0167612 0.1050563 -0.9833047 0.1476285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2723 2724 -0.647950 -0.179963 0.775247 0.0113492 0.2511496 -0.7327323 0.6323752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2724 2725 0.138299 -0.826296 0.589919 -0.6767946 -0.0831934 0.3082568 0.6633292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2725 2726 -0.413178 -0.562176 -0.598774 0.1609281 -0.1080666 0.4451949 0.8741998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2726 2727 -1.044373 0.042369 -0.595183 0.5425817 -0.4579322 0.7020683 0.0548030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2727 2728 0.011933 0.692867 -0.692168 0.0883861 0.8623072 0.1389518 0.4788597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2728 2729 0.637253 0.850193 0.118133 0.3803364 -0.7724637 -0.1699958 0.4793178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2729 2730 -0.277149 0.569794 -0.485797 -0.0340769 -0.6171047 -0.3407322 0.7084646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2730 2731 -1.039254 -0.221523 0.340009 -0.4456061 0.0291672 -0.6692782 0.5938444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2731 2732 0.266111 -0.862355 -0.353138 -0.3438228 -0.7275577 0.3013014 0.5115302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2732 2733 -0.870579 -0.136611 -0.387182 0.5789329 -0.4679975 0.6238141 0.2380567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2733 2734 0.085634 0.915894 -0.559891 -0.2168368 0.2664932 0.9391207 0.0039316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2734 2735 -0.209777 -1.113287 -0.109041 -0.4351398 -0.6178887 -0.2157963 0.6183032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2735 2736 -0.392676 -0.695556 -0.844968 0.5256791 -0.1258029 -0.2009576 0.8169768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2736 2737 0.071979 -1.054933 0.229235 0.0217145 0.2963694 0.9526546 0.0643651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2737 2738 -0.363168 0.957946 -0.283888 0.0970481 0.5506925 -0.8022321 0.2091482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2738 2739 0.071681 -0.378339 -1.003577 0.1984177 0.7071283 -0.6478669 0.2021593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2739 2740 -0.767361 0.460523 -0.566279 -0.3873793 -0.3538167 0.0695759 0.8484752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2740 2741 -0.895738 -0.305417 -0.417493 -0.1695114 0.1937476 -0.8844220 0.3892627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2741 2742 0.971270 -0.264052 -0.710903 -0.0600596 0.4595784 0.7144471 0.5241621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2742 2743 -0.342726 -1.051264 0.148524 -0.1005261 -0.2060362 -0.9666548 0.1141145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2743 2744 0.463539 0.825219 -0.442712 0.0117596 -0.0033767 0.9689150 0.2470910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2744 2745 0.204522 -1.010060 -0.314723 -0.0180471 -0.3206450 0.2720347 0.9071153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2745 2746 -0.550788 -0.829234 -0.240218 -0.5606951 -0.5447380 0.2802404 0.5570878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2746 2747 -0.898586 0.109987 0.229375 -0.2950135 0.0784425 0.9449603 0.1177447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2747 2748 0.638912 0.235490 0.678612 -0.3567318 -0.4780764 -0.6049216 0.5274991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2748 2749 0.535207 0.566934 0.515316 0.2707942 0.3409733 0.2361595 0.8686981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2749 2750 0.609810 0.811200 0.237769 0.4917841 -0.2465174 -0.5774000 0.6033132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2750 2751 -0.677066 0.397380 -0.766254 -0.3289690 0.5123581 0.7625229 0.2186948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2751 2752 0.936009 -0.026221 0.254433 0.1208142 -0.3245291 -0.8214302 0.4531415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2752 2753 -0.323128 0.893156 -0.212692 0.3893025 -0.0467436 0.8866100 0.2453189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2753 2754 0.527110 -0.425395 -0.694713 -0.1589054 0.6917983 -0.1599638 0.6859853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2754 2755 0.642163 -0.244643 0.616065 -0.3029310 -0.4084881 -0.6434577 0.5721297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2755 2756 0.487167 0.883878 0.129743 0.5503110 -0.1499440 0.8155466 0.0977667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2756 2757 -0.030167 -1.109938 0.064037 0.5666068 -0.2642262 0.7802928 0.0168660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2757 2758 0.470169 0.673819 0.346486 0.1940445 0.3108107 0.1908217 0.9106758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2758 2759 0.335934 0.701884 0.341776 0.7816836 0.1128716 0.5621605 0.2453698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2759 2760 -0.225167 -0.043190 1.000516 -0.8438156 0.0049355 -0.4083766 0.3481082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2760 2761 -0.806473 -0.457576 -0.332556 -0.1937768 -0.3284940 0.3805738 0.8424404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2761 2762 -0.804499 0.043394 0.442820 0.3157802 0.4402458 -0.7924062 0.2802836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2762 2763 0.187517 -0.822943 -0.118005 -0.4110973 0.0183778 0.1640440 0.8965215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2763 2764 0.052304 -0.544991 -0.670744 -0.2699301 0.3674629 -0.8885329 0.0511671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2764 2765 -0.023224 1.106167 0.012244 -0.1629671 0.2105098 -0.4401203 0.8575672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2765 2766 -0.971663 0.518638 -0.126287 -0.1053896 -0.1864897 -0.9399367 0.2657699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2766 2767 0.605394 -0.741891 0.136563 0.0763904 -0.1534369 -0.0075126 0.9851727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2767 2768 0.621261 -0.802334 -0.110020 0.2518264 -0.5248790 -0.6615490 0.4726927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2768 2769 0.440545 0.395374 -0.654042 -0.0586873 0.7597078 0.6276537 0.1595326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2769 2770 -0.123301 -0.729973 0.679063 -0.4632218 -0.4172777 -0.7526771 0.2116176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2770 2771 0.436221 0.430083 -0.691966 -0.3014791 -0.0984336 -0.7998193 0.5096178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2771 2772 -0.879900 0.338847 -0.207754 0.3492085 0.3098755 0.8240778 0.3208215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2772 2773 0.770130 -0.065458 -0.623937 0.0999912 -0.5390228 -0.7133940 0.4364918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2773 2774 -0.572392 -0.391611 -0.660827 0.0142635 -0.4585014 -0.5789715 0.6740661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2774 2775 -0.299824 -1.100666 -0.167345 -0.3506475 0.0352584 0.5468222 0.7594661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2775 2776 -0.875336 0.197583 -0.666632 0.6294559 -0.0367392 -0.3856338 0.6735890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2776 2777 -0.534405 -0.799878 0.240628 -0.4379672 -0.7347984 0.0033895 0.5179233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2777 2778 -0.469091 -0.915872 -0.220883 0.4880091 0.1934221 0.6192590 0.5839120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2778 2779 -0.915271 0.310198 -0.050262 0.4451021 -0.2469099 -0.2854251 0.8120666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2779 2780 0.361881 -0.251695 0.913360 -0.0523079 0.4496132 0.1199355 0.8835877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2780 2781 0.868059 -0.364946 0.318735 -0.0786986 -0.3443508 -0.7725098 0.5276910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2781 2782 0.231335 1.112334 -0.187220 -0.1129895 -0.1281602 0.9746496 0.1444527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2782 2783 0.225520 -1.113413 -0.098720 -0.2212500 0.7186997 -0.2482330 0.6106550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2783 2784 0.527876 -0.849571 0.381969 0.8504531 -0.1069021 0.2827627 0.4305191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2784 2785 0.652793 0.333521 0.529435 0.6486240 -0.3034102 -0.6979899 0.0062640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2785 2786 -0.865804 -0.339767 -0.573706 -0.0129595 -0.0251647 -0.1105214 0.9934706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2786 2787 -0.770811 -0.463009 -0.405324 0.5038457 -0.2773529 0.8153325 0.0666919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2787 2788 0.107386 0.913494 -0.443886 -0.6267060 0.3245344 -0.4091126 0.5783977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2788 2789 -0.723208 0.407903 0.571718 -0.4800854 0.0343953 0.1290754 0.8669917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2789 2790 -0.675690 0.056858 0.800671 0.5355883 -0.0769545 0.6835626 0.4898625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2790 2791 0.312526 0.796641 -0.270330 0.1314097 0.5147227 0.2958274 0.7939006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2791 2792 0.945605 0.375712 0.508305 -0.3841507 0.6872632 0.5369624 0.3029338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2792 2793 -0.940220 -0.304840 0.201965 -0.7376072 -0.1325063 -0.5452129 0.3756602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2793 2794 0.031840 -0.305866 -0.975259 -0.0790773 0.6428789 -0.6386320 0.4154547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2794 2795 0.547978 0.865471 0.144499 -0.2327981 -0.6645110 0.2522109 0.6637920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2795 2796 0.418747 0.674534 -0.440805 -0.6262118 0.3088567 -0.5774638 0.4230861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2796 2797 -0.775170 0.161881 0.598601 -0.6233955 0.3403533 0.3803551 0.5923409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2797 2798 -0.874579 0.292292 0.388954 0.6547859 -0.4841202 0.4239275 0.3964449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2798 2799 -0.054505 0.698608 -0.650551 -0.0211533 -0.3388213 0.9026326 0.2645886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2799 2800 -3.540839 2.358623 18.595205 0.4036042 -0.4562074 0.6056035 0.5120770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2800 2801 -1.024149 0.004916 0.052008 0.3201669 0.3365001 0.8033162 0.3727517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2801 2802 0.421892 0.299836 -0.756903 -0.6232970 0.1755846 -0.7619123 0.0126754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2802 2803 -0.838767 -0.187227 0.287835 0.1424119 -0.2496289 0.7294997 0.6206726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2803 2804 0.315783 0.794268 0.470025 0.4855147 0.7071971 -0.5135549 0.0202247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2804 2805 0.276040 -0.146513 -1.020941 0.0242313 -0.1934607 0.0249970 0.9804901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2805 2806 -0.072071 -0.129030 -0.997307 0.7337032 -0.2863106 -0.0464291 0.6144511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2806 2807 -0.385280 -0.668663 0.493169 -0.0774510 -0.2990844 -0.8666084 0.3918416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2807 2808 1.096354 0.356586 -0.102747 -0.3553539 -0.5306524 -0.5044402 0.5810953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2808 2809 -0.127326 1.001721 -0.059681 -0.2221987 -0.0581350 0.3529365 0.9070192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2809 2810 0.542286 1.013594 0.519581 -0.3843641 -0.0304046 -0.9120633 0.1395718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2810 2811 0.040962 -0.732506 0.648585 0.4521106 -0.2737031 -0.7143193 0.4587272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2811 2812 0.565980 0.753810 0.457082 -0.5882573 0.6637151 0.2811168 0.3666183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2812 2813 -0.876737 -0.334592 0.487312 -0.1705271 -0.9043709 -0.3433933 0.1873893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2813 2814 0.915323 -0.165642 -0.480282 -0.3397716 0.3921900 -0.1200216 0.8463670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2814 2815 0.997120 0.022783 0.149332 -0.0861180 0.2744515 -0.6322340 0.7194027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2815 2816 -0.009473 0.952525 0.553077 0.6760264 0.4389571 0.0202980 0.5915175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2816 2817 0.119392 0.629692 -0.815465 -0.5824203 -0.0188768 -0.2611120 0.7695783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2817 2818 -0.475012 0.991706 0.401876 0.6900733 -0.0312989 -0.4289530 0.5820811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2818 2819 -0.819847 -0.001216 -0.311333 -0.1765057 -0.0909152 0.0750198 0.9772166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2819 2820 -0.103252 -0.920480 -0.419683 0.2890439 -0.4909112 0.6735808 0.4709021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2820 2821 -0.010937 -0.969245 0.243858 0.1990732 0.0337727 -0.5841252 0.7861470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2821 2822 0.970635 -0.057263 0.638793 -0.4331894 0.0347312 -0.6236868 0.6497350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2822 2823 0.595072 0.165602 0.937538 0.3935214 -0.5153886 0.2983410 0.7003629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2823 2824 0.845678 -0.151655 -0.279385 0.3371288 -0.2622255 -0.7511444 0.5033528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2824 2825 -0.009268 0.498435 -0.821528 0.1683799 0.0499025 -0.8577280 0.4831776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2825 2826 -0.050180 -0.369791 -0.906758 0.8063655 0.3008551 -0.1933198 0.4710503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2826 2827 0.778020 -0.445208 0.748957 0.1632451 -0.7753129 0.2499685 0.5565579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2827 2828 0.771762 -0.706919 -0.194876 0.8546618 -0.2049682 0.4700951 0.0809434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2828 2829 0.341306 0.398431 0.931991 0.2086664 -0.7927280 0.5604514 0.1180459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2829 2830 0.048698 -0.733115 -0.689899 0.4453393 -0.0437371 -0.2296741 0.8642973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2830 2831 0.569887 -0.766173 0.135608 -0.3584517 -0.2444310 -0.4690143 0.7692798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2831 2832 0.791412 0.072888 -0.468615 0.2385193 0.1505934 -0.8417335 0.4603421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2832 2833 -0.144179 0.460774 -0.648729 -0.1411195 -0.1931428 0.3724411 0.8966988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2833 2834 0.159785 0.892948 -0.400619 -0.7335433 -0.1209764 -0.1961654 0.6393731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2834 2835 -0.126369 0.344876 1.029296 0.5847740 -0.3545854 0.6447204 0.3415320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2835 2836 0.854591 -0.208812 -0.338402 0.2016591 -0.0242575 0.4960338 0.8442130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2836 2837 0.155116 -0.899441 0.223374 0.1750539 0.0503584 -0.0318250 0.9827550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2837 2838 0.427553 -0.939665 0.313602 -0.2609413 0.2404616 0.8293289 0.4316266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2838 2839 -0.777995 0.292410 -0.458930 0.0283863 0.0326704 -0.7608926 0.6474328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2839 2840 -0.844389 -0.099077 0.330975 -0.1716349 0.0769624 0.7622469 0.6193528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2840 2841 0.621062 -0.286377 0.628843 -0.1630800 -0.0911571 -0.7432096 0.6424443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2841 2842 0.444408 0.768790 0.644208 0.7352485 0.4310160 0.5101412 0.1157181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2842 2843 1.038307 0.060042 0.205197 -0.7049724 -0.5182260 -0.4414799 0.1988749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2843 2844 0.434956 1.031104 0.338931 -0.6173467 -0.3588231 -0.6547149 0.2479463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2844 2845 0.308223 -0.131526 0.916310 -0.8906355 -0.2327160 0.0843328 0.3814441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2845 2846 0.198607 -0.447890 -0.738865 0.4951686 0.7478515 -0.1754747 0.4058754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2846 2847 0.501331 -0.136405 1.091288 -0.2341794 -0.0255033 -0.9710875 0.0387129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2847 2848 0.010636 0.133781 0.772913 0.8207672 0.4708285 0.3197505 0.0492059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2848 2849 0.788508 0.311571 -0.499241 -0.7507714 0.1665416 0.6116927 0.1855755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2849 2850 0.944003 -0.504387 -0.287008 -0.5590763 -0.5910408 0.3157890 0.4882436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2850 2851 -0.515837 0.361551 -0.627286 0.7939149 0.5506002 -0.2430852 0.0863025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2851 2852 0.563256 -0.638511 0.707137 0.2386332 -0.3790960 0.6916565 0.5665260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2852 2853 -0.018778 -0.465035 0.747618 0.1701989 0.2280514 -0.3661804 0.8859666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2853 2854 0.140716 -0.136789 1.103324 0.0917359 -0.8659190 -0.4916975 0.0015460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2854 2855 -0.064826 0.707329 -0.763869 -0.1142700 0.0261667 -0.7123534 0.6919612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2855 2856 -0.852495 -0.002206 -0.605649 0.4171761 0.2768733 -0.8398941 0.2094831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2856 2857 1.020022 -0.334569 0.148102 0.3006668 -0.5360253 -0.0271309 0.7883782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2857 2858 0.634420 -0.252066 -0.767931 0.1884966 -0.2537266 0.8242817 0.4697356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2858 2859 -0.913094 -0.383952 -0.312938 0.2584800 0.1473898 -0.4153957 0.8595992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2859 2860 0.963384 -0.411798 0.199986 -0.2965862 0.5141873 -0.3873876 0.7053927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2860 2861 -0.949760 0.407886 0.057683 0.4123488 -0.5584239 0.4793302 0.5370044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2861 2862 0.370221 0.877926 -0.132143 0.5739801 -0.0512888 -0.3478214 0.7395516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2862 2863 -0.356117 0.221142 -1.028268 -0.7314188 -0.3643674 0.5653964 0.1122042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2863 2864 0.909470 0.238299 0.669773 0.6352162 0.2469527 -0.1929525 0.7058924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2864 2865 0.289169 0.726438 -0.302855 0.2751109 -0.4145917 -0.4545807 0.7387720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2865 2866 -0.772474 0.160552 -0.445894 -0.5066321 0.2449573 -0.6094976 0.5584196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2866 2867 -0.548241 -0.079659 -0.899754 0.0607558 -0.6170265 -0.3449056 0.7047177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2867 2868 -0.519972 -0.846430 0.299807 0.5373907 0.0185422 -0.0662384 0.8405236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2868 2869 -0.612674 -0.122339 0.674776 -0.6902789 0.5609615 -0.0682960 0.4518549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2869 2870 -0.550011 0.015617 -0.985808 0.2912405 -0.0808572 -0.6147953 0.7284695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2870 2871 -0.060494 -0.977158 -0.620140 0.1671782 -0.0944653 0.7921718 0.5793027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2871 2872 -1.076791 0.007987 -0.262077 0.2639975 -0.6483012 -0.4071472 0.5867214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2872 2873 -0.109513 -0.332122 1.132018 -0.3918444 0.4535387 -0.7301788 0.3280238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2873 2874 0.541291 -0.660135 0.489930 -0.7380890 -0.1920787 0.5935965 0.2568532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2874 2875 -0.579821 0.295602 -0.690358 -0.7113199 -0.5877706 0.3077837 0.2319891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2875 2876 0.591490 -0.089621 0.998745 0.5303032 -0.2151683 0.1314521 0.8094451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2876 2877 0.740912 0.484835 0.272386 0.3876728 -0.2099734 -0.6509099 0.6180107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2877 2878 -0.497214 0.620563 -0.524087 -0.2142111 -0.2258425 -0.9503083 0.0047930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2878 2879 0.185498 -0.948603 -0.306813 0.4550120 -0.3320217 -0.1295924 0.8160463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2879 2880 -0.307100 0.217527 0.939778 -0.5989278 -0.5861345 -0.5223615 0.1577032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2880 2881 0.128447 -0.764199 0.734101 -0.0615675 -0.6986200 -0.4737062 0.5326744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2881 2882 0.730218 -0.040655 -0.834486 0.3567831 0.7562329 0.5416135 0.0864435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2882 2883 -0.849096 -0.311382 0.568088 0.1769670 -0.1570521 -0.3646304 0.9005898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2883 2884 -0.245650 -0.573885 0.926218 -0.2474391 0.0350191 -0.9682665 0.0027427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2884 2885 0.611109 0.602015 0.703186 0.3726011 -0.7008791 0.2591302 0.5502621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2885 2886 0.435465 -0.306629 -0.832974 -0.8060908 -0.2010531 -0.5268946 0.1793803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2886 2887 -0.502143 0.401032 0.842935 0.3974168 -0.1178239 0.8842786 0.2150089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2887 2888 1.201347 0.045662 -0.168857 0.4410433 -0.0633339 0.6433589 0.6225423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2888 2889 0.122745 -0.704723 0.639162 0.0444015 0.2695928 -0.7447501 0.6088476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2889 2890 0.794671 0.136386 0.631073 -0.3901721 0.3193701 -0.8605378 0.0724103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2890 2891 0.297145 -0.536969 0.871268 -0.3230041 0.6184552 -0.4975208 0.5154169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2891 2892 0.058743 -0.845729 0.291224 -0.1757761 -0.4341796 0.8796632 0.0823619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2892 2893 -0.546934 0.315812 0.851620 0.5532127 -0.3802439 0.4050306 0.6207419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2893 2894 0.592886 0.776446 -0.219938 0.3994293 0.0686719 -0.4054478 0.8193610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2894 2895 -0.105542 0.214492 -1.118676 -0.5905237 -0.3383817 -0.1183020 0.7230382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2895 2896 -0.363261 0.897478 0.224409 -0.1106939 0.5183802 -0.0168118 0.8477890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2896 2897 -0.472483 0.850604 0.097057 -0.5013505 0.1505076 -0.2728891 0.8071720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2897 2898 -0.918528 0.104157 0.178627 -0.8352751 -0.1689121 0.5221957 0.0331028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2898 2899 -0.738934 -0.551556 0.462884 -0.0946320 0.0693376 0.6429921 0.7568343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2899 2900 0.444392 -0.789336 0.606787 -0.1927949 0.0254194 -0.2500996 0.9484905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2900 2901 0.689233 0.347349 -0.617038 -0.0169125 -0.3793828 -0.5572401 0.7384214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2901 2902 -0.573987 0.551218 -0.508151 -0.6636761 0.3273756 0.6624672 0.1161741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2902 2903 0.414960 -0.547656 0.808204 0.5594688 0.3803649 -0.7364101 0.0041642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2903 2904 -1.138972 0.030830 -0.038876 0.3442784 0.3723418 -0.2786439 0.8155928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2904 2905 -0.388608 -0.753418 -0.536557 0.6030563 0.3636426 -0.7098323 0.0150087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2905 2906 0.376242 0.479553 0.981500 0.5081793 -0.5968138 0.4619504 0.4149324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2906 2907 0.706000 -0.436253 -0.941081 0.1113879 0.4344849 -0.4696597 0.7604179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2907 2908 0.860811 0.437537 0.186284 0.1098699 -0.6875475 -0.4530068 0.5567692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2908 2909 -0.364966 0.787129 -0.648399 -0.1351185 -0.3462873 -0.9207124 0.1188141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2909 2910 0.234312 -1.069757 -0.032741 0.2618721 0.4164981 0.7056805 0.5098699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2910 2911 -1.013013 0.088071 -0.177818 0.1444056 -0.0362610 -0.2347484 0.9605859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2911 2912 -0.858922 -0.251906 -0.047304 -0.0945154 -0.3320914 0.2307562 0.9096888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2912 2913 -0.855226 -0.000354 0.435821 -0.0666544 0.4184362 -0.0541353 0.9041779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2913 2914 -0.897789 -0.101508 -0.374270 0.4247489 -0.5027977 0.1223961 0.7428338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2914 2915 -0.910382 0.183316 0.554771 -0.4804886 -0.1966101 -0.3657610 0.7724597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2915 2916 -0.158758 -0.821810 0.537534 0.1545187 -0.4830019 -0.6547665 0.5604587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2916 2917 0.922635 0.151502 -0.201680 -0.5039413 -0.2683181 -0.8104814 0.1310282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2917 2918 -0.400612 0.254103 0.793477 0.4149268 0.7718464 0.0455708 0.4795959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2918 2919 -0.251980 0.402126 -0.731420 0.2262521 0.1657508 -0.5812372 0.7638717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2919 2920 -0.730378 0.681232 -0.263125 -0.9642934 0.0157979 0.2563950 0.0644221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2920 2921 -0.614941 -0.606242 -0.573135 0.8300270 0.1927938 -0.4827284 0.2021360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2921 2922 0.269324 0.001984 0.812647 0.7818778 0.3828989 -0.4917198 0.0163470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2922 2923 -0.555958 -0.225529 -0.561864 -0.6303518 -0.1473010 0.1981901 0.7359889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2923 2924 -0.750303 0.743372 -0.209103 0.4053133 0.1404856 0.1195802 0.8953689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2924 2925 -0.560947 0.581426 -0.721103 0.0843511 -0.4174010 -0.4769225 0.7688993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2925 2926 -0.945309 -0.405374 0.078129 0.4026530 0.4215006 -0.7844188 0.2118842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2926 2927 0.487273 -0.462414 0.762962 0.4420899 0.7194232 -0.3485436 0.4068220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2927 2928 -0.967542 0.376510 -0.279125 -0.3576356 -0.5792955 0.6990867 0.2186121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2928 2929 0.866510 -0.059446 0.354811 -0.0951829 -0.1255825 0.9523623 0.2611039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2929 2930 -0.843251 -0.489552 0.352146 -0.0188059 -0.0369125 -0.9816329 0.1862273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2930 2931 1.032935 0.031786 0.349393 -0.4764416 0.2228084 0.8242474 0.2097047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2931 2932 -0.792710 -0.537644 -0.509872 -0.1746371 -0.3355301 0.7066734 0.5979415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2932 2933 -0.433991 0.881797 -0.002174 0.4293952 -0.3541659 -0.8156163 0.1579758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2933 2934 -0.245332 -0.435329 0.806512 -0.5971811 0.4530446 0.1784296 0.6374074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2934 2935 -0.559182 -0.325620 -0.732426 -0.2368481 0.7147135 0.5496442 0.3619101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2935 2936 0.824033 -0.230340 -0.442876 -0.3895818 -0.2317441 0.5858191 0.6718159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2936 2937 -0.163512 -0.160637 -0.959474 0.7616831 -0.1542718 0.2992378 0.5536207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2937 2938 -0.613823 -0.600994 0.498821 -0.4805183 -0.0295069 0.4969239 0.7220098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2938 2939 -0.842084 0.098833 0.095054 0.4758159 0.0591809 0.6111883 0.6297187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2939 2940 -0.585383 -0.638781 -0.510018 -0.3377876 -0.1194506 -0.8667592 0.3469287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2940 2941 0.639910 0.647591 0.415176 0.6188310 -0.2454249 0.3008559 0.6828620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2941 2942 0.713894 -0.297581 -0.598803 0.4276583 -0.2456485 -0.1052413 0.8635331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2942 2943 0.547994 -0.569006 -0.513456 0.7010980 -0.4142262 0.5793285 0.0354502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2943 2944 -0.029362 -0.037038 0.989112 -0.0158323 0.8033465 -0.2639647 0.5335788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2944 2945 -0.688082 -0.635832 -0.569451 0.2994796 -0.0672572 0.1591400 0.9383298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2945 2946 -0.871770 -0.479661 -0.178132 0.0808896 0.3504750 -0.9197830 0.1569184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2946 2947 1.005298 0.157449 0.382873 -0.3188847 -0.6388929 0.2346180 0.6596080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2947 2948 0.607963 0.119512 -0.940663 0.1568455 -0.0497979 -0.9863223 0.0093846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2948 2949 -0.069845 -0.029600 -0.753277 -0.5322429 0.4280306 -0.0106060 0.7303388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2949 2950 0.425898 0.864952 -0.119147 -0.6520329 0.3568209 0.6484373 0.1645020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2950 2951 -0.255186 -0.956841 0.349024 -0.6415206 -0.1211459 -0.5661644 0.5032224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2951 2952 0.478422 0.159066 -0.791859 0.5721656 0.0369321 -0.6782708 0.4595772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2952 2953 0.554346 0.080592 -0.802515 0.1764247 0.4726478 0.6527316 0.5651724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2953 2954 -0.110217 -0.944352 0.234960 0.4950534 -0.4326010 0.5451161 0.5202182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2954 2955 -0.179388 0.096011 1.115191 0.7691186 0.5149144 -0.2489131 0.2852402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2955 2956 -0.532498 0.214522 -0.874769 -0.5551859 0.5926714 0.4262237 0.3985506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2956 2957 0.647044 0.451599 0.207274 -0.8054774 0.0746409 0.2307016 0.5407510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2957 2958 0.574006 -0.708921 0.234855 0.4618024 -0.7365126 -0.2633303 0.4182642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2958 2959 0.542170 -0.399962 -0.670078 0.2115514 0.1912275 -0.7935259 0.5375823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2959 2960 0.210882 0.263869 0.953004 0.6073769 -0.7018677 -0.0460597 0.3692608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2960 2961 0.921349 0.500357 0.273119 -0.7698066 -0.2814310 -0.3298136 0.4684201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2961 2962 0.837572 0.443318 0.402597 0.1668287 0.2464608 -0.8700084 0.3930785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2962 2963 -0.833382 0.330159 -0.073107 -0.1904835 0.4958051 -0.8233963 0.1997795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2963 2964 0.887562 -0.398315 -0.473283 -0.4033630 -0.2072173 0.8728624 0.1801957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2964 2965 -0.161644 0.530253 -0.913358 0.1584959 -0.2079947 -0.9562797 0.1309441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2965 2966 0.256828 -0.722526 -0.400480 -0.0423132 0.2394539 0.9294322 0.2775377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2966 2967 -0.594073 0.262440 -0.870151 -0.5548343 0.2122601 -0.2367771 0.7687920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2967 2968 -0.616743 0.912031 -0.268637 0.3022132 -0.3514172 0.8699168 0.1685763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2968 2969 0.277375 -0.152104 -1.100723 0.5908364 0.4404829 0.6536216 0.1722381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2969 2970 -0.889263 -0.521507 0.277140 0.0093272 0.6375605 0.3187316 0.7013129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2970 2971 -0.371118 0.064172 -0.946990 0.2626413 -0.0818493 -0.9551506 0.1095792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2971 2972 0.973133 -0.101902 -0.491250 0.3902319 0.7045352 0.1765548 0.5658424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2972 2973 0.308191 -0.291287 0.956665 -0.5429530 -0.2325975 -0.6867724 0.4236085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2973 2974 0.933698 0.082666 0.268851 0.5386759 -0.5412658 0.3313266 0.5541501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2974 2975 0.453700 -0.738714 -0.240780 0.6851733 0.2958334 -0.1912737 0.6375222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2975 2976 0.512880 0.180976 0.838868 -0.1608442 0.1441896 0.4923318 0.8431772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2976 2977 0.069906 -0.710598 0.815392 -0.4463755 0.6074150 -0.5561451 0.3499979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2977 2978 0.520833 -0.824965 -0.124182 -0.0071619 -0.0952759 0.9516662 0.2918948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2978 2979 -0.933073 0.483262 0.327647 -0.2097588 0.8530895 0.0710027 0.4724385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2979 2980 -0.597383 -0.579968 -0.508246 -0.4415919 -0.3243564 -0.6745722 0.4947141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2980 2981 1.027558 0.141826 -0.229303 0.2664749 0.8941156 -0.2491682 0.2597378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2981 2982 -0.542441 0.877952 0.623072 -0.2486780 0.3333179 0.9084586 0.0419688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2982 2983 0.310669 -0.142570 0.984907 -0.6068718 0.1471117 -0.6746548 0.3935806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2983 2984 0.720721 -0.438232 0.247243 0.5521855 -0.0793563 -0.5901273 0.5835611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2984 2985 0.440277 0.893595 -0.260911 -0.3426347 0.5956730 0.4947713 0.5319553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2985 2986 0.156301 -0.004700 0.883381 -0.8180040 -0.3865899 0.2304018 0.3582356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2986 2987 0.005577 -0.398229 -0.889015 0.8736661 -0.0782311 -0.3869038 0.2844166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2987 2988 0.557678 -0.140276 0.839752 -0.6229730 0.2887243 -0.4967854 0.5307987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2988 2989 0.590956 -0.569468 0.701611 -0.3064553 -0.6951234 0.1060391 0.6415951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2989 2990 0.413023 -0.659751 -0.566700 0.1016687 0.3542718 0.8040198 0.4665909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2990 2991 -0.504152 -0.482883 -0.647490 -0.4441468 -0.3537577 0.0874613 0.8184984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2991 2992 -0.949108 0.196633 -0.194537 0.2689578 0.5830553 -0.6418036 0.4192807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2992 2993 0.562718 -0.664646 -0.395618 0.4748717 0.4644826 -0.6883191 0.2914956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2993 2994 0.127552 0.949438 0.278803 -0.5185508 -0.0518838 0.5073413 0.6863074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2994 2995 0.780709 -0.408452 0.690567 -0.1474686 -0.8654592 0.4371076 0.1953722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2995 2996 -0.652946 -0.639852 -0.560917 0.8381352 -0.0259789 0.4448231 0.3146219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2996 2997 -0.813186 0.528561 0.060925 -0.1273114 -0.8565259 -0.2299595 0.4441553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2997 2998 0.537732 0.028118 0.833864 -0.7788539 -0.4249395 -0.4091098 0.2131717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2998 2999 0.739671 0.466300 -0.236211 -0.0825114 0.3144277 -0.7209587 0.6120013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2999 3000 0.617883 0.470423 -0.433084 -0.5424825 0.5303246 0.0265724 0.6509704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3000 3001 0.642577 -0.543313 -0.152588 0.6199568 -0.6046074 -0.3430977 0.3638508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3001 3002 0.644878 -0.555261 -0.559319 -0.2206165 0.6643664 -0.3627707 0.6150960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3002 3003 0.690227 -0.015096 0.792070 -0.2705928 0.3545387 0.5157870 0.7314681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3003 3004 -0.020560 -0.692170 0.802555 0.3610674 0.1630997 -0.9143286 0.0838574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3004 3005 -0.467635 0.161965 0.788952 0.7256640 0.0618303 -0.5415089 0.4199486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3005 3006 -0.862622 -0.034504 -0.029844 -0.6562397 -0.4016364 -0.0262213 0.6382398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3006 3007 -0.630365 -0.432969 0.475965 0.2746164 0.4448804 -0.0225563 0.8521493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3007 3008 -0.978207 -0.202068 0.067022 -0.4277360 -0.2042857 0.8647564 0.1658483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3008 3009 0.367492 0.206095 0.955559 -0.0438659 0.0981833 0.8788921 0.4647413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3009 3010 -0.138005 -0.266863 0.948255 0.4146881 0.0566943 -0.8010864 0.4278787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3010 3011 -0.426056 0.446923 0.762614 0.7016496 -0.1473197 -0.5205244 0.4637230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3011 3012 -0.918465 0.361746 0.284698 -0.0486273 -0.4259952 0.8191128 0.3810744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3012 3013 0.904371 0.154639 0.338862 0.3666561 -0.6396977 0.6043176 0.3019113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3013 3014 -0.322216 -0.941685 -0.202436 -0.1801372 0.3882310 -0.0376957 0.9029985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3014 3015 0.181636 -0.756623 -0.452029 -0.4077724 -0.4672209 -0.1297996 0.7736784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3015 3016 -0.221600 -0.155182 -0.969823 0.5812188 0.5361073 -0.5963003 0.1385630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3016 3017 0.684162 0.033555 0.663561 -0.3691139 -0.1964684 0.3178099 0.8509712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3017 3018 0.578054 -0.824208 -0.117833 -0.2508096 -0.6466267 0.2183605 0.6865035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3018 3019 -0.622661 -0.430068 -0.713953 0.8877516 0.0453854 0.4540784 0.0604163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3019 3020 -0.232973 -0.562065 0.943753 -0.5197158 -0.5075204 -0.1581187 0.6688176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3020 3021 0.413669 0.485971 -0.783937 0.3179676 -0.1766730 0.6092123 0.7046585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3021 3022 0.083090 -0.537555 -0.783473 -0.0431660 0.6407793 -0.7613261 0.0890006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3022 3023 0.101597 0.979513 0.322034 0.6716196 -0.4772547 -0.5662356 0.0230707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3023 3024 -0.842110 -0.375122 0.272477 -0.5459963 -0.0676253 0.6846663 0.4780658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3024 3025 -0.430524 0.554481 0.677097 0.1071969 0.6867625 -0.2651246 0.6682627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3025 3026 -0.547774 -0.008261 -0.643115 0.2122693 -0.4244404 0.4840976 0.7351473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3026 3027 -0.630655 0.950192 -0.050191 -0.5875555 0.2872435 0.5891312 0.4745462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3027 3028 0.119855 0.060647 1.129124 0.2624901 -0.3952565 -0.0677119 0.8776596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3028 3029 0.621274 0.805949 0.290031 -0.0909195 -0.4333590 -0.2265115 0.8675403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3029 3030 0.634361 0.778607 -0.025883 -0.1906428 0.3001098 -0.6350259 0.6858072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3030 3031 -0.698897 0.449338 0.092176 -0.0282030 0.4083715 0.1678140 0.8968142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3031 3032 -0.291821 0.848916 -0.394957 -0.0928090 0.3644026 -0.9116825 0.1656270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3032 3033 0.114650 -0.496701 -1.021260 -0.0255388 -0.5916283 0.2850552 0.7537024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3033 3034 -0.958515 0.210583 -0.293692 0.1116536 -0.0971839 0.8414613 0.5196457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3034 3035 0.457649 0.674312 -0.192216 0.8544649 -0.0255729 -0.4450721 0.2667331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3035 3036 0.052920 -0.701042 -0.440024 0.1631599 -0.4190941 -0.1822992 0.8743603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3036 3037 0.060724 -0.899513 -0.259506 -0.3343325 -0.2084810 0.5533388 0.7338758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3037 3038 -0.720297 -0.089206 -0.680919 0.2314585 0.2388949 -0.0823701 0.9394527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3038 3039 -0.378886 -0.416511 -0.917197 0.1158535 0.0377000 0.9907537 0.0596980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3039 3040 0.719273 -0.839940 -0.309208 -0.1101669 -0.1500152 -0.9716647 0.1456925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3040 3041 0.514555 0.460513 0.645633 -0.3608142 -0.4893185 0.6159922 0.5009332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3041 3042 0.199275 -0.747453 -0.614401 0.3198074 -0.2383668 0.0804711 0.9134708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3042 3043 0.153932 -0.860770 -0.119494 0.2652412 0.7422334 0.4077261 0.4609731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3043 3044 -0.892741 -0.450081 -0.193052 -0.3744067 -0.3558531 -0.8004469 0.3040938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3044 3045 0.655886 -0.530332 -0.831780 0.7321742 -0.2181632 0.6437379 0.0439007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3045 3046 -0.610292 0.332785 0.652954 -0.8318460 0.2178947 -0.4144271 0.2980004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3046 3047 -0.184323 -0.729391 -0.698926 0.0513299 0.8373302 -0.3870271 0.3826922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3047 3048 0.755873 -0.253119 0.775378 0.1178175 0.7630321 -0.6339597 0.0446783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3048 3049 -0.898889 -0.452470 0.068810 0.0302321 -0.3246052 -0.1709117 0.9297885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3049 3050 -0.587091 -0.726536 0.735976 -0.8020168 0.5003569 -0.3191608 0.0674417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3050 3051 0.800263 0.398056 -0.573282 0.1592297 -0.4937919 0.5044442 0.6901823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3051 3052 -0.230298 -0.179860 -0.901534 0.2683791 0.7604739 -0.2017707 0.5558244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3052 3053 0.874564 -0.282655 0.363513 0.1762946 -0.8362867 0.5081895 0.1062457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3053 3054 -0.856822 -0.645869 0.141777 0.1430645 0.2352716 -0.9611429 0.0196012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3054 3055 0.750959 0.311762 0.704742 -0.9010985 -0.1832671 0.0646485 0.3876277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3055 3056 0.602707 -0.497441 -0.419882 0.2085154 -0.3796237 0.0353403 0.9006432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3056 3057 0.392324 -0.802457 -0.376036 0.5848297 -0.4381771 0.0607358 0.6799163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3057 3058 0.353034 -0.714824 0.303357 0.0204774 0.3309288 -0.5675477 0.7536288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3058 3059 0.366349 -0.126060 0.868877 0.0190698 -0.6662465 -0.2922933 0.6857963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3059 3060 -0.314732 1.004850 -0.161804 -0.3687883 0.2701091 -0.3250117 0.8278911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3060 3061 -0.477641 -0.783705 -0.456283 0.0891524 0.2317467 0.3204789 0.9141327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3061 3062 -0.526665 -0.542085 -0.602411 -0.6810389 0.0060071 0.7165460 0.1507042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3062 3063 0.400713 0.880826 0.212903 -0.4518346 -0.1177907 0.2904497 0.8352304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3063 3064 0.814097 0.038502 0.450886 0.8165505 -0.3098907 -0.4271845 0.2339368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3064 3065 0.344689 0.261323 -1.067728 0.0733476 -0.5608534 -0.3888335 0.7272360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3065 3066 -0.851661 -0.323334 -0.440444 -0.7203246 -0.2496482 0.6070991 0.2241402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3066 3067 0.155343 0.386219 0.884272 0.6483441 -0.5277755 -0.4940943 0.2386917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3067 3068 -0.577874 0.691284 -0.479685 -0.5819348 0.6964526 0.4130166 0.0756505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3068 3069 -0.064669 0.412432 0.933921 0.1395690 -0.1936905 0.9706456 0.0291834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3069 3070 0.370234 -0.703930 0.487729 -0.1359556 -0.2640155 -0.9489332 0.1064783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3070 3071 0.092436 0.889949 0.346427 -0.1446199 -0.6280507 -0.1419802 0.7513182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3071 3072 0.142314 0.730847 0.476867 0.4057584 0.5704563 0.0627795 0.7113357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3072 3073 0.077887 1.192176 -0.255023 -0.2453081 0.3709415 0.2863620 0.8486596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3073 3074 0.497192 0.665650 0.475994 0.3375742 -0.8277425 0.0565584 0.4446203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3074 3075 -0.133819 0.216843 -1.007381 -0.2194428 -0.3539573 -0.3889315 0.8217611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3075 3076 -1.041260 0.280464 -0.300617 0.2153362 -0.6904110 -0.5384285 0.4325016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3076 3077 0.299688 -0.212107 0.848475 0.3300836 -0.2026044 -0.8121733 0.4363151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3077 3078 -0.085836 0.891585 0.367745 0.2658201 0.1684180 -0.4881162 0.8140747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3078 3079 -0.747303 0.391936 -0.172010 0.2510161 -0.1153552 -0.9576688 0.0809608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3079 3080 -0.613895 -0.498384 0.578320 -0.3262314 -0.6410517 -0.0915056 0.6886600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3080 3081 -0.285081 0.262652 0.973179 -0.8873803 0.4264135 -0.0931297 0.1485082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3081 3082 -0.175256 -0.231519 -0.956654 -0.3310928 -0.3672807 0.5668523 0.6589089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3082 3083 -0.511375 0.836210 -0.355989 0.2477885 -0.0795783 -0.2999259 0.9177759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3083 3084 -0.989655 0.062630 -0.390660 -0.3259269 -0.8412615 0.1953694 0.3845537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3084 3085 0.354219 -0.013924 1.133016 -0.4908012 -0.8418378 0.2050375 0.0915580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3085 3086 -0.330020 -0.005663 -1.027019 0.3570486 -0.2318334 -0.8851830 0.1876716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3086 3087 0.794943 -0.593047 -0.476380 0.7609488 0.4503172 0.4476721 0.1332705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3087 3088 -0.371740 0.595825 0.703501 -0.0402000 0.0674441 -0.7638251 0.6406298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3088 3089 -0.360277 -0.686748 0.558061 0.1277519 -0.2790452 -0.7289440 0.6119263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3089 3090 0.969302 -0.126459 0.598863 0.3687340 0.1590341 0.7999447 0.4459057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3090 3091 0.039712 -0.095249 0.854373 -0.6036607 -0.4663935 -0.0415645 0.6452466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3091 3092 0.487665 -0.612036 -0.446550 0.0773011 -0.2183688 -0.8566371 0.4609907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3092 3093 0.171576 0.666285 -0.872316 -0.7488434 0.3249716 0.5752033 0.0526137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3093 3094 0.627351 -0.837627 0.190914 0.3019029 -0.0462815 -0.6211116 0.7217569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3094 3095 0.698346 0.529712 0.294922 -0.2099787 -0.7410491 0.6181906 0.1568294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3095 3096 -0.538464 0.000165 -0.801089 0.2857080 0.8985118 -0.3329930 0.0127769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3096 3097 0.422170 0.246033 0.866056 -0.0680050 -0.5974001 -0.3003696 0.7404502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3097 3098 0.827262 0.744575 -0.114170 0.7637602 -0.1020547 0.5969544 0.2233845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3098 3099 0.156776 -0.640445 0.415806 0.3277136 0.1215244 0.4583751 0.8171462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3099 3100 0.753145 -0.760952 0.218595 0.1401362 -0.0661280 0.9030812 0.4005413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3100 3101 -0.616511 -0.379234 -0.924323 -0.2285979 -0.5926609 0.6487377 0.4190889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3101 3102 -0.399376 0.882553 0.597373 0.1695666 -0.5141079 0.4736835 0.6946684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3102 3103 0.791414 0.596951 -0.257494 -0.2620899 0.3685103 -0.2740617 0.8487634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3103 3104 -0.075375 0.817987 0.473882 -0.3002017 -0.4942896 0.1813729 0.7953996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3104 3105 0.850363 0.261251 0.417114 -0.2374655 -0.1915208 0.8359239 0.4562469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3105 3106 -0.317764 -1.031450 -0.335752 0.0895542 -0.0490456 0.9668550 0.2340214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3106 3107 -0.125533 0.963669 -0.213341 -0.2816265 0.2860053 0.1932086 0.8952977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3107 3108 0.301559 0.960075 0.456180 0.6866387 0.2552617 0.4723155 0.4901905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3108 3109 1.176154 -0.009466 -0.101582 -0.3510412 0.0551318 0.4640654 0.8114024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3109 3110 0.567483 -0.789458 -0.174037 0.1284092 0.6225134 -0.7658399 0.0973518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3110 3111 -0.309568 0.740085 0.711085 0.6915720 -0.2544264 -0.3383075 0.5852721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3111 3112 -0.850455 0.509044 -0.197249 -0.1016393 -0.2287172 0.9501641 0.1858660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3112 3113 1.047606 0.006646 -0.272253 0.7972344 -0.3278332 0.4001885 0.3111140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3113 3114 0.275506 -0.875869 0.458600 0.4518429 0.1428718 0.8168415 0.3289309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3114 3115 -0.287483 0.784387 0.453429 -0.2254434 -0.4150167 0.8759954 0.0978186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3115 3116 0.454725 -0.949538 -0.064325 0.2479464 -0.0101409 0.0905574 0.9644787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3116 3117 0.323815 -0.843857 0.329506 -0.3975579 -0.7240841 0.4796349 0.2959734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3117 3118 -0.878365 -0.540574 -0.036006 -0.1519247 0.8109034 -0.4211770 0.3767817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3118 3119 0.788542 -0.569466 -0.459429 0.2369442 0.7890530 -0.3013397 0.4800492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3119 3120 0.548435 -0.845644 0.305383 -0.1465964 -0.8058199 0.3128853 0.4809018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3120 3121 -0.939559 0.181135 0.288470 0.4503667 0.4467415 -0.1475637 0.7588260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3121 3122 -0.590507 -0.172204 -0.730216 0.1876935 0.0967510 -0.6392346 0.7394522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3122 3123 0.326504 -0.840629 -0.749479 0.3301166 0.2114428 -0.1636512 0.9052808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3123 3124 0.571104 -0.749410 0.206034 -0.2639400 -0.9289090 0.2134639 0.1479761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3124 3125 -0.973846 -0.290985 -0.020540 0.3284801 0.0341665 -0.1144276 0.9369310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3125 3126 -0.906989 -0.571387 0.089611 -0.3225101 -0.0302393 0.3954848 0.8594560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3126 3127 -0.908513 0.086724 -0.072772 0.2567782 0.0773664 -0.7397891 0.6170830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3127 3128 0.144735 -1.062577 0.179392 0.1488317 0.6857057 0.6357881 0.3216059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3128 3129 -0.829662 0.015930 -0.595513 -0.0906837 -0.7157853 -0.2396514 0.6496115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3129 3130 -0.460937 -0.557415 0.645739 -0.2841452 0.0827012 -0.9187508 0.2613790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3130 3131 1.034843 -0.052301 0.491534 0.3001469 0.2371224 -0.6289096 0.6768734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3131 3132 -0.129849 0.828600 0.053840 0.2486248 0.6869109 -0.6290284 0.2658240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3132 3133 0.037641 -0.177759 -1.206653 0.6323229 0.4450947 0.0739260 0.6297566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3133 3134 0.434141 -0.929688 0.409004 0.1004713 -0.5064046 0.1704924 0.8392808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3134 3135 0.442471 -0.981555 -0.271195 -0.4294686 0.0325019 -0.8341592 0.3444978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3135 3136 0.272039 0.968598 -0.110125 0.0103120 -0.2569301 0.1611479 0.9528441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3136 3137 0.548473 0.686937 -0.264530 -0.0160220 0.4064959 -0.7056741 0.5801107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3137 3138 -0.707496 0.572765 -0.222776 0.3847737 0.2882231 0.8762109 0.0336308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3138 3139 0.359322 -0.835275 -0.462681 -0.3640762 0.6681808 -0.3686526 0.5339271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3139 3140 -0.177261 1.050979 0.403415 0.0641543 0.1707706 0.6274656 0.7569733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3140 3141 0.124025 0.552286 -0.985066 0.2373989 -0.0224080 -0.0163193 0.9710166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3141 3142 -0.056191 -0.146353 -1.028451 -0.4107440 -0.2664299 -0.8665630 0.0968147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3142 3143 -0.661569 -0.420074 -0.570154 0.3049284 -0.2835080 -0.1361199 0.8989512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3143 3144 -0.642117 -0.948767 0.320120 0.9173059 -0.0026293 -0.0827594 0.3894790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3144 3145 -0.581461 0.451037 0.582349 0.0772093 0.9316408 0.0165668 0.3546965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3145 3146 0.179976 0.476609 -0.797952 -0.3612356 -0.0013134 -0.4174232 0.8338255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3146 3147 -0.740313 0.771851 -0.115339 0.4509687 -0.7143231 0.1716985 0.5068425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3147 3148 -0.449380 0.866162 -0.052870 0.5523987 0.3952973 0.3095242 0.6654250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3148 3149 0.327418 0.114747 -0.940510 0.8494688 0.2113021 0.4815841 0.0427902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3149 3150 -0.652386 0.026531 0.795738 -0.4235198 0.2631989 -0.1802761 0.8478548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3150 3151 -0.469338 -0.750295 0.127067 0.6394148 0.4626682 0.2705443 0.5512645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3151 3152 -0.912960 -0.313742 -0.139107 -0.1766791 0.9128136 0.3159491 0.1890292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3152 3153 0.973117 0.141919 -0.127868 -0.3335898 -0.6515908 -0.3844981 0.5624131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3153 3154 -0.362973 0.993717 -0.343365 -0.2809442 -0.1569408 0.6244860 0.7116581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3154 3155 0.921355 0.764136 0.007906 -0.2415974 0.4242095 -0.6014912 0.6323649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3155 3156 -0.631099 0.497330 0.801209 0.2124512 0.4342316 0.8451349 0.2281545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3156 3157 0.725541 0.432801 0.218316 -0.7634379 0.1184689 0.0876579 0.6288432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3157 3158 0.807491 -0.532634 0.462562 -0.3310204 -0.2669559 0.2289330 0.8756425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3158 3159 0.302487 -0.776146 -0.358667 -0.0070490 -0.5010885 0.8197502 0.2772548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3159 3160 0.625459 0.720690 0.335079 -0.0473845 0.6192067 0.1700209 0.7651344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3160 3161 0.497770 -0.443946 0.384646 -0.0992276 -0.9160028 0.2339144 0.3104461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3161 3162 -0.628401 -0.716271 -0.464298 -0.4057526 0.7109458 -0.5667242 0.0935124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3162 3163 0.545151 0.551029 0.148704 0.3218567 -0.0478960 -0.9286625 0.1780456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3163 3164 -0.978785 -0.022052 -0.010487 0.1000481 0.0070264 -0.1136946 0.9884405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3164 3165 -0.774813 -0.521170 0.014598 -0.1855920 -0.0644162 -0.7902174 0.5804848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3165 3166 0.723559 -0.634395 -0.399689 0.6465295 0.4005610 -0.5015545 0.4123028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3166 3167 0.323491 0.712480 0.376025 0.0340826 -0.8387730 0.4527078 0.3005894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3167 3168 0.278817 0.219141 -0.840162 0.0025516 0.7123121 0.3568075 0.6043950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3168 3169 0.740174 -0.585123 0.161807 0.7093028 -0.2618283 0.2151622 0.6180944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3169 3170 0.758110 -0.339654 0.443124 -0.7314334 0.1415168 0.3828952 0.5462321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3170 3171 0.129856 -0.593989 -0.596007 -0.3515558 0.0574820 -0.3023542 0.8841303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3171 3172 0.217620 0.086830 -0.990648 -0.0024871 -0.8118830 0.4701559 0.3461117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3172 3173 -0.847588 0.793565 0.027512 0.1142082 -0.7557424 0.5617885 0.3165495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3173 3174 0.768265 0.657873 -0.317508 0.3350214 -0.0006369 -0.7208636 0.6067256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3174 3175 -0.504073 0.344238 -0.797009 -0.7541234 0.5520748 -0.0214690 0.3550357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3175 3176 -0.303993 0.640123 0.643748 0.8490218 -0.1654448 -0.2751436 0.4196260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3176 3177 -0.755572 -0.111929 -0.535409 -0.2048361 0.4231707 0.6883518 0.5523953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3177 3178 0.687928 0.619652 -0.337846 -0.3168421 0.5782213 0.4699866 0.5868422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3178 3179 0.683260 -0.512906 0.667951 0.0746519 -0.7109988 0.2379432 0.6574883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3179 3180 0.215204 0.643750 -0.894130 -0.7224681 0.1796603 0.5262621 0.4108651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3180 3181 -0.167968 -0.192216 0.903716 0.5791298 0.6743804 0.0400933 0.4563028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3181 3182 -0.454283 0.090845 -0.693846 0.0072855 0.0170448 0.6083255 0.7934711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3182 3183 0.107307 0.527517 -0.920499 0.4318965 -0.8174377 -0.3723284 0.0814407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3183 3184 -0.221270 -0.518769 0.929570 -0.2647048 -0.4201284 0.3638544 0.7880568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3184 3185 -0.133466 -0.669063 0.495533 -0.8295902 -0.0271068 -0.4750113 0.2922491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3185 3186 0.564878 0.133799 -0.655187 0.3539270 0.2850051 -0.6866141 0.5675111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3186 3187 0.299471 0.663113 -0.739764 -0.5490626 -0.0100341 0.2029483 0.8107043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3187 3188 0.762756 0.801817 0.302655 0.3904160 -0.2547768 0.8808818 0.0819229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3188 3189 -0.144163 -0.933634 0.109016 -0.0929560 0.5940872 -0.7788803 0.1782276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3189 3190 0.354842 0.083425 0.751873 -0.1912398 0.0921734 0.9713891 0.1064645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3190 3191 -0.934553 -0.302456 0.639457 -0.2473240 -0.1993698 -0.3605909 0.8769588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3191 3192 -0.168158 -0.943264 0.428490 -0.1405269 0.2735777 -0.6112804 0.7292076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3192 3193 0.542557 -0.620594 0.270574 -0.0320941 -0.0629326 -0.7228786 0.6873544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3193 3194 0.582335 0.825692 0.006400 0.5025396 -0.1150275 0.7980404 0.3120163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3194 3195 0.199053 -0.804508 0.171376 0.0661397 0.5402254 0.6160297 0.5694642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3195 3196 -0.940859 -0.298861 -0.207415 0.0970207 -0.3100490 -0.6372718 0.6988142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3196 3197 0.026468 -0.965806 0.141975 -0.1206919 0.0855631 0.0371271 0.9882985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3197 3198 0.026775 -0.783775 -0.026219 0.4685051 -0.1375733 0.1842881 0.8530032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3198 3199 -0.256553 -0.477642 0.940783 -0.1819848 -0.3395732 -0.9099817 0.1533131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3199 3200 -10.922890 -15.386730 -2.689494 0.1441631 -0.0285890 0.4513306 0.8801707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3200 3201 1.087632 -0.029539 -0.097188 0.2024458 0.5339077 0.4311469 0.6986205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3201 3202 0.181402 -0.458519 0.863926 -0.1890003 -0.3535763 0.8913956 0.2113683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3202 3203 -0.500506 -0.621612 0.838568 0.0963756 0.0051716 0.6671500 0.7386446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3203 3204 -0.529956 0.629248 0.664133 0.4862418 0.4094190 -0.6486854 0.4185119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3204 3205 -0.612970 -0.683543 -0.328817 -0.0718290 -0.4535589 -0.7987578 0.3887300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3205 3206 0.817769 -0.660299 -0.518756 -0.1316916 0.0750563 0.2438885 0.9578843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3206 3207 0.591579 -0.700883 -0.564159 -0.5840164 0.2938206 0.0150880 0.7565492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3207 3208 0.956969 0.385726 -0.321754 0.5152056 0.6040542 0.4066546 0.4520109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3208 3209 0.143959 -0.008790 1.078233 0.3520447 -0.3633557 -0.6707194 0.5423768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3209 3210 0.023249 0.871134 0.351797 0.1185743 -0.5928839 0.6825013 0.4106346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3210 3211 0.527586 -0.283826 -0.740794 0.6317714 0.6635183 0.1095073 0.3855082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3211 3212 0.035542 0.089939 1.019473 -0.3248075 -0.4847333 -0.6550901 0.4799902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3212 3213 0.844886 0.427473 0.240317 -0.2486468 0.4393560 -0.1586911 0.8485035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3213 3214 0.100148 0.358522 0.917131 0.8238271 -0.1648676 -0.0738230 0.5372874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3214 3215 0.154885 0.542216 -0.783237 0.0789886 -0.4843379 0.2731666 0.8273800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3215 3216 -0.092143 0.776811 -0.669298 0.0488964 -0.2957748 -0.7750680 0.5562338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3216 3217 -0.627039 -0.710469 -0.293529 0.1321779 -0.5157856 -0.0846121 0.8422203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3217 3218 -0.206829 -0.866079 0.563097 -0.8038627 -0.4047078 -0.2122639 0.3807367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3218 3219 -0.264084 -0.496842 -0.872023 0.4151400 0.3469281 0.7747208 0.3272725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3219 3220 -0.237904 -0.615424 0.484251 -0.1743121 -0.0379171 -0.7584899 0.6267940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3220 3221 -0.413258 0.550736 0.837181 -0.2284612 -0.4945283 0.1963535 0.8152868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3221 3222 0.770688 -0.118441 0.823926 -0.3470364 0.0602334 0.8124021 0.4646940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3222 3223 -0.553564 -0.781814 0.132958 0.5074186 -0.3314432 -0.7542114 0.2526599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3223 3224 0.554304 0.565202 0.370999 -0.1925675 0.1940407 0.5091092 0.8161334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3224 3225 0.523552 -0.497582 0.848851 -0.0326267 0.2975961 0.4278056 0.8528507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3225 3226 -0.497845 -0.353016 0.712620 -0.2508463 -0.0477552 -0.1762499 0.9506479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3226 3227 -0.376261 -0.985568 0.561327 -0.3697350 0.0409018 -0.3132333 0.8737894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3227 3228 0.228169 -1.069143 -0.271445 0.0765694 -0.1924181 -0.5408299 0.8152395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3228 3229 0.791055 -0.186060 -0.298390 -0.3150138 0.1073255 -0.9429469 0.0099368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3229 3230 -0.972971 0.420469 0.094854 -0.3526726 0.3052104 0.7163648 0.5189317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3230 3231 0.305382 0.699508 0.349423 -0.6507358 -0.1527116 0.7433337 0.0260233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3231 3232 -0.346773 -1.199747 -0.248672 0.0357746 -0.2213703 -0.9061819 0.3585383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3232 3233 0.671695 0.520837 -0.562613 -0.1483782 0.0307622 0.6629710 0.7331487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3233 3234 0.602077 -0.759984 -0.469247 -0.0476672 0.1148309 0.1524885 0.9804534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3234 3235 0.408049 -0.963749 -0.414946 -0.3277963 -0.5176618 0.6604615 0.4340120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3235 3236 -0.625260 0.518464 -0.012429 -0.2248028 -0.7264410 0.6462253 0.0643433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3236 3237 0.983095 0.030962 -0.181643 0.1166129 -0.8060209 0.4133926 0.4072325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3237 3238 -0.670932 -0.535506 -0.454608 0.3944523 -0.2405275 -0.3172707 0.8281867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3238 3239 -0.100470 -0.986004 0.391015 0.0399927 0.1704576 0.7566709 0.6299159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3239 3240 0.446687 0.801860 0.013678 0.3831621 -0.1185953 -0.9066006 0.1311382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3240 3241 -0.302181 0.496142 -0.733869 -0.1840887 0.7385612 0.6380356 0.1164014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3241 3242 0.625402 -0.519594 0.572041 -0.2020989 -0.4514032 0.1038281 0.8629084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3242 3243 0.551312 -0.682634 -0.490411 -0.0699557 0.0643292 0.9945941 0.0418401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3243 3244 -0.791575 0.732775 -0.654617 0.1715564 0.0790863 -0.8780255 0.4397556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3244 3245 0.013566 -0.716866 -0.714050 -0.4105554 0.5371681 -0.1426237 0.7228784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3245 3246 0.891283 -0.002801 -0.383878 0.3866311 -0.1226831 -0.7785250 0.4789197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3246 3247 -0.135482 0.609022 -0.849826 -0.1595804 -0.0490900 -0.5795654 0.7976391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3247 3248 -0.844743 0.162913 -0.505781 0.6097691 -0.3850135 -0.6339036 0.2794860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3248 3249 0.402414 -0.611476 0.866789 0.0613985 -0.1242927 -0.3891302 0.9106916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3249 3250 0.800048 0.032100 0.690137 -0.5684194 0.0327669 0.1108681 0.8145759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3250 3251 0.549851 -0.709536 0.175871 0.0348636 -0.8097661 0.5847706 0.0332680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3251 3252 -0.648942 -0.263318 0.873654 0.2742760 -0.6551847 0.7033438 0.0285145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3252 3253 0.976445 -0.476218 0.319536 -0.1050455 0.3241585 0.8916955 0.2979359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3253 3254 -0.920667 -0.292020 -0.151241 -0.4033035 0.8155672 -0.0558402 0.4111913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3254 3255 0.631062 0.528606 -0.658843 -0.1465813 -0.5855365 -0.3319014 0.7249154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3255 3256 -0.512613 0.690187 -0.291807 0.3183939 0.2711448 -0.2285835 0.8791220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3256 3257 -0.568066 -0.169905 -0.974572 -0.6049596 -0.1587984 0.7802504 0.0040290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3257 3258 0.604216 0.192502 0.236648 -0.0258101 0.8355671 -0.4844190 0.2578755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3258 3259 -0.929525 0.024045 0.089967 -0.2009277 -0.8073268 0.3480794 0.4320789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3259 3260 -0.495920 0.559199 0.450655 0.1740522 -0.9378869 0.2290331 0.1939532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3260 3261 0.202650 0.657663 0.764136 -0.5235110 0.5309480 -0.6591325 0.0978505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3261 3262 -0.126639 -0.893204 -0.201036 0.4871526 -0.2293850 -0.4410905 0.7179861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3262 3263 0.600319 -0.563407 0.623302 -0.3428116 0.0521807 -0.4648870 0.8146395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3263 3264 0.992261 -0.022636 0.245842 -0.4254237 0.2152050 -0.8040908 0.3551612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3264 3265 -0.067016 0.116878 1.003087 0.0833533 -0.7468590 0.6442752 0.1419974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3265 3266 0.346848 -1.007116 0.047382 -0.7991505 0.1614267 0.5772565 0.0455498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3266 3267 0.606129 0.701038 -0.612024 -0.6620284 0.4216693 0.5890425 0.1922036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3267 3268 0.211177 -0.892843 0.534951 -0.2874610 0.0242287 -0.5676102 0.7711017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3268 3269 1.085659 -0.148053 0.009064 0.0137793 0.3908538 -0.4549121 0.8000615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3269 3270 0.651443 0.354314 0.728212 0.5058560 -0.1246275 0.3054668 0.7970368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3270 3271 0.944252 0.374372 -0.090044 0.1778984 0.2337548 -0.5603486 0.7744161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3271 3272 0.108581 1.252544 -0.255499 -0.7736717 -0.0226479 0.0095157 0.6331103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3272 3273 0.116386 -0.139817 0.935590 -0.6813557 -0.1998288 0.6099883 0.3517629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3273 3274 -0.731967 -0.857579 -0.223047 0.2923861 -0.2346201 -0.5646620 0.7352691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3274 3275 0.750989 -0.583052 0.510737 0.1919330 0.4591278 0.8670867 0.0228926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3275 3276 -0.650981 0.743331 -0.124741 -0.1662183 0.3006737 -0.5294959 0.7756293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3276 3277 -0.874169 0.138372 -0.622988 -0.4558220 -0.6219997 -0.0902157 0.6302410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3277 3278 -0.606827 -0.396203 0.745800 0.6435614 -0.0716148 0.7536166 0.1129694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3278 3279 0.702463 0.743308 -0.116174 0.6897031 0.4352085 0.3335837 0.4728902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3279 3280 -0.444526 0.034575 0.854243 0.4666911 0.7166149 0.5115841 0.0833323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3280 3281 0.564073 -0.698198 -0.115452 -0.5089918 0.6070846 0.3309881 0.5126621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3281 3282 0.319777 -0.761050 -0.580391 -0.0502048 -0.8542155 -0.1758469 0.4866961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3282 3283 -0.525193 -0.819910 -0.209550 -0.1864642 -0.1566428 -0.7551673 0.6086185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3283 3284 0.665922 -0.403046 -0.588469 0.4536145 0.5220485 0.7201719 0.0552417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3284 3285 -1.207992 -0.022566 0.161262 -0.5796385 0.1169021 -0.7568665 0.2783993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3285 3286 0.394874 -0.364561 -0.886656 -0.3847862 0.6830384 -0.5873832 0.2009454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3286 3287 -0.214195 0.819665 0.754345 -0.1992569 0.8026625 -0.4275717 0.3649823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3287 3288 -0.450242 -0.406904 -0.686219 0.7801526 0.0671268 -0.2513622 0.5689227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3288 3289 0.106259 -0.630871 0.729432 -0.4148068 0.4506128 0.6879649 0.3893426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3289 3290 -0.980462 0.521570 -0.720357 0.0372749 0.2296539 -0.9695642 0.0762554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3290 3291 0.752603 -0.272063 -0.646986 0.2140694 -0.3586653 -0.8609253 0.2904155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3291 3292 -0.291112 -0.253948 -1.005861 -0.7899498 0.1861942 -0.1720035 0.5583241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3292 3293 -0.179263 0.881641 0.009240 -0.6344816 0.1415969 0.6676906 0.3627296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3293 3294 0.028223 -0.665462 0.898033 -0.4792882 -0.4787853 0.7344788 0.0398532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3294 3295 -0.779671 -0.203300 0.534149 0.5619983 0.1454070 -0.6102398 0.5390937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3295 3296 -0.380645 -0.657729 0.684171 0.1265252 0.3057818 0.9381766 0.1015555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3296 3297 0.255729 1.113661 0.225366 -0.0352298 -0.1731198 0.9827896 0.0539721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3297 3298 -0.170195 -0.786818 -0.198259 0.2796778 0.3095387 -0.7068492 0.5712533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3298 3299 0.962409 -0.049878 0.451669 -0.1492695 -0.7812324 0.5767250 0.1865017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3299 3300 0.663053 0.255030 -0.728026 0.4942998 0.2574600 0.6110759 0.5621106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3300 3301 0.908055 0.016930 0.532745 0.4791718 -0.5770529 -0.0779862 0.6567514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3301 3302 0.572062 0.194823 -0.763597 0.1147454 -0.4532605 -0.6721193 0.5741464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3302 3303 -0.596357 0.133019 -0.595795 -0.0426128 0.0511011 -0.9762316 0.2062635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3303 3304 0.350403 -0.018111 -0.770145 -0.2474212 0.7115126 -0.3941863 0.5264502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3304 3305 0.196153 0.557355 0.722165 -0.1666627 -0.4691703 0.8611058 0.1029545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3305 3306 -0.041156 -1.057480 -0.101787 -0.0557047 0.2743693 -0.9508585 0.1322372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3306 3307 0.686677 0.863625 0.250239 0.3255111 0.5084600 -0.7213425 0.3393758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3307 3308 -0.542706 -0.081250 -0.879924 -0.6919768 -0.0311019 0.5076049 0.5123846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3308 3309 0.086420 0.851142 0.226502 -0.2387846 -0.0571767 -0.7961102 0.5531015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3309 3310 -0.561395 -0.242081 0.741894 0.4428671 0.7235005 -0.4937612 0.1913521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3310 3311 -0.327545 -0.908864 0.026866 -0.8008697 -0.2382076 0.5328276 0.1340134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3311 3312 -0.733617 0.757131 0.324804 -0.2161218 -0.2831966 -0.9151805 0.1885092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3312 3313 0.624258 -0.535166 0.538134 -0.2747155 -0.9369507 -0.1104004 0.1856518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3313 3314 -0.487434 -0.003441 -1.019219 -0.1715000 0.1853707 0.4066558 0.8779843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3314 3315 0.310645 0.452524 -0.826514 0.3989752 0.3928167 -0.0222899 0.8282614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3315 3316 0.827006 -0.021584 -0.455129 -0.8400234 0.4205956 0.2393537 0.2452954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3316 3317 0.733721 -0.537370 0.180122 0.5674627 -0.3466048 -0.7247675 0.1804532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3317 3318 0.073341 0.182279 -0.971488 -0.8430280 0.3025941 -0.3384480 0.2884330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3318 3319 -0.705299 0.459531 0.691642 0.2989641 0.0015372 -0.7916597 0.5328161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3319 3320 -0.488475 0.933623 0.295315 -0.7484754 0.1349639 -0.5529660 0.3402911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3320 3321 -0.637736 0.039191 0.720917 -0.4377596 0.3033487 0.0607538 0.8441890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3321 3322 -1.193175 -0.344321 0.200280 0.4488212 0.0279673 0.4815370 0.7522629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3322 3323 -0.571540 0.804935 0.189223 0.3628302 -0.4636445 -0.0036258 0.8083161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3323 3324 -0.677120 0.633411 -0.026754 -0.3685428 0.1776550 0.9023515 0.1355605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3324 3325 0.551851 -0.385891 0.730278 0.0786707 -0.5031127 -0.3701045 0.7769886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3325 3326 0.932727 0.344612 -0.018025 0.1426139 0.8158637 -0.4646146 0.3133066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3326 3327 -0.707372 0.886191 0.344829 0.1789168 -0.1934197 -0.8376752 0.4784118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3327 3328 -0.376295 -0.811142 0.507397 0.3012487 0.0738093 0.2729278 0.9106656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3328 3329 -0.777776 -0.050029 0.592918 -0.4904599 0.0821717 -0.3862901 0.7768377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3329 3330 -0.405445 -0.834678 0.166532 -0.5373547 0.3241427 -0.0378064 0.7776581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3330 3331 0.161077 -0.321940 -0.790260 -0.3805590 0.5102949 -0.6966786 0.3307763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3331 3332 0.198126 1.167972 0.156285 -0.0186179 0.4107655 -0.9095015 0.0610900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3332 3333 -0.130577 -0.605408 -0.643629 0.3823593 0.6186926 -0.4833457 0.4872348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3333 3334 0.702683 0.090380 0.666753 0.6356816 -0.4143615 -0.4957360 0.4224444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3334 3335 0.155795 0.720510 -0.974331 -0.4319424 0.4421076 0.7532696 0.2248367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3335 3336 0.636240 -0.873902 0.199620 0.4268254 -0.3201792 -0.7336169 0.4208464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3336 3337 0.658608 0.620736 -0.401942 -0.1873758 0.3785795 -0.9004661 0.1035799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3337 3338 -0.874128 -0.067399 -0.711976 -0.1369922 -0.1095456 -0.3523378 0.9192883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3338 3339 -0.730132 -0.563589 -0.484051 0.2497980 0.3060674 -0.6297288 0.6688537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3339 3340 0.533504 0.797704 -0.104384 -0.5745338 -0.4425211 -0.0911152 0.6824837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3340 3341 -0.310376 -0.164614 1.063611 0.9848874 0.1033665 0.0979354 0.0985941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3341 3342 -0.362321 0.365624 -0.801492 -0.8176431 -0.3474932 -0.4386717 0.1351867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3342 3343 -0.491190 -0.373364 0.811028 0.2449005 0.0766143 -0.5963609 0.7605969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3343 3344 0.026780 -0.530270 0.768029 0.0792104 0.0866297 0.0894646 0.9890486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3344 3345 -0.051111 -0.386831 0.801313 -0.6654771 0.3153885 -0.1664501 0.6557170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3345 3346 0.164060 -0.936254 -0.598839 0.6351086 -0.1022430 -0.5716950 0.5092625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3346 3347 0.906300 -0.052487 0.427593 0.1925609 0.1454395 -0.0404611 0.9696033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3347 3348 0.660959 0.580501 0.544643 -0.3808563 -0.2646573 -0.2678856 0.8444775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3348 3349 0.509139 0.280928 0.526077 0.3364286 0.3128730 0.2149185 0.8618215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3349 3350 0.628692 0.549951 0.545240 -0.5903694 -0.6724434 0.4344414 0.1026863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3350 3351 0.024624 0.054327 -1.072017 -0.1906259 0.7398519 -0.4369780 0.4746906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3351 3352 0.198537 0.971143 0.400116 0.7232928 0.4468781 0.2621187 0.4565537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3352 3353 0.892700 0.098828 -0.271347 -0.0870471 0.1658316 -0.1539965 0.9701586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3353 3354 0.999083 0.335719 0.091287 -0.6321810 -0.2024587 0.4773704 0.5757388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3354 3355 0.850240 -0.449841 -0.387864 0.4288110 -0.1015860 -0.0343113 0.8970084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3355 3356 0.863282 -0.431719 -0.229567 -0.3656482 0.5354801 0.7360481 0.1944110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3356 3357 -0.576859 -0.477054 -0.888084 0.4215590 -0.3990158 0.5581437 0.5929165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3357 3358 -1.037458 0.199530 -0.066866 -0.7683312 0.1056207 0.0055582 0.6312531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3358 3359 -0.982663 0.123668 0.159020 0.0087242 -0.3125147 -0.7924379 0.5237371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3359 3360 -0.365722 0.363464 0.894094 -0.4329235 -0.2315979 -0.7492981 0.4444007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3360 3361 -0.613266 -0.777822 0.038570 -0.0106795 -0.2595917 -0.9254981 0.2755927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3361 3362 0.900208 0.023948 -0.215658 -0.5688272 0.3407648 -0.0774253 0.7445269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3362 3363 0.585730 -0.080473 0.835306 0.5246585 0.0835463 0.7528074 0.3886315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3363 3364 0.320877 -0.294652 1.247354 0.2224722 -0.8157555 -0.5297824 0.0661787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3364 3365 -0.453793 0.508347 -0.644369 -0.3051224 0.3038752 -0.5640814 0.7045370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3365 3366 -0.528635 0.547028 -0.660691 0.7722727 -0.0039548 -0.4615071 0.4365666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3366 3367 -0.065726 -0.991380 0.116266 -0.1212914 -0.5737357 -0.7881253 0.1870140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3367 3368 0.184632 0.548165 -0.973987 -0.0721673 0.8108943 0.5616424 0.1476488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3368 3369 0.092628 -0.829379 0.726230 -0.5386867 0.1115056 0.8116116 0.1966462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3369 3370 -0.649214 0.557493 0.118243 0.3873107 -0.1897132 -0.7346262 0.5237591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3370 3371 -0.483735 -0.713865 0.503784 0.2407858 0.1140498 0.9453946 0.1877337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3371 3372 0.213122 1.102210 0.124263 -0.6402438 -0.4142183 -0.6339800 0.1287647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3372 3373 0.416222 -0.377148 0.774758 -0.1220268 0.2631137 -0.9182038 0.2697821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3373 3374 -0.124569 0.034771 0.974873 0.4884953 -0.1330359 -0.4954898 0.7058071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3374 3375 -0.280813 0.726971 0.433233 0.0891229 0.3743090 -0.7815010 0.4911274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3375 3376 -0.635081 -0.768081 -0.253911 0.5435773 0.5048116 -0.6541994 0.1473505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3376 3377 0.302096 0.056799 1.012521 -0.3872044 -0.5235256 0.6882725 0.3198041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3377 3378 -0.161921 -0.603647 -0.034594 0.4348749 -0.1671862 0.8795718 0.0963643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3378 3379 0.168907 0.872087 0.300066 0.2316351 0.1633849 -0.4211536 0.8615569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3379 3380 -0.689590 -0.117458 0.865138 0.1519376 0.4536074 0.8768216 0.0483649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3380 3381 -0.674661 0.827911 -0.063552 0.0188302 -0.6252254 0.6928516 0.3587412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3381 3382 0.696695 0.231980 -0.232931 0.7360439 -0.0598138 -0.3866741 0.5523992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3382 3383 0.495348 0.070651 -0.640961 0.2882276 0.6733620 0.6739891 0.0961622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3383 3384 -0.471196 -0.560869 0.078440 -0.3580821 -0.0544199 0.4500060 0.8162783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3384 3385 -0.877186 0.221537 -0.088765 0.0923157 -0.4607569 -0.8544753 0.2214786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3385 3386 0.950201 -0.464041 0.479570 -0.7599668 -0.2311018 -0.0592396 0.6045933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3386 3387 0.623116 0.227522 -0.546401 0.2680365 0.6569731 0.1793619 0.6814485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3387 3388 0.846647 -0.153292 0.564142 0.3439974 -0.0010893 0.3492764 0.8715908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3388 3389 0.403480 -0.116562 1.080363 -0.4734936 -0.1878671 0.5829332 0.6330077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3389 3390 -0.024444 -1.076823 0.133023 0.2028489 -0.1184624 0.8900566 0.3906638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3390 3391 -0.498530 0.719630 0.256036 -0.1931407 0.0922331 -0.4598039 0.8618411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3391 3392 -1.124024 -0.316471 0.428353 0.5051643 0.3864484 0.7068856 0.3094826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3392 3393 0.134500 0.472227 -0.937759 -0.1715501 -0.7418398 -0.5257334 0.3792738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3393 3394 -0.787445 -0.187939 0.439987 0.0992805 -0.0755944 0.9329957 0.3375618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3394 3395 0.469685 0.585338 0.229716 0.1019386 0.6859328 -0.4643922 0.5508581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3395 3396 -0.813322 0.804347 -0.054452 -0.0859737 0.0976860 -0.8300397 0.5423099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3396 3397 -0.372334 -0.738015 -0.129860 0.2708529 0.3565154 0.7389899 0.5034178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3397 3398 -0.759312 0.306277 -0.675372 0.0445107 -0.0837227 -0.9925188 0.0769135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3398 3399 0.642287 -0.406840 -0.432783 0.3364063 0.4560558 0.4672069 0.6786470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3399 3400 -0.916668 0.218497 0.118453 -0.7385218 0.1220446 -0.5820158 0.3177237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3400 3401 -0.861481 -0.299540 0.393655 0.2034926 -0.2055950 0.8065720 0.5155221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3401 3402 0.202916 0.926176 0.449280 0.0652735 0.1518470 -0.9145020 0.3692804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3402 3403 -0.891108 -0.199439 0.085495 0.8793835 -0.1780314 0.1871381 0.3999611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3403 3404 -0.713434 0.584244 -0.228735 -0.0104739 -0.3694837 -0.9012455 0.2261166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3404 3405 0.438914 -0.654836 0.339615 -0.2165423 0.3277445 0.7870190 0.4757037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3405 3406 -0.909436 0.015245 -0.218965 -0.5046417 0.5072874 0.6761687 0.1754769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3406 3407 0.424510 0.276162 0.518494 0.8180251 -0.1262242 -0.2114120 0.5198148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3407 3408 0.123308 0.227886 -0.961072 -0.0468124 -0.1320562 0.2835751 0.9486596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3408 3409 0.036727 0.348826 -0.981023 -0.4112341 -0.7589273 -0.4765119 0.1668899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3409 3410 -0.414693 -0.458207 0.978641 0.5671023 -0.2778642 0.7281410 0.2664528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3410 3411 0.879290 0.528984 0.047906 -0.4053610 0.3420523 -0.8351958 0.1453639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3411 3412 -0.765314 -0.362558 0.642615 0.2134046 0.2274557 0.8987408 0.3082003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3412 3413 0.461327 0.774605 -0.017507 0.5379268 -0.1684206 0.4328706 0.7034858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3413 3414 0.464114 -0.378778 -0.724438 -0.3987072 0.4274225 -0.3947660 0.7088740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3414 3415 0.901675 0.678211 0.118368 -0.2810336 0.5323836 0.4889270 0.6312988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3415 3416 -0.175777 -0.458346 1.090874 -0.0484169 -0.7399040 0.1987656 0.6408511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3416 3417 0.670086 -0.567769 -0.118737 -0.5736855 0.0617646 -0.7861266 0.2215289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3417 3418 0.032454 0.782022 0.478330 -0.3539475 0.5165350 -0.2813740 0.7271461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3418 3419 -0.820898 -0.301402 0.224572 0.6928362 -0.3641881 -0.0166753 0.6221471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3419 3420 -0.646811 -0.466528 0.464087 -0.1272761 0.5633046 -0.6664943 0.4714596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3420 3421 0.577683 0.578727 0.692107 0.1945444 -0.1014422 -0.4566076 0.8621899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3421 3422 0.057683 1.005965 0.589369 0.2197072 0.7027407 -0.6369336 0.2284727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3422 3423 -0.117264 -0.235001 -1.122238 -0.2526787 -0.8196868 0.1389668 0.4949296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3423 3424 -0.941341 0.125428 0.542604 -0.0423947 -0.1940153 0.4683219 0.8609503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3424 3425 0.104786 0.530086 0.999532 -0.3631988 -0.6676861 0.6052121 0.2366437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3425 3426 0.544860 -0.602884 -0.759441 -0.2608822 -0.5326253 0.4945426 0.6353569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3426 3427 -0.993905 0.183180 -0.428764 -0.4575656 -0.5911168 0.6635037 0.0312647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3427 3428 0.761825 -0.065837 0.362265 0.0182582 -0.5456821 0.1454810 0.8250654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3428 3429 0.767477 -0.308398 -0.499825 -0.2704250 -0.1761046 -0.3839623 0.8651187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3429 3430 0.317996 0.516825 -0.817350 0.8198403 0.0458339 0.5448740 0.1699216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3430 3431 -0.138152 -0.775140 0.501766 0.2752258 0.0682660 0.8262473 0.4867299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3431 3432 -0.418560 0.841839 0.445329 -0.0405250 -0.3684884 0.9213351 0.1171138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3432 3433 0.382738 -0.965264 -0.071240 0.3964041 -0.1566484 0.4641781 0.7764431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3433 3434 -0.208534 -0.577870 0.628900 0.5396213 0.3241348 0.5820261 0.5147729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3434 3435 -0.509874 0.827248 -0.076365 -0.2015779 0.0407074 -0.3407036 0.9174041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3435 3436 -0.801675 0.439286 0.033393 -0.7419462 -0.2979452 -0.4234017 0.4259994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3436 3437 -0.221363 -1.082740 0.084322 0.3226318 0.0324604 -0.1272632 0.9373682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3437 3438 -0.228801 -0.754417 0.445056 -0.6690858 0.4831362 -0.0122446 0.5645827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3438 3439 0.310102 -0.332243 -0.827114 -0.5478437 -0.0721652 0.8143247 0.1775804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3439 3440 0.263819 0.421456 0.841253 0.2052871 -0.6635539 -0.2817079 0.6619623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3440 3441 1.020911 -0.237980 0.249502 0.1710809 -0.5637879 0.0961798 0.8022618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3441 3442 0.755227 -0.379821 -0.545619 -0.0006067 0.7610954 0.4452813 0.4716546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3442 3443 -0.088552 -1.132273 0.104097 0.3560373 -0.3650250 -0.6769462 0.5307900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3443 3444 0.721413 0.388157 0.136751 -0.4227127 -0.0001394 -0.5317344 0.7338749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3444 3445 0.195838 0.793647 0.490869 0.4536836 -0.2096848 -0.2505222 0.8291213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3445 3446 -0.334215 0.930174 -0.310113 0.2062332 0.6795599 0.2893271 0.6418380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3446 3447 0.728599 0.219045 -0.140199 -0.3088167 -0.4766345 0.0549931 0.8212354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3447 3448 0.509276 0.694162 -0.640786 0.2805962 -0.1819445 -0.8706727 0.3606814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3448 3449 -0.764372 -0.532188 -0.405142 -0.2526521 -0.0067960 -0.7508038 0.6102576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3449 3450 0.137669 -0.420287 -0.914208 0.5618388 -0.6347713 0.1526029 0.5080501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3450 3451 -0.460536 -0.693724 0.567127 0.3278106 0.5168098 -0.3604108 0.7039545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3451 3452 -0.578476 -0.951579 0.546264 -0.0989557 -0.1486041 -0.8899483 0.4196625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3452 3453 1.023093 0.302548 0.172689 -0.1172224 -0.0913363 0.9257419 0.3477335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3453 3454 -0.824730 -0.550368 -0.179285 0.2570656 -0.4269989 -0.7480515 0.4381873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3454 3455 1.044052 -0.120795 -0.145728 -0.0119043 -0.4824248 0.5196956 0.7050114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3455 3456 0.078774 -0.705912 -0.549541 0.4837342 0.3662141 -0.7333062 0.3068395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3456 3457 0.607173 0.739555 0.645430 -0.4849166 -0.6872511 -0.5334549 0.0892618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3457 3458 0.612208 0.834657 0.581670 0.2532288 0.8057658 -0.3495142 0.4055324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3458 3459 -0.533448 0.645606 -0.647656 -0.3544194 -0.0238832 -0.7598229 0.5445049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3459 3460 0.789980 -0.017478 -0.875382 0.0094671 -0.0661037 0.5060556 0.8599119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3460 3461 0.781696 -0.459737 0.360929 0.8512100 0.0055458 -0.5246692 0.0115292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3461 3462 -0.210314 0.430777 -0.663795 -0.2134968 -0.0615208 -0.9130062 0.3421316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3462 3463 -0.552616 -0.383729 -0.716399 0.9622193 0.0989605 0.0859264 0.2386577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3463 3464 -0.952796 -0.034057 0.496206 -0.4163759 0.1054158 0.7094457 0.5587535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3464 3465 -0.367765 0.417783 0.992577 -0.1139664 -0.1575202 -0.6661510 0.7200291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3465 3466 -0.343129 -0.181068 1.058395 0.0873689 -0.7988184 -0.5792168 0.1369810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3466 3467 0.366095 0.728888 -0.494745 0.1307108 -0.8459661 -0.5084137 0.0936565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3467 3468 -0.534129 -0.064484 0.857048 0.2255329 -0.3436763 0.8785418 0.2432816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3468 3469 1.009324 -0.085278 0.407060 -0.0875210 -0.9758474 0.1985502 0.0252921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3469 3470 -1.009874 0.059665 -0.379008 0.2916902 -0.4058850 -0.3163491 0.8062862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3470 3471 -0.829089 -0.452785 0.455925 0.6819345 0.1695322 0.6551309 0.2775385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3471 3472 -0.027391 0.747710 -0.544718 -0.0463447 0.8676268 0.4948968 0.0123695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3472 3473 0.447440 -0.001842 0.981402 -0.7714929 -0.2805289 -0.5606962 0.1082682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3473 3474 1.024439 0.362058 -0.277295 0.3710136 -0.6902718 0.2997838 0.5440620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3474 3475 -0.486851 -0.383150 -0.875617 0.2762209 -0.2390585 -0.1710693 0.9150346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3475 3476 -0.225321 -0.824189 -0.169614 0.4483352 0.4508662 0.5271315 0.5637798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3476 3477 -0.949654 0.014641 -0.274794 0.3630443 0.0443719 -0.4918890 0.7901109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3477 3478 -0.224560 -1.030038 0.023442 -0.8654466 -0.2136674 0.4513201 0.0407252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3478 3479 -0.575770 0.689865 0.428285 -0.3613208 -0.4548776 0.2791564 0.7645949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3479 3480 0.489362 -0.843082 0.055329 0.1400930 -0.5866945 -0.0147191 0.7974628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3480 3481 -0.951419 -0.153468 0.365138 -0.0673567 0.1340735 0.8700595 0.4695571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3481 3482 0.125410 1.149672 0.200417 0.4350017 -0.6610508 -0.5390913 0.2883851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3482 3483 -0.853505 0.245182 0.011049 0.3215924 0.4588385 0.7371505 0.3776965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3483 3484 0.762126 0.679075 -0.644380 0.2315149 -0.2300917 -0.6581873 0.6784159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3484 3485 -0.457216 0.151262 -0.967644 -0.4074019 -0.2544176 -0.8754883 0.0530629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3485 3486 -0.237412 -0.789488 -0.586613 -0.1412411 -0.2522417 -0.9117589 0.2917548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3486 3487 0.606217 0.153173 -0.920440 0.1643899 -0.9073312 -0.3681750 0.1190513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3487 3488 -0.557420 -0.755476 0.480850 0.6173096 -0.5415835 -0.5653932 0.0771146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3488 3489 0.282921 1.051720 -0.100894 -0.2466928 -0.3353146 -0.7354872 0.5345702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3489 3490 -0.795572 0.031342 0.650786 0.6629059 0.2899245 0.2067223 0.6586087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3490 3491 -0.558154 0.414691 -0.712697 -0.3834015 -0.2601084 -0.4346160 0.7723055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3491 3492 -1.112069 -0.042347 -0.004289 -0.7251761 0.0766848 0.3201528 0.6047654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3492 3493 -0.833563 0.620395 0.188647 -0.2788048 -0.5773916 0.4045304 0.6521058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3493 3494 0.533378 0.219975 0.882100 0.0732065 -0.8688083 0.4880545 0.0401963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3494 3495 -0.467220 -0.707942 -0.650554 -0.9013338 -0.0675248 -0.4215579 0.0729841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3495 3496 -0.605577 0.663061 -0.016444 0.1390348 0.6828401 0.4036375 0.5928538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3496 3497 0.868716 0.313516 -0.293770 -0.6518392 0.4101585 0.5078106 0.3860104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3497 3498 0.366207 -0.917188 0.506226 0.2793721 -0.0097826 0.2770010 0.9193073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3498 3499 -0.015861 -0.575185 0.785420 -0.1991219 -0.5106028 -0.7161503 0.4321620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3499 3500 -0.042695 0.933266 0.519206 0.4508934 0.3421902 0.5629648 0.6022222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3500 3501 -0.370189 0.592115 -0.592200 0.0871860 0.6280412 0.7732185 0.0097991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3501 3502 0.513054 -0.865671 0.338497 -0.1521145 0.3173952 -0.9202925 0.1708306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3502 3503 -0.024049 0.201767 0.940302 0.1039781 -0.2370402 -0.6233570 0.7378527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3503 3504 -0.046299 0.488547 0.724869 -0.2137969 -0.0383159 0.4491588 0.8666482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3504 3505 0.328942 0.105179 0.878222 0.6780865 0.3110180 0.3760922 0.5495645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3505 3506 0.408924 0.851570 0.093271 -0.2113732 -0.6789347 -0.5701757 0.4114229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3506 3507 -0.145681 0.594169 0.721543 0.0536407 0.4797793 -0.0696989 0.8729700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3507 3508 -0.756642 0.487932 -0.071878 -0.0638451 -0.6287856 -0.7396293 0.2313030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3508 3509 0.461380 -0.321391 0.588046 -0.5172260 0.2810456 0.3863474 0.7100889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3509 3510 -0.439534 -0.826414 -0.291674 0.1674546 -0.3700592 0.3591783 0.8402417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3510 3511 -1.034630 -0.324853 0.587961 0.7198086 0.3423059 -0.2144501 0.5645470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3511 3512 -0.908852 -0.510311 0.177408 -0.3268918 0.7605933 0.5524683 0.0970481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3512 3513 0.809627 0.721269 -0.232085 -0.0888502 0.0977618 0.6535309 0.7452822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3513 3514 0.543069 -0.749916 0.204946 -0.4298353 0.0849187 -0.6739693 0.5948073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3514 3515 0.650822 0.656646 0.468948 -0.0654149 0.6939310 -0.4360731 0.5692283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3515 3516 -0.698394 0.561034 0.102486 -0.2662218 -0.2699938 -0.1503437 0.9130313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3516 3517 -0.822013 0.015687 0.692358 -0.3154373 -0.5004972 0.7380742 0.3244200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3517 3518 0.263740 -0.577293 0.887979 -0.0654661 -0.5884606 0.8053726 0.0283414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3518 3519 -0.511181 -0.499274 0.887707 -0.6216561 0.7011054 -0.2883596 0.1970880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3519 3520 -0.672943 -0.785795 -0.367176 -0.3129863 0.0072944 -0.0843880 0.9459731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3520 3521 -0.813539 -0.314132 0.529462 0.4485630 -0.3653729 -0.0618654 0.8133059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3521 3522 0.151818 0.501356 0.772506 0.1485918 0.2690886 -0.8522136 0.4233718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3522 3523 -0.814865 -0.525693 0.482045 -0.1468136 -0.0467803 -0.3433594 0.9264781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3523 3524 -0.005794 -1.243206 0.220364 -0.0231580 -0.0843259 -0.9931399 0.0776269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3524 3525 0.109668 0.798680 -0.018352 -0.6685924 -0.2587094 -0.6930781 0.0754747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3525 3526 0.350253 -0.799000 0.580486 -0.6579372 0.3613450 -0.3549417 0.5572834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3526 3527 0.668748 -0.404003 -0.185091 0.7586208 -0.5476043 0.0689904 0.3462144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3527 3528 0.620715 -0.755325 0.217845 -0.6846216 0.6194791 -0.1288696 0.3618447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3528 3529 0.732612 -0.552033 -0.134831 0.0492031 0.0221907 0.9967989 0.0589793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3529 3530 -0.792621 0.562978 -0.150202 -0.7924617 -0.2063470 -0.0491578 0.5718470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3530 3531 -0.577208 -0.412343 0.888593 -0.1725012 0.6439512 -0.0070092 0.7453329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3531 3532 -0.607571 -0.439895 -0.623836 0.3877859 -0.3870163 -0.2043017 0.8112344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3532 3533 -0.435535 -0.828813 0.592971 -0.6169223 0.5175001 -0.0165871 0.5927272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3533 3534 -0.067042 -0.339871 -0.864202 0.1872916 0.4773412 0.0094428 0.8584743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3534 3535 0.776811 -0.507533 -0.391414 -0.3039800 -0.2652451 0.4133432 0.8163263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3535 3536 -0.257097 -0.184282 -0.965109 0.0087963 -0.2347063 -0.1607753 0.9586380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3536 3537 -0.487477 -0.311394 -0.560575 0.3237164 0.2384877 -0.7856823 0.4701431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3537 3538 1.058718 -0.309335 -0.239456 -0.3308403 0.5175150 -0.6301297 0.4750363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3538 3539 0.000843 0.454628 0.839104 0.8234536 -0.2786828 0.3066166 0.3876163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3539 3540 -0.793548 0.681393 -0.080346 -0.1604653 0.1230119 -0.5218620 0.8287213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3540 3541 0.154173 -1.103381 0.593970 0.5991453 -0.6659118 -0.3986423 0.1966486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3541 3542 0.716271 0.514013 -0.442301 -0.3680326 0.8446777 0.3867721 0.0384577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3542 3543 -0.509307 -0.589698 0.607890 0.3335906 -0.0602796 -0.1695987 0.9253756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3543 3544 -0.241653 -0.172465 0.788422 -0.1596253 -0.3271444 0.4180422 0.8323082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3544 3545 0.075702 -0.373671 0.830489 -0.2746693 0.9003379 0.2225338 0.2538249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3545 3546 -0.459686 -0.097272 -0.929362 0.6060718 -0.0986377 -0.5445280 0.5713466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3546 3547 0.353866 -1.052314 -0.014680 -0.3855958 -0.5717304 -0.5653039 0.4526276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3547 3548 0.166102 0.146931 -1.058570 0.7962922 0.5913776 0.1228069 0.0333127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3548 3549 0.163478 -0.200464 0.957195 -0.2635904 0.5449205 -0.0853605 0.7913882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3549 3550 -0.482215 -0.621423 0.167707 -0.1555860 -0.2306322 0.2888389 0.9160643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3550 3551 -0.872598 -0.319479 0.571449 -0.5970291 0.4954975 0.1753848 0.6060352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3551 3552 -0.678837 0.507935 -0.774127 0.1666488 -0.3952043 -0.7667049 0.4777084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3552 3553 -0.109381 -1.028644 0.130833 -0.3230090 0.3428830 -0.7538886 0.4579830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3553 3554 0.926793 0.292816 0.086974 0.4527113 -0.0912249 0.7772534 0.4273263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3554 3555 -0.107952 -0.750938 0.563432 -0.3437005 0.6412652 -0.4048508 0.5538455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3555 3556 0.379803 -0.751329 0.047801 -0.4253942 -0.6544892 -0.0054408 0.6250233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3556 3557 -0.505624 -0.174820 -0.799402 0.0434744 0.7628331 -0.0609242 0.6422491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3557 3558 0.974639 -0.313045 -0.161434 0.3177266 -0.2161812 -0.9066895 0.1738669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3558 3559 -0.288978 0.239533 -0.815004 0.9881858 -0.0777513 0.1281589 0.0319194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3559 3560 0.450418 0.207467 0.815737 0.1496703 -0.3546981 0.6540963 0.6511115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3560 3561 -0.412170 -0.328230 -0.909570 0.1392636 -0.3714772 0.8881656 0.2318885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3561 3562 -0.221035 0.950192 -0.488256 -0.1246992 0.4332255 0.7913089 0.4130326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3562 3563 0.973108 -0.498918 0.317609 0.4396206 -0.6517668 0.0811187 0.6126610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3563 3564 0.434914 -0.829552 -0.339694 -0.8695122 0.2955734 0.0595543 0.3912010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3564 3565 1.010258 0.400155 -0.246773 -0.8030908 0.0297639 -0.5549269 0.2149776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3565 3566 -0.009880 -0.310624 1.042596 -0.2497921 -0.0185288 0.6839643 0.6851667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3566 3567 -0.414245 -0.353902 0.920414 -0.5771929 0.6724447 -0.3233202 0.3318591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3567 3568 0.281196 -0.375847 -0.808566 0.4475613 0.4213395 0.1012536 0.7822466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3568 3569 0.519332 -0.552841 0.346028 0.1224514 0.0053424 -0.6671067 0.7348100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3569 3570 0.796120 0.599243 0.451050 -0.1119346 -0.5452922 0.7797380 0.2865932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3570 3571 -0.181979 -0.931446 -0.646725 -0.0981872 -0.3421993 0.9062869 0.2278223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3571 3572 -0.169049 1.156755 0.040135 -0.4375988 0.1310409 0.8886885 0.0396033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3572 3573 -0.026158 -0.979103 0.437795 -0.0424259 0.2782513 -0.9594767 0.0134417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3573 3574 -0.081675 0.666895 0.742024 0.2038049 -0.2750888 0.7930742 0.5038085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3574 3575 0.949240 -0.424022 0.322582 -0.0276738 -0.4403127 -0.5144743 0.7353061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3575 3576 0.579484 0.558905 -0.510248 -0.5872563 0.4075080 -0.6979563 0.0438672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3576 3577 -0.835419 -0.345051 0.193860 0.0362817 -0.0417898 0.4094545 0.9106505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3577 3578 -0.786723 0.375137 0.206196 0.0909411 0.3816091 0.9191170 0.0364452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3578 3579 0.718276 -0.330961 0.429065 -0.4389403 -0.6266905 -0.5317643 0.3630662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3579 3580 -0.945455 -0.008488 0.325055 -0.2099227 0.2775132 0.7805972 0.5192176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3580 3581 -0.806592 0.344575 -0.512288 -0.5214056 0.1398472 0.6244187 0.5645177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3581 3582 0.439299 0.723636 0.455079 -0.0517864 0.1467484 -0.8619140 0.4825840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3582 3583 -0.776553 -0.222236 0.563577 0.5174889 0.6429298 -0.0061629 0.5646314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3583 3584 -0.681268 -0.317743 -0.562121 -0.3449680 0.2206541 0.5060269 0.7591085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3584 3585 0.147471 0.745957 -0.625245 0.0394210 -0.6780103 0.3222546 0.6594695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3585 3586 -0.362116 0.751881 -0.434388 0.0897058 0.4934442 0.0696113 0.8623340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3586 3587 0.294718 0.631331 -0.510244 -0.7295128 -0.2996496 -0.1292415 0.6010972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3587 3588 0.293571 0.673626 0.681411 0.1899049 0.2917796 0.6934526 0.6308124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3588 3589 0.652891 0.183875 0.768480 0.0392371 0.0190679 -0.9288109 0.3679771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3589 3590 -0.628052 0.356565 0.632573 0.4815711 -0.3320205 0.7691139 0.2575179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3590 3591 0.827007 0.246073 -0.307933 0.1828240 0.5400403 -0.3360757 0.7496566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3591 3592 0.457382 0.655730 0.342319 -0.0526288 0.2870653 -0.9425427 0.1625944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3592 3593 -0.597677 -0.640496 0.195417 0.4724318 0.6202223 0.1183688 0.6149157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3593 3594 -0.572864 -0.526867 -0.348566 0.1713641 -0.3898964 0.6205870 0.6583972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3594 3595 -0.678292 0.471705 0.387882 0.5500205 -0.2230758 0.8022793 0.0637376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3595 3596 0.887718 -0.471050 -0.535584 0.3166029 -0.2848554 -0.0989336 0.8993509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3596 3597 0.463204 -0.636631 -0.581514 -0.0916040 0.0626275 -0.9507804 0.2893149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3597 3598 0.160392 0.820287 -0.381131 -0.1284298 0.7030034 0.6646222 0.2181039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3598 3599 0.020614 -0.423388 0.629407 -0.4220850 -0.0170305 -0.0331749 0.9057889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3599 3600 -7.106560 17.867269 0.076893 -0.1154756 -0.1689904 0.7899332 0.5780252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3600 3601 -0.945447 -0.119095 -0.008019 0.4268518 0.5675710 0.4710270 0.5232535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3601 3602 0.167792 -0.021903 -0.969335 -0.0944370 -0.6417298 -0.5623913 0.5128163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3602 3603 -0.887821 -0.422987 -0.163963 -0.0091533 -0.5734621 0.0923025 0.8139642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3603 3604 -0.419149 -0.252862 0.886867 0.5950282 0.6557679 -0.0694074 0.4594481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3604 3605 -1.171094 -0.186915 -0.545514 -0.3708321 0.0657317 0.6586207 0.6514458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3605 3606 0.095652 0.878930 -0.140822 0.4284776 0.6082041 0.0509767 0.6662553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3606 3607 0.835411 0.746843 -0.413184 -0.2921937 0.6967489 0.2248165 0.6153222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3607 3608 0.443686 -0.125602 0.885148 -0.6201857 -0.1858053 0.3283471 0.6877749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3608 3609 0.054989 -0.962111 0.005556 -0.3406785 0.3271283 0.6912906 0.5468479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3609 3610 -0.493471 -0.092496 -0.975613 -0.0572478 -0.6735393 0.7307342 0.0953678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3610 3611 0.636400 0.944534 -0.141234 0.1571741 0.6329414 -0.6440424 0.3998637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3611 3612 -0.570719 0.546500 -0.673141 0.5664610 0.3605500 -0.7409273 0.0123403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3612 3613 0.917520 -0.232675 0.008217 0.0358412 0.0179391 0.7755780 0.6299781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3613 3614 -0.514999 -0.841839 -0.011417 -0.6131396 0.2776529 0.5321265 0.5136245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3614 3615 -0.493951 0.872734 -0.460283 0.1838830 0.1043615 -0.8588816 0.4664956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3615 3616 -0.176874 -0.709990 -0.513387 0.2323047 -0.6239033 0.1167009 0.7369939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3616 3617 -0.568111 -0.659288 0.366871 -0.0782819 -0.5789841 0.8056610 0.0977739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3617 3618 0.416978 -0.186661 0.984611 0.0311077 -0.6120588 -0.2190216 0.7592403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3618 3619 1.148772 0.219627 -0.038287 0.4760540 0.3184683 0.1029729 0.8132325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3619 3620 -0.203166 1.111372 -0.111259 -0.4479065 0.3234702 0.7963765 0.2460310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3620 3621 0.812656 0.641666 0.173582 0.2576917 -0.8510238 -0.4275392 0.1629836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3621 3622 -1.032406 0.312331 -0.070113 -0.1163383 0.3764542 0.0752218 0.9160182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3622 3623 -0.615940 0.603126 -0.716445 -0.2140848 -0.7130771 -0.5359600 0.3980398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3623 3624 -0.105287 -0.515679 0.831757 0.0203100 -0.1045598 0.9570149 0.2697724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3624 3625 -0.085217 0.544864 0.842447 0.0566755 0.5620494 -0.6264086 0.5371225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3625 3626 -0.912454 -0.725582 -0.029090 -0.2633637 -0.6541144 0.6860107 0.1793408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3626 3627 0.310459 0.268237 0.955706 0.1275752 -0.2742183 0.2140652 0.9288192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3627 3628 0.673140 0.139933 0.648480 0.2438453 0.0315075 0.0258256 0.9689581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3628 3629 0.863701 0.377259 0.566767 -0.4362062 -0.4529175 -0.5835811 0.5138317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3629 3630 0.419595 0.748247 0.609187 0.9190147 -0.0509972 0.0677222 0.3850000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3630 3631 0.555058 -0.332882 -0.741229 0.0677222 0.0594172 0.9655550 0.2441043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3631 3632 -0.685696 -0.043528 -0.678925 0.0169193 -0.4829862 0.7302923 0.4828159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3632 3633 -0.108817 0.960934 0.077037 0.0334462 -0.4264627 0.5753562 0.6971199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3633 3634 0.870036 0.376410 -0.457985 0.2329491 0.2211832 0.9452597 0.0574179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3634 3635 -0.874645 -0.348430 0.140427 -0.5869041 0.1963351 -0.4458386 0.6467024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3635 3636 0.171240 -0.322443 -0.871677 -0.7696541 0.1483875 0.5599178 0.2685252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3636 3637 0.872003 0.437918 -0.071596 0.7568698 -0.1071836 -0.6447103 0.0028927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3637 3638 0.185030 -0.871221 -0.667686 0.7315600 -0.0256475 0.3312168 0.5953634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3638 3639 -0.613431 -0.365050 0.637463 -0.0336964 -0.0980344 0.9130390 0.3944789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3639 3640 0.480674 0.635934 -0.535734 0.4681543 -0.4376231 0.7485664 0.1701936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3640 3641 -0.540190 0.905950 0.024801 0.0046038 -0.0870026 -0.2634784 0.9607229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3641 3642 -0.649731 0.510303 0.218399 -0.4149554 0.3425698 0.1494204 0.8295369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3642 3643 -0.741407 0.507731 -0.069770 0.5976647 -0.7211357 -0.0486365 0.3469793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3643 3644 -0.596282 0.934237 0.116327 -0.2477089 0.6401857 -0.6614818 0.3020669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3644 3645 -0.428194 -0.001055 -0.990988 0.5802315 -0.6080122 0.1686097 0.5149984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3645 3646 -0.682710 -0.212631 0.606256 -0.2585009 0.0973128 -0.6271800 0.7282532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3646 3647 0.168094 -1.040982 0.350963 -0.0998022 0.2257096 0.6482464 0.7203272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3647 3648 -0.841111 -0.356980 -0.301243 -0.4408216 0.2208625 -0.2208000 0.8415126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3648 3649 -0.686284 0.067323 -0.858731 0.5314125 -0.4999427 0.5514563 0.4044181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3649 3650 -0.713426 0.738232 -0.197705 0.7763457 0.6027920 0.1587880 0.0933573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3650 3651 0.592969 -0.869486 0.130257 -0.8487636 -0.1915016 -0.4661104 0.1602141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3651 3652 0.040549 1.074761 0.138624 -0.0288746 0.4639164 -0.8847588 0.0339060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3652 3653 -0.219300 -0.673340 -0.676566 0.7266754 0.5262219 -0.4202718 0.1356650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3653 3654 0.276660 0.156109 0.767190 0.2888569 -0.7440791 0.0128942 0.6022804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3654 3655 0.609508 0.348342 -0.511305 -0.4686017 0.2370342 -0.5290379 0.6665929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3655 3656 -0.246890 0.897277 0.503541 -0.4366874 -0.1896574 0.4978748 0.7248826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3656 3657 0.689810 -0.220591 0.777222 0.4231479 -0.0458848 0.2366952 0.8733933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3657 3658 0.703775 0.327890 0.465853 -0.4791604 -0.4945671 0.6673332 0.2836813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3658 3659 -0.259648 -0.648623 -0.804441 0.7510159 -0.0279684 0.5021851 0.4277885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3659 3660 0.200233 -0.438187 0.843919 0.4283716 0.5278408 0.5114758 0.5256181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3660 3661 -0.152144 -0.296555 0.987993 0.3358904 0.6095893 0.6482699 0.3087468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3661 3662 0.035194 0.956188 -0.165754 -0.0514864 -0.3704348 0.0941431 0.9226398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3662 3663 -0.049492 1.003274 0.132394 -0.3184953 -0.4432770 -0.8064563 0.2273643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3663 3664 -0.065924 -0.634579 0.711177 0.0378055 0.5182625 -0.1018818 0.8482894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3664 3665 -0.404634 -0.610826 0.439468 -0.3248765 0.3299514 0.0850803 0.8822407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3665 3666 -0.759496 -0.456675 -0.437759 0.4463484 -0.2768947 -0.5972893 0.6060923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3666 3667 0.443999 -0.855596 0.544125 -0.5841388 -0.6558130 0.2384678 0.4145170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3667 3668 -0.610729 -0.315621 -0.795202 0.2820438 0.2732481 0.4726960 0.7888886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3668 3669 -0.588606 -0.418309 -0.864605 0.0696031 -0.2847185 0.7368014 0.6092737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3669 3670 -0.456548 0.825471 -0.558718 -0.0404997 0.3309602 0.0379086 0.9420128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3670 3671 -0.420168 1.024071 -0.474555 -0.2401351 0.1589885 -0.4383197 0.8514303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3671 3672 -0.813239 0.487599 -0.307028 0.2987129 -0.4419347 0.4450880 0.7192781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3672 3673 -0.245722 1.097210 -0.213977 0.2454373 0.7272201 0.5013395 0.3994623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3673 3674 0.856233 0.063226 0.242337 -0.2015281 0.0658165 0.2721894 0.9385987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3674 3675 0.828984 -0.423418 0.627686 -0.5558061 0.3898364 0.7308846 0.0701061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3675 3676 -0.558829 0.047608 -1.008791 -0.2842975 -0.2166889 0.8710166 0.3369731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3676 3677 0.761947 0.622941 -0.404328 0.1051346 0.2673763 -0.8417632 0.4570463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3677 3678 -0.786160 0.622034 -0.550810 -0.0105599 -0.4149209 -0.0456447 0.9086505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3678 3679 -0.917879 0.248070 0.327085 0.1359455 0.2768815 0.7593830 0.5728812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3679 3680 0.743265 -0.718325 0.364188 -0.1511372 0.1699036 -0.9724567 0.0511688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3680 3681 0.818989 0.607848 0.169109 0.6866919 -0.4712871 0.5396232 0.1230833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3681 3682 -0.211853 -0.846195 -0.007981 0.6309456 0.3409216 -0.3548246 0.5998163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3682 3683 -0.147653 -0.230835 1.072775 -0.3912660 0.6205185 0.2144664 0.6448813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3683 3684 -0.832444 -0.282543 -0.251834 -0.0044369 -0.4389072 -0.2273903 0.8692724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3684 3685 -0.574190 -0.762447 0.492829 -0.3515228 -0.2701530 -0.8470003 0.2933251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3685 3686 1.045872 0.109418 -0.278124 0.0323052 0.6294029 -0.5919790 0.5023636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3686 3687 -0.346676 0.882560 0.407983 -0.3215780 -0.1223604 0.8178226 0.4612827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3687 3688 0.622146 -0.677069 0.616500 -0.2326674 -0.2624810 0.7949831 0.4949459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3688 3689 -1.069291 -0.412742 0.230586 -0.0656395 -0.0377138 0.5865500 0.8063673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3689 3690 -0.527405 0.588235 0.173499 -0.2105301 -0.3896387 0.1627487 0.8816868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3690 3691 -0.069946 0.602312 0.978764 0.0339619 0.0603109 0.9721478 0.2239150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3691 3692 0.321917 -0.304287 0.821342 -0.3071610 -0.2911856 -0.9013467 0.0918542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3692 3693 0.250104 0.902897 0.394368 -0.1273002 0.7875613 -0.5733880 0.1864617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3693 3694 -0.562800 -0.244347 -0.681673 -0.2105728 -0.1932080 -0.5736233 0.7676497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3694 3695 -0.300761 -0.532762 -0.685454 0.1963790 0.1132753 -0.7618695 0.6067610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3695 3696 0.961090 -0.206091 -0.296314 -0.3899661 -0.6034558 -0.6781877 0.1543666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3696 3697 -0.776503 0.420077 0.103179 -0.6947399 -0.1878082 -0.2046315 0.6634685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3697 3698 -0.489736 -0.382225 0.677751 0.0246873 -0.1118059 -0.8447813 0.5227184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3698 3699 0.874767 -0.345051 0.545847 0.7535463 0.0296124 0.6310633 0.1817971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3699 3700 -0.563410 -0.290582 0.723805 0.9259669 0.1167998 0.2152844 0.2873948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3700 3701 -0.948500 -0.181407 0.135062 0.0822686 -0.4802009 -0.7524920 0.4431645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3701 3702 0.916041 -0.297410 0.443683 -0.0049443 -0.8130098 -0.1881658 0.5509847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3702 3703 0.395412 0.203991 -1.057150 -0.4010723 0.7331938 0.4107637 0.3644737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3703 3704 0.668298 -0.373841 0.653364 0.2456015 -0.2157784 0.9080098 0.2619881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3704 3705 -0.353154 -0.210181 0.867013 0.3252661 0.5463084 -0.3191911 0.7027561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3705 3706 -1.042146 -0.094237 0.142481 0.4325143 -0.8302633 -0.3513535 0.0120370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3706 3707 0.676391 0.628491 0.105887 0.4503045 -0.3928111 -0.7032189 0.3852383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3707 3708 -0.777412 -0.192195 -0.597117 0.2681792 0.0233577 0.2186642 0.9379340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3708 3709 -0.843175 0.138224 -0.476945 -0.3775944 -0.1600511 0.1129831 0.9050088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3709 3710 -1.035200 0.524220 0.048584 0.0391623 0.0697410 0.8947266 0.4393936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3710 3711 1.092060 0.612376 -0.084268 -0.1515185 0.0350425 -0.5489602 0.8212532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3711 3712 0.044494 0.932358 0.056123 0.3379508 -0.4663907 -0.7649210 0.2883830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3712 3713 -0.395966 -0.423485 0.529018 -0.7673732 0.3646269 0.5146505 0.1154143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3713 3714 -0.575310 0.921375 0.060052 0.4951289 -0.2876023 -0.7557800 0.3176931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3714 3715 -0.502725 -0.577181 0.453270 -0.6112901 0.3324190 -0.0965795 0.7116842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3715 3716 -0.108715 -0.251075 -0.688137 0.3345322 0.3841104 -0.1056792 0.8540371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3716 3717 0.488797 -0.850288 -0.153740 -0.2940927 -0.7547384 0.2570159 0.5270884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3717 3718 -0.824512 -0.344288 -0.252646 0.1949426 0.3613942 0.6912562 0.5946062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3718 3719 -0.153351 0.518084 -0.940389 -0.2350469 0.3268319 0.7736847 0.4892299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3719 3720 -0.005952 -0.759594 0.648203 0.1064433 -0.0569634 -0.6072436 0.7852899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3720 3721 -0.495113 -0.759000 0.428333 0.1549724 -0.0602500 -0.0935461 0.9816326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3721 3722 -0.246403 -0.596641 0.673133 -0.1830646 -0.7018752 -0.6685601 0.1639695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3722 3723 0.429010 0.645135 -0.427638 0.1155981 -0.0024072 -0.3378540 0.9340696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3723 3724 0.346043 0.827276 -0.706250 0.0604155 0.7673546 0.2214878 0.5987153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3724 3725 0.729023 0.236619 0.293435 -0.8974355 0.0058436 0.2176115 0.3836934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3725 3726 0.581900 -0.777127 -0.356135 0.4334295 -0.4094067 0.2782548 0.7530599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3726 3727 0.099902 -1.021283 0.238241 -0.0634216 0.6238407 -0.7579747 0.1796517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3727 3728 0.561103 -0.052972 0.822404 -0.4370569 -0.3933980 0.7341328 0.3395119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3728 3729 -0.514814 -0.855262 -0.277232 -0.9106898 -0.3299418 0.2475788 0.0220738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3729 3730 -0.791344 0.425820 0.684344 0.8907787 0.2412663 -0.0554473 0.3810899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3730 3731 -0.497055 -0.352059 -0.941731 -0.1407612 0.5246619 0.7818263 0.3060454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3731 3732 0.765104 0.014150 -0.632776 -0.3582009 0.3487886 -0.7489576 0.4348576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3732 3733 -0.406361 0.864092 0.262425 -0.4426768 -0.7431805 0.4962818 0.0736505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3733 3734 0.648166 -0.573463 -0.352196 0.2666156 -0.1666817 -0.9491963 0.0126373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3734 3735 -0.431146 0.374218 -0.798949 0.2130463 0.5675905 0.4329185 0.6671086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3735 3736 0.616916 -0.193715 -0.725464 0.3413728 0.7540460 0.5371893 0.1621941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3736 3737 -0.574079 -0.329431 0.563669 0.2584373 -0.3382970 -0.0569465 0.9030628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3737 3738 -0.193936 0.018706 0.989750 -0.2573095 0.0867143 -0.3273345 0.9050550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3738 3739 -0.093809 -0.646010 0.667269 -0.4590911 0.0113276 0.8277389 0.3224210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3739 3740 -0.397988 -0.547515 -0.934781 0.1522729 -0.5942228 -0.0712027 0.7865383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3740 3741 0.455024 -0.548712 -0.857058 0.2858662 0.4151236 -0.5550599 0.6617109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3741 3742 0.964576 0.151188 -0.097782 0.6296800 -0.1025937 -0.7582520 0.1342815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3742 3743 -0.116939 -0.102710 -0.944278 -0.0421316 -0.7465719 0.6638453 0.0128355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3743 3744 -0.042098 1.020646 0.163790 -0.4861943 0.7194105 -0.4317245 0.2442900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3744 3745 -0.856630 -0.161045 -0.446545 0.7793256 -0.4508791 0.4075118 0.1526229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3745 3746 -0.505214 0.945059 -0.096228 -0.6921099 0.2227765 -0.3599402 0.5846346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3746 3747 -0.959631 -0.156742 0.132884 0.5019108 0.0739268 -0.0366987 0.8609725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3747 3748 -1.042665 -0.047641 0.222881 -0.3979008 0.4849057 -0.5120282 0.5868292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3748 3749 0.000268 -0.347507 -0.978887 0.7460766 -0.1385197 0.0724733 0.6472477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3749 3750 -0.377782 -0.899193 0.251166 -0.3411024 -0.3977057 -0.2282968 0.8205851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3750 3751 0.104972 -0.844746 -0.331451 -0.3435005 -0.5594533 0.7396846 0.1479392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3751 3752 -0.305238 0.656301 0.591480 0.3749697 -0.4444630 0.7256079 0.3678905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3752 3753 0.645990 -0.066948 -0.467875 -0.8972860 -0.0654856 0.0657586 0.4315845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3753 3754 0.907946 0.414033 0.132952 -0.3709813 0.1735391 -0.6750134 0.6136888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3754 3755 -0.589337 0.496724 0.811466 -0.4821416 0.3886739 0.0617147 0.7827281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3755 3756 -0.975905 0.140590 0.436010 0.0489390 0.3587218 0.7225626 0.5889201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3756 3757 0.080733 0.831410 -0.341215 -0.1194722 0.8247114 0.5417731 0.1098153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3757 3758 -0.279372 0.227778 1.109832 -0.2747801 -0.0235378 -0.7927822 0.5435423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3758 3759 0.728637 -0.406593 0.626870 -0.1369189 0.5963708 0.7452167 0.2650418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3759 3760 0.313825 -0.170903 -0.987504 -0.4928685 0.7113232 0.4045192 0.2957434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3760 3761 -0.369906 -0.789278 -0.391478 0.6967971 -0.3563718 -0.4542777 0.4255641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3761 3762 0.835103 0.096480 0.793125 -0.0757360 -0.3713351 -0.3565878 0.8539435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3762 3763 0.659683 0.568116 -0.110690 0.6712124 -0.2548875 -0.6207000 0.3150203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3763 3764 -0.443932 -0.445294 -0.762404 0.2744547 -0.4643227 -0.5869677 0.6037781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3764 3765 0.349317 -0.932166 0.113036 0.3043987 0.4916582 0.7415277 0.3402210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3765 3766 -0.948399 0.419168 -0.327342 0.3479468 0.4391459 0.8113638 0.1666517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3766 3767 0.655455 -0.511286 -0.625044 -0.3543700 0.3714847 -0.1733870 0.8404511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3767 3768 1.005746 0.247615 -0.051815 0.3483442 0.2916432 0.5434355 0.7058884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3768 3769 0.405133 -0.501047 0.733413 -0.1591401 0.6502001 0.6623343 0.3364929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3769 3770 -0.934687 0.185768 -0.219086 -0.8157910 -0.0416570 0.1110852 0.5660475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3770 3771 -0.982295 0.305680 0.296809 -0.0072333 0.4295728 -0.9024519 0.0315500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3771 3772 0.499692 -0.579891 0.020173 -0.0816402 -0.5411385 -0.7783240 0.3077593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3772 3773 -0.437190 0.687175 -0.742209 -0.3640882 0.5967465 -0.3363708 0.6310215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3773 3774 -0.115135 0.810849 -0.408447 -0.7372554 -0.3662937 0.5150460 0.2387698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3774 3775 0.743824 -0.473204 0.275406 0.8365969 0.2233848 -0.1653492 0.4720853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3775 3776 0.323536 0.779203 0.087813 0.1804472 0.3903023 -0.6227853 0.6536371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3776 3777 -0.677026 0.560802 -0.372485 -0.3414827 -0.8723349 0.0847172 0.3394766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3777 3778 0.668858 0.103185 0.807315 -0.8014988 0.3621632 -0.4733770 0.0484945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3778 3779 0.682923 -0.788980 -0.161469 -0.4278395 0.3017556 -0.6034414 0.6014611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3779 3780 -0.150930 0.982188 -0.529240 -0.2376685 -0.6435365 0.3803341 0.6202584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3780 3781 -0.370833 0.230632 0.989133 0.2121517 0.4078269 -0.8395558 0.2895080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3781 3782 -0.120437 -0.931150 0.269640 -0.8757042 -0.2819961 0.0470733 0.3891072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3782 3783 -0.724240 0.072357 -0.835440 0.4564520 0.6679933 -0.1656507 0.5639117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3783 3784 0.601416 -0.784804 -0.585174 -0.0380038 0.3546196 -0.3871672 0.8502365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3784 3785 0.790207 0.134634 0.323826 0.9397983 -0.2338902 -0.1578517 0.1927623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3785 3786 0.562000 -0.213444 -0.610610 -0.3928523 0.6063666 0.6569752 0.2153372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3786 3787 0.090351 -0.913830 -0.252290 -0.1402594 0.2019471 -0.8797788 0.4068586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3787 3788 0.534046 0.792522 -0.091272 -0.2454195 0.1146739 -0.9507888 0.1503987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3788 3789 -0.585249 -0.601681 0.178598 0.2147956 0.7789429 0.5635242 0.1719049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3789 3790 0.308439 -0.106499 -0.977632 -0.7397207 0.0672384 -0.5078212 0.4363600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3790 3791 -0.415137 0.822577 0.232398 0.3322772 -0.1539867 0.8407893 0.3986894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3791 3792 0.871360 -0.215142 -0.388947 0.2162784 0.1031868 0.6849674 0.6880377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3792 3793 -0.210624 -1.043654 -0.017880 -0.0434027 -0.5089451 -0.8423131 0.1720458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3793 3794 0.416727 0.524716 -0.784058 -0.2365179 -0.6821140 -0.6221483 0.3028387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3794 3795 -1.090644 -0.055183 0.262146 0.4814197 -0.2115973 -0.7515350 0.3983174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3795 3796 0.294744 -0.077878 1.113382 -0.5543424 0.3192202 0.5711685 0.5143633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3796 3797 -0.928007 -0.205016 0.235991 0.1186670 -0.0889447 -0.6456860 0.7490638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3797 3798 0.107017 -0.946683 0.359366 0.0432434 -0.3839975 -0.3699176 0.8448887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3798 3799 1.137351 -0.502973 -0.017461 0.3490130 -0.3205296 -0.3885123 0.7902588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3799 3800 0.551046 -0.195150 0.631067 0.3481636 0.6987135 0.5580434 0.2813701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3800 3801 0.383073 0.458763 -0.513598 0.1753713 0.1704157 -0.4374908 0.8653353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3801 3802 0.346001 0.732280 -0.881985 -0.3779280 0.2531353 0.4986886 0.7378365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3802 3803 0.882647 -0.173568 0.178032 0.4840618 -0.0456988 -0.5881799 0.6462509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3803 3804 0.417269 0.775572 -0.471191 -0.6522715 0.1580862 0.1585008 0.7241741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3804 3805 0.672192 0.383679 0.555821 -0.3346965 -0.6868138 0.3888143 0.5148674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3805 3806 0.545024 -0.271258 -1.012477 -0.2194078 0.3799881 -0.2794606 0.8540322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3806 3807 0.717951 0.153408 -0.277355 0.1443234 0.8884583 -0.1869946 0.3935042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3807 3808 -0.507448 0.692224 0.531004 0.0417449 -0.9734593 0.1812808 0.1333105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3808 3809 0.395515 0.332461 -0.803153 -0.0887883 0.8005351 -0.1021829 0.5837970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3809 3810 0.340372 0.896816 0.704401 -0.1895413 -0.3673737 -0.1558731 0.8971144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3810 3811 0.579363 0.583393 0.502684 0.2494906 -0.7934478 0.5062142 0.2279084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3811 3812 -0.157647 -0.484933 -0.777173 0.4530082 0.2224419 0.4657346 0.7269075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3812 3813 -0.608997 -0.669070 -0.347013 0.3998161 -0.4715615 -0.7358654 0.2761865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3813 3814 0.871453 -0.039735 0.057385 0.3639923 -0.3541065 0.1614380 0.8462009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3814 3815 0.876506 -0.309061 -0.613946 -0.1351169 0.9590628 0.2264956 0.1031591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3815 3816 -0.395407 -0.743493 0.358584 0.5367750 -0.6940447 -0.0639209 0.4754878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3816 3817 0.797348 0.295800 0.484397 -0.8224233 0.1216223 0.5005380 0.2414325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3817 3818 0.202134 -0.791906 -0.729806 0.5854766 -0.3871892 0.6375430 0.3175540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3818 3819 -0.759455 0.452967 0.400591 -0.5037391 0.6589627 0.1138746 0.5468525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3819 3820 -0.122263 -0.559069 -0.898655 0.5855085 -0.2831665 0.4498737 0.6120541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3820 3821 0.520234 -0.611044 0.716313 -0.5965702 -0.1890919 -0.7704494 0.1214737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3821 3822 0.534552 0.775986 0.446703 0.3600338 0.4745938 0.1499484 0.7890829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3822 3823 0.694329 0.923952 0.343876 0.1953756 0.2345453 0.9475518 0.0946698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3823 3824 -0.123915 -0.640305 0.700808 -0.1253921 0.1422571 -0.9539343 0.2324847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3824 3825 0.465854 0.328566 0.770554 0.3778739 -0.5316404 -0.7563030 0.0507503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3825 3826 -1.052344 0.315882 0.007545 0.8517806 -0.0696397 0.5181354 0.0339977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3826 3827 -0.421479 -0.253606 -0.724410 -0.3920812 0.6456032 -0.6100180 0.2394722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3827 3828 0.346234 0.943637 -0.255449 -0.1834344 -0.1051725 -0.9613888 0.1761308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3828 3829 -0.563822 -0.913770 0.184639 -0.3743739 0.1604193 -0.9104657 0.0718477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3829 3830 0.884400 0.892237 -0.014944 0.6754388 -0.5454255 0.3249256 0.3751223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3830 3831 -0.097432 -0.610044 -0.659924 0.4786970 0.1158951 0.8105218 0.3169731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3831 3832 -0.654431 0.218575 -0.440660 -0.4143451 -0.6542150 0.3431459 0.5315747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3832 3833 0.061632 0.273326 0.841798 -0.6544270 0.1088342 -0.5487439 0.5086851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3833 3834 0.433948 -0.830054 0.423527 -0.5845270 -0.2098998 -0.4864557 0.6145170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3834 3835 0.735823 0.204962 -0.336145 0.0267598 -0.2089231 -0.1566084 0.9649398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3835 3836 0.513178 0.390041 -0.744856 -0.7699034 0.3005817 0.0781500 0.5574872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3836 3837 0.656992 0.275799 0.790181 0.2853435 0.0171981 -0.9276307 0.2403843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3837 3838 -0.933651 0.240274 0.526260 -0.3298601 0.1848687 -0.6174655 0.6897480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3838 3839 -0.060477 -1.058599 -0.287157 -0.5149212 0.0467407 0.4907722 0.7012946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3839 3840 0.147912 0.865958 0.271326 0.4523335 0.1533149 -0.7137620 0.5122818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3840 3841 -0.507689 0.697691 0.383583 0.2219365 -0.0567464 0.9331139 0.2771686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3841 3842 0.936945 -0.439451 -0.052824 -0.5653057 0.4023520 0.3198736 0.6451537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3842 3843 0.412120 -0.890972 -0.368704 -0.0497162 -0.8010080 0.4999050 0.3255909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3843 3844 -0.864284 -0.270919 0.493564 0.1984855 0.6980655 -0.1164902 0.6780399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3844 3845 -0.469381 -0.664932 -0.887328 -0.2177842 0.2272957 0.7216540 0.6165405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3845 3846 0.111317 0.388753 -0.857548 -0.2662221 -0.9297027 -0.0615859 0.2469533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3846 3847 -0.359162 0.459988 0.945682 0.6102202 0.1612969 0.7736616 0.0553396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3847 3848 1.034286 -0.316585 0.084259 -0.0472243 -0.0563133 -0.9195326 0.3860810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3848 3849 -0.508710 0.862608 -0.055751 -0.1706690 0.6057610 0.4526228 0.6317106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3849 3850 0.558580 0.922994 0.335072 0.4908006 0.2252668 -0.8415227 0.0144666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3850 3851 -0.371451 -0.512812 -0.657800 0.1284529 0.0072804 -0.8656086 0.4839097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3851 3852 0.843352 0.224300 -0.547169 -0.1343056 0.2540814 -0.3208890 0.9024604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3852 3853 0.811000 0.669689 -0.014146 0.5556822 0.3409393 -0.2139044 0.7274768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3853 3854 0.423681 0.747720 -0.342350 -0.7265584 0.0156415 0.6041000 0.3270037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3854 3855 0.843627 -0.525562 0.030739 -0.4329124 0.5400940 0.7190249 0.0623572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3855 3856 -0.333288 -0.335958 -1.018577 -0.7753985 0.3537756 0.1829488 0.4900303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3856 3857 0.290736 0.777082 0.249188 0.0155085 0.1772228 0.9648145 0.1936091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3857 3858 -0.112242 -0.641210 0.816128 -0.3901814 0.4576404 -0.6758377 0.4261069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3858 3859 0.986195 -0.398281 0.365690 -0.6509875 0.1447976 0.6922623 0.2757205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3859 3860 -0.580238 -0.956455 0.448510 -0.2893011 -0.1595753 -0.9433512 0.0304819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3860 3861 0.174338 0.145019 0.940808 -0.2357040 0.2231301 0.1107095 0.9393615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3861 3862 -0.433915 -0.444098 1.046154 0.0669984 -0.8620889 0.4001658 0.3036137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3862 3863 0.820724 -0.734586 -0.020041 0.2049529 -0.6272629 -0.3323116 0.6738728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3863 3864 0.296445 -0.310879 -0.819656 -0.3609450 0.3072236 0.1856632 0.8607332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3864 3865 0.940729 0.096618 -0.413588 0.8644814 0.0394054 0.4975170 0.0599667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3865 3866 -0.105059 -0.170282 0.894545 -0.1198200 0.5518515 -0.4255754 0.7070988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3866 3867 -0.470662 -0.697496 0.560296 -0.8715124 -0.3305153 0.3247119 0.1605861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3867 3868 -1.055379 0.128469 -0.126821 0.8425529 -0.3798514 0.3428068 0.1682293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3868 3869 -0.667022 0.638724 -0.410269 -0.6057537 0.1029076 0.4690697 0.6343864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3869 3870 0.653825 0.686528 0.539388 0.5179501 -0.5451905 0.6589588 0.0163826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3870 3871 -0.029377 -0.780825 -0.178783 -0.3126672 -0.4560475 0.8331893 0.0074528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3871 3872 -0.070699 0.634134 0.663920 0.0730739 -0.6748978 -0.1282173 0.7230031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3872 3873 0.313759 0.800526 0.192786 0.5237572 0.6187121 0.0151450 0.5853584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3873 3874 0.789460 0.846737 -0.193939 -0.7235007 -0.4965377 0.1427621 0.4578383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3874 3875 0.871708 0.224834 0.283797 0.1548970 0.1037518 -0.4707091 0.8623662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3875 3876 0.159538 0.954032 0.266630 0.3303431 0.0404746 0.9382079 0.0948750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3876 3877 -0.098316 -1.101276 0.298469 -0.0983531 -0.5525724 -0.7530901 0.3432866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3877 3878 0.299461 0.327193 -1.131537 -0.4901939 0.6886565 0.0557702 0.5313680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3878 3879 0.626134 0.267633 0.861633 0.7215473 -0.4962599 -0.4094819 0.2557738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3879 3880 0.847427 0.185821 -0.369070 -0.6280036 -0.3823374 0.4377158 0.5175274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3880 3881 -0.265819 -0.872516 -0.719384 0.2409655 0.2437525 0.8932975 0.2907576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3881 3882 -0.436841 0.294745 -0.855488 -0.2438732 0.2142386 0.8063081 0.4944642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3882 3883 0.953051 0.182497 -0.211784 -0.4079306 0.5704751 -0.4040855 0.5872527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3883 3884 -0.159008 0.450717 0.868320 -0.0583558 0.0581850 -0.1061251 0.9909322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3884 3885 -0.267187 0.156640 0.940928 0.3411291 -0.2179430 -0.6613773 0.6314364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3885 3886 -0.702231 0.196926 0.634036 -0.5351691 0.4054335 -0.7315329 0.1186478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3886 3887 0.726931 -0.654460 -0.667715 -0.4414327 0.2289079 0.5265453 0.6895567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3887 3888 0.220212 -0.332622 -0.776314 -0.0023132 -0.8177260 -0.0840863 0.5694281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3888 3889 -0.873521 -0.557528 0.195792 -0.4457476 0.5118919 -0.7282223 0.0946994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3889 3890 0.666845 0.620172 -0.482840 0.5090017 -0.0553938 0.1545142 0.8449699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3890 3891 0.696563 -0.364291 -0.391317 -0.4128768 0.6650816 -0.1937088 0.5913342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3891 3892 0.625788 0.014171 0.791864 -0.3329058 -0.1723062 -0.4659882 0.8014608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3892 3893 0.695329 0.175922 0.674295 -0.0374532 0.1107401 -0.9532967 0.2784947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3893 3894 -0.935001 -0.035627 0.490361 -0.3855548 0.6614687 0.6283049 0.1379838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3894 3895 -0.056603 0.949754 0.376920 -0.5696546 -0.2731055 0.5592287 0.5368149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3895 3896 0.719143 -0.477195 0.085461 -0.1798032 -0.4873416 0.7942823 0.3150947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3896 3897 -0.978121 -0.229559 -0.096766 0.3362142 0.1098634 -0.1209919 0.9274972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3897 3898 -1.099628 -0.077725 0.120205 0.2582798 -0.2489207 0.1115474 0.9267617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3898 3899 -0.709846 -0.098608 0.869978 0.1502957 0.4012175 0.8378331 0.3383361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3899 3900 -0.760791 0.378540 0.180675 0.1130461 0.7310076 -0.5361567 0.4066749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3900 3901 0.829277 -0.372453 0.539386 0.3447131 0.0417043 -0.3772138 0.8585706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3901 3902 0.674845 0.425690 0.642157 -0.2667270 0.4512617 -0.6168962 0.5870764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3902 3903 -0.772743 -0.072970 0.760635 -0.2146061 -0.0297397 -0.1981767 0.9559214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3903 3904 -0.586927 -0.484653 0.424804 -0.8669441 0.0649671 -0.4379427 0.2288960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3904 3905 0.324278 0.355476 -1.037936 0.9182731 -0.0323045 0.3941168 0.0200741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3905 3906 -0.751185 -0.219283 0.858858 0.8719260 0.0550353 0.4529622 0.1775987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3906 3907 0.349372 0.436376 -0.733800 -0.6328006 -0.4940122 -0.5960029 0.0172023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3907 3908 -0.384951 -0.471330 0.927581 -0.3105832 0.7041219 -0.3397040 0.5406956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3908 3909 -0.357425 -0.818017 -0.452688 -0.1847825 -0.5827083 0.6333924 0.4744687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3909 3910 -0.634415 0.236047 0.478680 0.2708687 -0.5458385 0.7909545 0.0555113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3910 3911 0.870094 -0.209865 -0.396942 0.5824712 -0.0976593 -0.8006218 0.1009689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3911 3912 0.212615 0.058120 -1.100252 -0.4454336 -0.4045811 0.7712394 0.2075881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3912 3913 0.719283 0.611037 -0.444599 -0.4412882 0.6908307 -0.4966034 0.2853117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3913 3914 -0.652128 0.378040 0.606559 0.0599338 -0.5206499 -0.5225712 0.6724960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3914 3915 -0.004288 -0.230188 0.931948 0.0037458 0.5515589 -0.5842084 0.5953732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3915 3916 -0.570847 -0.648158 0.455865 -0.6898707 -0.4270950 -0.1104708 0.5739899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3916 3917 -0.270675 -0.724552 -0.486802 -0.3312033 0.1402694 -0.7544993 0.5489624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3917 3918 0.828719 0.296949 -0.589024 0.8589809 0.3127768 0.3123283 0.2584056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3918 3919 0.271422 -0.447818 0.707720 -0.5640914 -0.2043467 -0.3764632 0.7059170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3919 3920 -0.230743 -0.790690 0.440731 -0.0321823 -0.1475870 0.0157660 0.9883996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3920 3921 -0.715230 0.434800 0.454156 -0.2406297 -0.0163655 -0.0523338 0.9690669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3921 3922 -0.769634 0.189922 0.646907 0.0608830 0.6297141 0.2043318 0.7469953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3922 3923 -0.521453 0.416891 -0.678449 0.0221430 -0.3945577 0.7311712 0.5560779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3923 3924 0.220245 0.837774 -0.402605 -0.4227246 0.2867197 -0.2371046 0.8263638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3924 3925 0.070944 0.696615 0.331695 0.3316292 -0.1881219 -0.8475940 0.3690753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3925 3926 -0.888380 -0.415905 0.401650 -0.1573941 0.2442122 0.8087052 0.5114522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3926 3927 -0.321657 0.909095 0.170456 -0.2762881 0.5673718 -0.3166618 0.7081522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3927 3928 -1.059914 0.443443 0.029958 0.1852217 -0.6765916 0.2937795 0.6493153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3928 3929 -0.057964 0.883658 0.230367 -0.0057579 -0.0293461 0.3578015 0.9333187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3929 3930 0.384122 0.715711 0.278691 -0.1201352 0.1444357 -0.1298547 0.9735726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3930 3931 0.257883 0.783651 0.436077 0.4175430 -0.0058967 -0.5193307 0.7455996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3931 3932 -0.817681 0.614312 -0.385753 0.0400510 -0.1808725 0.8154522 0.5483784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3932 3933 0.650251 0.521392 -0.520452 -0.0846454 -0.4688361 0.8791715 0.0092372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3933 3934 -0.816396 -0.298007 -0.674205 -0.2109587 -0.1357653 -0.7882179 0.5619402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3934 3935 0.051273 -0.613937 -0.927337 0.5299518 -0.1916185 0.7740487 0.2885863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3935 3936 -0.791386 0.364834 -0.112987 0.0343997 0.0106597 0.9963016 0.0780143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3936 3937 0.798349 -0.271686 -0.267074 -0.4934638 -0.0512900 0.4447055 0.7457210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3937 3938 0.346154 -0.549113 -0.742186 0.0152975 -0.9805059 0.1389445 0.1380888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3938 3939 -0.475631 -0.235890 0.736574 0.4385363 0.0725523 -0.3884038 0.8071955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3939 3940 0.097892 -0.919568 0.078327 -0.8231218 0.1511055 -0.2663639 0.4782131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3940 3941 0.239105 0.668964 0.883978 -0.1280362 -0.8329192 0.5373448 0.0333602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3941 3942 -0.141596 -0.698613 -0.842308 -0.1506806 -0.2099175 0.3298200 0.9079916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3942 3943 -0.602364 -0.063889 -0.770803 -0.2168844 -0.0139934 0.6831834 0.6971554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3943 3944 0.126589 0.924600 -0.383349 -0.2707433 0.2763372 -0.4224524 0.8196766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3944 3945 -0.569866 0.837957 0.189027 -0.3904475 -0.8096390 0.2391746 0.3671933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3945 3946 0.783664 0.438817 0.412790 0.5671089 0.2232039 0.0780589 0.7889704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3946 3947 0.659690 0.426935 0.180293 0.2364047 -0.3586027 -0.8831309 0.1886710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3947 3948 -1.037272 -0.167064 0.229219 0.3892658 0.7180640 0.5064514 0.2763388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3948 3949 0.441570 -0.276525 -0.849384 -0.2966065 0.8097931 0.3907606 0.3218166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3949 3950 0.423838 -0.709185 0.401525 0.4578000 -0.2743258 0.7163251 0.4494917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3950 3951 -0.249683 0.126356 0.919473 -0.1861943 0.6987044 0.6640881 0.1900810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3951 3952 -0.355309 0.766615 0.006322 -0.0624706 -0.4767207 0.8768056 0.0068397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3952 3953 0.601406 -0.429051 -0.776626 0.0652670 0.1057951 0.9603672 0.2494845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3953 3954 -0.736045 0.009522 -0.638740 0.7917322 -0.2628961 -0.4607963 0.3028408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3954 3955 0.088275 -0.414823 0.852802 -0.1787041 -0.4177572 -0.7821966 0.4262771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3955 3956 0.652875 0.845473 0.152466 -0.2135872 0.0159640 -0.9767345 0.0107387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3956 3957 -0.706704 -0.387072 0.346474 -0.2928114 -0.2130140 0.9302289 0.0596715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3957 3958 0.214553 0.509336 0.913423 -0.1081366 0.1917683 -0.7582441 0.6136753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3958 3959 -0.538232 -0.419672 0.723775 0.4862834 0.7461429 0.4445658 0.0957106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3959 3960 0.913513 0.279740 0.394119 -0.5035636 -0.1246582 0.8501193 0.0904499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3960 3961 -0.752442 0.057933 0.508376 0.0476146 -0.3753792 -0.1013200 0.9200856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3961 3962 -0.084112 -0.020574 1.084269 0.2334146 -0.1743720 0.6633991 0.6892123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3962 3963 0.576067 0.199759 0.862072 0.4639482 0.2038548 -0.2564048 0.8230746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3963 3964 -0.050042 0.972365 0.214192 0.0836615 -0.1019733 -0.6993818 0.7024723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3964 3965 -0.975075 -0.153796 0.326698 0.3323874 -0.2719317 0.8273475 0.3620331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3965 3966 0.733374 0.817664 -0.102731 -0.3026143 -0.0565569 -0.2018036 0.9297856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3966 3967 0.254718 0.704993 0.394683 0.4806429 -0.2435707 -0.2467406 0.8054656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3967 3968 -0.206538 0.673349 -0.737828 0.1172484 0.3487967 -0.1707487 0.9140233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3968 3969 0.288200 0.647717 -0.582227 0.0321478 0.4113921 0.3272943 0.8500597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3969 3970 0.876803 0.100375 -0.308826 0.0113648 -0.1488460 0.4068879 0.9011981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3970 3971 0.821944 -0.659723 -0.439079 -0.8154010 0.1236786 0.0574618 0.5626038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3971 3972 0.935195 0.406541 -0.274681 0.2946615 0.0977499 0.9220097 0.2313389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3972 3973 -0.480237 -0.692482 0.402088 0.6635576 -0.5318693 -0.5259091 0.0150285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3973 3974 0.209795 0.872099 -0.242538 -0.6537530 -0.6914998 -0.0469716 0.3036918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3974 3975 0.607249 0.442341 0.409290 0.8378084 -0.0924381 0.3844845 0.3764359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3975 3976 0.772523 -0.516550 0.154755 0.4017566 0.4551228 0.7945972 0.0083796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3976 3977 -0.925258 0.553027 0.107851 -0.2596948 0.1846403 -0.0050148 0.9478615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3977 3978 -0.774280 0.387335 -0.066013 0.4787816 0.3030047 0.6939896 0.4442238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3978 3979 0.456602 0.106561 -1.015707 -0.5203162 0.5715274 0.2445863 0.5854955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3979 3980 -0.000079 1.043958 0.264609 -0.1512154 -0.3083396 0.5959909 0.7258481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3980 3981 -0.222651 0.917788 -0.081265 -0.4739534 -0.3268698 0.7802506 0.2444042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3981 3982 0.536814 -0.785817 -0.129249 0.8166405 0.0438198 -0.5130485 0.2606902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3982 3983 0.521262 0.734723 -0.060745 0.5473897 -0.5603733 -0.2300946 0.5774104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3983 3984 -0.524791 -0.041824 -0.680548 -0.4329660 0.0213558 0.3210469 0.8420292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3984 3985 -0.226742 0.883822 -0.445147 -0.3084204 0.1769485 -0.9243777 0.1381735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3985 3986 -0.302861 -0.492115 -0.599859 -0.0128337 0.2433236 -0.4697663 0.8484978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3986 3987 0.698010 -0.429996 -0.633081 0.2132074 0.6040344 -0.7023986 0.3103566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3987 3988 -0.045488 1.110965 0.349367 -0.4345861 0.2706954 0.7360365 0.4428422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3988 3989 -0.136117 -0.424595 0.888721 0.0209715 0.4786813 0.8453379 0.2362800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3989 3990 -0.357112 0.907572 0.212926 -0.7084443 0.0710002 -0.2920082 0.6385898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3990 3991 -0.736726 -0.303951 0.673214 0.9150258 -0.1050597 0.3388211 0.1920691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3991 3992 -0.189181 1.002192 -0.466394 0.0748185 0.1148597 -0.5124354 0.8477142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3992 3993 -0.271459 0.208296 -0.761127 -0.4989652 0.0923669 -0.2757153 0.8163842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3993 3994 -0.688615 0.521357 -0.416992 -0.0414160 -0.4797577 0.1180395 0.8684376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3994 3995 -0.639515 0.873703 0.451323 -0.6435847 0.4313219 -0.4599056 0.4338744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3995 3996 -0.996333 -0.730937 -0.382387 0.1913171 0.6474737 0.3763590 0.6344521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3996 3997 -0.182146 -0.436232 -0.893283 0.8726390 -0.0825166 0.0614431 0.4774065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3997 3998 -0.269183 -0.445052 1.027375 0.4215317 -0.2105449 -0.8744120 0.1156959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3998 3999 -0.231322 0.724004 0.677341 0.1683131 0.7411907 -0.1763579 0.6254638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3999 4000 9.730774 -10.712264 12.402882 -0.4811386 -0.4908036 0.7245949 0.0507911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4000 4001 0.912761 0.045425 0.032966 0.4354588 -0.0139224 0.7736046 0.4601279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4001 4002 -0.197450 -0.753381 0.902405 0.2269013 0.4463180 -0.1637343 0.8500042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4002 4003 -0.662253 -0.455711 0.741476 -0.8162058 0.3692025 0.3765441 0.2360342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4003 4004 -0.507947 0.762831 -0.424607 0.2799156 -0.5234672 0.5186690 0.6153144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4004 4005 -0.169213 0.959923 -0.577712 0.0515617 -0.0182459 0.9550096 0.2914880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4005 4006 0.267780 -0.530694 -0.797740 -0.0062621 0.8164221 -0.4653869 0.3418051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4006 4007 0.087439 0.157716 0.777771 -0.0777222 -0.0315479 -0.9873410 0.1346167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4007 4008 -0.096754 -0.219376 0.848857 0.1245069 0.8807227 -0.0852255 0.4489567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4008 4009 -0.708721 0.032805 -0.767391 0.0918884 -0.4783369 -0.8682924 0.0939078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4009 4010 0.837409 -0.544785 -0.381972 -0.4448407 0.0453148 -0.8358179 0.3185462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4010 4011 0.017832 1.024837 0.349119 -0.4751691 0.1816475 -0.2255831 0.8308615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4011 4012 -0.644896 -0.233687 0.654520 0.7178991 0.3726532 0.1409277 0.5708677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4012 4013 -0.529698 0.566599 -0.779634 0.1867342 -0.0172680 0.9514869 0.2439363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4013 4014 0.534704 -0.274185 -0.913784 -0.3359312 0.6467790 -0.3025610 0.6142345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4014 4015 0.656892 0.332546 0.393630 0.1310088 -0.3544880 0.0701324 0.9231773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4015 4016 0.664014 0.579588 -0.119292 -0.5799864 0.2190323 -0.7322791 0.2817942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4016 4017 -0.585445 -0.131572 0.835386 -0.3955112 -0.2959805 0.2217280 0.8407159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4017 4018 -0.500970 -0.502412 0.716281 0.7839956 -0.5116349 0.2498968 0.2472491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4018 4019 0.693834 0.715454 -0.431743 -0.3816308 0.6268484 0.0283643 0.6786859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4019 4020 -0.836575 -0.192878 0.084059 -0.4380613 -0.2905577 0.7847260 0.3284565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4020 4021 0.378900 0.959780 -0.272848 0.4758990 -0.2562410 -0.8191650 0.1919097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4021 4022 -0.495661 -0.920542 -0.288930 0.1377101 -0.0637253 -0.3253344 0.9333448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4022 4023 0.071603 -0.858906 -0.036576 0.4810325 -0.2213088 0.8375897 0.1344383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4023 4024 0.220066 0.873726 0.554376 0.7355801 0.0298872 0.1568623 0.6583486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4024 4025 0.314068 0.406331 -1.003868 -0.3724749 0.0882753 -0.6621178 0.6442592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4025 4026 -0.743320 0.583720 -0.082307 0.1563606 0.6769266 0.7190995 0.0147540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4026 4027 0.851481 -0.601133 0.439656 -0.4658833 0.5264002 0.6303249 0.3294634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4027 4028 -0.569026 -0.457499 -0.574527 -0.0072937 0.4645979 -0.5796219 0.6694281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4028 4029 0.652047 -0.082846 -0.702643 -0.2294252 0.5930517 -0.3185355 0.7029857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4029 4030 0.452754 0.481452 0.779845 -0.3475202 0.6650099 -0.3056509 0.5861476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4030 4031 -0.616940 -0.414560 0.441664 0.0141879 0.3567050 -0.4529793 0.8169272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4031 4032 -0.199690 -1.062810 0.131442 -0.3816550 0.2045611 0.7380492 0.5174724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4032 4033 -0.625905 0.893661 -0.484922 0.6345509 -0.3798565 -0.6686495 0.0772142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4033 4034 0.116903 -0.486323 0.773599 0.0543099 0.1443031 -0.8942048 0.4202676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4034 4035 0.222373 0.280523 1.050976 -0.4496592 -0.6101916 0.6426509 0.1116808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4035 4036 -0.438518 -0.941495 -0.591802 0.1760901 -0.3925569 -0.8918928 0.1393502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4036 4037 0.587665 -0.108414 -0.745385 -0.9387571 -0.2352846 0.1324778 0.2140696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4037 4038 0.686262 0.514763 0.399917 0.4904169 0.3989338 -0.1957078 0.7496944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4038 4039 0.027593 0.908034 0.053617 -0.4509557 -0.0229638 0.1651024 0.8768425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4039 4040 0.992158 -0.254676 -0.199484 -0.0843616 -0.1858278 0.7943616 0.5721370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4040 4041 0.023207 0.537829 -0.595944 -0.5479664 0.1703255 0.5759080 0.5822817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4041 4042 0.769777 0.247236 0.451662 -0.7810310 -0.1630202 -0.0751907 0.5981316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4042 4043 0.818277 -0.354482 0.255630 -0.3619356 -0.1440148 0.8230044 0.4134322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4043 4044 -0.587512 -0.409678 -0.452974 -0.1400670 0.5769239 0.7808532 0.1944439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4044 4045 0.829829 -0.135861 -0.445635 -0.0768253 -0.2565874 0.3569399 0.8949049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4045 4046 0.053676 -0.358836 -0.976675 -0.4205601 0.8631431 -0.2358217 0.1500044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4046 4047 0.251031 -0.027576 1.050591 -0.0332614 0.1025373 -0.9885961 0.1051544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4047 4048 -0.147909 -0.294773 1.048921 -0.0571239 0.2899610 -0.1799239 0.9382360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4048 4049 -0.617875 -0.600833 0.635357 -0.2859599 0.2110817 0.8602597 0.3655472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4049 4050 -0.403192 0.867845 0.372460 -0.2180796 -0.5394859 0.6099032 0.5379724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4050 4051 1.131283 -0.022252 -0.012408 0.7744420 0.3254117 -0.5422991 0.0160746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4051 4052 0.274272 0.609230 -0.715767 0.0079055 -0.1391613 0.2614844 0.9550903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4052 4053 -0.008829 0.405970 -0.976160 -0.9209821 0.1965662 0.3231239 0.0935134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4053 4054 0.564101 -0.399470 0.693210 -0.6025638 0.1121872 0.7788342 0.1332221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4054 4055 -0.945830 -0.004234 -0.581663 -0.7550533 -0.5513869 -0.2260095 0.2734714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4055 4056 -0.616279 -0.684248 0.478141 0.1563586 -0.0534139 -0.8763390 0.4524699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4056 4057 0.861689 0.003880 0.606614 -0.7373472 -0.2332759 -0.6243875 0.1097346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4057 4058 0.574129 0.558234 0.563059 -0.2326967 0.5278409 -0.7973019 0.1776116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4058 4059 -0.597464 -0.503349 0.295010 -0.5072806 -0.0999215 0.0586295 0.8539582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4059 4060 0.237640 -0.077276 -0.844668 -0.0510475 0.1023858 -0.7648515 0.6339664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4060 4061 -0.947861 0.538245 0.373285 0.4317740 0.2714794 0.7026767 0.4961005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4061 4062 0.677480 0.518502 -0.486045 0.0885101 0.3390763 -0.6833416 0.6404978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4062 4063 -0.265553 0.710325 -0.568125 0.0568506 -0.8231860 -0.3781498 0.4196850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4063 4064 -0.528807 0.159952 0.887100 0.3713353 -0.0183613 0.8292783 0.4172176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4064 4065 0.776537 0.632536 0.216705 -0.5318086 -0.1374847 -0.8355770 0.0094105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4065 4066 0.115383 -0.378481 0.865442 -0.3016367 -0.3584847 0.1692160 0.8671044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4066 4067 0.204757 -0.961803 0.186933 0.0158153 0.3908543 -0.3023603 0.8692302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4067 4068 0.405393 -0.743201 0.654369 -0.6698285 0.3610394 -0.1661546 0.6271945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4068 4069 0.704332 -0.611945 -0.166354 0.6453073 -0.3592449 0.2105860 0.6404491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4069 4070 0.317929 -0.759348 0.662873 -0.0230501 -0.4567072 -0.1762613 0.8716761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4070 4071 0.846944 -0.241477 -0.158107 -0.3000514 0.0045646 -0.7761777 0.5545237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4071 4072 -0.026709 0.940972 0.294635 -0.3925126 -0.1927359 0.8814450 0.1784415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4072 4073 0.138523 -0.961177 -0.106650 0.6172697 0.4467753 -0.6429207 0.0776075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4073 4074 -0.283833 0.871427 0.530748 0.4680662 -0.6714346 -0.3648364 0.4438288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4074 4075 -0.755457 0.855759 0.232991 -0.0659198 0.5473269 -0.8259389 0.1179527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4075 4076 0.284851 -0.465960 -0.976936 0.1852087 -0.8195510 -0.0411860 0.5406825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4076 4077 -0.440380 -0.589448 0.038126 -0.4867515 0.2904887 0.0942413 0.8184179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4077 4078 -0.609892 -0.223703 -0.820670 0.2279672 0.7604864 -0.5501262 0.2589450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4078 4079 0.825199 0.157857 0.321100 -0.4004156 -0.1183375 -0.5940142 0.6876124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4079 4080 0.450259 0.430279 -0.763242 0.1357843 -0.5790311 0.5252034 0.6086436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4080 4081 -0.997815 0.046688 0.621299 0.6947542 0.1756634 0.3159495 0.6217997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4081 4082 -0.345401 0.487190 -0.882856 0.5220330 -0.1433512 -0.0133537 0.8406864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4082 4083 -0.524705 -0.359828 -0.683333 -0.6872420 0.4435345 0.3036754 0.4886275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4083 4084 0.492367 0.939618 -0.198119 0.4431150 -0.4705110 -0.4699453 0.6011821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4084 4085 -0.796265 0.246172 -0.486115 0.1615859 -0.4492460 -0.6962168 0.5360505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4085 4086 0.005755 -1.074333 0.201956 0.0139478 -0.6397705 0.6806548 0.3566626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4086 4087 -0.263918 -0.021073 0.843665 0.6505239 0.5980558 -0.3784459 0.2755479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4087 4088 -0.905758 -0.441353 -0.383229 -0.0781995 0.0571180 -0.6244894 0.7750067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4088 4089 0.322850 -1.040183 -0.372549 0.5810328 -0.4404004 -0.5261001 0.4377980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4089 4090 0.884478 -0.045971 0.055752 0.5133999 0.0267028 0.8557667 0.0580587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4090 4091 -0.479209 0.145501 0.776180 0.3374830 -0.2163227 0.6234083 0.6713209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4091 4092 0.790760 0.773087 0.522000 -0.0351505 0.2350769 0.2047826 0.9495090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4092 4093 0.412837 0.234007 0.757929 0.4547925 -0.5616579 -0.0790478 0.6866262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4093 4094 0.657517 0.560676 -0.618506 0.5431376 0.4335786 0.1718721 0.6981913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4094 4095 0.931273 -0.207118 0.262070 -0.1542613 0.0456472 0.9693860 0.1855007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4095 4096 -1.086183 0.007167 0.029612 0.2765995 -0.1901038 0.1404007 0.9314724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4096 4097 -1.010814 0.167382 0.267141 -0.5143909 -0.0463620 0.8312697 0.2055315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4097 4098 0.226009 0.010726 0.847382 -0.2675600 -0.8617320 -0.0249669 0.4303560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4098 4099 0.536740 -0.113305 -0.634240 -0.7690558 0.4882778 -0.3862945 0.1446185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4099 4100 -0.779186 -0.725656 -0.334858 0.6725307 -0.3099224 0.1264155 0.6600529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4100 4101 -0.498115 -0.749081 -0.126628 0.3756075 0.4762328 0.0387168 0.7941173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4101 4102 -0.763580 -0.704393 0.159371 -0.2770802 -0.3781009 -0.8606152 0.1990168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4102 4103 0.867331 0.375597 -0.722144 -0.6007594 0.0377877 -0.7957827 0.0662578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4103 4104 -0.767372 -0.138775 0.448254 0.1501078 -0.4164807 0.4098663 0.7975093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4104 4105 0.138151 0.381916 0.980812 -0.0070416 -0.4336316 0.7085322 0.5566832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4105 4106 0.911600 -0.585547 0.235250 -0.1383929 -0.7665138 0.4535989 0.4330728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4106 4107 -0.916699 -0.441620 -0.140425 -0.0950127 0.1968187 -0.8112248 0.5423553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4107 4108 0.884252 -0.250489 -0.479016 0.3106639 0.1203376 0.7721182 0.5411472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4108 4109 -0.677446 -0.654891 0.384464 0.3112451 0.6423137 0.5638621 0.4154745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4109 4110 -0.467208 0.329721 -0.634830 -0.1690235 -0.3932129 -0.6878090 0.5862878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4110 4111 -0.644526 -0.758101 -0.253162 -0.1958792 0.4152365 0.8771259 0.1409257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4111 4112 0.610920 0.403631 -0.510306 0.0527526 0.2508382 0.7780387 0.5735444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4112 4113 0.252356 -1.068580 -0.000601 -0.5386504 -0.2544246 -0.5646150 0.5712564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4113 4114 0.269538 0.386009 -1.013600 0.2345204 0.8758291 -0.1079390 0.4077655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4114 4115 0.341140 0.500711 0.560863 0.2430488 -0.5196802 0.4920128 0.6548153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4115 4116 0.935246 -0.258888 -0.647450 0.6418563 0.4953885 0.5542348 0.1882404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4116 4117 -0.592749 0.020308 0.867559 -0.2412081 0.1277124 -0.6156758 0.7392236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4117 4118 -0.113536 -0.788435 0.289896 0.3920593 0.0247900 0.8254939 0.4052590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4118 4119 -0.393350 0.801153 0.549670 0.3962636 -0.0148218 0.5548728 0.7313492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4119 4120 0.651200 -0.733934 -0.365593 -0.0957291 0.5026206 0.8572220 0.0581280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4120 4121 0.466879 0.637187 -0.522313 0.1904824 0.7522127 0.5505142 0.3079392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4121 4122 0.166388 -0.177892 0.959338 0.1954724 0.7063074 0.4100027 0.5429716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4122 4123 -0.712061 0.587803 -0.088108 0.0564325 -0.6397911 -0.2737929 0.7159051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4123 4124 -0.315381 0.146178 1.130723 -0.1761617 -0.7130976 -0.6103166 0.2966016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4124 4125 0.729152 0.668376 0.198156 -0.1115712 -0.8974867 -0.4263593 0.0169494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4125 4126 -0.455582 0.755307 0.272209 -0.7031043 0.6290645 0.0380322 0.3293565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4126 4127 -0.915001 0.321072 0.004712 -0.2829200 -0.4654563 0.1509849 0.8249304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4127 4128 -0.347120 0.390741 0.958163 -0.2943157 0.4627272 -0.8299886 0.1018861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4128 4129 0.602666 -0.778559 -0.260321 -0.2314283 0.0892484 -0.6129639 0.7501673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4129 4130 0.958339 0.312168 -0.089615 -0.2086642 -0.4232595 0.8806662 0.0416853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4130 4131 -0.781049 0.153981 -0.585151 0.0101426 -0.2733947 0.8032713 0.5290630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4131 4132 0.191815 0.863046 -0.446318 0.0051074 0.2021997 0.6652634 0.7186890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4132 4133 0.963476 -0.334698 -0.021797 -0.0011862 -0.6556963 -0.7330346 0.1808902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4133 4134 -0.910157 0.233086 -0.448811 0.1206310 -0.0552614 0.5591485 0.8183809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4134 4135 -0.141043 0.784372 -0.478267 -0.0795828 0.3485025 0.5596756 0.7476469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4135 4136 0.847738 0.389119 -0.216861 0.1502053 0.3803912 -0.5558171 0.7237460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4136 4137 0.008885 1.088204 -0.015483 0.2438404 -0.5942280 -0.6471820 0.4105975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4137 4138 -0.775123 0.058801 0.477747 -0.4417724 0.2174354 -0.8091877 0.3205842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4138 4139 0.542635 -0.731074 -0.326382 -0.2843025 -0.4212200 0.5493853 0.6632658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4139 4140 0.438373 -0.732443 -0.546974 -0.8479003 -0.0321931 0.5170889 0.1124622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4140 4141 -0.340635 -0.138740 -0.939990 -0.1786319 -0.9593657 -0.1469792 0.1615712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4141 4142 -0.488950 -0.441096 0.839248 -0.8151669 0.3296798 -0.1850137 0.4388440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4142 4143 0.313053 -0.577358 -0.878688 0.2504319 0.3732308 -0.2179685 0.8662981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4143 4144 0.579123 -0.660654 -0.106264 0.1728902 -0.4881794 -0.1747157 0.8374152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4144 4145 0.383057 -0.238785 -0.580513 0.3957482 0.7567956 0.4801233 0.2003130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4145 4146 -0.925185 -0.385902 0.400271 0.2498749 -0.3236803 -0.6785462 0.6102201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4146 4147 0.659289 -0.466684 0.604280 -0.6615979 0.1655333 0.3608049 0.6361656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4147 4148 -0.144236 -0.765373 -0.493658 -0.0094030 -0.2329464 0.0449670 0.9714039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4148 4149 -0.371515 -0.781125 -0.187302 0.5862825 0.0625373 -0.4481981 0.6719229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4149 4150 0.067602 -0.556543 0.821247 -0.2048951 -0.7493132 -0.0418524 0.6283281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4150 4151 0.858124 -0.610854 -0.503268 -0.0223524 0.4163304 0.8904455 0.1824174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4151 4152 -0.804685 -0.364598 -0.593347 0.4590113 -0.0112276 -0.7025249 0.5437291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4152 4153 0.620875 -0.804070 0.317336 0.0706983 0.1308368 -0.8495955 0.5060346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4153 4154 0.348256 0.746442 0.333841 0.2145657 -0.0808203 0.9477348 0.2218749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4154 4155 0.386325 -0.787411 0.053446 0.3063467 -0.2912746 0.6066569 0.6732594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4155 4156 -0.585036 -0.174076 0.869686 0.1717789 0.1270060 -0.5427765 0.8122531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4156 4157 0.013319 -0.763282 0.785042 0.1165836 0.5536403 0.8086816 0.1610115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4157 4158 -0.180909 0.861496 -0.049193 -0.2357049 -0.0373226 0.1026660 0.9656655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4158 4159 0.343570 1.116562 0.311296 0.0554525 0.2030010 0.5559704 0.8041222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4159 4160 0.550221 -0.806754 -0.400044 -0.4475218 -0.1917227 0.1499152 0.8605185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4160 4161 -0.994583 0.393541 -0.152591 0.0257795 -0.2814304 0.3526312 0.8920670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4161 4162 -0.425736 0.792015 0.147610 -0.8153971 0.2979574 0.4939288 0.0488183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4162 4163 -0.650334 -0.386342 0.554624 -0.8034869 0.0966893 0.4851761 0.3311558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4163 4164 -0.837241 0.407771 -0.204713 -0.0079803 0.2198882 0.7739578 0.5937801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4164 4165 0.873974 0.599293 -0.207518 0.1598583 0.3401480 0.7992765 0.4689367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4165 4166 0.430919 -0.728195 0.484854 -0.2866061 0.4477951 0.8339032 0.1481283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4166 4167 -0.543842 0.676743 -0.376810 -0.3253636 -0.8675745 -0.1583540 0.3411408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4167 4168 0.085224 0.307516 0.983631 -0.4971235 -0.5017861 0.7013128 0.0961213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4168 4169 -0.721245 -0.934324 -0.236942 0.6132774 0.5133627 -0.5922858 0.0977094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4169 4170 -0.142817 -0.054543 0.924398 0.6284558 0.3352500 0.2275474 0.6639826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4170 4171 -0.240091 1.128800 0.122296 0.3677963 -0.2235639 -0.6915039 0.5801442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4171 4172 -0.920076 -0.222798 0.088915 -0.1321385 0.0095011 0.1947652 0.9718620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4172 4173 -0.987976 -0.265099 0.051144 0.5905908 0.1672882 0.6400353 0.4621384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4173 4174 -0.070249 0.452731 -0.796903 -0.8078325 0.5538310 0.1310196 0.1533356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4174 4175 -0.135927 0.184016 1.003607 0.8303999 -0.3063161 -0.3857663 0.2603667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4175 4176 -0.543430 0.492196 -0.767375 -0.7039640 0.5355384 0.3693657 0.2849601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4176 4177 0.116318 0.232800 0.863249 0.2902581 0.1943744 -0.6921689 0.6315624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4177 4178 -0.747988 0.188432 0.703363 0.0641094 0.4000473 0.4679992 0.7853846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4178 4179 -0.496713 0.840824 -0.133178 0.0659981 -0.4019532 0.9022090 0.1417632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4179 4180 0.291728 0.869672 -0.287850 -0.0584135 0.1366148 -0.9772848 0.1511245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4180 4181 0.336598 -0.600915 0.590746 -0.5529402 -0.4333363 0.2852561 0.6520013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4181 4182 -0.319377 -0.583749 -0.759247 -0.0395309 -0.4036144 0.2218396 0.8867468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4182 4183 -0.944984 -0.290812 -0.035799 0.5015769 -0.0036135 -0.2047597 0.8405243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4183 4184 -0.482332 -0.710508 0.315259 -0.6243749 0.1149293 -0.7715523 0.0406721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4184 4185 0.854255 0.705932 -0.428140 0.2651082 0.2902731 -0.8889204 0.2351164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4185 4186 -0.596000 -0.166744 -0.853587 -0.4292330 -0.3556872 0.7417022 0.3729926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4186 4187 0.422796 0.891292 -0.116888 0.4185986 0.0132223 0.3389308 0.8424526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4187 4188 0.861699 0.094086 -0.495350 -0.5521328 -0.2660794 -0.7817305 0.1151025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4188 4189 -0.788612 0.062486 0.296141 -0.4148625 -0.1851636 -0.2283829 0.8610719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4189 4190 -0.488676 -0.584523 0.491620 -0.6578825 -0.0020490 -0.3760215 0.6525291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4190 4191 0.318607 -0.608342 -0.608183 0.6903430 -0.0642672 0.0877022 0.7152654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4191 4192 0.134675 -0.760533 0.628255 -0.2872593 -0.8177675 -0.4657118 0.1784685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4192 4193 -0.050943 0.441432 -1.078010 -0.6108388 -0.4622900 0.5156286 0.3837852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4193 4194 0.494590 0.825438 0.166941 -0.5424692 0.8338419 -0.0745571 0.0698287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4194 4195 -0.965595 -0.308292 -0.072105 0.1586754 -0.4029903 0.8562886 0.2814086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4195 4196 0.798427 0.690961 -0.080623 -0.8626652 0.1075487 0.4040098 0.2846369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4196 4197 0.442099 -0.698285 0.211524 -0.2077456 -0.4528618 0.3048781 0.8116695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4197 4198 -0.304388 -0.837950 -0.612031 0.1422726 0.1222858 0.9751810 0.1175870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4198 4199 0.039308 0.443602 -0.923893 0.6850109 -0.0169904 0.5670915 0.4570325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4199 4200 -0.490568 -0.024377 0.746826 0.2730530 0.3401317 0.1546260 0.8864780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4200 4201 0.349736 0.817265 0.346125 0.7228328 -0.0388652 0.6302490 0.2806929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4201 4202 0.588204 -0.499935 -0.057523 -0.1257579 0.0800446 0.8865495 0.4379587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4202 4203 -0.787274 -0.074481 -0.489098 0.1933551 0.7038929 -0.3304115 0.5983117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4203 4204 0.577895 -0.563597 -0.691151 0.5608894 -0.1239407 -0.8172248 0.0467483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4204 4205 0.522312 0.507951 -0.795041 -0.5678063 -0.5222411 -0.4580915 0.4416020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4205 4206 -0.762079 0.404154 0.434436 -0.2959373 -0.2790264 0.5972540 0.6912692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4206 4207 0.561594 0.368246 0.791415 -0.4149943 0.1341747 0.7884641 0.4337064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4207 4208 -0.748523 -0.636090 0.432001 -0.2594366 -0.6399541 0.1695202 0.7031460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4208 4209 -0.134503 -0.763571 0.441812 -0.3305088 0.3373702 -0.6552718 0.5895457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4209 4210 0.801548 -0.253060 0.308515 0.0805197 -0.0864707 0.6099135 0.7836102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4210 4211 -0.024532 -0.941058 0.434521 0.0612201 -0.8103976 -0.4367283 0.3857153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4211 4212 0.573335 -0.342477 -0.692882 0.1195032 0.0283288 0.9316214 0.3420497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4212 4213 -0.642969 -0.217783 -0.742340 -0.2289094 0.1231930 0.9645833 0.0447544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4213 4214 1.105002 0.231004 -0.082349 0.4414416 -0.2585308 -0.7650778 0.3910846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4214 4215 -0.422180 0.142723 -0.881964 0.2680371 0.3431052 -0.2688999 0.8591436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4215 4216 0.193865 -0.599829 -0.871392 -0.0462414 -0.1464819 0.6371195 0.7553036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4216 4217 -0.434080 -0.036951 -0.820012 -0.1848155 -0.0675458 0.6170168 0.7619521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4217 4218 -0.229170 0.622817 -0.639700 0.1402292 0.2444312 -0.4120181 0.8665046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4218 4219 -0.406752 0.292400 -1.138693 -0.3150628 -0.2105445 0.8285204 0.4122625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4219 4220 -0.361980 0.617396 0.496797 0.1411059 0.6670659 -0.0171956 0.7313115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4220 4221 -0.554746 -0.650492 -0.483329 0.5017175 0.1094105 -0.8487397 0.1262926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4221 4222 0.845044 0.234890 0.603570 -0.1903050 0.5291172 -0.5242665 0.6395027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4222 4223 -0.676742 0.046951 0.811352 0.5072003 -0.8282098 0.1914744 0.1419645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4223 4224 0.365615 0.362754 -0.776750 -0.2091933 0.5973355 -0.4120758 0.6554556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4224 4225 0.096817 0.923062 0.281166 0.4192116 0.2029264 -0.6051300 0.6456781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4225 4226 -0.691656 0.175603 -0.580579 -0.5640754 -0.5990907 -0.0129529 0.5681034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4226 4227 -0.536381 -0.191486 0.749210 0.2370235 -0.3317451 -0.0485047 0.9118181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4227 4228 -0.187652 0.221292 0.866588 0.3298563 0.4533241 0.4884074 0.6686930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4228 4229 0.121859 1.009273 0.392261 -0.1450478 -0.2063151 0.2331360 0.9391714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4229 4230 0.510081 0.597336 0.407215 0.3943648 -0.5150655 0.6219182 0.4386361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4230 4231 0.405075 -0.532483 -0.656199 -0.3627982 0.4687983 0.5787402 0.5600584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4231 4232 0.235263 -0.414840 -0.854207 -0.4737601 -0.7263675 0.3202461 0.3812925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4232 4233 -0.961896 0.547551 0.295811 -0.3167811 -0.1817670 0.5583490 0.7448871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4233 4234 0.457661 0.579678 0.706379 -0.1948701 0.0355230 -0.3550305 0.9136285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4234 4235 0.017320 0.329972 0.708704 0.3435751 -0.8558214 0.0930806 0.3753157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4235 4236 0.549217 0.528189 -0.713273 0.1456505 0.5419616 0.6109255 0.5584206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4236 4237 0.568781 -0.802969 0.366746 0.5937059 -0.4493562 0.1187425 0.6568809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4237 4238 0.687837 -0.386649 0.534641 -0.1654064 -0.2394561 -0.5955665 0.7487336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4238 4239 0.646036 0.644427 0.130297 0.1025805 0.1923939 0.9718230 0.0895654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4239 4240 -0.343812 0.689783 0.779927 0.1771069 -0.7317211 0.6422993 0.1437673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4240 4241 -0.384224 0.164741 -0.609094 -0.7754993 -0.0682592 0.6263058 0.0410199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4241 4242 0.380988 -0.102783 0.871221 -0.5920670 0.5335407 0.4979338 0.3418375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4242 4243 -0.544165 -0.464767 -0.465300 -0.4704512 -0.2795014 -0.5457532 0.6345928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4243 4244 -0.648858 -0.359172 -0.760293 0.7323985 0.4440584 0.2677473 0.4412663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4244 4245 -0.437970 -0.870130 0.244394 -0.5211022 0.6905087 0.4648267 0.1886434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4245 4246 0.554152 0.479838 -0.439219 0.6480247 -0.6226911 -0.4162517 0.1380373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4246 4247 -0.464325 -0.826250 0.123280 -0.3275251 0.0364902 0.3296970 0.8847009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4247 4248 -0.866924 -0.166141 -0.245539 -0.4215628 -0.6524316 -0.2309496 0.5859011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4248 4249 -0.401801 -0.942727 0.394949 0.8082632 0.2754904 0.3065294 0.4205417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4249 4250 -0.757150 0.560960 0.099516 -0.5190495 -0.7507647 -0.4020739 0.0726395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4250 4251 0.890644 -0.598080 0.140061 0.0384883 0.7522389 -0.0971527 0.6505510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4251 4252 -0.308222 -0.467516 0.940999 -0.2903197 -0.8012827 -0.2658213 0.4505547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4252 4253 0.643562 -0.265473 -0.721076 -0.0052165 -0.1656852 0.9847450 0.0529011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4253 4254 -0.753093 0.486770 -0.446568 0.8458038 0.0125068 -0.3881153 0.3658223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4254 4255 -0.352258 -0.816667 0.518330 -0.3829930 0.0803783 0.5071772 0.7678717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4255 4256 -0.950637 -0.338579 -0.319530 0.0026382 0.0440234 0.1902958 0.9807357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4256 4257 -0.847702 0.299380 -0.298006 0.4657494 0.0183211 0.5217084 0.7145364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4257 4258 -0.186995 0.572179 -0.659615 -0.2957752 0.8802951 0.2970219 0.2222062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4258 4259 0.512392 0.089702 0.842497 0.3053402 -0.4391440 0.7165663 0.4477194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4259 4260 0.325835 -0.133117 -0.853702 0.0551321 0.9136910 0.3421309 0.2123101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4260 4261 0.944995 0.479239 0.256638 0.0403970 0.5434359 0.7371397 0.3995880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4261 4262 -0.440774 -0.248435 0.949300 -0.8684616 0.2547847 0.0634432 0.4205164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4262 4263 -0.565275 -0.434955 -0.712469 0.1490136 -0.3845718 0.8972462 0.1576348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4263 4264 0.068315 0.931749 -0.445801 -0.4008296 0.5107389 0.1030155 0.7535710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4264 4265 0.000704 0.558784 0.726978 -0.1019772 0.3095811 -0.8614511 0.3894383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4265 4266 -0.430274 -0.819776 0.266128 -0.3636840 0.7487132 0.1761550 0.5254826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4266 4267 0.167768 -0.155808 -1.024109 0.3465385 0.4074393 -0.4686749 0.7030278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4267 4268 0.871339 0.179589 -0.167302 -0.0457813 -0.4272387 0.7169480 0.5489598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4268 4269 -0.502680 -0.424970 -0.668470 0.2736826 0.2841809 -0.9127438 0.1060090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4269 4270 0.889841 0.354631 -0.033430 -0.2797322 -0.0885432 0.9532569 0.0721893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4270 4271 -0.540866 -0.858384 -0.348395 -0.4247759 0.0089254 0.6798735 0.5977104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4271 4272 -0.359484 0.930975 -0.464391 0.4426839 -0.2625374 -0.5937262 0.6185421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4272 4273 -0.847446 -0.486970 -0.132836 0.2387738 0.5951177 0.5912297 0.4891517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4273 4274 -0.234011 0.152093 -1.024358 -0.6648680 -0.2661776 -0.5345136 0.4487708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4274 4275 -1.013691 0.233989 -0.022380 -0.1860189 -0.5471947 0.4420054 0.6860075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4275 4276 0.141307 0.444082 1.030887 0.6206661 -0.0165708 0.6928650 0.3666566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4276 4277 1.085478 -0.035467 -0.126914 0.1374661 -0.4569408 -0.0560021 0.8770245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4277 4278 0.704101 -0.062161 -0.786734 -0.6142458 0.4620225 -0.2671913 0.5812454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4278 4279 0.470540 0.520490 0.586509 -0.1952475 -0.8753363 0.3938091 0.2014425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4279 4280 -0.766049 -0.996128 -0.005353 0.7640036 0.5797770 -0.1653287 0.2298337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4280 4281 -0.755028 0.062748 -0.951914 -0.1701307 0.3051319 0.3169893 0.8817414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4281 4282 0.284116 0.528639 -0.877524 -0.3613723 0.4075013 0.5642149 0.6204952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4282 4283 0.814915 -0.283723 0.281479 0.3022592 -0.1471230 0.7636119 0.5512631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4283 4284 -0.444234 -0.752674 0.498248 0.1224261 -0.2877899 -0.9447258 0.0983972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4284 4285 0.403145 0.896573 -0.028489 0.3825823 0.0231970 0.2119470 0.8989834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4285 4286 0.722341 0.417422 -0.379433 -0.2260073 -0.3066205 -0.2558050 0.8885203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4286 4287 -0.101746 1.090070 -0.393846 -0.1503248 -0.0312221 -0.0919979 0.9838516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4287 4288 -0.349399 0.918898 -0.137312 -0.2054957 0.2899075 -0.9130061 0.2003622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4288 4289 -0.090261 -0.825475 -0.415290 0.0688469 0.5363767 -0.8268145 0.1547186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4289 4290 0.335047 0.796586 0.468683 0.0706814 -0.4116514 0.8283784 0.3732781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4290 4291 0.361050 -0.937078 -0.335662 0.2178745 0.7484707 0.5173441 0.3530970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4291 4292 -0.651632 -0.588474 -0.447043 0.7019454 -0.0300786 -0.7096435 0.0526690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4292 4293 0.390597 0.726886 0.720247 -0.2626872 -0.2121769 0.3138473 0.8873986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4293 4294 0.901120 -0.128468 0.441180 0.8134187 -0.3198242 0.0354838 0.4845652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4294 4295 1.003711 0.039240 -0.415815 -0.4362434 -0.8386779 -0.1426050 0.2932148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4295 4296 -0.672973 0.759422 0.043622 0.2608775 0.9126344 0.3102596 0.0527288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4296 4297 0.801099 0.139485 0.074221 0.1928967 0.7799269 0.5619352 0.1968087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4297 4298 -0.563312 0.310661 0.625796 -0.2089401 0.1927999 0.8705537 0.4016324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4298 4299 0.067949 0.572832 0.856932 0.3562811 -0.0194493 -0.5261365 0.7719235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4299 4300 -0.705433 -0.733179 -0.085518 0.5943152 -0.4157514 -0.0114333 0.6883382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4300 4301 0.490744 -0.915525 0.381402 -0.8091321 -0.1929900 -0.5522443 0.0555551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4301 4302 0.227494 0.743677 0.249021 0.0864981 -0.5279644 0.7908093 0.2973084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4302 4303 0.014618 -0.476459 -0.773947 0.6867894 0.0267550 -0.2071542 0.6961980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4303 4304 0.363113 -0.765818 0.489574 -0.5440558 0.0754739 -0.1710375 0.8179567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4304 4305 0.900191 -0.401923 -0.381427 0.5487482 -0.2362023 -0.5011653 0.6260329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4305 4306 0.955696 0.145778 -0.433467 0.2805436 -0.5050134 -0.8153969 0.0372108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4306 4307 -0.509325 -0.758875 -0.605492 -0.4734766 -0.0528402 0.2471218 0.8437764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4307 4308 -0.593764 0.430478 -0.777423 0.0167156 -0.6421788 0.4119329 0.6462495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4308 4309 -0.123612 0.773106 0.327184 -0.0485053 0.0944183 -0.6894690 0.7164949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4309 4310 -1.129954 -0.069410 -0.008086 -0.1657380 -0.2431705 -0.9517539 0.0869686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4310 4311 0.762509 -0.176791 -0.329303 -0.2217407 -0.2336259 -0.6522421 0.6861707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4311 4312 -0.242994 0.901614 -0.287534 0.2212116 -0.0921223 0.8910907 0.3854040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4312 4313 0.551744 -0.144684 -0.878691 0.0832695 0.4226381 -0.8981656 0.0879876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4313 4314 -0.369025 1.004467 -0.322844 0.3517364 0.0003663 0.8799361 0.3193648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4314 4315 0.673436 -0.597356 -0.631483 0.2093298 -0.3968504 0.7474224 0.4899496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4315 4316 -0.880340 -0.195938 0.051851 0.8994479 0.3490690 0.0663611 0.2544414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4316 4317 -0.948207 -0.277512 -0.345224 -0.6574657 0.4995486 0.5232898 0.2106128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4317 4318 0.337233 0.929767 0.088276 -0.3781989 -0.6340552 0.6716440 0.0619186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4318 4319 -0.056708 -0.231313 -1.012337 0.6910262 0.3019032 -0.5722780 0.3222344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4319 4320 -0.125763 -0.530050 0.926733 -0.0095389 0.4294213 0.8678685 0.2496210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4320 4321 0.802051 0.556276 -0.442902 0.2427600 -0.1502155 -0.9391188 0.1912034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4321 4322 -0.724990 0.029302 -0.783372 -0.0378173 0.0836731 -0.9895592 0.1110910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4322 4323 0.840582 0.069490 -0.742447 0.0368104 -0.1903350 0.2325933 0.9530571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4323 4324 0.335883 -0.203409 -0.921467 0.0774995 0.5765365 -0.8120388 0.0468240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4324 4325 -0.242787 0.956877 -0.173250 0.1232059 -0.0884163 -0.8049865 0.5735848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4325 4326 -0.779584 -0.610357 0.264555 0.7967111 0.1868527 0.0895789 0.5677262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4326 4327 -0.984994 -0.163783 0.149628 -0.1223944 -0.2991104 -0.6780245 0.6601782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4327 4328 0.285381 -0.811882 0.266876 -0.5852895 -0.6391271 -0.2551311 0.4287901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4328 4329 -0.145919 -0.046346 -1.095388 0.9237512 0.3739049 0.0345891 0.0753827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4329 4330 -0.275629 0.017606 0.837982 0.0402711 0.6338940 0.4264207 0.6439892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4330 4331 -0.697506 0.720244 -0.095533 0.1443972 0.5149866 0.7470797 0.3947280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4331 4332 0.843940 0.162728 0.011048 -0.3440624 -0.5152069 0.7610735 0.1922239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4332 4333 -0.331927 0.043172 -0.815398 0.5212129 -0.0291852 -0.4232290 0.7405150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4333 4334 0.056986 -1.112692 -0.136831 -0.0906454 -0.0788909 -0.8804898 0.4585818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4334 4335 0.636482 0.593265 -0.444305 -0.2921044 0.2005560 0.8905486 0.2852640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4335 4336 -0.070057 -0.913465 -0.348754 -0.5815173 -0.3725437 0.3046531 0.6559232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4336 4337 -0.774724 0.371894 -0.550126 -0.0541842 0.1631447 -0.0510491 0.9837895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4337 4338 -0.675387 0.026684 -0.571788 0.0745922 0.1250599 -0.7573672 0.6365461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4338 4339 0.323237 -0.600112 -0.498815 0.0967046 0.8591586 -0.0985917 0.4927214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4339 4340 0.062061 0.694534 0.738647 0.3094036 -0.0689734 0.3300465 0.8891464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4340 4341 -0.496551 0.554087 -0.793331 -0.3658433 0.6551367 0.5066462 0.4245753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4341 4342 0.653259 0.040941 0.382524 0.2300290 -0.3114954 -0.8209220 0.4196955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4342 4343 -0.474305 0.939507 -0.230868 0.3114413 0.1662611 0.1032320 0.9298950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4343 4344 -0.069082 0.305540 -0.598593 0.3829135 -0.4964012 -0.4804583 0.6132886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4344 4345 -0.765260 -0.591021 -0.082806 0.0617734 0.3505185 0.5566131 0.7506681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4345 4346 -0.407690 0.284174 -0.753084 0.2363180 -0.0151676 -0.1146301 0.9647713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4346 4347 -0.567304 -0.123499 -0.616929 -0.1292051 0.8302318 0.4234701 0.3386655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4347 4348 1.106700 -0.036627 -0.277030 -0.3760093 0.8015509 0.4310553 0.1741391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4348 4349 -0.420693 -0.996376 -0.165641 -0.6285087 0.0208296 0.6023596 0.4916359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4349 4350 -0.307771 1.005785 -0.190641 -0.5910502 -0.0137247 0.5367894 0.6019372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4350 4351 0.388673 0.172569 0.752551 -0.4286742 -0.1064753 -0.1881915 0.8772032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4351 4352 0.573266 -0.461114 0.698006 0.6166681 -0.1784992 0.7456411 0.1785439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4352 4353 0.583535 -0.084834 0.836447 -0.2583521 0.3785595 -0.2265240 0.8594380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4353 4354 -0.186586 -0.576949 0.801512 0.0038825 -0.6543183 -0.2225662 0.7227149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4354 4355 1.028574 -0.289891 0.236818 -0.4995187 0.4353127 -0.4828096 0.5726070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4355 4356 0.322646 -0.124985 1.056887 0.0617338 0.3786547 -0.6133612 0.6903605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4356 4357 -0.679631 0.099619 0.795232 0.4860111 0.5068854 -0.6928235 0.1638779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4357 4358 -0.512763 -0.909868 0.462653 0.4576317 -0.0121987 -0.8257294 0.3295381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4358 4359 0.367810 0.420249 0.823484 0.1191479 0.5179424 -0.3973512 0.7480985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4359 4360 0.521296 0.178489 0.884534 0.3150332 0.3808230 0.0474030 0.8680328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4360 4361 0.651031 -0.348793 0.732025 -0.2568063 -0.6447368 0.4046371 0.5955114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4361 4362 0.091680 -0.847171 -0.396251 -0.1443709 0.5338680 -0.4143166 0.7228303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4362 4363 0.968338 -0.451064 0.115732 0.4578628 -0.5300384 -0.2602491 0.6645986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4363 4364 0.687761 0.094177 -0.619017 -0.2074733 0.4336879 -0.8417494 0.2456169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4364 4365 -0.633204 0.969851 0.192755 -0.4760989 -0.5858598 0.3437876 0.5584875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4365 4366 0.712423 0.101588 0.701170 0.6392220 -0.2664637 -0.6209493 0.3671707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4366 4367 -0.313462 0.524313 -0.801789 -0.1209227 0.9301398 0.2860412 0.1959544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4367 4368 0.459006 0.153665 0.790425 -0.1021055 -0.0436073 0.6554081 0.7470696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4368 4369 0.359758 -0.535668 0.694679 0.4700495 0.2772746 0.8089288 0.2186470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4369 4370 -0.009945 0.865621 0.419281 0.0991366 -0.1807906 -0.8600793 0.4666371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4370 4371 -0.542840 -0.348450 0.383399 -0.8020429 -0.3261892 0.0207762 0.4998961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4371 4372 -0.446623 -0.746064 -0.377203 0.4647743 -0.1138828 0.1650553 0.8624224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4372 4373 -0.905824 -0.398692 0.457717 -0.2750533 0.1921966 0.4076936 0.8492303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4373 4374 -0.759544 0.418726 0.033722 -0.0564746 -0.3488595 0.5041878 0.7879736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4374 4375 -0.170419 0.963270 0.401730 0.4782844 0.2830380 0.7114456 0.4300914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4375 4376 1.168064 -0.044347 0.227902 -0.7897930 0.4280362 -0.1233614 0.4216563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4376 4377 0.705092 -0.814128 0.609069 0.5812710 0.0470831 -0.5465687 0.6009741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4377 4378 0.007882 1.070937 0.176432 0.5349217 0.0843571 -0.5465710 0.6387510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4378 4379 -0.721652 0.181236 -0.760041 0.4144967 -0.3492077 0.4858907 0.6856797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4379 4380 -0.450509 -0.016023 0.885435 -0.6386851 -0.3404429 -0.0812606 0.6852567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4380 4381 0.668999 -0.056245 -0.663336 0.3798165 0.0465014 -0.3172804 0.8677040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4381 4382 0.706416 -0.451137 -0.851565 -0.6884058 -0.4992103 -0.5249227 0.0366427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4382 4383 -0.813109 0.374244 0.726024 0.5033728 0.3624847 -0.3614201 0.6961294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4383 4384 -0.869342 -0.169417 -0.266026 0.4120250 0.0100374 0.9080809 0.0743221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4384 4385 0.285514 0.349638 -0.836650 -0.3618262 0.3019579 -0.2095784 0.8567264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4385 4386 0.438271 0.887729 0.014574 0.2803734 0.7427816 -0.5327442 0.2930014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4386 4387 -0.253198 0.850740 -0.917109 0.4770084 0.0811564 -0.6843219 0.5455090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4387 4388 0.227346 -0.747962 -0.754176 0.1043843 0.5553818 -0.7764362 0.2789297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4388 4389 0.465831 0.874091 0.428587 0.0704908 -0.5353672 0.7825797 0.3098097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4389 4390 0.224117 -0.793700 -0.684306 -0.1098787 0.0685437 0.2549433 0.9582444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4390 4391 -0.316230 -0.453988 -0.726685 -0.2994762 -0.3876968 -0.5140396 0.7041083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4391 4392 -0.516114 -0.171239 -0.727459 0.7282030 -0.0639986 -0.5648501 0.3828432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4392 4393 0.814651 -0.508285 0.407231 -0.4319539 -0.2406124 -0.3664894 0.7881668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4393 4394 1.091257 -0.026655 -0.209168 0.4971982 -0.0540217 0.8204259 0.2770864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4394 4395 -0.505065 -0.596590 0.719144 -0.2400514 0.6850727 -0.5285348 0.4401156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4395 4396 0.518702 -0.961871 -0.106132 0.0581735 0.7695549 -0.6192931 0.1444890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4396 4397 -0.448310 0.157892 0.852944 0.7702014 0.4250899 0.3714596 0.2968268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4397 4398 0.497751 0.539751 -0.719548 -0.4365028 -0.7976422 0.1974697 0.3663849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4398 4399 0.174792 0.724626 0.325882 -0.1398036 0.1805562 0.1769675 0.9573593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4399 4400 -3.250967 -14.817370 -11.560391 0.1487003 0.3819962 -0.6761123 0.6122412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4400 4401 -1.049320 0.086016 -0.076678 0.1698431 -0.4165422 0.0096854 0.8930577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4401 4402 -0.672856 0.192806 0.544405 -0.1956502 0.7713908 -0.0177098 0.6052798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4402 4403 -0.495194 0.156200 -0.880086 0.7942160 -0.2872869 0.1039324 0.5252478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4403 4404 -0.881119 -0.124920 0.265343 -0.4764685 0.5984398 0.3944660 0.5091603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4404 4405 -0.178095 0.799758 -0.516876 -0.4179950 0.6202169 0.3563483 0.5600242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4405 4406 0.508751 0.498665 0.678896 0.9725059 0.0401999 -0.2240169 0.0493228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4406 4407 0.267568 -0.558099 -0.790510 0.4052102 -0.0645217 -0.5999150 0.6868359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4407 4408 0.752090 -0.400093 -0.544447 0.0758508 0.1815772 -0.9475635 0.2517933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4408 4409 -0.357428 0.915759 -0.387096 0.0223617 0.2064410 -0.3230830 0.9233090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4409 4410 -0.459987 0.442478 -0.787880 -0.4335006 -0.5804006 -0.2943704 0.6233446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4410 4411 -0.661154 -0.163860 0.693304 0.1601387 -0.0160342 0.1743042 0.9714507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4411 4412 -0.540135 0.386119 0.841847 0.6753638 -0.2240589 -0.2389023 0.6607624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4412 4413 -0.620841 0.508342 0.360725 -0.6178217 0.3361673 -0.6261727 0.3364455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4413 4414 -0.443940 -0.462830 -0.832698 0.3934102 -0.4537989 -0.6153240 0.5105599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4414 4415 0.453662 -0.752995 0.049523 -0.1962402 0.7619824 0.4160292 0.4558424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4415 4416 -0.559298 -0.584140 -0.458274 -0.1234433 -0.2755992 -0.9401222 0.1580415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4416 4417 0.671441 0.192181 -0.849612 -0.2869502 0.5569485 0.7134301 0.3138239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4417 4418 0.306719 -1.071023 -0.167481 -0.7174609 0.2617732 0.6248216 0.1622427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4418 4419 0.260019 0.386905 -0.818817 0.4403296 -0.5254913 -0.4140771 0.5987562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4419 4420 -0.212470 -0.388388 0.715104 0.1774895 -0.9742917 -0.0729596 0.1180256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4420 4421 -0.484460 0.538696 -0.541633 -0.2385959 0.6870153 0.3442835 0.5937600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4421 4422 0.817034 0.619877 -0.094363 0.2410536 -0.3511031 -0.4737505 0.7708308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4422 4423 -0.338622 0.651563 -0.726193 -0.3082151 0.6219359 0.2088522 0.6888977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4423 4424 0.423153 0.978864 -0.032534 0.1915386 0.2041592 -0.7307455 0.6226099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4424 4425 -0.880481 0.283582 -0.107236 0.1546408 0.6131551 -0.2192856 0.7429945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4425 4426 0.016433 -0.262212 -1.066993 -0.0004432 0.4636577 -0.5676844 0.6802616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4426 4427 0.861970 0.281715 -0.342162 0.4534117 0.6570608 0.3377597 0.4986054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4427 4428 0.352985 -0.126011 0.834581 -0.4040885 -0.1331404 -0.1281857 0.8958541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4428 4429 0.586533 -0.811183 0.504277 -0.3890433 -0.4546962 -0.0399703 0.8001869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4429 4430 0.390314 -0.404436 -0.700741 -0.4542980 -0.5862652 0.6390724 0.2036979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4430 4431 -0.214404 1.036743 0.086402 -0.1969827 -0.9247876 -0.0972735 0.3106503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4431 4432 0.367410 0.724065 0.581413 0.3206678 0.1175036 0.2646555 0.9018440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4432 4433 0.723656 0.422416 0.210454 -0.0782465 0.4789102 -0.8589122 0.1636837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4433 4434 -0.918947 -0.208336 -0.145534 -0.3374961 0.3562112 -0.2562424 0.8327964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4434 4435 -0.420537 -0.191558 -0.987276 0.5836334 0.0460715 -0.0819856 0.8065531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4435 4436 -0.277742 -0.941728 -0.118626 -0.1197624 -0.0334892 0.2565485 0.9584979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4436 4437 -0.453046 -0.598417 -0.393498 -0.2550006 -0.0034337 -0.9621586 0.0959884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4437 4438 0.574537 0.805403 -0.466813 0.2907082 -0.4935253 0.7565987 0.3154043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4438 4439 -0.687555 -0.217622 -0.637901 0.4641758 0.7170820 -0.1123280 0.5076579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4439 4440 -0.277420 -0.180168 -1.010637 0.8129715 -0.1825625 0.1224014 0.5392273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4440 4441 -0.631062 -0.160679 -0.747555 0.1433227 -0.2854314 -0.6781592 0.6618819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4441 4442 0.121107 -0.904359 -0.260560 0.0936898 0.3663396 -0.3453702 0.8589161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4442 4443 0.792000 -0.599459 0.287239 0.5444022 -0.2421598 -0.0021284 0.8031067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4443 4444 0.718442 -0.325908 0.390213 -0.1099857 0.4316540 -0.8939265 0.0497330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4444 4445 -0.648747 -0.176270 0.798169 -0.0421179 -0.6818017 0.7300922 0.0183816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4445 4446 0.585831 -0.738121 0.018065 0.0297922 -0.4226664 -0.5075607 0.7502317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4446 4447 0.974274 0.544489 -0.572281 0.1445427 -0.5387272 0.4327010 0.7082727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4447 4448 -0.354764 -0.370666 -0.871947 -0.3992629 -0.3488546 0.8449556 0.0702829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4448 4449 0.612842 0.810172 -0.080782 0.1337297 -0.7884640 -0.6003673 0.0000494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4449 4450 -0.679300 0.072024 0.596850 -0.3031329 0.1302402 0.8421116 0.4266098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4450 4451 -0.182927 0.565522 0.848016 0.0159253 0.7760378 -0.6240314 0.0899804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4451 4452 0.025264 -0.659804 -0.820375 -0.3334069 -0.1201468 0.6516357 0.6706530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4452 4453 -0.477696 0.612096 -0.628951 0.7282265 -0.6674723 -0.0750099 0.1361631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4453 4454 -0.497867 0.271383 0.705874 0.3070507 0.3739464 0.7780145 0.4007210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4454 4455 0.323268 0.796153 -0.027376 0.2910362 0.2327644 -0.6146188 0.6952427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4455 4456 -0.803498 0.548051 -0.687370 0.3556995 -0.4134232 -0.6304601 0.5523396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4456 4457 -0.592891 -0.681284 0.495843 -0.3019807 0.4559420 0.0546791 0.8354249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4457 4458 -0.586948 -0.649834 -0.546054 0.2112819 -0.9315215 -0.0236095 0.2950765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4458 4459 0.382189 -0.632978 0.814672 -0.5713618 -0.2644020 -0.7677400 0.1192165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4459 4460 -0.710874 0.328207 0.536027 -0.0873677 -0.3735305 0.0685487 0.9209468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4460 4461 -0.758284 -0.639078 0.212443 -0.2791736 0.3970744 -0.1877724 0.8538943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4461 4462 -0.141455 -0.786909 -0.544288 -0.1851863 0.0626025 -0.4728043 0.8592107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4462 4463 0.447217 -0.283396 -1.106058 0.8522992 0.0348428 0.4987682 0.1536303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4463 4464 -0.458057 -0.015875 0.833061 -0.3885212 0.1583430 0.5040300 0.7549388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4464 4465 -0.974207 0.301278 0.671647 0.2898279 0.8349694 -0.1871391 0.4287246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4465 4466 0.129082 -0.743801 -0.801877 -0.0042489 -0.0643624 0.4958897 0.8659866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4466 4467 -0.670031 -0.505371 -0.646485 0.0666222 0.0080562 -0.3158272 0.9464406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4467 4468 -0.162393 -0.770423 -0.784654 0.4260980 -0.1953501 -0.7644427 0.4426129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4468 4469 0.957849 -0.139453 -0.017547 0.5694851 0.0548301 0.6306084 0.5244172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4469 4470 0.043553 -0.720537 0.747129 0.5280573 0.7774312 0.2396272 0.2435878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4470 4471 -0.778139 0.230846 -0.490879 0.0427567 0.0533720 -0.1629152 0.9842672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4471 4472 -0.794855 -0.029352 -0.807545 -0.3354162 -0.0490218 0.2832031 0.8971560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4472 4473 -0.473037 0.658286 -0.183621 -0.2396640 -0.8046584 -0.5297437 0.1202399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4473 4474 0.505390 -0.487736 0.878518 0.3101900 0.1973205 0.8923806 0.2617321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4474 4475 0.067204 0.534814 0.825415 -0.2569121 0.7775726 -0.4147952 0.3966383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4475 4476 -0.548709 -0.788724 -0.612159 0.8529121 0.0787263 -0.4563216 0.2410680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4476 4477 0.387560 0.059657 1.086108 -0.2044274 -0.8395991 -0.0843100 0.4961598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4477 4478 0.696777 0.058486 -0.752903 0.0166684 -0.2989231 -0.7946111 0.5281669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4478 4479 -0.840287 0.419339 -0.591893 -0.0561134 -0.4283314 -0.7084271 0.5581348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4479 4480 -1.041473 0.336952 0.120928 0.1260688 0.3433457 -0.3858866 0.8469427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4480 4481 -0.307543 0.906395 -0.371530 -0.3366903 -0.6172169 -0.0582764 0.7087220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4481 4482 -0.127139 0.771021 0.688489 -0.2661892 0.5042489 -0.5891797 0.5724890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4482 4483 -1.039960 -0.646348 0.206644 0.4759740 -0.6427326 0.4281464 0.4207543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4483 4484 0.470585 0.728255 0.623529 0.4994434 0.3075230 0.8079669 0.0563495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4484 4485 0.492255 -0.123656 0.885504 -0.4869020 -0.2941017 -0.0414642 0.8214082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4485 4486 0.849567 -0.484958 -0.223268 0.2974518 0.1479545 0.1757962 0.9266756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4486 4487 0.415730 -0.562030 0.435490 -0.1800001 -0.6905263 -0.3409048 0.6120109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4487 4488 0.622181 -0.056998 -0.753168 -0.5499542 -0.0645156 0.5164894 0.6531667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4488 4489 0.659584 0.403172 -0.625088 0.2927887 0.6925154 -0.1854231 0.6327049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4489 4490 0.764095 0.715682 0.347053 -0.4504868 -0.6510013 0.5891572 0.1617182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4490 4491 -0.022375 -0.172486 -1.082150 0.6145557 -0.2276266 0.2357104 0.7175988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4491 4492 -0.559471 -0.667165 -0.203186 -0.2663532 -0.6209032 0.1242005 0.7267114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4492 4493 -0.616088 -0.585590 0.319791 -0.3378663 0.6843580 0.0881678 0.6400991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4493 4494 -0.345394 -0.040304 -1.030045 0.1275726 -0.4508027 0.3630653 0.8054103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4494 4495 -0.852743 0.142942 -0.194628 0.2005418 0.2668487 0.4045020 0.8514416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4495 4496 -0.251407 0.710110 -0.886235 0.4087582 -0.2675267 -0.6846142 0.5409710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4496 4497 -0.070697 -0.888532 -0.303789 0.4522319 -0.5148095 -0.7260674 0.0573020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4497 4498 0.966402 0.366084 -0.766046 -0.8991936 0.0352023 0.0129622 0.4359400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4498 4499 0.886218 0.151474 0.576686 -0.3568857 -0.2769450 0.8576759 0.2456136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4499 4500 0.577527 -0.767333 0.559019 -0.5795992 0.1527757 0.4304105 0.6748860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4500 4501 0.330926 -0.903604 0.394398 0.6447929 -0.5653527 0.0171899 0.5141234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4501 4502 1.024935 -0.180808 0.021985 -0.2122694 0.8825840 0.2358147 0.3469561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4502 4503 -0.577451 -0.536844 0.517343 -0.1978974 -0.5097973 0.4427440 0.7105780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4503 4504 -0.498156 -0.573286 0.827449 0.3811818 0.7742543 0.3548958 0.3595549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4504 4505 -0.459823 0.301680 -0.883854 -0.7696914 0.3872895 0.1117613 0.4950671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4505 4506 -0.078426 0.792302 0.601424 -0.1388105 -0.0988467 0.9520759 0.2539931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4506 4507 0.356049 -0.784892 0.573076 0.1936957 -0.3237353 -0.8813251 0.2845057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4507 4508 0.217465 1.030455 -0.108867 -0.0864594 0.3197369 0.3774084 0.8647867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4508 4509 0.957465 0.617479 0.151227 -0.4681878 -0.3747437 -0.4830748 0.6379703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4509 4510 0.440819 0.764325 0.575056 0.0979044 -0.7803104 0.1603357 0.5965090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4510 4511 0.510200 0.402243 -0.654388 0.2971546 -0.3204769 0.7679691 0.4682064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4511 4512 -0.588984 -0.187409 -0.686016 -0.0998569 -0.5942493 -0.0281173 0.7975624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4512 4513 -0.939874 -0.305431 0.466464 0.4234240 -0.1534731 -0.6503041 0.6117702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4513 4514 0.069301 -0.301523 1.077644 -0.1133794 0.5290112 0.6953111 0.4731118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4514 4515 -0.782884 0.495781 0.198145 0.0704306 -0.0305575 0.4694307 0.8796253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4515 4516 0.016944 1.169446 -0.091267 -0.4857462 -0.0057080 0.6148861 0.6212351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4516 4517 0.699820 -0.289068 0.761196 -0.1897308 0.2615758 0.9445504 0.0583518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4517 4518 -1.029145 0.529626 -0.005435 -0.4085741 0.3693339 0.5988510 0.5814096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4518 4519 0.145173 0.843438 0.521479 -0.1092606 -0.7901854 0.5944882 0.1012568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4519 4520 -1.083564 0.029903 -0.070205 0.0214251 -0.1481255 -0.0759093 0.9858182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4520 4521 -0.122125 0.352956 0.813451 -0.4442727 -0.1329003 0.8841451 0.0569798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4521 4522 -0.722631 -0.564266 0.506542 -0.7691476 0.0498835 0.6369881 0.0130262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4522 4523 -0.450778 0.616780 0.480983 0.8381340 0.3170130 -0.3546510 0.2669398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4523 4524 -0.716635 -0.596962 -0.719582 0.0636339 -0.6922683 0.1734279 0.6975945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4524 4525 -0.702117 -0.485118 0.668211 -0.2002548 0.7885443 0.5692344 0.1186091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4525 4526 0.336657 0.809891 -0.599247 -0.4655866 -0.1206492 -0.0490748 0.8753654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4526 4527 -0.100637 0.948290 0.293256 0.0937994 0.3575591 -0.4163760 0.8306528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4527 4528 -0.694962 0.506354 -0.258689 0.8687027 0.1479939 -0.3464192 0.3216320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4528 4529 -0.347610 -0.967291 0.334057 -0.0027499 0.2495252 -0.6678464 0.7012209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4529 4530 0.722803 -0.386519 0.208916 0.1190035 -0.9400035 0.1683112 0.2718510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4530 4531 -0.532845 -0.668860 -0.566187 0.1364190 -0.2575533 -0.8307500 0.4742475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4531 4532 0.839634 -0.144456 -0.283812 -0.7244700 -0.0903260 0.4066581 0.5491936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4532 4533 0.685749 -0.031362 -0.700521 -0.3405612 0.0655853 0.1571779 0.9246685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4533 4534 0.677424 0.363650 -0.462478 0.7936755 -0.0353435 0.2856209 0.5359578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4534 4535 0.403324 -0.866269 0.162969 -0.6877166 -0.1229664 -0.4019820 0.5918916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4535 4536 0.915380 0.398956 -0.455227 -0.0163924 0.9120595 0.0197468 0.4092540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4536 4537 -0.173042 0.381698 0.882649 0.4835587 -0.7403173 -0.3560205 0.3022428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4537 4538 -0.319521 0.973322 -0.147740 -0.7823876 0.0799511 -0.3386521 0.5165193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4538 4539 -0.841270 -0.115180 0.551153 0.4366077 -0.1993250 0.1872350 0.8570801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4539 4540 -0.239562 -0.705842 0.606983 0.6976306 0.2713440 0.3635823 0.5545195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4540 4541 -0.162860 -0.214992 1.030813 0.4185074 0.4077614 0.5321314 0.6127138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4541 4542 -0.570049 0.983399 0.121751 -0.2445317 -0.1740036 0.8627192 0.4069921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4542 4543 1.057763 -0.356579 0.314579 0.5559810 0.0973281 -0.5063619 0.6519279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4543 4544 0.389483 0.835972 -0.161396 -0.2928404 -0.0555682 0.5268204 0.7960006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4544 4545 1.011659 -0.067773 0.126592 0.4086798 -0.3678359 0.8095833 0.2055542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4545 4546 -0.354336 -0.604812 0.611178 0.1235125 0.3393448 0.9150522 0.1796362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4546 4547 0.071012 1.122948 -0.086234 0.2313709 -0.3876696 -0.1460646 0.8802527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4547 4548 -0.338755 0.746850 -0.460698 -0.1048084 -0.7043951 -0.5678138 0.4128320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4548 4549 -0.315341 -0.270021 0.789998 -0.1297881 -0.0666985 0.8432402 0.5173512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4549 4550 -0.440557 0.455024 0.734777 0.1259013 0.2475916 0.8314875 0.4811193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4550 4551 0.645287 0.544487 0.563523 -0.0624137 -0.5738456 0.7746149 0.2584136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4551 4552 -0.060860 -0.761788 -0.599540 -0.1888611 0.1614150 0.1296751 0.9599276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4552 4553 -0.183263 -0.571278 -1.008835 0.1257216 -0.1892932 0.1201412 0.9663996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4553 4554 -0.382378 -0.723160 -0.555006 0.3379281 -0.5251995 0.3934566 0.6746569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4554 4555 -0.640154 0.105586 0.724738 0.5673875 0.2314034 0.2734381 0.7414550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4555 4556 -0.488578 0.786106 -0.208126 -0.2761198 -0.3994260 -0.1898121 0.8533394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4556 4557 -0.552578 0.385233 0.620972 -0.4752243 0.4534075 -0.3309486 0.6775371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4557 4558 -0.652825 -0.583347 -0.469863 0.3520774 0.4984976 0.2144986 0.7625825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4558 4559 -0.318901 -0.866654 -0.665581 0.5368367 -0.0399106 -0.8333406 0.1255262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4559 4560 0.530179 -0.982392 0.123475 -0.2998941 -0.1549097 0.7746091 0.5348339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4560 4561 -0.178395 0.787755 0.329272 0.4202677 -0.4868746 -0.3270257 0.6923745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4561 4562 -0.707681 0.706539 0.063637 0.3185186 0.5465742 -0.0382116 0.7735259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4562 4563 -0.279991 0.327741 -1.160266 -0.4847807 -0.8441498 -0.1444030 0.1776132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4563 4564 -0.232714 -0.182999 0.795883 -0.1457463 0.2954992 -0.4986483 0.8017407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4564 4565 -0.415243 -0.882033 0.458979 0.1829386 0.0491653 0.9633463 0.1899476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4565 4566 0.088582 0.878645 0.398592 0.1354674 0.7757850 -0.5882756 0.1836792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4566 4567 -0.323313 -0.125150 -0.938499 0.3557793 -0.5636590 -0.5956452 0.4482370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4567 4568 0.271659 -1.030742 0.051514 -0.2963867 0.5179278 0.1230626 0.7929447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4568 4569 -0.080576 -1.012106 -0.270429 0.4097554 -0.5243121 -0.7167053 0.2086404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4569 4570 0.760921 0.009811 -0.658413 -0.8234650 0.0225527 -0.3031945 0.4790301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4570 4571 0.443580 0.492291 0.730537 0.3226977 -0.6436331 0.6452580 0.2554304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4571 4572 0.100772 -0.837964 -0.524374 -0.1847057 -0.1476041 0.7071657 0.6663434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4572 4573 -0.684490 -0.086012 -0.629145 -0.0074354 -0.3899268 0.2125818 0.8959413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4573 4574 -0.717327 0.599200 -0.028312 0.7376147 0.0831311 0.1281154 0.6577235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4574 4575 -0.593307 0.241166 -0.898384 -0.6165069 -0.2093986 -0.5324338 0.5409119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4575 4576 -1.053325 -0.179286 -0.226562 0.3269940 -0.1965886 -0.8400906 0.3855848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4576 4577 0.707720 -0.548438 0.627841 -0.4228885 -0.6953952 -0.0893875 0.5741086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4577 4578 -0.105688 0.057052 -0.886560 -0.2835472 0.8876993 0.0805059 0.3537086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4578 4579 0.776846 -0.021305 0.920756 -0.6775175 -0.4494926 0.2257855 0.5366072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4579 4580 0.922046 0.085874 0.408933 0.4049577 -0.3766929 -0.4473504 0.7028438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4580 4581 -0.669625 0.642824 0.620750 0.2888103 -0.0703039 -0.2493113 0.9216777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4581 4582 -0.720884 0.624658 0.377014 -0.3680396 0.4553027 0.3141468 0.7473674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4582 4583 -0.632120 0.773260 0.295001 0.4472369 -0.3335141 -0.8297999 0.0134011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4583 4584 -0.169083 -0.291168 0.960386 -0.3344531 0.3888211 0.2234816 0.8288638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4584 4585 -1.029816 -0.625164 0.151772 -0.1733204 -0.1533770 -0.6343307 0.7376042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4585 4586 0.528795 -0.844914 -0.060751 0.0631140 -0.7933683 0.5294224 0.2937605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4586 4587 -0.706479 -0.374540 0.949542 -0.5374157 0.2384431 -0.3156332 0.7447852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4587 4588 -0.115016 -0.876063 -0.515466 -0.0297423 -0.6352594 0.7035051 0.3172405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4588 4589 -0.341079 0.440530 0.781705 -0.1720108 -0.8912922 0.3149904 0.2771130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4589 4590 0.882057 -0.239925 -0.507749 0.6159344 0.5926945 -0.1717203 0.4897451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4590 4591 0.712401 0.359779 0.919306 -0.1179995 -0.3894961 0.0181323 0.9132580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4591 4592 1.175827 0.210929 0.424500 -0.2088839 -0.1876097 0.8323313 0.4779066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4592 4593 -0.138568 -0.895100 -0.308408 -0.0301564 -0.0570172 0.9469894 0.3147232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4593 4594 -0.364636 1.033925 -0.051845 -0.3465480 0.3189516 -0.7349481 0.4878787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4594 4595 -0.708168 -0.402244 -0.390642 -0.2968794 0.7802630 -0.5498376 0.0270365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4595 4596 0.786209 0.662613 0.116329 0.1727348 0.1235372 0.8928287 0.3971877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4596 4597 -0.034070 -0.804797 0.592871 -0.1710943 -0.0318460 0.5907942 0.7878292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4597 4598 -1.039314 -0.388674 0.218366 0.0709364 -0.4080278 -0.3128095 0.8547699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4598 4599 -0.248975 -0.702958 0.806355 0.3112843 0.7872728 0.3420319 0.4078208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4599 4600 0.512328 0.457047 -0.590579 -0.4966841 0.1650561 -0.1838769 0.8320160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4600 4601 0.787330 -0.311244 0.390012 0.2891511 0.3733721 -0.8814598 0.0036773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4601 4602 -0.961859 0.104531 0.311922 0.3464965 -0.3090349 -0.4927178 0.7359802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4602 4603 -0.243553 -0.179767 0.841638 0.1639316 -0.2997599 0.9395170 0.0240452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4603 4604 0.521279 -0.157700 0.738143 0.5467125 -0.6064873 0.3660623 0.4464045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4604 4605 0.778030 -0.623928 -0.101917 0.1085234 0.7744927 0.0962593 0.6157255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4605 4606 -0.354003 -0.350003 0.942095 0.5678818 0.2189006 -0.7407878 0.2842994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4606 4607 -0.621692 0.327913 0.532907 0.0980199 -0.1395660 -0.0864592 0.9815489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4607 4608 -0.391383 0.272963 0.859497 0.7523541 0.2933069 -0.5740095 0.1358214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4608 4609 -0.710187 -0.584102 -0.004882 0.2275396 -0.6815502 -0.6902618 0.0851688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4609 4610 0.832865 0.174793 -0.411896 0.4740991 -0.0052230 -0.5225986 0.7085855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4610 4611 0.429196 0.509822 -0.933145 -0.1569528 -0.4924565 0.5684103 0.6401267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4611 4612 0.106327 0.523185 -0.885398 -0.0408518 -0.3512185 -0.8208923 0.4484557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4612 4613 -0.731127 -0.739645 -0.388027 -0.5113911 0.2841021 0.5193901 0.6228956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4613 4614 -0.021369 0.702296 -0.755916 -0.4877337 0.6374164 0.4285723 0.4148999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4614 4615 0.435570 0.217531 0.818771 -0.8545258 -0.3759966 -0.0798544 0.3493358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4615 4616 0.817927 -0.138346 -0.787509 -0.2685716 -0.2782911 0.9160060 0.1065658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4616 4617 -0.382880 0.524619 -0.565276 -0.0032305 0.6181629 0.6970023 0.3633896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4617 4618 0.766485 -0.446852 0.083739 0.1213893 0.1836847 -0.0696626 0.9729706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4618 4619 0.782148 -0.073714 0.429915 0.4120247 -0.4449716 -0.7547562 0.2501579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4619 4620 -0.337056 -1.015853 -0.016910 -0.5940010 -0.6927461 0.2493216 0.3241982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4620 4621 -0.297570 -0.250389 -1.177658 0.5407485 -0.3839755 -0.1217906 0.7384585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4621 4622 -0.487625 -0.933308 0.457624 0.0727584 0.2137157 0.9701246 0.0888263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4622 4623 0.285609 1.142896 -0.218969 -0.7011345 -0.6488874 0.2140884 0.2037690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4623 4624 1.106557 0.352551 -0.047296 0.1136242 0.1026097 0.9197296 0.3614668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4624 4625 -0.604794 -0.884858 0.104814 -0.2038797 -0.0911308 0.1484564 0.9633737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4625 4626 -0.946279 -0.531764 0.084761 -0.2333308 0.1929727 -0.5851258 0.7522939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4626 4627 0.456593 -0.435820 -0.479419 0.7043849 -0.4321396 -0.4313234 0.3620184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4627 4628 0.960665 -0.264256 -0.131631 -0.7092461 -0.2783156 -0.6159953 0.2001505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4628 4629 0.018602 0.725645 0.522960 0.7237210 0.2250897 -0.1519213 0.6344151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4629 4630 -0.276831 0.457900 -0.905807 -0.3983966 0.4695370 0.4258956 0.6628938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4630 4631 1.087648 0.212224 -0.157418 -0.1014570 0.4706127 -0.1890967 0.8558461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4631 4632 0.491509 0.527332 0.674673 -0.4019771 -0.3014838 0.6830809 0.5300212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4632 4633 0.141600 -0.748090 -0.018972 0.4751237 -0.7339183 -0.1628642 0.4572708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4633 4634 0.812829 -0.727652 -0.139350 -0.7185590 -0.2329719 -0.3086275 0.5780537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4634 4635 0.492986 0.714091 -0.653198 0.2375862 -0.1674550 -0.5104044 0.8093201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4635 4636 -0.323085 0.231747 -0.814388 -0.8259679 0.0465604 -0.3583267 0.4326790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4636 4637 -0.859581 0.535993 0.281954 0.6805024 -0.0920908 -0.3571966 0.6331243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4637 4638 -0.987815 0.112918 0.058980 -0.3208053 -0.1556429 0.8892958 0.2863777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4638 4639 0.334836 0.365866 0.777343 0.3378038 -0.4618089 -0.0779477 0.8164223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4639 4640 0.587128 -0.694120 -0.519349 0.0017880 0.6107661 0.1078504 0.7844296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4640 4641 -0.208414 -0.748060 -0.609646 0.4846457 0.1446611 -0.7905342 0.3453221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4641 4642 0.981715 -0.020392 0.342543 -0.6111326 -0.2931317 0.5134200 0.5262990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4642 4643 0.128062 -0.564033 -0.770609 0.6179212 -0.4054144 -0.4341326 0.5151131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4643 4644 0.625164 -0.764482 -0.055549 0.0007918 -0.1633680 0.9743243 0.1549274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4644 4645 -0.938652 0.651534 0.458722 0.4214520 0.0750463 -0.8664394 0.2569611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4645 4646 0.045582 -0.875463 0.596582 0.3496015 0.3453821 0.0211463 0.8706565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4646 4647 -0.459295 -0.139700 0.864398 -0.7566110 -0.2821362 -0.0366926 0.5887212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4647 4648 -0.347213 -0.942264 -0.568180 -0.1209632 -0.2509041 0.9016639 0.3307828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4648 4649 -0.486299 0.814702 0.099821 -0.4897114 -0.4148981 -0.1715011 0.7474153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4649 4650 -0.095180 -0.160355 0.826615 -0.0016549 0.1951554 -0.8499877 0.4893184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4650 4651 -0.233157 -0.275207 0.995643 -0.1038354 0.5861234 0.4156969 0.6876581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4651 4652 -1.059222 0.113041 -0.161599 -0.3830026 -0.3851656 0.1826630 0.8195064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4652 4653 -0.480244 -0.053232 0.976827 -0.3256095 0.4028219 -0.7988290 0.3059171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4653 4654 0.470875 -0.993057 -0.169100 -0.3570591 0.3757711 0.8447769 0.1328790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4654 4655 -0.295608 0.346037 -1.087101 -0.5679981 0.0521807 0.1857669 0.8000913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4655 4656 -0.038823 0.969599 -0.068922 0.5286334 -0.5239571 -0.6585949 0.1107634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4656 4657 -0.727637 -0.672808 0.396861 -0.0349993 -0.8837460 -0.2356339 0.4027962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4657 4658 0.920008 -0.522589 0.162100 -0.5744179 -0.4391207 -0.4355275 0.5362208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4658 4659 0.180968 0.803646 -0.447463 -0.0956248 -0.0768980 -0.9885023 0.0883505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4659 4660 0.894321 -0.421904 -0.036083 0.6678906 0.0885465 -0.6505568 0.3505102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4660 4661 -0.692954 -0.494871 -0.812363 -0.7480136 -0.4935347 0.4276803 0.1182734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4661 4662 0.029918 0.463906 0.900290 0.1167196 -0.1228081 -0.1477160 0.9744099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4662 4663 0.193858 0.566901 0.869514 0.1136342 0.2297857 0.9624730 0.0890586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4663 4664 -0.046158 -0.107263 0.985648 0.0127524 -0.5956702 -0.5716866 0.5640824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4664 4665 0.684193 0.606060 0.371638 0.3433950 -0.5839135 -0.7047673 0.2107792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4665 4666 -1.072554 0.038315 -0.126584 0.1677045 -0.0108850 0.8724693 0.4588616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4666 4667 0.411531 0.610704 -0.381296 -0.8390410 0.4736269 -0.0774396 0.2563023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4667 4668 0.000248 -0.384249 0.791866 0.3324152 -0.2474562 0.7725950 0.4810016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4668 4669 0.445249 0.556365 0.850425 0.2073276 -0.7643978 -0.0150804 0.6103145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4669 4670 0.625630 0.347578 -0.759407 -0.3065957 0.5354513 -0.4907123 0.6152174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4670 4671 -0.373932 1.044286 0.132231 -0.1827600 0.3157521 0.1733213 0.9148000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4671 4672 -0.202247 0.910585 0.384558 0.3565722 -0.2375954 -0.3054480 0.8503565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4672 4673 -0.535640 0.836497 -0.137209 -0.5354637 0.0641223 -0.1912289 0.8201210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4673 4674 -0.785113 0.118629 0.529617 0.1077680 0.3051574 -0.9086429 0.2638807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4674 4675 0.372985 -0.848718 0.153948 0.2533906 0.3902430 -0.4125989 0.7831129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4675 4676 0.441230 0.112010 1.027290 -0.3588188 -0.3327462 -0.8718979 0.0179750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4676 4677 0.271672 0.602508 0.659598 0.6667792 0.2021638 0.6245112 0.3528755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4677 4678 0.988952 0.104815 0.142708 0.3197248 -0.5187247 -0.6512705 0.4522692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4678 4679 -0.466869 0.483430 -0.752718 -0.4048496 0.7059051 0.4610728 0.3538455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4679 4680 -0.245829 -0.940138 0.418948 -0.2210192 0.1053232 -0.9189017 0.3093173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4680 4681 0.533001 0.209730 -0.880935 0.4503952 0.1343502 0.8658986 0.1712127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4681 4682 -0.877312 -0.396095 -0.041094 -0.4399667 0.3887708 0.0173389 0.8093120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4682 4683 -0.367926 0.025622 -0.972834 -0.5637196 0.2741686 0.7160763 0.3070610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4683 4684 0.899964 0.236943 -0.002560 -0.5020104 -0.5227290 -0.1461730 0.6733301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4684 4685 0.603284 0.616802 -0.312429 0.3532492 0.0926952 0.2477393 0.8973561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4685 4686 0.845910 0.024169 -0.485810 0.5653569 -0.0070035 -0.5798147 0.5866323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4686 4687 0.626581 0.342040 -0.738543 -0.3902728 0.0332028 -0.8332840 0.3901571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4687 4688 -0.793539 0.499905 -0.102894 -0.1697537 -0.4519244 0.8716823 0.0843677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4688 4689 1.000021 -0.163230 -0.078315 -0.0699235 -0.2827781 -0.7787679 0.5555788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4689 4690 -0.135120 0.868013 -0.619331 -0.1815602 0.0621483 -0.9694281 0.1529139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4690 4691 -0.300055 -0.784516 -0.689856 0.2873968 -0.0556374 -0.8997539 0.3236517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4691 4692 0.823766 0.139490 -0.087265 -0.0690295 0.0841022 -0.9437247 0.3123227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4692 4693 -1.044039 0.520575 0.031992 -0.0819448 -0.7185354 -0.0844735 0.6854606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4693 4694 0.122147 0.013120 0.941334 0.2520978 0.6491512 -0.3418607 0.6310157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4694 4695 -0.962704 -0.018903 0.028805 -0.1874452 -0.4352675 -0.4397322 0.7629168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4695 4696 -0.369154 -0.967371 0.403860 0.0000654 0.2840085 -0.8592526 0.4254693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4696 4697 0.592795 -0.176707 0.581295 0.3122097 -0.7359578 -0.6007159 0.0056209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4697 4698 -0.835252 0.565538 -0.508408 -0.2589094 0.8450086 -0.0689681 0.4627848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4698 4699 0.433539 0.773291 -0.390510 -0.0655648 -0.2049072 -0.6681214 0.7122697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4699 4700 -0.311473 -0.539851 -0.914037 0.7130297 0.3088077 -0.5682416 0.2707914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4700 4701 -0.161973 1.084676 -0.209138 -0.1267567 -0.7345208 0.1567981 0.6479400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4701 4702 0.241106 1.071250 0.009875 -0.0939084 0.8873989 -0.3882456 0.2301515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4702 4703 -0.430928 0.884880 -0.776100 -0.4428432 -0.6733992 0.0319679 0.5911019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4703 4704 -0.087398 0.481893 0.930677 0.4918748 0.3437553 -0.0138579 0.7998121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4704 4705 -0.555278 0.781988 -0.294073 0.0039307 -0.4663457 0.8842546 0.0244941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4705 4706 0.438854 -0.313151 -0.886964 0.3899967 -0.4718778 0.6998060 0.3681107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4706 4707 -0.974553 0.048867 0.350271 0.6290280 0.3150773 -0.7105562 0.0126510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4707 4708 0.004934 -0.402270 0.988814 0.6466276 -0.6197744 -0.4158423 0.1575679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4708 4709 0.213694 0.711264 -0.542227 -0.7474311 -0.4686440 0.4091653 0.2330307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4709 4710 0.827918 0.327533 0.071403 0.3243613 -0.6010181 0.2399055 0.6899365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4710 4711 0.411044 -0.402270 -0.644952 0.1594108 -0.3337209 0.7143421 0.5940824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4711 4712 -0.919200 -0.068188 -0.387624 -0.3104687 0.0384410 -0.8021136 0.5086700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4712 4713 0.167709 -0.552978 -0.767664 -0.2446818 -0.0307672 -0.9362458 0.2502560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4713 4714 -0.294194 0.434925 -0.990762 0.1627233 0.6764082 0.5153717 0.5003849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4714 4715 0.959575 -0.358483 0.076066 -0.9182694 -0.0640155 -0.1405504 0.3645942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4715 4716 0.856523 0.463694 -0.154755 -0.4913378 0.5751806 -0.2093736 0.6196104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4716 4717 -0.096650 0.065880 0.869558 0.5446989 0.6605477 0.2166287 0.4690967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4717 4718 -0.402951 0.730082 -0.612838 0.4854642 -0.2608243 -0.8301791 0.0842488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4718 4719 0.433582 -0.596623 0.262540 -0.0934801 -0.3880445 0.6449984 0.6516594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4719 4720 -0.198113 0.572306 0.572104 0.6236579 0.0199961 0.7008509 0.3456285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4720 4721 0.097128 -1.061444 0.275704 -0.1346492 -0.5825044 -0.5560104 0.5774173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4721 4722 0.724896 -0.318374 -0.612498 -0.9699346 0.1767684 -0.0697459 0.1520373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4722 4723 0.544164 0.102013 0.658798 0.6984350 0.4659635 0.4708069 0.2709382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4723 4724 0.575157 0.754574 0.189408 -0.6012807 0.2848234 0.6637766 0.3416690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4724 4725 -0.320131 -0.862179 0.470754 -0.5734528 0.1870005 -0.7483479 0.2759678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4725 4726 1.003774 0.342269 -0.124344 0.9180084 -0.2519698 0.2508955 0.1755655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4726 4727 0.432473 -0.789153 0.241771 0.0086458 -0.4698109 -0.8775549 0.0953960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4727 4728 -0.141839 0.700863 -0.748247 -0.2548930 -0.7162128 -0.4517702 0.4668753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4728 4729 -0.680332 -0.097526 0.848624 -0.5307025 0.3640204 -0.4276593 0.6347847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4729 4730 -0.389342 -0.787500 -0.782489 0.1761086 0.6179184 0.4220433 0.6395640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4730 4731 -0.115619 -0.748345 -0.492897 -0.6163377 -0.1960700 0.6844086 0.3365550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4731 4732 -0.178694 0.964409 0.038850 -0.5556382 0.1552285 0.2004710 0.7918217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4732 4733 -0.220481 0.383355 0.902443 -0.4371735 -0.7465132 0.3962517 0.3075419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4733 4734 0.521924 -0.852634 -0.459505 0.0391978 0.6102051 -0.0664794 0.7884756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4734 4735 0.447563 -0.888041 0.413458 -0.6656690 0.0433693 0.5035208 0.5490636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4735 4736 -0.488642 -0.596188 -0.715473 -0.5316398 -0.7658996 0.1603431 0.3241096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4736 4737 -0.619610 -0.009861 0.775255 0.0635613 -0.3304804 0.8923085 0.3008791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4737 4738 0.552520 -0.303089 0.767417 0.2031990 0.7016531 -0.5701736 0.3758925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4738 4739 -0.791406 -0.014732 0.277922 0.8748522 -0.4256697 0.1001952 0.2083266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4739 4740 -0.548994 -0.002989 0.797202 0.4031337 0.5114780 0.7430682 0.1540231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4740 4741 -0.724050 0.622010 -0.018735 -0.3311788 -0.4485559 0.6667139 0.4945814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4741 4742 0.762317 0.265202 0.312625 0.5944153 -0.6715469 0.2168273 0.3855918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4742 4743 0.154206 -0.639748 -0.661997 -0.4981619 0.7466724 -0.2733279 0.3458424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4743 4744 0.964623 0.220709 0.674704 0.1437613 0.6476909 -0.0521484 0.7463978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4744 4745 -0.348551 0.365806 0.993312 0.3771521 0.0675931 -0.0309370 0.9231632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4745 4746 -0.675634 0.807650 0.271778 -0.2405595 -0.0842839 0.7011287 0.6659173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4746 4747 0.563694 0.372042 0.657403 -0.2946979 0.4453321 0.8031088 0.2642890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4747 4748 -0.714861 -0.200417 0.380883 0.0219055 -0.0222471 0.2185953 0.9753160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4748 4749 -0.972908 -0.074467 0.449556 -0.5911090 -0.3380084 -0.2097779 0.7016650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4749 4750 -0.318588 -1.010024 0.228124 0.1739256 0.3358889 0.7201748 0.5816157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4750 4751 -0.797611 0.444814 -0.417027 -0.5461729 -0.0375374 0.5336205 0.6446203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4751 4752 0.538377 0.618086 0.516173 0.6809022 -0.4560463 -0.3708755 0.4368585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4752 4753 -0.625057 0.294875 -0.893498 -0.1200837 -0.8861218 -0.3402906 0.2908098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4753 4754 0.056824 -0.265356 0.918101 -0.1738600 0.5864593 -0.0817802 0.7868610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4754 4755 -0.629195 -0.692586 0.221941 0.1420154 -0.6396955 -0.0385514 0.7544104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4755 4756 0.291152 -0.584803 0.732580 0.1261834 0.6307159 0.4779568 0.5981910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4756 4757 -1.016346 0.281988 0.167818 0.1736318 -0.4882933 -0.5698788 0.6376988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4757 4758 -0.014259 -0.476624 0.925519 0.2746693 -0.8848094 -0.3528824 0.1309317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4758 4759 0.130917 0.434933 -0.654048 -0.3040463 0.8989174 0.1308478 0.2870229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4759 4760 -0.562339 -0.582997 -0.023847 -0.1619139 -0.2315264 -0.9591079 0.0170724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4760 4761 -0.085650 -0.242300 -0.677733 0.8517586 0.0055531 -0.1239155 0.5090397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4761 4762 0.147748 -0.540758 0.708534 0.0273782 0.2396895 0.5104694 0.8253607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4762 4763 -0.656469 -0.055298 0.842173 -0.0899549 -0.0615843 0.8824217 0.4576543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4763 4764 0.201453 0.563096 0.563445 -0.2440059 -0.0413484 -0.5843946 0.7728094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4764 4765 0.108938 0.019831 0.835939 0.3698566 -0.8406261 0.0289337 0.3946095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4765 4766 0.677653 0.326199 -0.708410 -0.4288210 0.2255338 -0.7271189 0.4863590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4766 4767 -0.566256 0.740636 0.283454 -0.1273256 0.8790574 0.0959082 0.4492749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4767 4768 -0.005774 0.961730 -0.518453 0.0622685 -0.4052750 0.7621849 0.5009481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4768 4769 0.569936 0.161196 -0.729979 0.5060416 0.5034359 -0.3740697 0.5920693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4769 4770 0.728531 0.224379 0.212255 -0.8595509 0.0537961 -0.2871346 0.4193233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4770 4771 0.559108 -0.178962 0.897824 0.8377344 -0.1884802 0.2059948 0.4692999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4771 4772 0.665798 0.263986 -0.371722 -0.9690806 0.0412519 -0.1269969 0.2074917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4772 4773 0.755271 -0.121595 0.596071 0.4359076 -0.0606250 -0.3804528 0.8133664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4773 4774 0.631644 0.797652 0.274145 0.0297426 0.4560193 0.7910994 0.4065999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4774 4775 0.315861 -0.543883 0.762733 -0.0272854 -0.3317020 0.9344724 0.1264538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4775 4776 -0.246223 -0.269267 0.916478 0.3758368 0.1491087 -0.7396910 0.5379317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4776 4777 -0.490300 -0.170415 0.808801 0.1261041 0.3015627 0.3395917 0.8819496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4777 4778 -0.855240 0.367060 0.424102 0.4071183 0.6644198 0.3489220 0.5206290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4778 4779 0.442258 0.545430 -0.670597 0.0723629 0.2053545 0.2090290 0.9533625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4779 4780 -0.412246 0.906616 -0.376780 0.7058794 0.2851169 0.6072911 0.2272446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4780 4781 0.354041 0.367305 -1.177284 0.1949275 0.4734550 0.0543842 0.8572549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4781 4782 0.925535 -0.088403 -0.249655 0.1251243 -0.3704303 -0.9198371 0.0320143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4782 4783 -0.813922 -0.433772 -0.261331 0.3296009 -0.6437695 -0.6905943 0.0019151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4783 4784 0.948073 0.069234 0.146208 -0.9049102 -0.2876162 0.1592391 0.2702914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4784 4785 0.688023 0.340818 -0.538328 0.0748154 -0.3009109 0.1994638 0.9295533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4785 4786 0.375131 -0.038299 -1.127651 0.3245542 0.8679153 -0.1068016 0.3605288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4786 4787 0.540087 0.068489 0.939340 -0.4881164 -0.4682801 0.4616198 0.5739018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4787 4788 0.135249 -0.933910 -0.513884 0.6953448 0.4852789 -0.4615252 0.2607574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4788 4789 0.063371 0.607486 0.827533 -0.2249181 -0.0827923 0.5123269 0.8246687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4789 4790 0.536236 -0.083275 0.771984 -0.0135156 0.1005288 -0.8361570 0.5390294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4790 4791 -0.202926 0.280215 0.878265 -0.3416685 0.4115151 -0.7971483 0.2801295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4791 4792 0.122624 -0.908338 -0.065908 -0.1641101 0.1361123 0.1995979 0.9564006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4792 4793 -0.176971 -0.807799 -0.166649 0.3072323 0.3623621 -0.5176554 0.7115721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4793 4794 0.693831 -0.637142 0.525763 0.0784637 -0.3742986 0.2139015 0.8988827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4794 4795 0.657104 -0.972347 -0.024899 -0.2778428 -0.1752124 -0.7799540 0.5327060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4795 4796 0.504895 0.813198 -0.493163 -0.0989590 0.3385176 0.8503494 0.3905366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4796 4797 0.384156 -1.009941 0.175842 0.2761243 -0.6620935 -0.5520448 0.4250107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4797 4798 0.681683 0.071178 -0.669039 -0.0269356 0.9401835 0.3386655 0.0252039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4798 4799 -0.634648 -0.763414 0.528364 -0.1351681 -0.0497976 0.2274757 0.9630704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4799 4800 14.636136 6.171422 -10.116248 -0.2188977 -0.3220057 -0.8796387 0.2731884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4800 4801 1.031023 -0.031455 -0.097904 0.5855006 0.1219239 -0.5959073 0.5359274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4801 4802 0.350378 0.863387 -0.378458 -0.0636843 -0.1050791 -0.6798256 0.7230075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4802 4803 -0.836418 0.551419 -0.399264 0.4981530 0.0574517 -0.5539456 0.6645954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4803 4804 -0.139532 -0.982372 -0.004220 -0.1196527 0.7175734 -0.2932454 0.6203054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4804 4805 0.578599 -0.750752 0.155204 0.2730530 -0.7143451 -0.3609223 0.5337492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4805 4806 0.528344 -0.278081 -0.778558 0.2506643 -0.4892196 0.7310454 0.4042329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4806 4807 -1.199797 0.022521 0.093721 0.2750891 0.0821646 -0.0711253 0.9552571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4807 4808 -0.961148 -0.069706 0.125464 0.2996547 -0.1739721 0.9379656 0.0127014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4808 4809 0.891659 0.260895 -0.600883 -0.3155436 0.4408806 -0.8317585 0.1193078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4809 4810 -0.995088 0.131287 -0.113681 0.1622633 0.6271816 -0.3829886 0.6585087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4810 4811 0.082097 -0.846121 -0.844973 0.1293631 0.0640681 -0.4439208 0.8843612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4811 4812 0.581699 -0.685981 -0.600080 -0.0106509 0.0670888 -0.5594264 0.8260919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4812 4813 0.742398 0.388187 -0.434315 -0.3720169 -0.1421248 0.3625103 0.8426092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4813 4814 0.632108 -0.121498 -0.489580 0.7903163 0.3710626 0.4150321 0.2558534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4814 4815 0.004121 -0.103922 0.933267 0.4268075 -0.8830391 -0.1950770 0.0047221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4815 4816 0.163091 0.123971 -0.887254 -0.1347588 0.1754967 -0.0529170 0.9737766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4816 4817 0.204849 0.525414 -0.805395 0.0523601 -0.5587118 -0.3594748 0.7455719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4817 4818 -0.805902 0.130056 -0.370510 0.1023456 -0.1915960 -0.0615367 0.9741815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4818 4819 -1.048374 -0.065775 -0.095799 -0.1213081 0.4917005 0.8329759 0.2228589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4819 4820 -0.515129 0.872845 -0.324888 -0.6946641 0.3986322 0.2107579 0.5604598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4820 4821 -0.346843 0.553002 -0.513884 0.4533074 -0.2568597 0.4406153 0.7310224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4821 4822 -0.222570 0.159860 -0.834380 -0.9322396 0.0304872 0.0365607 0.3586966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4822 4823 -0.263655 0.382181 0.742471 0.4019760 0.1742276 0.0666817 0.8964450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4823 4824 -0.481161 1.087850 0.039350 0.0992923 -0.4631342 0.7284125 0.4950384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4824 4825 0.725311 0.180400 -0.505268 0.0104825 0.3829077 0.0925081 0.9190833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4825 4826 1.031223 -0.007249 0.227666 -0.4326186 -0.3570760 -0.8168082 0.1347675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4826 4827 -0.362940 0.755283 0.645323 -0.2366626 0.1482746 -0.0267329 0.9598389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4827 4828 -0.560059 0.231866 0.456226 0.1582883 -0.4335457 0.8703238 0.1718120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4828 4829 0.926708 -0.319481 0.021191 -0.3693977 -0.7296596 0.1643966 0.5514671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4829 4830 -0.324009 -0.046940 -1.033079 0.3001395 0.0307403 -0.8999418 0.3147634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4830 4831 0.693518 -0.117909 -0.460228 -0.8167365 0.3344255 0.1856416 0.4320165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4831 4832 1.144957 -0.332604 0.185311 -0.1336534 0.0480852 -0.6989640 0.7009093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4832 4833 0.149906 0.728767 0.367815 -0.0209341 0.6645446 0.3846737 0.6402877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4833 4834 0.019235 0.855360 0.617100 -0.6344636 0.2113064 0.6498790 0.3611965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4834 4835 -0.652066 -0.733568 0.334291 -0.0996293 -0.5629427 0.0806654 0.8164941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4835 4836 0.104961 -0.602264 0.746736 -0.4123885 0.0291225 -0.7659293 0.4923818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4836 4837 0.933669 0.084502 0.205798 0.2525805 -0.6203032 0.7422149 0.0233245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4837 4838 -0.786718 -0.660197 0.236363 0.5280940 -0.0969650 0.5520722 0.6379112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4838 4839 -0.287244 0.922958 0.174776 -0.4663401 0.5700487 -0.6741699 0.0553746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4839 4840 -0.982907 0.157553 0.208792 0.7107943 0.2330864 -0.4722521 0.4662833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4840 4841 -0.946048 0.509952 -0.490717 -0.6334159 0.2791877 0.3879982 0.6085195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4841 4842 -0.003266 0.860003 0.324966 -0.2761163 0.4375926 0.7618335 0.3897206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4842 4843 -0.088425 -0.045832 0.855950 0.0510203 -0.7209596 -0.3315246 0.6063874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4843 4844 0.873627 0.342436 -0.024788 0.3907623 -0.5411215 -0.3670976 0.6478671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4844 4845 -0.460348 0.248103 -0.936456 0.1238685 -0.7830947 -0.4136818 0.4475339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4845 4846 -0.574780 -0.690133 0.415908 -0.2735807 -0.2691584 0.4379294 0.8129731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4846 4847 -0.566704 -0.333509 0.875736 -0.2538481 0.4273356 -0.3113812 0.8099303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4847 4848 -0.420246 -1.109984 -0.286877 0.1711767 -0.0658107 0.9585229 0.2181774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4848 4849 -0.161313 0.790235 -0.166998 0.4341845 -0.3051013 -0.2849968 0.7982317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4849 4850 -0.848353 0.313911 -0.414083 -0.3383180 -0.0741966 -0.6614892 0.6651825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4850 4851 -0.651413 -0.697118 -0.470646 0.0732709 0.2769183 0.9157725 0.2816174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4851 4852 0.181559 0.220197 -0.872825 -0.8700508 0.0949626 -0.4352612 0.2110485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4852 4853 -0.738983 0.043710 0.529633 -0.1959731 0.4469904 -0.3878641 0.7818923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4853 4854 -0.587864 -0.656408 -0.460720 -0.2412743 -0.1585334 0.9114763 0.2930270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4854 4855 0.057152 1.015567 0.037804 -0.2624262 -0.7058998 0.5346609 0.3833740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4855 4856 0.719348 -0.071073 -0.904684 -0.1534601 0.1133683 0.7869096 0.5868312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4856 4857 0.041690 -0.659184 -0.762984 0.8987076 -0.3663044 -0.1832334 0.1567523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4857 4858 0.834390 0.122195 0.578882 -0.0711559 -0.7878105 -0.5996997 0.1210442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4858 4859 -0.464492 0.785292 -0.005373 -0.7078421 0.2576482 -0.2520651 0.6074867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4859 4860 -0.394159 -0.346749 -0.777991 0.2877200 0.1066496 -0.7726903 0.5556913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4860 4861 0.061786 1.030757 -0.592433 -0.7664883 0.0919508 -0.5410411 0.3336394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4861 4862 -0.923337 -0.235789 0.517283 0.5528965 0.5068707 0.5575369 0.3557248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4862 4863 -0.094014 0.524406 -0.754297 -0.8965401 -0.3150746 0.0020179 0.3113514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4863 4864 -0.057855 0.146013 0.938061 0.4897059 -0.8527764 0.1521872 0.0989924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4864 4865 0.455817 -0.139144 -0.873449 0.7989766 0.3176462 -0.0536427 0.5077989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4865 4866 0.620103 -0.488984 0.601436 -0.3952861 -0.6164686 -0.3632131 0.5760136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4866 4867 0.538415 0.391121 -0.830032 -0.4885566 -0.6713107 -0.2906781 0.4755635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4867 4868 -0.552071 0.516400 0.590575 0.6384212 -0.1253625 0.7462223 0.1409073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4868 4869 0.704706 -0.230735 -0.845586 -0.0401117 0.6493668 -0.7447998 0.1482802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4869 4870 -0.325869 0.840949 0.142120 -0.3563907 0.0090368 -0.9175542 0.1760635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4870 4871 0.170406 -1.192962 0.320233 -0.2511215 -0.2973211 -0.8869669 0.2486524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4871 4872 0.376827 0.586662 -0.687016 -0.5574764 0.0435153 -0.6237924 0.5460856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4872 4873 -0.822982 0.419132 0.295655 0.6445332 0.2634299 0.2248788 0.6816240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4873 4874 -0.429250 0.226646 -0.882770 -0.3978899 -0.3685198 0.6174956 0.5697157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4874 4875 0.501444 0.930072 0.141270 -0.4050786 0.0779414 -0.0233168 0.9106552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4875 4876 0.325367 0.579801 0.872648 -0.5318885 -0.5087409 0.6767684 0.0161799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4876 4877 -0.484699 -0.621115 -0.728975 -0.9655355 -0.2235377 -0.0660750 0.1157851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4877 4878 -0.591454 0.833766 0.437114 -0.0450564 -0.3455051 0.8881159 0.2997436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4878 4879 0.980803 -0.196980 0.185539 -0.7095056 0.1027084 -0.6698110 0.1934063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4879 4880 0.862739 0.413773 -0.433572 0.9585090 0.0114375 0.2845073 0.0136091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4880 4881 -0.655278 0.345285 0.649196 -0.1943509 0.4219962 -0.6070607 0.6446892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4881 4882 -0.629233 -0.928390 -0.360142 -0.1646478 -0.5000339 -0.6865062 0.5015640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4882 4883 0.519529 -0.470669 -0.927884 0.3282700 -0.2375068 -0.8696275 0.2820944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4883 4884 0.289179 0.178164 -0.840735 -0.3349647 0.6367112 0.6916018 0.0639106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4884 4885 0.283793 -0.938693 0.237086 0.2736009 -0.0525864 -0.4639199 0.8409254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4885 4886 0.954763 -0.188908 0.204771 -0.6760312 -0.4314649 0.0284916 0.5966642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4886 4887 0.648955 0.050349 -0.850914 -0.3224837 0.4069070 -0.8544828 0.0170304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4887 4888 -0.868184 0.322812 -0.066722 0.3380930 -0.5340037 -0.1731952 0.7553387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4888 4889 -0.365552 0.103154 0.718545 -0.3481015 0.3886390 -0.8211776 0.2311978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4889 4890 0.533387 -0.863423 -0.174803 -0.6000829 -0.3477060 0.5854268 0.4198530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4890 4891 -0.921484 0.559798 -0.507318 -0.0489351 0.2531373 -0.7420829 0.6187406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4891 4892 -0.203583 -0.499274 -0.811745 0.3691971 0.3358739 0.3664657 0.7852293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4892 4893 -0.615692 -0.809434 -0.476140 -0.0079771 -0.4982927 -0.8269678 0.2603171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4893 4894 0.672932 -0.299032 -0.898732 -0.5669667 0.1911786 -0.5379859 0.5937766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4894 4895 0.026088 1.153450 -0.078245 -0.0155062 0.5609599 0.0723161 0.8245325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4895 4896 -0.094212 0.970341 0.224220 -0.1040624 -0.7455813 0.2790288 0.5961731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4896 4897 0.820566 0.590117 -0.041128 -0.3969480 -0.0336449 -0.6524251 0.6447029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4897 4898 -0.574161 0.578555 0.414837 -0.8244173 0.3355827 -0.4058743 0.2073317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4898 4899 -0.474017 -0.331242 -0.628150 -0.3513059 0.6335337 -0.6873125 0.0531098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4899 4900 -0.752797 0.183502 0.570202 0.0464104 -0.6432617 0.6905673 0.3273794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4900 4901 -0.360992 0.374614 0.928095 -0.5074969 -0.6591509 0.5434008 0.1126171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4901 4902 -0.110623 -0.792211 -0.512182 -0.7399124 -0.2181557 0.5420325 0.3333745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4902 4903 -0.289332 1.073536 0.092116 -0.0694989 -0.8404178 0.4023046 0.3563969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4903 4904 0.645187 0.642273 -0.322318 -0.1601086 0.1080951 0.6348424 0.7481015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4904 4905 0.907602 -0.468175 -0.010701 0.1547821 0.2172333 -0.8385268 0.4751053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4905 4906 -0.131252 0.840225 0.092073 0.4110030 -0.3321481 0.6442503 0.5528976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4906 4907 0.491930 -0.009354 -0.795738 0.1631741 0.8840292 0.0330042 0.4367807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4907 4908 0.104009 -0.008825 1.051227 0.5902551 -0.1270954 -0.7916685 0.0933095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4908 4909 -0.822499 0.282948 0.229181 -0.7246092 0.1563094 -0.1067430 0.6626574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4909 4910 -1.069009 0.072751 -0.018900 0.0570841 0.7675951 -0.0126298 0.6382630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4910 4911 0.091043 -0.233366 -0.935670 0.0504377 -0.1755012 0.1438337 0.9726085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4911 4912 -0.072208 -0.387668 -0.894794 -0.4887541 -0.1990096 0.5953174 0.6058975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4912 4913 -0.219023 0.917747 -0.294287 -0.5528281 0.0575748 0.4434959 0.7031199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4913 4914 0.686092 0.321315 0.714490 -0.0240575 -0.0622328 -0.3326773 0.9406775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4914 4915 0.412115 0.540154 0.562840 -0.1968712 -0.3681931 -0.8943981 0.1603983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4915 4916 -0.129371 -0.016921 1.047626 -0.3277755 0.4029499 0.1689869 0.8376384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4916 4917 -1.051299 -0.118231 0.259006 -0.3314135 0.2076257 0.3198642 0.8629853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4917 4918 -0.681464 0.098932 -0.057515 0.3764802 -0.4205737 -0.4516822 0.6909150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4918 4919 -0.481103 -0.250493 0.863158 -0.5064302 -0.0737628 0.0041572 0.8591101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4919 4920 -0.408327 0.494649 0.808121 0.0599705 -0.0274293 0.2259451 0.9719053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4920 4921 0.731077 0.433210 -0.503135 -0.2902273 0.3939086 -0.4791303 0.7287237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4921 4922 -0.071009 0.980766 0.588067 0.0275104 -0.2981928 0.7440555 0.5972484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4922 4923 0.963235 -0.117484 0.121973 0.4827222 -0.4681590 -0.5960709 0.4387549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4923 4924 -0.065428 0.279860 -1.004263 0.2994015 0.4083704 0.3042433 0.8068633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4924 4925 0.542511 -0.674875 -0.565941 -0.0685144 -0.5307325 -0.6964311 0.4781344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4925 4926 -0.479702 0.119670 -1.025350 -0.6336737 -0.0658249 0.6600323 0.3980981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4926 4927 0.979798 0.662789 -0.118619 0.3971251 0.4767157 0.0275321 0.7837574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4927 4928 0.688066 0.854908 0.305162 0.3307631 0.3045692 0.8214558 0.3507758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4928 4929 0.367754 -0.567267 0.646715 -0.7481207 -0.6389985 -0.0345498 0.1755067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4929 4930 -0.154935 0.297540 -0.896718 -0.7418422 0.2099034 -0.3654758 0.5215728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4930 4931 -0.366864 0.846741 0.107772 -0.4414939 -0.5729702 0.5637870 0.3986633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4931 4932 1.026315 -0.306632 0.343425 0.1936892 -0.2733706 0.4023029 0.8520008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4932 4933 0.340339 -0.750140 0.050987 0.2636135 -0.1827425 0.1927212 0.9273466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4933 4934 0.473776 -0.798011 0.400403 -0.6239883 0.3138552 -0.0443403 0.7142601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4934 4935 0.325846 -0.846603 -0.540184 0.2437077 0.6581811 -0.6954989 0.1539008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4935 4936 -0.462424 0.722528 0.735184 -0.3870760 -0.4749064 -0.7901578 0.0169317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4936 4937 0.927737 -0.074383 0.380804 0.0835175 0.5190446 0.7561845 0.3896185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4937 4938 -0.827792 -0.349171 0.510581 -0.1470400 0.4486406 0.8295620 0.2982075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4938 4939 0.396279 0.811558 -0.001896 0.0682763 -0.6360324 -0.5654854 0.5206028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4939 4940 -0.490209 -0.859446 0.138030 0.2035778 0.0042363 -0.4499196 0.8695462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4940 4941 0.837353 0.220395 -0.363302 -0.3222889 -0.5610388 -0.6352701 0.4216600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4941 4942 -0.640600 0.696467 0.094305 0.1838560 0.3111618 0.4907917 0.7927792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4942 4943 0.393328 0.742988 -0.524773 -0.1175531 0.1077652 -0.7325745 0.6617421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4943 4944 -0.794755 0.438374 -0.387930 -0.3955364 0.3775546 -0.0714155 0.8342082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4944 4945 -0.412436 0.777244 -0.565736 -0.1951625 0.2445017 0.9461890 0.0828058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4945 4946 0.708798 -0.836379 0.068921 -0.4037275 0.6353224 -0.0177121 0.6580698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4946 4947 0.451181 -0.932424 0.228078 0.6318598 0.3311353 -0.7003137 0.0257552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4947 4948 -0.345371 0.616928 0.130647 0.4144244 -0.2314226 -0.6168880 0.6278099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4948 4949 -0.898705 -0.447081 0.412133 0.3284750 -0.0841183 -0.8407057 0.4221874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4949 4950 0.487112 -0.260214 0.813622 -0.5044358 0.0974865 0.1026735 0.8517623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4950 4951 0.255510 -0.770839 0.312725 -0.5422079 -0.1021900 -0.0067738 0.8339796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4951 4952 0.308461 -0.229863 -0.745778 0.2204205 0.5318188 -0.8028157 0.1551467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4952 4953 0.226086 0.810615 0.116986 -0.0892197 -0.6831394 0.2398674 0.6839767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4953 4954 0.387048 0.705834 -0.453529 0.2489575 -0.6755776 0.6805635 0.1358250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4954 4955 -0.654663 -0.092967 -0.605345 0.3314530 0.7066767 -0.4529133 0.4308324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4955 4956 0.786670 -0.535945 -0.001408 0.0845653 0.2550242 -0.0398632 0.9624044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4956 4957 0.937130 -0.347367 0.386818 0.2271172 0.5472497 -0.7472311 0.3009671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4957 4958 -0.952979 0.433156 0.376285 0.1040351 0.4339160 0.1757941 0.8774908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4958 4959 -0.679118 0.836121 -0.250344 -0.5721300 0.4282766 0.6979329 0.0462189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4959 4960 -0.699888 -0.644131 -0.162534 0.1610933 -0.3949081 -0.7293261 0.5349579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4960 4961 -0.435601 -0.990367 -0.482077 0.0744265 -0.6689335 0.2950956 0.6781646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4961 4962 -0.683747 -0.420049 0.684800 0.2182415 0.0029942 -0.3031564 0.9276087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4962 4963 -0.177464 -0.342454 0.780523 -0.3457549 -0.1453717 -0.8955279 0.2394793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4963 4964 0.899278 0.093858 0.405757 -0.0028458 -0.2767084 0.9471477 0.1622826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4964 4965 -0.771653 -0.656612 0.158550 0.1705309 0.7257990 -0.3658065 0.5570642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4965 4966 0.272261 -1.036980 -0.038351 -0.3239545 0.2607047 0.6052955 0.6787517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4966 4967 -0.486670 -0.369949 -0.936060 -0.0349458 0.3864297 0.7871183 0.4794744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4967 4968 0.262294 0.050197 -0.799878 -0.5190866 0.3188804 -0.6787148 0.4101349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4968 4969 -0.489868 0.910360 0.094323 0.0504685 0.4887966 0.8707460 0.0182268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4969 4970 0.411696 -0.347197 0.718534 -0.0222597 -0.0483604 0.1262306 0.9905714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4970 4971 0.571611 -0.417277 0.783571 -0.1847612 0.5234212 0.7294624 0.3997226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4971 4972 -0.968882 -0.153736 -0.163618 0.1208154 -0.3557218 0.7965592 0.4736656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4972 4973 0.504344 0.981369 0.155668 0.4032313 0.3428357 0.7965903 0.2920825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4973 4974 0.601113 -0.419527 0.801146 -0.3735457 -0.5677511 -0.4566883 0.5740715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4974 4975 0.943451 0.237134 -0.478347 -0.1165067 0.5452183 -0.6138696 0.5588626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4975 4976 -0.289623 1.015169 0.365073 0.6887391 -0.6050985 -0.3795244 0.1243200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4976 4977 -1.103395 -0.071184 0.303666 -0.7562545 -0.2016162 -0.0057956 0.6224117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4977 4978 -0.775605 -0.517122 0.108551 -0.3046472 0.4316886 0.1381073 0.8377120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4978 4979 -0.637171 0.055030 -0.633698 -0.0246779 -0.3500465 0.8107770 0.4685073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4979 4980 -0.993280 0.199410 -0.057599 0.4085409 0.5868587 0.6914629 0.1028114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4980 4981 -0.225460 0.254443 -0.808088 -0.8694760 0.0371963 -0.4810162 0.1060720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4981 4982 -0.960966 -0.177883 0.227931 0.3770349 0.0571450 -0.6118070 0.6930161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4982 4983 -0.103089 -0.801328 0.530677 -0.1253910 -0.0388863 -0.9684095 0.2120094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4983 4984 0.478107 0.796238 0.526301 0.2659408 0.0866007 -0.9407067 0.1919552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4984 4985 -1.171364 -0.247276 -0.183164 -0.2469735 0.4607889 -0.2589337 0.8121767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4985 4986 -0.330362 -0.427494 -0.652278 0.1181315 0.1940238 0.5849896 0.7785800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4986 4987 -0.214223 -0.403800 -0.795182 -0.4548264 -0.1503140 -0.3202775 0.8172888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4987 4988 -0.592459 0.127674 -0.898740 0.2130275 -0.7929116 -0.2185955 0.5273770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4988 4989 -0.612991 -0.170045 0.746675 0.6738361 0.1648207 0.0048485 0.7202469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4989 4990 -0.712727 0.814902 0.197943 0.1413849 -0.0219012 0.8776656 0.4574208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4990 4991 0.934160 0.192590 -0.251508 -0.1694736 0.7446238 -0.3129679 0.5646815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4991 4992 -0.182218 0.308303 1.067075 -0.1418471 0.8244887 -0.0931035 0.5398421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4992 4993 -0.778853 0.069359 -0.470670 0.3909554 -0.1358347 0.7161908 0.5619374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4993 4994 -0.432896 0.371135 -0.814509 -0.2088786 -0.7575065 -0.1139394 0.6079238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4994 4995 -0.412388 0.325445 0.717588 -0.5627717 0.5641440 0.3543303 0.4893665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4995 4996 -0.896538 0.486455 0.056747 -0.0648857 0.5300617 -0.5486945 0.6432408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4996 4997 -0.273164 -0.609182 -0.853644 0.3396946 -0.2243513 0.0976308 0.9081532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4997 4998 -0.754400 -0.787476 -0.334903 0.1432186 0.4668462 -0.5037936 0.7125553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4998 4999 0.500665 -0.970987 0.097656 0.1944713 -0.4321288 -0.7722636 0.4231483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4999 5000 0.762379 -0.112199 0.436440 -0.4079264 0.1870041 -0.2338990 0.8625061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5000 5001 -0.121223 -0.966770 -0.172248 0.0400621 0.2561755 0.7208344 0.6427806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5001 5002 -0.964540 -0.099405 -0.361289 -0.7067483 -0.4173550 -0.2370114 0.5197569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5002 5003 -0.867269 -0.497709 0.173036 0.1151876 -0.4802023 0.6662754 0.5587617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5003 5004 0.109511 0.552631 0.689659 0.5704202 -0.6874345 0.4485549 0.0292082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5004 5005 -0.091666 -0.581504 -0.700642 0.0375166 0.6965801 0.2035570 0.6869740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5005 5006 0.694828 -0.795117 -0.132398 0.2240604 0.2115913 0.6468831 0.6975445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5006 5007 -0.668223 -0.500304 0.347965 -0.8812973 -0.0930942 0.2988385 0.3540397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5007 5008 -1.069245 0.150335 -0.017523 0.7145200 -0.3653936 -0.3608689 0.4751025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5008 5009 -0.690184 0.064074 0.682830 -0.1658746 0.0095475 -0.6801572 0.7139892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5009 5010 -0.162749 -0.862037 0.574994 -0.1012881 -0.3069112 0.9355713 0.1423116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5010 5011 -0.445881 0.294941 0.747852 0.0645216 -0.7633921 0.5711009 0.2948106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5011 5012 0.862519 -0.399556 -0.316505 -0.0982563 -0.8015964 -0.0823220 0.5839624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5012 5013 -0.277852 -0.376953 -0.620394 0.2907529 -0.1614721 -0.2160587 0.9179914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5013 5014 -0.466695 -0.922734 -0.239703 0.3611264 0.1768816 -0.0798654 0.9120977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5014 5015 -0.169335 -0.794614 0.266418 -0.2425756 0.6534437 -0.1071541 0.7090038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5015 5016 0.002660 -0.966511 -0.549976 -0.1454524 -0.2262130 0.6397106 0.7200289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5016 5017 -0.802476 0.090107 -0.305248 -0.5466451 -0.0832885 -0.8066046 0.2088809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5017 5018 -0.048096 -0.435801 -0.779334 0.2739718 -0.1841125 0.9355119 0.1259350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5018 5019 -0.613123 0.698556 -0.239333 -0.0563699 -0.6460824 -0.6377919 0.4154774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5019 5020 0.391368 -0.800735 -0.389771 0.0144229 -0.2476852 0.7199412 0.6481733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5020 5021 0.161405 -0.004966 -1.046998 0.4934850 0.4463699 -0.7419804 0.0818019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5021 5022 0.687961 0.652990 -0.302083 -0.3799214 -0.2877556 0.8339455 0.2781929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5022 5023 0.278157 -0.398463 -0.951004 -0.5991417 0.6154869 -0.4925174 0.1401129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5023 5024 -0.197828 0.645634 0.850069 0.5557335 0.3767620 0.7006070 0.2415790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5024 5025 0.978209 0.193917 0.172194 -0.0511274 -0.5243539 -0.5075812 0.6817626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5025 5026 0.035908 0.784737 -0.453560 0.4177743 -0.4653169 -0.7236701 0.2919699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5026 5027 -0.471010 -0.704025 0.145327 0.1591654 0.2798445 -0.9385487 0.1244181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5027 5028 0.332976 0.202663 0.826448 0.0147459 -0.0096645 0.3426308 0.9393047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5028 5029 0.416220 -0.083026 0.761154 -0.2998084 -0.6957919 0.5169565 0.3984275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5029 5030 -0.146821 -0.538132 -0.772079 0.6855980 0.2119313 0.0502248 0.6946351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5030 5031 -0.326971 -0.760571 0.605251 0.1306601 -0.2026324 -0.6717370 0.7004551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5031 5032 1.032095 0.124320 0.616776 0.1283359 0.0230009 0.3856628 0.9133811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5032 5033 0.615491 -0.500719 0.601288 0.3840552 -0.3797236 -0.4948680 0.6807476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5033 5034 0.647725 0.847535 -0.227616 -0.5152577 0.1044132 -0.2558144 0.8112745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5034 5035 0.544628 0.773026 0.643024 0.6429427 -0.4479758 0.5775862 0.2287718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5035 5036 0.469024 -0.692587 -0.559856 -0.3432408 -0.0176027 -0.4864509 0.8032692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5036 5037 0.458968 0.579217 -0.591783 0.2332740 0.0792324 -0.3928698 0.8859790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5037 5038 0.216202 0.637053 -0.822495 -0.4487262 0.5101235 0.3634551 0.6374317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5038 5039 0.967081 0.128441 0.526388 0.1682948 0.3617264 0.9166583 0.0238443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5039 5040 0.228140 1.012616 -0.188946 -0.1377215 0.8468537 -0.3905890 0.3336343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5040 5041 0.184040 0.335284 0.773243 0.4790813 0.6733819 -0.4056034 0.3905429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5041 5042 -0.599880 0.055169 -0.517861 -0.5355902 -0.4888975 0.6849856 0.0701223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5042 5043 0.871560 0.218754 0.755600 0.3186132 0.1056687 0.8952254 0.2930720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5043 5044 -0.161783 -0.286623 0.939724 -0.2874377 -0.8101840 -0.5106392 0.0151342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5044 5045 0.062062 0.582789 -0.846528 -0.5801606 0.1492781 -0.2813176 0.7496600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5045 5046 -0.376982 0.660628 0.159422 0.1693858 -0.2389493 -0.8181415 0.4948294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5046 5047 -0.711106 -0.144190 0.598399 0.0964225 0.6355326 0.7636186 0.0607267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5047 5048 0.512778 0.762213 -0.221027 -0.6875905 -0.0320846 0.6578347 0.3056851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5048 5049 0.752948 -0.738878 -0.404018 0.4291344 0.4948209 -0.6350982 0.4094462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5049 5050 0.369267 0.910287 0.496971 0.2767609 0.5914623 -0.5120185 0.5580437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5050 5051 -0.672813 0.184365 -0.506435 0.7074795 0.3062353 -0.3712684 0.5175446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5051 5052 -0.020392 -0.944316 0.183782 0.5294535 -0.4988953 0.2100991 0.6531775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5052 5053 0.301433 -0.383701 0.831458 -0.7897374 0.1783120 0.4367389 0.3921464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5053 5054 -0.538081 -0.498419 -0.695493 -0.2362894 -0.9198780 0.2722765 0.1544578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5054 5055 0.202404 -0.086647 0.987148 0.6640510 -0.7156701 0.1275545 0.1748786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5055 5056 0.354830 -0.266446 -1.073268 -0.0111811 0.0288767 -0.7608852 0.6481472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5056 5057 -0.057743 0.526310 -0.868724 -0.3108759 -0.6149582 0.1704138 0.7043733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5057 5058 -0.430725 0.878544 0.192436 0.6434207 0.0445832 0.2187836 0.7322266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5058 5059 -0.019544 0.331833 -0.871609 -0.1543903 0.3021254 0.1229653 0.9326111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5059 5060 -0.670503 0.409846 -0.029413 0.6828568 -0.0276358 0.6791695 0.2677155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5060 5061 0.532987 0.754582 -0.139845 0.3267308 0.5355321 0.6849248 0.3705812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5061 5062 0.486575 -0.522022 0.573066 -0.2436175 -0.5460291 0.4016634 0.6936637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5062 5063 0.026129 -1.037476 -0.172228 0.1851683 0.4389777 0.5386423 0.6948926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5063 5064 -0.795640 -0.482391 -0.301274 -0.4273090 0.7589434 0.4905893 0.0270923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5064 5065 1.080459 0.273869 -0.026705 -0.7264998 -0.2837786 0.2726149 0.5633373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5065 5066 0.900911 0.049574 -0.326513 -0.4308820 0.1208859 -0.5182814 0.7287741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5066 5067 0.176862 1.050516 0.296867 0.6947981 -0.2971490 0.5829038 0.2986323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5067 5068 -0.060950 -0.930058 -0.822071 0.1854177 0.4163745 0.4926636 0.7413063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5068 5069 -0.555304 -0.807131 -0.221047 -0.1700781 -0.2907151 0.1048576 0.9357153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5069 5070 -0.791374 -0.516064 -0.341946 -0.3427578 -0.2987228 -0.0116958 0.8905869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5070 5071 -0.768623 -0.483545 0.024199 0.5553084 0.0457418 0.2156623 0.8018915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5071 5072 -0.946093 0.255878 0.223404 -0.1314099 -0.3864188 0.9129064 0.0037271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5072 5073 0.939614 -0.266754 0.362899 0.5614223 -0.3532274 0.2912093 0.6893711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5073 5074 0.792553 -0.627385 0.011742 -0.0619025 0.7221535 0.0317167 0.6882270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5074 5075 -0.111592 -0.594869 0.761755 0.2653929 0.0430993 -0.7640808 0.5864210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5075 5076 0.336279 0.153177 0.858845 0.7598424 0.5513403 -0.3419767 0.0414172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5076 5077 -0.381067 -0.100162 -1.065603 0.3998973 -0.3660516 0.7347669 0.4076837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5077 5078 -0.745294 0.479680 -0.399108 0.1148362 0.1606833 0.7216632 0.6634725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5078 5079 0.845829 0.377057 -0.560969 0.0903127 0.2207029 0.8456222 0.4775531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5079 5080 -0.490875 0.169023 -0.844326 -0.4467743 -0.2060841 0.5607350 0.6659566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5080 5081 0.782959 -0.205394 0.599306 0.4090634 -0.1625013 -0.7895255 0.4276798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5081 5082 -0.204110 0.949454 -0.347097 -0.6445821 -0.2607733 0.5851189 0.4173094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5082 5083 0.788521 -0.380441 0.363322 0.5525823 -0.0927681 -0.1343723 0.8173071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5083 5084 1.063575 0.357287 0.070301 0.2192224 -0.6742046 0.5588397 0.4302184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5084 5085 -0.558856 -0.852446 -0.449365 0.7578544 0.1929810 0.0130218 0.6230935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5085 5086 -0.593575 -0.537720 0.609756 -0.5437093 -0.0477866 -0.6635036 0.5117221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5086 5087 0.860527 -0.558827 -0.223763 -0.0303053 -0.3120722 -0.5539490 0.7712542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5087 5088 0.351687 0.558036 -0.966706 -0.7497220 0.0168769 0.2591835 0.6086509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5088 5089 0.730721 0.576655 0.279854 0.8311800 -0.4012187 0.1865297 0.3367046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5089 5090 0.612163 -0.646600 -0.621741 -0.0020665 0.2123126 0.5915024 0.7778458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5090 5091 -0.424299 -0.780939 -0.512839 0.3155917 -0.4717177 0.8125053 0.1331144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5091 5092 0.132034 0.956766 0.444039 0.2730157 -0.0566378 0.9165397 0.2867220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5092 5093 0.703763 -0.533144 0.198920 -0.0093574 0.6515804 0.7498909 0.1141013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5093 5094 -0.710884 0.098581 -0.623726 0.5505975 -0.7517670 -0.3503232 0.0946698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5094 5095 0.540817 0.161795 0.840839 -0.0707696 -0.0706950 -0.0428348 0.9940619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5095 5096 0.559896 0.204619 0.851328 0.5701526 -0.3268376 -0.7009627 0.2770462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5096 5097 -0.709358 0.637606 -0.223345 -0.0494571 0.1046073 0.1065773 0.9875488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5097 5098 -0.667836 0.627345 -0.438816 -0.1593284 -0.1368490 0.1252793 0.9696349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5098 5099 -0.689127 0.842870 0.067510 -0.1369782 0.3229050 -0.2383943 0.9056144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5099 5100 0.088820 -0.535194 -0.903561 -0.8102608 -0.1573709 0.5589085 0.0795808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5100 5101 -0.095233 0.588171 -0.803980 -0.4743831 -0.2558405 0.3200506 0.7791495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5101 5102 0.036081 0.794690 0.062241 0.0495817 -0.4610868 0.5290794 0.7106445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5102 5103 0.632574 0.241333 -0.581618 -0.1073213 -0.3674302 -0.8300194 0.4056415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5103 5104 -0.865127 0.174236 -0.411754 -0.0904886 0.5481308 0.4333182 0.7096477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5104 5105 0.387388 0.616407 -0.778454 -0.4372984 0.5571689 0.2644341 0.6545285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5105 5106 0.662485 0.013360 0.767232 -0.7833149 -0.3675512 0.3754954 0.3321551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5106 5107 0.385669 -0.270653 -0.860206 -0.1216742 -0.3070455 0.6743000 0.6604831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5107 5108 -0.514797 0.546962 -0.946159 -0.1430916 -0.4216921 0.3369614 0.8295526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5108 5109 -0.499028 0.904073 -0.015112 -0.4899955 0.6519073 -0.2886981 0.5015722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5109 5110 -0.759383 0.613819 -0.184456 -0.1322113 -0.8564322 0.2666418 0.4218367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5110 5111 0.447322 0.849809 0.310607 0.1773983 0.6701946 -0.7205930 0.0107149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5111 5112 -0.555291 -0.185817 -1.000038 0.5045240 -0.4454654 0.6316461 0.3847587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5112 5113 -0.641687 0.893973 -0.082404 -0.8072391 0.0310195 -0.5712953 0.1449983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5113 5114 -0.566575 -0.562840 -0.355229 -0.6497861 0.5175060 -0.3845061 0.4026421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5114 5115 0.700553 0.461307 -0.427652 -0.3786914 0.8866123 -0.2637132 0.0310943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5115 5116 -0.879367 0.123739 0.332129 0.0115820 -0.6660163 0.6646947 0.3383328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5116 5117 0.821881 0.068783 0.119172 0.2328318 0.0056745 -0.7975180 0.5565268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5117 5118 -0.473814 0.632231 -0.194958 0.1928344 -0.5647943 -0.4139631 0.6873550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5118 5119 -0.853655 0.050791 0.461783 -0.1744162 -0.6934258 -0.0720635 0.6953751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5119 5120 -0.726488 0.518545 0.619650 -0.4383429 0.5305687 0.7134153 0.1318750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5120 5121 0.959533 -0.287616 0.339664 0.2551303 -0.2214619 0.0835984 0.9374830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5121 5122 0.848608 -0.313025 -0.111804 0.4016718 0.3575644 -0.3875757 0.7487272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5122 5123 0.174890 0.811434 0.482108 0.7241586 -0.4997232 -0.4537105 0.1414846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5123 5124 -1.011305 -0.120412 -0.227766 -0.6601565 0.2490857 0.6010008 0.3754302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5124 5125 0.194721 0.842889 0.512344 -0.3246195 -0.0321691 0.9325167 0.1549189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5125 5126 -0.078911 -0.933519 0.254936 0.0262049 -0.5043919 -0.8139441 0.2870491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5126 5127 0.665867 0.549374 -0.653723 -0.3311013 -0.2020379 -0.8258826 0.4092316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5127 5128 -1.136308 0.106504 -0.118151 -0.1334216 -0.5964730 0.3526683 0.7085504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5128 5129 0.061500 0.198938 0.870302 0.0729746 0.6393541 -0.7554542 0.1232478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5129 5130 -0.308573 -0.969155 -0.100128 0.2836219 -0.1302126 -0.9466947 0.0798272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5130 5131 0.625757 0.756755 -0.140031 -0.5248670 0.1387060 0.5737541 0.6132548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5131 5132 0.825321 -0.738503 0.140632 -0.8429538 0.1841102 0.5013801 0.0644231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5132 5133 0.280889 0.351403 -0.697475 -0.6147751 -0.4413350 0.4446908 0.4790878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5133 5134 0.595227 0.675144 -0.202111 -0.1597990 0.4341272 -0.5579256 0.6889970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5134 5135 -0.693147 0.625959 0.318914 -0.0953293 -0.5375768 0.6943544 0.4688234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5135 5136 0.847365 0.460691 0.041396 -0.0705574 0.9331287 -0.2402300 0.2580348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5136 5137 -1.088192 0.274185 0.455932 0.5154089 -0.1132651 0.4371546 0.7282998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5137 5138 -0.096481 0.932191 -0.563466 -0.1454661 0.5719692 0.2117480 0.7790081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5138 5139 0.523550 0.771971 0.107976 0.7847285 -0.5980114 -0.1355587 0.0905945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5139 5140 -0.066447 -0.253516 0.910447 0.5131963 -0.6949369 -0.3225952 0.3868135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5140 5141 -0.645015 0.113877 -0.683740 -0.2093154 -0.4102533 -0.0933367 0.8827047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5141 5142 -0.874500 -0.007898 0.300315 -0.1093825 -0.2437883 0.4005041 0.8764697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5142 5143 -0.549619 0.592833 0.733502 0.2619795 -0.2986301 -0.7959249 0.4568264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5143 5144 -0.437376 0.126808 0.939638 -0.4949113 -0.1143057 0.6035480 0.6145948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5144 5145 -0.236510 -0.338667 0.805384 0.1617394 0.0245393 0.5280235 0.8333243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5145 5146 -0.511903 0.335082 0.495611 -0.1376139 0.5539775 -0.0704278 0.8180533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5146 5147 -1.019298 0.475471 -0.196134 -0.3354985 -0.4861795 0.1685448 0.7890899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5147 5148 -0.395572 0.085251 1.008729 -0.1627424 -0.9812995 0.0397875 0.0947793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5148 5149 0.419612 0.104783 -1.024088 0.3387678 0.4081922 -0.5769080 0.6211221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5149 5150 0.698390 0.645845 -0.390232 -0.0541961 -0.0463069 -0.0006360 0.9974558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5150 5151 0.824190 0.697117 -0.328243 -0.4852819 0.2534052 -0.6969767 0.4631530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5151 5152 -0.677128 0.104829 0.676367 -0.1477561 0.4572137 -0.4423836 0.7572453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5152 5153 -0.875908 -0.523796 -0.239748 0.0466015 -0.5530692 0.8307277 0.0428271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5153 5154 0.589190 0.570633 0.574665 0.7805054 0.1728481 -0.1232510 0.5880000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5154 5155 0.282751 0.458800 -0.730718 -0.7850159 0.2878771 0.3185500 0.4465453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5155 5156 0.785051 -0.327254 0.449390 0.6262315 0.0380269 0.1517804 0.7637740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5156 5157 0.909375 0.008991 0.372375 -0.4138875 0.1177912 -0.5897531 0.6833840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5157 5158 0.138146 0.208960 1.058149 0.0318421 0.0250905 0.9958753 0.0811728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5158 5159 -0.136245 -0.116279 1.121799 -0.5485548 -0.0920562 -0.8293591 0.0526958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5159 5160 0.356641 -0.573571 -0.496311 -0.4207073 -0.6169797 0.4861043 0.4539207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5160 5161 -0.206487 0.239261 1.006281 0.0210539 -0.3024673 0.9095533 0.2842236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5161 5162 0.490662 -0.685982 0.744560 -0.3252233 -0.6383375 -0.0728203 0.6938676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5162 5163 0.524701 -0.400051 -0.523629 -0.2015962 0.1137380 0.8936307 0.3845085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5163 5164 -0.254403 -0.242858 -0.825386 0.7614721 -0.5534332 -0.1431782 0.3055682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5164 5165 -0.139667 -0.410176 1.071819 -0.8035705 0.5623306 -0.0554383 0.1870434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5165 5166 0.293213 -0.256379 -1.148237 0.8486630 0.1223151 0.3013850 0.4171058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5166 5167 -0.352464 -0.617854 0.470790 0.1243129 -0.6430163 -0.4456495 0.6103055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5167 5168 0.980216 0.034001 0.035701 0.2863766 0.6890147 0.4413092 0.4984911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5168 5169 -0.544087 0.059952 0.883750 0.1767240 -0.7387312 -0.6228522 0.1873498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5169 5170 0.535052 0.761063 -0.056084 -0.3895964 -0.0179704 0.9149596 0.1036368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5170 5171 -0.417423 -0.856799 -0.199730 0.2389375 0.3269131 -0.6144379 0.6771283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5171 5172 0.734369 -0.426949 0.619030 0.1354282 0.0065586 -0.1531934 0.9788503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5172 5173 0.934612 0.148808 0.489279 0.3337441 0.3524635 -0.3566984 0.7982171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5173 5174 -0.116542 0.871466 0.533772 0.6855871 0.1972777 -0.3854660 0.5852075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5174 5175 -0.522163 0.005887 -0.871122 -0.5730138 -0.4079845 0.0483986 0.7091272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5175 5176 -0.667786 0.471791 0.406214 0.1703083 -0.5807165 0.1909318 0.7728573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5176 5177 -0.044159 0.889177 0.547852 -0.3846133 0.1553150 -0.5342054 0.7365965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5177 5178 -0.654818 -0.262615 0.780709 0.7115482 0.1770095 0.1761730 0.6567571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5178 5179 -0.610633 0.631274 -0.336026 -0.3807651 0.5467781 0.7324911 0.1396724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5179 5180 -0.075983 1.109557 -0.159223 -0.4221981 -0.2775964 0.6778816 0.5340090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5180 5181 0.399281 1.094434 0.212243 0.7108263 0.0007866 0.6228045 0.3268638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5181 5182 0.410155 -0.771426 -0.193332 0.4296264 0.3123465 0.8335108 0.1520547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5182 5183 -1.028191 0.329543 -0.123393 0.2836911 0.3986983 -0.1528243 0.8586057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5183 5184 -0.577238 0.006290 -0.683393 0.4279887 -0.0716511 -0.8859560 0.1636268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5184 5185 1.192958 -0.253302 0.001986 0.3545360 0.0325622 -0.8377941 0.4139383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5185 5186 -0.201957 0.871551 -0.373832 -0.3643007 0.3020293 0.4655076 0.7479078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5186 5187 0.554672 0.676415 0.441404 -0.1856184 0.6356046 0.7492652 0.0124193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5187 5188 -0.926907 0.088845 0.506945 -0.7941478 0.1805339 0.1385966 0.5634960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5188 5189 -0.855332 -0.071832 0.080728 0.0670834 -0.4353829 0.5997709 0.6679943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5189 5190 0.160313 0.763832 0.520408 -0.0294574 0.0875860 -0.9639582 0.2494905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5190 5191 -0.443088 -0.906183 0.400836 -0.0095909 -0.0487761 0.9762769 0.2107425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5191 5192 0.347109 0.882918 0.749167 0.1917493 -0.5610366 -0.7575273 0.2731712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5192 5193 -0.640996 0.619010 0.738361 -0.3759089 0.3392558 0.8398766 0.1954620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5193 5194 -0.052990 0.205942 0.889451 -0.0250219 0.2852530 -0.7286598 0.6221411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5194 5195 -0.396835 -0.625014 0.525383 -0.7438443 0.6226588 -0.1530226 0.1886154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5195 5196 0.374418 0.278680 -0.956844 0.3359864 -0.5405689 0.5538711 0.5367730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5196 5197 -0.897025 -0.308984 -0.303065 0.5913597 -0.2226500 0.7749695 0.0119559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5197 5198 -0.074313 0.330097 -0.672678 0.0681405 0.7873806 0.1180799 0.6012036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5198 5199 0.914440 0.633467 0.221525 0.1413415 -0.2514263 0.2957410 0.9106836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5199 5200 -16.221265 4.706778 8.899999 -0.2921357 -0.4883261 -0.8221257 0.0174284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5200 5201 -1.005522 -0.099888 -0.111412 -0.1125641 0.2429420 -0.9051020 0.3303011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5201 5202 0.806675 -0.673963 -0.297971 0.1763208 -0.4093516 -0.2282956 0.8655769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5202 5203 0.478047 -0.480897 -0.780131 0.6124613 0.4557852 -0.1774406 0.6210200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5203 5204 0.847035 -0.113227 0.735810 -0.3617254 0.0555264 0.5375265 0.7596952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5204 5205 -0.315515 -1.001229 0.024967 0.0070230 0.0953471 -0.6651284 0.7405834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5205 5206 0.974319 -0.340393 0.402403 -0.2969322 -0.2240359 0.7403095 0.5599831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5206 5207 -0.538109 -0.767518 -0.415804 0.5580031 -0.0137382 0.7798059 0.2834547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5207 5208 -0.419361 0.800247 -0.500548 -0.8262784 -0.1995612 -0.0695213 0.5221169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5208 5209 -0.147488 -0.216398 0.887435 0.6591937 -0.0407738 -0.3910014 0.6410297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5209 5210 -0.574163 0.742013 0.589536 0.0490952 0.5165380 0.8395857 0.1608537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5210 5211 0.848914 0.291717 0.666517 0.2807886 -0.1889428 0.7407179 0.5803407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5211 5212 0.722617 -0.624738 0.571477 -0.6346301 0.4159811 0.5971087 0.2601259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5212 5213 -0.246880 -0.136010 -1.015196 -0.4310909 0.1900783 0.6879380 0.5520617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5213 5214 0.609667 0.649347 -0.500612 0.0947082 0.9298298 0.3150175 0.1649571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5214 5215 -0.521913 0.288009 0.984485 -0.6093924 -0.0424084 -0.0925266 0.7863086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5215 5216 -0.098941 -0.807642 0.488147 -0.5023072 0.3168780 -0.6928512 0.4089413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5216 5217 1.099044 -0.025896 -0.032688 -0.0355371 -0.6375262 0.6061499 0.4742149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5217 5218 -0.587226 -0.418128 -0.716890 0.4208066 0.2301650 0.7012364 0.5274594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5218 5219 -0.786106 -0.039587 -0.631227 -0.8276107 -0.1158033 -0.0171318 0.5489595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5219 5220 -0.364146 0.068145 -0.968346 0.2236325 -0.5893731 0.1912299 0.7523689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5220 5221 0.081692 -1.009008 -0.675410 -0.3481168 0.0071293 0.7350657 0.5817579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5221 5222 -0.596700 0.232045 -0.858766 0.3100785 -0.4797472 -0.1676267 0.8034894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5222 5223 -0.946743 -0.147171 0.212889 -0.1215262 -0.3419101 -0.0948760 0.9269992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5223 5224 -0.585493 -0.474772 0.794151 -0.0342061 0.0089624 -0.9715269 0.2342755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5224 5225 0.661598 0.112257 0.604704 0.2490530 -0.2668790 0.5387365 0.7592834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5225 5226 0.569118 -0.582788 0.354949 0.5930984 0.5871645 0.5176676 0.1883943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5226 5227 -0.693411 0.797277 0.105118 -0.3434556 -0.1989852 -0.7813264 0.4816349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5227 5228 -0.075279 -1.068448 0.350901 0.3481819 -0.5174487 -0.6538821 0.4283157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5228 5229 0.934834 0.473314 0.294503 -0.3843004 0.3646281 0.8189816 0.2205191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5229 5230 -0.621953 -0.966256 0.100399 0.4059974 0.2825744 0.6242010 0.6047238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5230 5231 -0.896181 0.371342 -0.369840 -0.1024912 -0.1283078 -0.3482171 0.9229179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5231 5232 -0.866951 -0.061339 -0.028473 -0.0751373 -0.3760956 0.6603034 0.6456825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5232 5233 0.249150 0.759057 0.738104 -0.0874842 -0.0085336 0.0123992 0.9960522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5233 5234 0.203653 0.566196 0.776855 -0.3942944 0.4755531 -0.4137773 0.6687073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5234 5235 -0.766344 -0.566142 0.545523 0.1945019 -0.0738508 -0.9684874 0.1369204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5235 5236 0.741242 0.514743 0.553400 -0.2366516 -0.7181323 -0.4293922 0.4938668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5236 5237 0.017292 0.978154 0.003409 0.2814825 -0.1165729 0.3504238 0.8856532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5237 5238 0.672604 0.398773 -0.444502 0.2890196 0.6564404 -0.0916184 0.6907675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5238 5239 0.749704 0.591744 0.456715 0.4112221 -0.0563889 0.1542227 0.8966226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5239 5240 0.323403 -0.113005 1.140737 -0.0850618 -0.7582548 0.0149705 0.6462120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5240 5241 0.355046 -0.607725 0.828405 -0.6733254 0.4378817 0.5428681 0.2453299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5241 5242 -0.899399 0.343254 -0.748254 0.2591698 0.3738336 -0.6937029 0.5584405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5242 5243 0.584692 -0.666563 -0.685703 -0.2251726 -0.0763733 -0.6855751 0.6880779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5243 5244 0.177636 0.405766 -0.814658 0.2366157 -0.1591472 -0.2117365 0.9348010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5244 5245 -0.273067 -0.017684 -0.663255 -0.5422916 0.7828390 0.0799757 0.2944262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5245 5246 0.420045 0.662415 0.689150 0.0402485 0.4044301 -0.7228331 0.5588638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5246 5247 -0.907933 0.000889 0.269820 0.1934600 -0.9417131 0.0001859 0.2752265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5247 5248 1.006998 0.370095 0.361302 -0.3390204 -0.8275301 0.4463733 0.0317788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5248 5249 -0.688069 0.253502 -0.644484 0.6913010 -0.2120262 0.0781945 0.6863187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5249 5250 -1.025185 -0.257175 -0.263232 0.0214547 0.0410259 0.7346575 0.6768567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5250 5251 -0.239136 0.892968 -0.093158 0.2953399 0.5867291 0.3034095 0.6902651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5251 5252 0.981793 0.500889 -0.349033 -0.2128997 -0.2709912 0.9338428 0.0957869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5252 5253 -0.621972 -0.373317 -0.573588 0.1523811 -0.5064890 0.2196466 0.8197587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5253 5254 -0.920675 0.168259 0.365558 -0.3054762 -0.3460399 -0.8373880 0.2927832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5254 5255 0.768647 -0.546759 -0.241895 0.6182133 0.1738579 0.7381568 0.2066646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5255 5256 -0.500900 0.504873 0.637054 0.1100991 0.6284342 -0.3614578 0.6799242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5256 5257 -0.679526 -0.411690 -0.696832 0.4259905 0.2345210 -0.2550845 0.8357415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5257 5258 -0.097927 -0.797476 -0.041718 -0.1195379 -0.6762557 0.7144840 0.1337966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5258 5259 -0.177563 0.167978 0.871325 0.3119360 -0.2718430 0.7508880 0.5147470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5259 5260 -0.436378 0.761571 0.470391 -0.2955783 -0.0132207 -0.9490630 0.1083428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5260 5261 0.342938 0.038855 -1.043194 -0.7554598 0.1490531 0.3620898 0.5253139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5261 5262 0.907777 0.464991 -0.211079 0.7099779 -0.5721879 0.3145633 0.2637846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5262 5263 -0.204610 -0.884716 0.019592 -0.5541882 -0.2779439 -0.7831752 0.0475322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5263 5264 -0.125808 0.855754 -0.711962 0.2408702 0.1560975 0.1732683 0.9421217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5264 5265 0.304118 0.077752 -0.838910 -0.5341880 0.4409153 -0.4917119 0.5276896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5265 5266 -0.531021 0.768971 0.297266 -0.5131438 -0.3106526 -0.0687708 0.7971506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5266 5267 0.034922 -0.009054 0.833466 -0.9166424 -0.2507988 0.2923746 0.1066951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5267 5268 -0.340597 -0.193416 -0.928775 -0.5745091 -0.5815087 0.3557890 0.4529914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5268 5269 -0.508443 0.776060 0.674121 -0.2603292 0.5195241 -0.6289709 0.5164485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5269 5270 -0.551229 -0.554340 -0.370268 0.3196921 0.2436383 0.9030470 0.1514712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5270 5271 -0.053552 0.117532 -1.015051 -0.1188933 0.5991356 0.1196016 0.7826853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5271 5272 1.060096 0.116643 -0.093066 0.0762935 0.1017862 0.6774476 0.7244885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5272 5273 0.221824 -1.013541 0.023165 -0.4163486 0.2716926 -0.6333070 0.5930929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5273 5274 0.898319 0.328770 0.200238 0.3470331 -0.4325302 0.8302755 0.0559299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5274 5275 -0.774058 -0.786178 0.095027 0.2076121 0.4902173 0.0089692 0.8464655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5275 5276 -0.784286 -0.507965 -0.110358 0.5107016 -0.0427776 -0.6685582 0.5388727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5276 5277 0.650971 -0.404936 0.857307 -0.3032144 -0.7010026 -0.5786590 0.2860248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5277 5278 -0.107233 0.896313 -0.460458 0.6522246 0.2193959 0.2885597 0.6657340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5278 5279 0.764907 -0.297254 -0.811761 -0.2486650 0.2419476 -0.5765701 0.7397256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5279 5280 0.627694 -0.513207 0.452323 0.0505329 -0.5366782 0.7883803 0.2964447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5280 5281 0.331263 0.323183 0.919560 0.9338537 0.3441454 0.0969508 0.0090405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5281 5282 0.485830 -0.064689 -0.909190 -0.8039595 0.1727991 0.4522765 0.3453050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5282 5283 0.948532 0.087474 -0.022937 -0.0920551 0.6358034 -0.7650795 0.0439683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5283 5284 -0.940905 0.081471 0.218697 -0.3588501 0.7077247 -0.4224473 0.4380533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5284 5285 0.330866 -0.097970 -0.817102 0.5396728 -0.7464163 0.1124008 0.3728030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5285 5286 -0.557437 -0.659177 0.465285 0.6063721 -0.0321128 -0.2345297 0.7591294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5286 5287 -0.503646 0.396911 0.865257 -0.7306210 -0.3634631 -0.5729039 0.0766072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5287 5288 1.067208 -0.261663 -0.634409 0.5096841 0.1631979 0.2263377 0.8138549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5288 5289 0.543747 -0.746410 0.429928 0.7366508 0.0019329 0.6670173 0.1114890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5289 5290 0.418188 0.842870 0.533091 0.1207571 -0.0951969 -0.7292379 0.6667588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5290 5291 -0.811847 0.242272 0.422933 -0.1045884 0.7725684 -0.2501706 0.5741203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5291 5292 -0.162538 0.059064 -0.953275 -0.7818998 -0.1364576 0.5972229 0.1154854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5292 5293 0.750097 0.453008 0.526704 0.1892176 -0.5521571 0.7838511 0.2118886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5293 5294 -0.389524 -0.934711 -0.167247 -0.1408148 0.1980975 -0.9440654 0.2228657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5294 5295 0.597536 0.477210 -0.077416 -0.1314293 -0.1168239 0.7327679 0.6573658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5295 5296 0.599118 -0.860154 -0.242138 0.3518688 0.4905243 -0.7909875 0.0995643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5296 5297 -0.364962 0.974951 0.195764 -0.3112235 -0.4326768 0.8320231 0.1538449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5297 5298 0.742384 -0.745554 -0.235530 0.4136145 -0.1359055 0.3945824 0.8091708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5298 5299 -0.054370 -0.978445 0.348494 -0.0106408 0.6701995 0.5398220 0.5092264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5299 5300 -0.284984 -0.965585 0.394439 -0.0448722 0.2153495 -0.5216419 0.8243184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5300 5301 0.085089 0.379783 0.895924 0.2796551 -0.0907627 0.2950544 0.9091194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5301 5302 0.580716 0.487091 0.522735 -0.1145930 0.1940650 0.4101845 0.8837171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5302 5303 0.288003 -0.050239 0.829946 0.2764357 -0.2560674 -0.2656973 0.8873656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5303 5304 0.551906 0.601187 0.399811 -0.8086681 0.4467356 0.3480585 0.1591806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5304 5305 -0.556010 -0.847840 0.048621 0.3440394 -0.1801577 -0.6186082 0.6830110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5305 5306 0.700452 -0.387098 0.563489 0.5949388 -0.0387389 0.7138348 0.3674058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5306 5307 0.268151 -0.089618 0.939261 0.2043516 0.4389280 -0.0685832 0.8722838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5307 5308 -0.742291 0.277441 0.678785 -0.8474234 0.5123414 0.1392012 0.0016908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5308 5309 -0.652538 0.575662 -0.327436 0.5019458 -0.1974846 -0.6857811 0.4886252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5309 5310 -0.158106 -0.986724 0.240114 -0.8283999 0.0784398 -0.3845371 0.3996649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5310 5311 0.327225 0.396139 -0.807659 -0.1492473 0.5489647 -0.1490215 0.8087989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5311 5312 0.580859 0.697829 0.293784 -0.1924052 -0.1469596 0.9410737 0.2361428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5312 5313 -0.337906 -0.992770 -0.369513 0.2048937 -0.4814604 -0.5868220 0.6179437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5313 5314 0.702396 -0.642322 -0.181189 -0.4363160 0.4261704 -0.3087072 0.7298678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5314 5315 0.856244 0.171679 0.327173 -0.1700433 -0.5174048 0.5719977 0.6133484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5315 5316 0.006571 -0.808257 -0.568203 -0.3022834 0.2347988 -0.9209370 0.0732755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5316 5317 -0.194323 0.907537 -0.147088 0.6991724 0.5011506 -0.0777528 0.5039450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5317 5318 0.520819 0.010676 -0.945596 0.0654997 -0.4932887 -0.7191633 0.4849538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5318 5319 -0.609242 -0.121129 -0.911442 0.2048699 0.2229738 0.7108730 0.6347996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5319 5320 1.116717 -0.033810 -0.033075 -0.4496638 0.2211933 0.0299859 0.8648565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5320 5321 -0.292148 -0.844388 0.473442 -0.3526047 -0.7776765 -0.4025375 0.3299283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5321 5322 0.420910 -0.342768 -0.799222 -0.1495416 -0.9511053 -0.2664776 0.0450084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5322 5323 -0.475784 -0.492976 0.626026 0.0546112 -0.6711373 -0.4995805 0.5449878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5323 5324 0.882825 -0.152325 -0.042201 0.4353643 -0.0412016 0.3020137 0.8470821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5324 5325 0.737098 -0.611326 0.171572 -0.8894351 -0.1124481 -0.1999625 0.3953172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5325 5326 0.865328 0.289200 -0.358853 0.9159090 0.0233062 -0.0580339 0.3964841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5326 5327 0.939861 -0.460355 0.196427 -0.4724873 0.4688511 -0.1333090 0.7342772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5327 5328 0.706131 -0.321009 0.303219 0.2910382 -0.1429923 -0.2678962 0.9072384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5328 5329 0.939491 0.339540 0.179281 -0.6302487 0.2165161 0.7397307 0.0933048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5329 5330 -0.279359 -0.845857 -0.692814 0.4912854 -0.2669543 0.6201776 0.5502306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5330 5331 -0.909492 0.271962 0.235626 -0.2073648 0.8545901 0.4581454 0.1295315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5331 5332 0.489532 0.684138 0.080226 -0.4323033 0.1209097 -0.6458191 0.6175860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5332 5333 -0.608279 0.240568 0.824705 -0.4663891 0.7431697 -0.4792482 0.0223874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5333 5334 0.533934 -0.367750 -0.585979 0.2701768 0.0105980 -0.2576058 0.9276483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5334 5335 0.921051 -0.299557 -0.584447 -0.5261231 0.5000325 -0.4117879 0.5509924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5335 5336 0.495164 0.326453 0.867826 0.3419482 0.5918447 -0.3215278 0.6552947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5336 5337 -0.655033 0.769365 0.018005 0.9751541 -0.1262644 -0.0745960 0.1660340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5337 5338 -0.872745 -0.757067 -0.349956 0.8506208 -0.2686796 -0.4518137 0.0109539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5338 5339 -0.132886 0.781613 0.420773 -0.1957806 0.0448041 -0.5749730 0.7931384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5339 5340 -0.701084 -0.148702 -0.765445 0.4790739 0.8179853 -0.2421980 0.2067084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5340 5341 -0.066243 0.741800 0.656620 -0.0555195 -0.3238079 0.7411261 0.5854897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5341 5342 0.882481 -0.474746 0.104915 0.2586737 0.5499575 0.1875309 0.7716650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5342 5343 -0.102098 -0.201591 0.890945 0.1772503 -0.8771672 -0.2021143 0.3978817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5343 5344 0.746324 0.390293 -0.442633 0.3653780 -0.0679158 -0.8711542 0.3208999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5344 5345 -0.083336 -0.029852 -0.914006 0.8324745 -0.1529181 -0.5112573 0.1490577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5345 5346 0.647503 -0.246002 0.772749 0.2057771 0.1469007 -0.8365722 0.4860276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5346 5347 -0.429618 0.807719 0.602042 0.7295142 -0.3436913 -0.2630025 0.5296367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5347 5348 -0.815533 0.468674 -0.350503 -0.4853688 0.0844671 -0.5202567 0.6975783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5348 5349 -0.876657 -0.328900 -0.491201 0.4218195 -0.0042104 0.5673547 0.7072194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5349 5350 -0.718800 0.524354 -0.484913 0.4837321 -0.6491725 -0.4262287 0.4036179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5350 5351 -0.379260 -0.224334 0.870613 -0.8735750 -0.0056302 0.4552188 0.1720780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5351 5352 -1.071724 0.023486 -0.434049 0.5050604 -0.2452171 -0.7226033 0.4032704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5352 5353 0.316895 -0.629283 0.775414 -0.6699291 0.0934905 -0.3417067 0.6524501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5353 5354 0.922782 -0.516241 -0.291911 0.1668001 -0.1404230 0.7808986 0.5853687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5354 5355 -0.640948 -0.851930 0.258785 0.1292021 -0.4256372 -0.8829792 0.1499585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5355 5356 0.798490 0.447087 -0.146212 -0.8714196 0.1539786 -0.2448526 0.3961890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5356 5357 0.670535 -0.133528 0.916128 0.9652010 -0.1419349 -0.0154810 0.2190934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5357 5358 0.488943 0.422745 -0.808673 -0.3912797 -0.2762400 -0.0854504 0.8736646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5358 5359 0.261826 0.652528 -0.565991 -0.2239432 0.3542051 -0.5378117 0.7315373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5359 5360 0.515667 0.709533 0.522852 0.7142676 -0.2725024 0.3695489 0.5282024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5360 5361 0.483284 -0.430718 0.843585 -0.2524739 0.2209005 0.6141075 0.7143752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5361 5362 -0.475642 -0.937686 0.540943 0.2683491 0.5067446 0.7106530 0.4076409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5362 5363 -0.232747 0.752231 -0.729080 -0.5053705 0.4625819 0.5868002 0.4316065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5363 5364 0.724137 -0.023762 0.641046 0.4425992 -0.6741468 -0.1091896 0.5811279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5364 5365 0.670846 0.168349 -0.929179 -0.4748123 -0.0546874 -0.7039882 0.5253219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5365 5366 -0.572138 0.807799 -0.092344 0.3199869 -0.1927184 0.8760739 0.3048976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5366 5367 0.766435 -0.075540 -0.616610 -0.2480091 0.3874435 -0.3416200 0.8195577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5367 5368 0.699547 0.664209 0.167948 -0.1559942 -0.1861258 0.9451071 0.2186219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5368 5369 -0.492159 -0.997045 -0.366285 -0.3704028 0.5808501 -0.7230719 0.0508123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5369 5370 0.585961 0.894923 0.322849 -0.3550744 0.3309876 -0.0053291 0.8742660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5370 5371 -0.025549 0.281040 0.885966 0.8573189 0.3746033 0.1104348 0.3353817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5371 5372 0.362987 0.349631 -0.990808 -0.5718844 -0.6580676 -0.3376656 0.3547919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5372 5373 -0.442010 0.325670 0.824720 0.0512593 -0.3161834 -0.6567085 0.6827405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5373 5374 0.077073 -0.220471 1.204114 0.6103363 0.1582079 0.5553742 0.5422355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5374 5375 0.316456 0.978817 0.203972 0.6892592 -0.0906266 0.7178368 0.0376690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5375 5376 0.130242 -0.900485 0.376079 -0.1920905 -0.1504388 -0.0758930 0.9668038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5376 5377 0.282419 -0.999063 0.027195 0.4781901 0.0568633 0.5690612 0.6665360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5377 5378 -0.908385 -0.239572 0.680975 -0.5446645 -0.1488266 -0.1321948 0.8146875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5378 5379 -0.524372 -0.939994 0.216801 0.7541740 0.0572360 0.2272465 0.6134368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5379 5380 0.158128 -0.869194 0.781091 0.3911744 0.1281922 -0.2547154 0.8750253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5380 5381 0.857140 -0.364256 -0.167631 0.4170696 0.6047592 0.5857882 0.3423032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5381 5382 -0.741025 0.236215 0.724174 -0.4030700 0.3290945 0.0531771 0.8522931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5382 5383 -1.136706 -0.089272 0.115156 0.1835902 -0.0460771 0.9025470 0.3867563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5383 5384 0.550230 0.869272 -0.286084 -0.3735874 0.4133128 0.7794315 0.2865160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5384 5385 0.070687 -1.079741 0.694498 -0.6180629 -0.4745646 -0.4802403 0.4026859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5385 5386 0.342735 0.176549 -0.888360 -0.4197764 0.4105882 -0.0485324 0.8079911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5386 5387 0.767806 0.875024 -0.081161 0.2382983 0.5946752 -0.2608943 0.7221561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5387 5388 0.103120 1.167052 -0.042598 -0.5868462 0.2123704 -0.6347059 0.4556960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5388 5389 -0.937780 -0.377654 0.351843 0.4221680 0.6584513 0.2572865 0.5674679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5389 5390 -0.352744 -0.117600 -0.899635 -0.5705472 -0.5354360 0.4280299 0.4522993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5390 5391 -0.419809 0.771922 0.663303 0.6450236 -0.0938894 0.1397662 0.7453823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5391 5392 0.058439 0.675079 -0.621947 0.2703730 0.2300834 -0.3941703 0.8476968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5392 5393 0.024982 0.346418 -1.157293 -0.4356894 -0.6964403 0.2468207 0.5140284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5393 5394 -0.279997 0.907137 0.559419 0.1889737 -0.3789374 0.4163027 0.8046039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5394 5395 0.846812 0.545935 -0.200741 0.0352512 -0.1229181 -0.9829508 0.1321220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5395 5396 -0.991541 -0.679131 -0.085587 -0.6127415 0.6320470 -0.0031678 0.4743989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5396 5397 0.146307 0.466229 -0.688909 -0.1207196 -0.6681127 -0.7206139 0.1405977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5397 5398 -0.452610 -0.631478 0.526844 -0.3700647 0.3590662 -0.4708850 0.7158148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5398 5399 0.418906 -0.813246 -0.458250 0.2961128 -0.4537313 0.8331912 0.1106235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5399 5400 0.854327 0.501471 -0.032737 0.0648156 -0.2171909 -0.8189800 0.5271610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5400 5401 0.196677 0.323158 -1.075685 -0.9038627 0.0740900 -0.0802648 0.4136429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5401 5402 0.169325 0.764447 0.716790 0.3224374 -0.3056316 -0.5675402 0.6931967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5402 5403 -0.532835 0.751121 0.433597 -0.2529917 -0.1707542 -0.1688725 0.9371874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5403 5404 -0.415674 0.288186 0.808423 0.5628717 0.2183244 0.7394512 0.2978621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5404 5405 0.859925 0.446385 -0.326097 0.1811931 -0.5077418 0.1720494 0.8244794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5405 5406 0.144793 0.147277 -0.975642 0.8001073 -0.1068974 0.3985992 0.4353388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5406 5407 -0.517813 -0.635393 0.659410 0.2210759 -0.1611597 0.1014225 0.9564865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5407 5408 -0.293273 -0.054509 0.961588 -0.5630545 0.3917240 0.4158931 0.5971221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5408 5409 -1.162487 0.217754 -0.105828 0.0932673 0.4617657 0.2187134 0.8545397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5409 5410 -0.470873 0.294538 -0.782569 0.2025901 -0.4861167 0.8290607 0.1878992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5410 5411 -0.117016 0.766491 -0.597976 -0.2886496 0.0623931 -0.1365572 0.9455901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5411 5412 -0.116140 1.039786 -0.077528 0.3344555 0.5622681 0.7019350 0.2815695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5412 5413 0.904007 -0.371322 0.478473 -0.7278240 0.0129975 -0.6399183 0.2461866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5413 5414 0.593780 0.502669 0.632156 -0.8112781 -0.2881143 -0.5087221 0.0044528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5414 5415 1.087401 -0.063248 0.341326 0.0696915 -0.3464275 -0.5915176 0.7247331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5415 5416 0.265125 1.015995 -0.445939 -0.3190115 -0.8090477 -0.2105915 0.4464579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5416 5417 0.023370 0.741656 0.604943 0.2056458 0.4044297 -0.2368095 0.8591086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5417 5418 -0.603684 0.629735 -0.251790 -0.3968417 0.3411903 0.6503372 0.5506063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5418 5419 0.336435 0.665046 0.567664 0.2016414 0.0768337 0.8176634 0.5337264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5419 5420 0.801020 -0.014532 -0.632486 0.1707665 0.8743166 0.2854531 0.3534484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5420 5421 1.067156 -0.076067 0.315866 -0.1210468 0.3310986 -0.2507739 0.9015729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5421 5422 0.620543 -0.170776 0.641853 -0.6002893 -0.4410180 -0.3981526 0.5353787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5422 5423 0.931678 0.542446 0.101482 0.0525630 -0.6912671 0.6541781 0.3023872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5423 5424 -0.507740 -0.452647 -0.474616 0.6182224 -0.0836036 0.6856870 0.3750264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5424 5425 -0.760184 0.477808 -0.305310 -0.5644668 0.6639193 0.1756998 0.4579498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5425 5426 0.052978 1.108009 0.172821 0.3541396 -0.3779145 0.0483574 0.8540652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5426 5427 0.115382 0.830650 -0.590089 0.5523150 -0.6726854 -0.4922845 0.0099251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5427 5428 -0.241660 -0.452053 0.959508 -0.4836765 0.0282199 0.8321622 0.2697531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5428 5429 -0.807379 0.536697 0.715259 -0.1464963 -0.2618840 0.9485835 0.1007222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5429 5430 0.593192 -0.627902 0.693406 -0.1553767 0.5308169 0.8255822 0.1118283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5430 5431 -0.720716 0.510895 -0.549570 -0.2459753 0.5377394 0.8029807 0.0745285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5431 5432 0.815691 0.031704 0.338122 -0.0015964 -0.1349803 0.3189187 0.9381197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5432 5433 0.668511 -0.672568 0.128955 -0.3165541 -0.1545798 -0.7927591 0.4974250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5433 5434 0.407552 1.047029 0.130376 0.3847576 0.0923796 0.9163079 0.0617038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5434 5435 -0.068175 -0.952045 0.403391 0.5211242 -0.3886415 -0.4642160 0.6015736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5435 5436 0.780921 0.628285 0.336969 -0.4910669 -0.0550603 0.8247712 0.2749075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5436 5437 -0.196240 -1.041411 -0.296184 0.1067302 0.5091883 0.1678947 0.8373454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5437 5438 -0.065846 -0.868826 -0.476759 -0.7355340 -0.2091144 0.4018492 0.5037639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5438 5439 -0.607973 0.833040 -0.462429 0.6870318 0.0178254 0.2934587 0.6644934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5439 5440 0.567599 0.533056 -0.457256 0.2561919 -0.2197492 -0.6978514 0.6317273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5440 5441 -0.367662 1.026330 0.516044 -0.1107704 -0.1144177 -0.9809358 0.1113704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5441 5442 0.250192 -0.751198 0.403367 -0.2763327 -0.8261533 -0.3982268 0.2872742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5442 5443 -0.190736 0.036636 -1.000840 0.2842827 0.5521465 0.7835779 0.0179765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5443 5444 -0.201346 -1.112869 -0.214772 0.5159617 -0.0017013 -0.3441841 0.7844220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5444 5445 0.381526 -0.553664 0.746363 -0.0920214 0.9193733 0.1386656 0.3564502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5445 5446 -0.808447 -0.632056 -0.377236 -0.8618067 -0.2942208 -0.1045437 0.3997423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5446 5447 -1.017216 0.098265 -0.150420 0.0549040 0.8345639 -0.3557324 0.4170648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5447 5448 0.729049 -0.185763 -0.792567 0.7213870 0.1082120 -0.3765830 0.5710309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5448 5449 0.838698 -0.015332 -0.078507 0.4080337 -0.1075417 0.8443657 0.3301361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5449 5450 -0.799079 -0.431812 0.572748 0.1542315 -0.4748773 0.6892752 0.5249799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5450 5451 0.490035 0.018897 0.870478 0.3242056 -0.5814151 0.1036187 0.7389928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5451 5452 0.987500 0.079276 -0.108824 0.4065502 0.6671023 0.3915302 0.4862053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5452 5453 0.137348 0.033821 1.063908 -0.9643721 -0.0958304 0.2409763 0.0522815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5453 5454 -0.483788 -0.262353 -0.873008 0.6188497 -0.0506173 -0.3976682 0.6755168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5454 5455 0.249610 -1.069167 0.112078 -0.4877517 -0.0074522 0.3984971 0.7766871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5455 5456 -0.707290 -0.253851 -0.749902 0.7360855 -0.3470970 0.0695928 0.5769391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5456 5457 -0.701716 0.004954 0.772513 -0.4513554 0.3593723 -0.4451212 0.6848335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5457 5458 -0.251116 -0.766776 -0.292637 -0.5203983 -0.3356958 0.7818920 0.0716856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5458 5459 0.024178 0.999668 0.507623 0.5853439 -0.5552707 -0.5545161 0.2038599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5459 5460 0.212363 -0.050940 0.819008 -0.7795795 0.5913644 0.1982136 0.0570551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5460 5461 0.561119 -0.935769 0.091175 0.5495506 -0.3784603 -0.6728138 0.3195050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5461 5462 0.534655 0.405033 -0.672711 -0.2945014 -0.0570243 0.4929344 0.8167207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5462 5463 0.700326 0.068930 -0.649427 0.8565195 -0.0310352 0.3468520 0.3809263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5463 5464 0.114559 -0.599317 0.652918 -0.4317342 -0.0583275 0.3481355 0.8300634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5464 5465 -0.572152 -1.015274 0.034419 0.2308884 0.0715793 0.9199344 0.3086872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5465 5466 -0.206768 0.872712 -0.417429 -0.7000480 -0.0240279 0.0328054 0.7129370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5466 5467 -0.027345 0.481118 0.870454 0.3713112 -0.6351098 0.2676286 0.6222045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5467 5468 1.015316 0.296538 -0.282701 0.5093495 0.0738201 0.1320689 0.8471549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5468 5469 0.984514 -0.220225 -0.266669 0.1186547 0.3227425 0.5014617 0.7939109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5469 5470 0.217858 -0.835715 0.621051 -0.6810936 0.2172475 -0.6679681 0.2067214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5470 5471 0.777447 0.440321 0.027668 0.3845238 0.0951803 0.8422196 0.3657161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5471 5472 -0.055803 -0.675623 0.708063 -0.7319013 0.1511137 -0.5557492 0.3641811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5472 5473 0.948388 0.058309 -0.330627 0.8282654 -0.4637394 0.2802662 0.1427343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5473 5474 0.435235 -0.777687 0.450970 -0.6151364 0.3497134 0.3551511 0.6108809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5474 5475 -0.142888 -0.700324 -0.824180 0.3002632 0.4603242 -0.2939350 0.7820139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5475 5476 0.612345 -0.435299 -0.116700 -0.0224098 0.2157461 0.9655760 0.1435773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5476 5477 -0.884172 0.274737 -0.353546 -0.7952924 -0.1072047 0.4956500 0.3321870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5477 5478 -0.041854 0.137232 0.942533 0.6514153 0.6229248 -0.3693046 0.2263557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5478 5479 -0.657270 -0.039384 -0.786083 -0.3309177 0.2253301 0.8509111 0.3401031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5479 5480 0.296685 -0.499143 0.549657 -0.4855765 -0.4759298 -0.3722033 0.6317997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5480 5481 0.128471 -1.083695 -0.040191 0.4763115 0.0470363 0.8056871 0.3489746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5481 5482 -0.746746 0.660778 0.386350 -0.1138452 0.0186320 -0.9388852 0.3243249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5482 5483 0.278902 -0.862691 0.149963 0.5268164 0.2773317 -0.8012216 0.0599625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5483 5484 -0.550248 0.952477 0.354356 -0.5090714 -0.5351810 0.6712524 0.0620315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5484 5485 0.478964 -0.810854 -0.317438 0.5285689 -0.2322938 0.5421250 0.6105367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5485 5486 -0.398003 -0.541602 0.960599 0.3379281 0.4697277 0.1819003 0.7950301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5486 5487 -1.034491 0.222406 0.368239 0.1237594 0.2730182 0.4292770 0.8519776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5487 5488 -0.153890 0.979554 -0.270414 -0.2455905 0.6443018 0.3592333 0.6288974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5488 5489 0.297416 0.718735 0.458731 0.4404046 -0.5938274 0.3405291 0.5809068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5489 5490 0.377184 -0.171956 -0.821167 -0.0074671 -0.4973206 -0.7243155 0.4774762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5490 5491 -0.670415 -0.386045 -0.668062 -0.0873419 -0.5284028 -0.6262943 0.5664956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5491 5492 0.035941 -0.880923 -0.193861 0.5669471 -0.3710359 0.0752498 0.7316015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5492 5493 0.181011 -0.438938 0.851477 -0.4330728 -0.1854106 0.6258546 0.6215922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5493 5494 -0.496534 -0.785356 0.409673 -0.2366451 0.7285216 -0.4760110 0.4320520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5494 5495 0.981694 -0.665525 -0.203711 -0.0141659 -0.2777838 0.9585615 0.0616062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5495 5496 -0.998389 0.329657 0.090260 0.4032089 -0.0234789 0.6922132 0.5980905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5496 5497 0.271996 0.833587 -0.814282 -0.3100646 -0.5713626 -0.5475707 0.5268502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5497 5498 -0.797883 0.206008 0.443513 -0.2798753 0.4386537 -0.0696825 0.8511152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5498 5499 -1.170409 -0.074416 -0.437452 -0.0927135 0.0918646 0.7943176 0.5933166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5499 5500 -1.009213 0.367275 0.095688 -0.3255463 0.3550145 -0.2984518 0.8239605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5500 5501 0.128753 -0.842617 -0.166196 -0.3059689 -0.6493509 -0.3247269 0.6158563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5501 5502 -0.352129 -0.484871 -0.787838 0.4223962 0.5950450 -0.2548934 0.6344543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5502 5503 0.611015 -0.689119 0.247490 -0.5035034 0.2746573 0.8119524 0.1085399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5503 5504 -0.514186 0.445539 -0.669499 -0.6782373 0.0442275 0.7238341 0.1187536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5504 5505 0.700162 -0.083648 0.425526 0.2046186 -0.4241817 -0.1050196 0.8758836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5505 5506 0.931329 0.266058 0.029690 0.0046276 -0.1041312 -0.7236014 0.6823022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5506 5507 -0.221290 0.892109 -0.420043 0.2461979 0.1857721 0.9077350 0.2844159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5507 5508 0.362529 -0.894572 -0.278627 0.0256527 0.5859451 0.7951055 0.1543292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5508 5509 -0.686743 -0.104913 -0.914221 -0.3868387 0.0136858 0.8820258 0.2686988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5509 5510 0.720503 0.526878 0.101981 0.3061653 0.2590976 0.6425957 0.6528416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5510 5511 0.578419 -0.560505 0.736885 -0.7071973 0.1177478 -0.0596859 0.6945826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5511 5512 0.545808 -0.676806 -0.518808 0.2147159 0.0459806 0.8421162 0.4925679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5512 5513 -0.963528 -0.208745 -0.155844 0.1175223 -0.2602703 0.6245205 0.7269265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5513 5514 -0.295159 1.050004 -0.012628 0.3205049 0.7659655 0.5398835 0.1382002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5514 5515 0.828309 0.163479 0.661938 0.0369961 0.4998656 0.7215797 0.4775860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5515 5516 -0.643861 -0.134238 0.800885 -0.3506652 0.6504575 -0.5571752 0.3788069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5516 5517 0.280868 -0.802992 -0.465621 0.0694798 -0.6166432 0.7584557 0.1991697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5517 5518 -0.532664 0.447424 0.512242 -0.0545545 -0.5917907 -0.7782420 0.2028471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5518 5519 0.693197 0.038416 0.915984 0.0387536 0.8293155 0.4765759 0.2891529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5519 5520 0.162968 0.345488 -0.964199 -0.6345215 0.4599848 0.5390382 0.3086004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5520 5521 0.048141 -0.458494 -0.779467 0.5685599 -0.6917101 0.1320626 0.4252485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5521 5522 -0.279146 -0.678375 0.576008 0.1636362 -0.4115436 -0.8010561 0.4026962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5522 5523 0.744537 0.481648 0.306024 -0.8146918 0.5002728 0.2454692 0.1604658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5523 5524 -0.286377 -0.900019 -0.009182 -0.1210538 0.4734898 0.7980083 0.3526132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5524 5525 -0.182828 0.363186 -0.879759 -0.4623186 -0.0237311 -0.8554458 0.2321870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5525 5526 -0.492734 -0.393470 -0.449365 -0.3579451 0.3020503 0.8675483 0.1673349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5526 5527 0.769125 0.352377 -0.160433 -0.2560334 -0.2142153 0.6325421 0.6988914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5527 5528 0.557003 -0.506720 -0.621102 0.5658629 0.1847446 -0.0466368 0.8021806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5528 5529 0.623252 -0.355658 0.345777 -0.3955091 0.3853792 -0.7918822 0.2607258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5529 5530 0.155859 -0.120813 1.132757 -0.3629149 -0.5735590 0.1291483 0.7229409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5530 5531 0.747151 -0.781458 -0.108192 0.5165787 -0.2769024 0.7270024 0.3576856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5531 5532 -0.440173 -0.262358 1.000723 0.0840096 0.0230014 0.1373785 0.9866815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5532 5533 -0.589520 0.221928 0.792379 -0.0871454 -0.4905144 -0.6417838 0.5830222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5533 5534 0.448718 -0.042121 0.838430 -0.1443341 -0.0754768 0.6664694 0.7275229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5534 5535 0.096190 -0.724692 0.685941 -0.7564177 0.4546099 -0.1519743 0.4450460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5535 5536 0.566209 -0.178244 -0.884243 0.5486816 0.3794497 0.2360149 0.7065857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5536 5537 0.365508 -0.712017 0.435053 0.0949953 0.2228801 -0.9413806 0.2347401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5537 5538 -0.090390 0.634270 0.785508 0.3739624 0.3085014 0.8174195 0.3111341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5538 5539 0.819364 0.220121 0.359043 -0.4589738 0.1211144 -0.5740334 0.6672032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5539 5540 -0.748760 0.674210 0.242080 0.1090171 -0.5867018 -0.2468073 0.7635329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5540 5541 -0.872471 -0.831513 -0.084013 0.5653493 -0.1485487 -0.1686217 0.7936499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5541 5542 -0.380795 -0.478058 0.777652 -0.3509392 0.6317141 -0.6227601 0.2999147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5542 5543 0.511765 -0.655049 -0.180398 0.0851895 0.5233636 -0.7718096 0.3509177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5543 5544 -0.088488 0.528932 0.914576 -0.0411829 0.7868582 -0.3028138 0.5361547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5544 5545 -0.930892 -0.253803 -0.561003 -0.0137999 0.6956941 -0.5648574 0.4435713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5545 5546 0.821034 0.000627 -0.238250 0.2847961 0.7577636 -0.5601590 0.1758050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5546 5547 -0.321749 0.808212 0.036959 0.4211241 0.2322428 0.6492526 0.5892273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5547 5548 0.930631 0.111088 -0.252464 -0.6543184 -0.2837519 0.2598107 0.6510382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5548 5549 0.841591 0.434152 -0.387298 0.0854931 0.7326834 -0.5748721 0.3541016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5549 5550 -0.499989 0.784274 0.135972 0.3536160 -0.2294033 -0.6183630 0.6632926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5550 5551 -0.871889 -0.307275 0.429628 -0.1900696 -0.3298285 -0.3920163 0.8375022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5551 5552 0.022761 -0.778532 0.467130 -0.1482129 0.3112725 -0.7898050 0.5072972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5552 5553 1.069035 0.268272 0.549468 0.0756526 -0.6897801 -0.3653997 0.6204540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5553 5554 0.248248 0.394086 -0.898585 0.1046509 -0.7643323 -0.6297292 0.0910244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5554 5555 -0.622596 -0.681760 0.620887 0.1914672 0.0090138 -0.7555910 0.6263716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5555 5556 0.707732 -0.073483 0.679187 -0.7457588 -0.0256671 0.6656034 0.0125332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5556 5557 -0.581920 0.143612 -0.654585 -0.0061094 -0.3040619 0.9457462 0.1143376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5557 5558 0.658954 0.194218 -0.553753 0.6028335 0.2897956 0.7364749 0.1010692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5558 5559 -0.513835 -0.387812 0.832300 -0.2524583 0.9023314 0.2854676 0.2014226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5559 5560 0.975344 -0.244971 0.085438 -0.9775999 -0.1324631 -0.1499929 0.0652228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5560 5561 0.274696 0.102107 -1.050066 0.5007291 -0.0161907 0.6815642 0.5333653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5561 5562 -0.594682 -0.558781 -0.528897 0.3648262 0.6356336 -0.6710099 0.1123272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5562 5563 0.491900 0.132374 0.869291 -0.2681892 -0.2035037 0.9170192 0.2138611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5563 5564 -0.819427 -0.653193 0.323268 0.7793202 0.2414844 -0.5774797 0.0293686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5564 5565 -0.608388 0.407307 0.905299 0.6112311 -0.0223451 0.3206232 0.7232552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5565 5566 0.006480 0.973674 -0.100392 -0.0523566 -0.1121111 0.1412601 0.9822095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5566 5567 0.140759 0.997385 -0.095654 0.1661476 0.3422803 0.8625383 0.3335669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5567 5568 0.550043 -0.474296 0.447712 0.3823094 -0.1421084 -0.2568577 0.8761671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5568 5569 0.748043 0.320724 0.441336 0.0720165 -0.8014042 -0.1167770 0.5821753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5569 5570 -0.061667 0.345359 -0.831966 -0.9066674 -0.3282628 -0.0099280 0.2647624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5570 5571 0.092910 0.217207 0.773684 0.6162714 -0.0758335 0.0116710 0.7837874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5571 5572 0.198232 1.081209 0.041152 -0.4657917 0.4403570 0.1915739 0.7432518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5572 5573 -0.044399 0.347887 0.978691 0.7380901 -0.4129465 -0.4380050 0.3047126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5573 5574 -0.696486 0.689034 -0.555415 -0.6898120 0.0215387 0.1830920 0.7001234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5574 5575 -0.268239 0.501232 0.787372 0.3180460 -0.1285924 -0.6103386 0.7140011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5575 5576 -0.743866 0.117097 0.596405 -0.5753928 -0.1176971 0.2129893 0.7808368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5576 5577 -0.536560 -0.552527 0.609734 0.5726954 -0.3328968 0.6397728 0.3897313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5577 5578 0.708836 0.742774 0.113055 0.4841999 0.2526970 -0.7599810 0.3523117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5578 5579 -0.524843 0.123799 -0.839816 0.1506997 0.9287210 0.3046881 0.1480948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5579 5580 0.506298 -0.447843 -1.020571 -0.4200588 0.0382240 0.7060741 0.5688136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5580 5581 0.549363 0.606196 0.424278 0.4860973 0.2139595 -0.7089644 0.4640045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5581 5582 -0.602953 0.535247 -0.678597 -0.8036380 0.4368263 -0.0613531 0.3994805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5582 5583 -0.280281 0.804916 0.363486 -0.0316269 0.0468963 -0.9983976 0.0016548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5583 5584 0.623741 -0.838615 0.206508 -0.0812197 0.3653241 -0.3575858 0.8556133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5584 5585 0.825778 -0.454576 0.466226 -0.2588091 -0.1685745 0.0446796 0.9500549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5585 5586 0.808069 -0.741792 -0.059492 -0.1772874 -0.3608231 0.5055875 0.7633853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5586 5587 -0.444947 -0.571576 -0.446542 0.0644207 0.1483532 -0.7716270 0.6151691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5587 5588 1.006729 -0.221726 -0.412377 0.2242028 -0.4366026 -0.5338146 0.6885879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5588 5589 0.184964 0.214635 -0.887802 -0.1396328 -0.4559636 -0.6296535 0.6132995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5589 5590 -0.697168 -0.326162 -0.630437 -0.0036833 -0.5586388 0.5209056 0.6454196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5590 5591 -0.283126 0.725659 0.489517 0.6276984 0.0101474 0.7689870 0.1206260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5591 5592 0.904451 -0.508179 -0.417056 -0.6045172 0.4289212 -0.4304062 0.5151078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5592 5593 0.472307 0.383195 0.660211 -0.1998640 0.5929692 -0.1712362 0.7609993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5593 5594 -0.629857 -0.158709 0.735600 -0.3335592 0.6512838 -0.5592275 0.3896567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5594 5595 0.370195 -0.726942 -0.761460 0.0142897 0.1421538 -0.2323868 0.9620730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5595 5596 0.690537 -0.320147 -0.452182 0.7268810 0.1288418 0.3137978 0.5971388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5596 5597 0.303915 -0.383802 0.972109 -0.4578610 0.0656732 -0.7736076 0.4331069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5597 5598 0.814741 -0.017398 0.351976 0.2838781 0.2663927 -0.4726523 0.7905997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5598 5599 0.023116 0.982130 0.530712 -0.8040849 -0.4487562 0.3847352 0.0635929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5599 5600 -7.079961 13.025119 11.662373 0.5915542 -0.0385898 -0.5908113 0.5472809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5600 5601 1.042625 -0.051672 0.098618 0.2918754 -0.1293638 0.8668493 0.3829439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5601 5602 -0.625400 -0.774124 0.403087 0.5654715 -0.0191060 0.1799631 0.8046677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5602 5603 -0.735889 0.220077 0.525938 0.0645937 0.3480601 -0.1993582 0.9137495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5603 5604 -1.133790 0.010786 0.020468 -0.4105586 0.4714854 0.4660276 0.6260682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5604 5605 -0.292052 1.118007 -0.079054 0.5583221 -0.4428408 0.1695253 0.6807566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5605 5606 -0.613084 0.416196 -0.835489 -0.1456505 0.3411950 -0.5309946 0.7618508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5606 5607 -0.158515 0.450745 -0.910523 -0.0458169 -0.2933310 -0.6407790 0.7079972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5607 5608 -0.774261 -0.274006 -0.573480 0.7971224 -0.0599825 -0.1530452 0.5810121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5608 5609 -0.559962 -0.502746 0.704302 -0.2083742 0.4641010 0.7647001 0.3955051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5609 5610 -0.206693 0.991463 -0.188819 -0.2903029 0.4349225 -0.4513131 0.7231066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5610 5611 -0.846529 0.326356 -0.189452 -0.2834853 -0.6205154 0.4604584 0.5679566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5611 5612 0.337636 0.567362 0.723369 0.0510535 0.4515837 -0.6429779 0.6164780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5612 5613 -1.044175 -0.058438 0.065386 -0.3655973 0.1319857 -0.8717267 0.2983471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5613 5614 0.803289 -0.251441 -0.600715 -0.1721635 0.4747955 -0.5368072 0.6758454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5614 5615 0.519598 0.806201 0.222661 0.1880004 -0.2967927 0.9249573 0.1449963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5615 5616 -0.289831 -0.963174 -0.142318 0.6202993 0.0391517 -0.0773581 0.7795586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5616 5617 -0.076821 -0.138346 1.139113 0.6494347 0.4478259 0.2941606 0.5395888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5617 5618 -0.361393 0.826881 -0.345107 -0.3344578 0.7725683 -0.2135893 0.4956368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5618 5619 -0.417514 0.793592 -0.134509 -0.0630035 0.1778401 -0.5319978 0.8254585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5619 5620 0.362535 -0.519488 -0.908467 0.2201598 0.0069589 0.9427328 0.2504719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5620 5621 -0.552685 -0.234153 0.849487 -0.2338252 0.4089686 -0.2229595 0.8534398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5621 5622 -0.749603 -0.846764 -0.341313 0.0988360 -0.1602722 -0.8092882 0.5564143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5622 5623 0.905029 -0.396106 -0.103875 0.7284074 0.3082846 -0.5826910 0.1866937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5623 5624 0.035743 0.987242 -0.598054 -0.2744491 -0.5644850 0.6485968 0.4305307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5624 5625 0.505694 0.476625 -0.488103 0.4349793 0.6222098 -0.2376183 0.6059583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5625 5626 0.886133 0.716586 -0.232022 -0.6949664 0.1368579 0.6967859 0.1130535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5626 5627 0.037165 -0.949807 -0.650958 0.2421942 -0.4091689 -0.8694622 0.1340085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5627 5628 0.330667 0.358707 -1.018132 0.0508907 -0.6082121 -0.7918852 0.0201487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5628 5629 -0.100610 -1.060946 -0.250066 0.5196223 -0.4576407 -0.4566386 0.5586044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5629 5630 0.791140 -0.317971 0.381052 -0.2617599 -0.2161515 -0.4571770 0.8220398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5630 5631 1.077208 0.505434 0.129052 -0.4451339 -0.4381501 0.1630809 0.7637309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5631 5632 0.724589 0.524993 -0.507497 -0.3004651 0.7716827 -0.4416415 0.3452237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5632 5633 -0.661011 0.108728 0.708119 0.8501352 0.0849160 -0.0874540 0.5122609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5633 5634 -0.655720 0.342877 -0.586058 -0.4408312 0.4315004 -0.0908692 0.7818043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5634 5635 -0.147441 0.870762 -0.491043 0.3368430 -0.4468579 0.5117095 0.6519265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5635 5636 -0.105115 0.477975 -1.008414 0.3815869 -0.4493921 -0.8045968 0.0711492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5636 5637 0.586902 -0.951603 0.208586 0.3127652 -0.6654998 -0.2378431 0.6346011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5637 5638 0.711438 -0.618742 -0.328674 -0.1885765 -0.4939338 0.8144689 0.2389742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5638 5639 -0.748589 0.485165 0.001776 0.0180933 -0.2608789 0.9650893 0.0147446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5639 5640 0.297588 -0.724877 0.740656 -0.3879670 0.3100712 0.3291850 0.8031032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5640 5641 -0.721291 0.491466 0.216442 -0.4162703 -0.1232314 0.6973650 0.5702764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5641 5642 0.643669 0.295223 0.833218 0.7972450 0.2364162 -0.4913108 0.2590784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5642 5643 -0.618557 0.488357 -0.836589 0.7796732 -0.5426628 -0.2594948 0.1740381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5643 5644 -0.109757 -0.118503 0.849008 0.1367903 0.0825914 -0.9788047 0.1280951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5644 5645 0.121822 0.079423 0.813818 0.2163280 -0.5091444 0.7276986 0.4054982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5645 5646 0.541495 -0.792319 0.183511 0.2789748 -0.4694498 -0.4561478 0.7026515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5646 5647 0.831701 0.081276 -0.543140 0.6944461 0.4930510 0.4655909 0.2405630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5647 5648 0.224299 0.038693 1.022768 -0.2871951 0.3938675 0.7559692 0.4369186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5648 5649 -0.722453 0.263811 0.501851 -0.6865317 -0.1898675 0.6618501 0.2336215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5649 5650 -0.402755 -0.361567 0.880923 0.6874983 -0.6334730 -0.1246233 0.3324563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5650 5651 0.583431 0.739132 -0.220215 -0.2918395 0.4311546 0.6339833 0.5718397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5651 5652 0.535342 -0.732406 0.460881 -0.3855869 -0.5790066 -0.6960637 0.1776779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5652 5653 0.036204 0.731925 -0.532732 0.1481720 0.2360647 -0.4109689 0.8679995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5653 5654 -0.338644 0.634432 -0.995456 -0.3271522 0.5177819 0.4599168 0.6429230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5654 5655 0.969590 0.331187 0.219428 0.5796197 -0.3123262 -0.7516255 0.0394005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5655 5656 -0.584793 -0.455037 -0.917680 0.2101604 -0.2720127 0.7237995 0.5982942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5656 5657 -0.603680 0.575240 -0.220062 -0.2709137 0.0777387 0.1024032 0.9539791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5657 5658 -0.431416 1.026581 0.094340 -0.4164045 0.0175491 0.7056910 0.5729742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5658 5659 0.636312 0.064853 0.658845 0.1378818 0.4259990 -0.7599184 0.4712086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5659 5660 -0.407416 -0.838355 -0.303960 0.2318342 0.3096091 -0.6285801 0.6747460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5660 5661 0.537925 0.800815 -0.243108 -0.7080615 -0.1873593 0.6168301 0.2882118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5661 5662 0.865183 -0.469458 -0.193942 -0.0682727 -0.9973792 0.0170789 0.0167868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5662 5663 -1.060894 -0.247922 0.374196 0.7541182 -0.4341908 0.1672922 0.4634625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5663 5664 -0.061646 0.970859 0.151366 0.5481776 -0.6112274 0.5226170 0.2297254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5664 5665 -0.381012 -0.426436 -0.755250 -0.1695389 0.4279460 -0.8732856 0.1596591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5665 5666 0.399340 0.977120 -0.447370 -0.2686590 0.3728164 -0.4178130 0.7837491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5666 5667 -0.447888 0.658974 0.061521 0.4320042 0.3800015 -0.8019647 0.1606980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5667 5668 0.369799 -0.900181 -0.356457 0.5010301 0.2102730 -0.2724976 0.7940398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5668 5669 0.719649 -0.190190 0.575249 -0.3945511 0.3532299 0.7961924 0.2926360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5669 5670 -0.863953 -0.222041 -0.328776 0.1848675 -0.3380516 -0.9053745 0.1784435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5670 5671 0.696469 -0.345598 0.190219 -0.0586277 -0.4648858 0.8637551 0.1853945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5671 5672 -0.908688 -0.326034 0.140165 0.5230706 -0.0552584 -0.7948689 0.3025344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5672 5673 0.383110 -0.201175 0.886319 0.4254223 0.3818090 0.8186928 0.0545876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5673 5674 0.501687 0.817082 0.472330 -0.5767596 0.4642320 -0.6602754 0.1259898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5674 5675 -0.401118 -0.944994 -0.051341 -0.1041845 0.8182670 0.0104353 0.5652219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5675 5676 0.197910 -0.612726 -0.472804 0.7060709 -0.5582038 -0.3556609 0.2517494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5676 5677 0.847229 -0.374412 0.113355 -0.3618783 0.3605033 0.0293061 0.8591988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5677 5678 0.643094 -0.507911 0.289461 -0.2996226 0.4589752 0.4522194 0.7036091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5678 5679 -0.161441 -0.849220 -0.281281 -0.3748910 -0.3761633 -0.1193184 0.8388808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5679 5680 -0.946110 0.256751 0.381231 0.3189640 0.6309771 -0.5466837 0.4486277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5680 5681 -0.658491 0.156276 -0.534226 0.5848421 -0.6679223 -0.3701014 0.2736137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5681 5682 0.043493 -0.111392 0.798059 -0.6732741 0.6111774 -0.1940992 0.3680892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5682 5683 -0.245724 -0.587720 -0.534963 0.2529640 -0.6865562 0.3452144 0.5877727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5683 5684 -0.665221 -0.238196 0.473248 -0.4214536 0.6022632 -0.3793548 0.5619127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5684 5685 -0.063260 -0.683228 -0.784391 0.1688156 0.2199969 -0.8485874 0.4505576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5685 5686 0.916413 0.450825 -0.395861 0.1355956 0.0774165 0.5663690 0.8092260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5686 5687 0.612160 -0.710494 -0.054091 0.1416182 -0.5103497 -0.0177410 0.8480405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5687 5688 0.255909 -0.707719 -0.528829 -0.2034965 0.5012673 0.6785857 0.4968317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5688 5689 0.058432 -0.387998 -0.833971 0.4491075 0.5516119 -0.3912700 0.5838960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5689 5690 0.622118 -0.168108 0.622352 0.7188888 0.4657396 -0.4062433 0.3182012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5690 5691 -0.453275 0.968124 -0.236158 0.0799174 0.0183223 0.4240848 0.9019033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5691 5692 0.392537 0.885988 -0.563690 -0.5366459 -0.6518595 0.1101632 0.5243610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5692 5693 0.326469 0.837043 0.321418 0.0268902 0.7884728 -0.0810394 0.6091142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5693 5694 -0.290928 0.960414 0.177815 0.4827671 0.0670214 -0.1888136 0.8525218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5694 5695 -0.561783 0.276020 -0.520843 -0.1473534 0.0368380 -0.9776254 0.1455286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5695 5696 0.330416 -0.532564 -0.865484 -0.3751961 -0.1275369 -0.7828159 0.4797515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5696 5697 -0.248889 0.819921 -0.647588 -0.2231073 0.7173393 0.6388580 0.1658549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5697 5698 0.459781 -0.223284 0.777489 -0.7886545 -0.2649370 0.5524530 0.0512656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5698 5699 -0.680880 0.038073 -0.767764 -0.1379959 -0.6186948 0.5202156 0.5723196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5699 5700 -0.985637 -0.060201 -0.117602 -0.2205790 0.2892081 0.9314943 0.0046917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5700 5701 0.038235 0.796074 -0.834138 -0.8956605 0.2003680 0.1173243 0.3793151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5701 5702 0.395050 0.322368 0.754741 0.6380900 -0.3272245 0.5348577 0.4468697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5702 5703 0.978122 0.059866 -0.163826 -0.5063727 0.0168912 0.6902227 0.5166180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5703 5704 0.154738 -0.544509 -0.894541 0.7546635 -0.3611110 0.2863302 0.4670085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5704 5705 -0.495911 -0.157568 0.963447 -0.2384247 -0.1540829 -0.1947413 0.9388759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5705 5706 0.092312 -0.569931 0.789431 -0.1417487 -0.5289786 -0.8297742 0.1075348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5706 5707 -0.040736 0.745160 -0.231578 -0.1528532 -0.1475930 0.6095392 0.7637500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5707 5708 0.918244 0.117754 -0.134350 -0.1305296 0.1475872 -0.8700435 0.4518897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5708 5709 -0.722221 0.709700 0.030027 0.4744279 -0.2582914 0.5238731 0.6586051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5709 5710 0.502207 0.765531 -0.704095 0.2158730 0.6568286 0.7176881 0.0830594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5710 5711 -0.240452 -0.498599 0.828301 -0.7184985 0.2789018 0.0304521 0.6364325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5711 5712 -0.046871 -0.586972 -0.769409 -0.2994947 -0.3438365 0.5366730 0.7099729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5712 5713 -0.723282 0.623133 -0.102714 0.3732825 -0.0701636 0.4421431 0.8125557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5713 5714 -0.545303 0.492788 -0.769022 -0.2309460 -0.8223455 -0.5182764 0.0424427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5714 5715 0.359688 -0.519777 0.917069 0.3675671 0.7092711 0.5506964 0.2419967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5715 5716 -0.371778 0.880474 -0.316273 0.1820226 0.0623812 -0.9740313 0.1193285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5716 5717 0.354768 -0.685740 -0.312081 0.6167404 -0.5055654 0.4711969 0.3768400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5717 5718 0.222707 -0.192444 0.964909 0.5867386 0.2251647 0.7386361 0.2438349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5718 5719 0.549631 0.786634 0.309568 -0.3616606 0.7037532 -0.4942833 0.3600237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5719 5720 -0.051810 0.294965 0.782786 0.6784664 0.2937881 -0.6726539 0.0301437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5720 5721 -0.112117 0.430278 -1.003064 -0.0539477 0.4886989 0.8635379 0.1120950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5721 5722 0.331577 -1.023525 -0.211828 -0.5599938 -0.0233064 0.0827788 0.8240215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5722 5723 0.122431 0.117034 -0.974639 0.2845850 -0.8624352 0.3347773 0.2512787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5723 5724 -0.796939 0.336681 0.832001 0.5066591 0.8110725 -0.2886851 0.0460307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5724 5725 0.095769 -0.860791 -0.564253 -0.1522421 -0.2119714 0.6686793 0.6962460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5725 5726 -0.905948 0.127926 -0.522204 -0.4308284 -0.0989154 -0.8688728 0.2228511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5726 5727 0.149343 -0.390301 -0.827792 0.0934900 0.0418989 0.6833283 0.7228876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5727 5728 -0.581277 -0.275483 -0.972626 0.3363155 -0.7335969 -0.1316620 0.5756671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5728 5729 -0.456528 -0.362526 0.742072 0.5722557 0.7144841 0.3325829 0.2267696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5729 5730 -0.189136 0.349454 -1.016322 -0.4994194 0.0941251 0.8238961 0.2508304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5730 5731 0.959506 -0.026926 -0.383618 0.0413931 -0.6378181 0.6759573 0.3668193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5731 5732 -0.694285 -0.271555 -0.554717 -0.2898202 -0.4728673 -0.3368681 0.7608684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5732 5733 -0.809386 -1.062630 0.114108 0.9229533 0.1347730 -0.1246185 0.3383248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5733 5734 -0.774472 0.382661 0.600441 -0.2355270 0.1437773 0.9373174 0.2128174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5734 5735 0.726098 -0.045909 0.745490 0.2177526 -0.2077986 0.5352709 0.7892329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5735 5736 0.801551 -0.425729 0.891753 -0.0645365 0.0842550 0.8099310 0.5768431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5736 5737 -0.865667 -0.390955 0.465516 -0.0888691 0.4097807 -0.3496012 0.8378312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5737 5738 -0.404500 -0.938317 0.025170 -0.4017941 0.1355410 0.5550105 0.7156490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5738 5739 -0.890883 0.375851 -0.694400 -0.1856345 0.0428288 -0.5007609 0.8443601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5739 5740 0.595826 -0.853363 0.171369 -0.4526831 -0.5843788 0.1518991 0.6561296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5740 5741 0.653500 -0.025859 -0.613336 0.6518733 0.4570919 -0.5093010 0.3267119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5741 5742 0.578806 0.986735 -0.071260 -0.4702021 0.5081552 0.4322624 0.5777867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5742 5743 0.186660 -0.255064 0.707865 0.1664055 -0.5089306 -0.4663309 0.7041551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5743 5744 0.629505 0.483273 0.301839 -0.3869614 -0.1470639 0.8934578 0.1742590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5744 5745 -0.314758 -0.747280 -0.704707 -0.6239521 -0.2062752 0.3648368 0.6595669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5745 5746 -0.647779 0.675139 -0.360671 0.3977563 0.1869462 0.0241031 0.8979199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5746 5747 -0.456818 0.089592 -0.830744 -0.0761225 0.1426377 -0.7269848 0.6673477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5747 5748 -0.244138 -0.043378 -1.051638 0.0731742 0.6830595 0.1177468 0.7170851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5748 5749 0.962309 -0.539437 -0.133061 0.3870451 -0.0841578 -0.6458679 0.6526624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5749 5750 0.459559 0.687817 -0.392975 -0.0473708 0.0999076 -0.7292454 0.6752596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5750 5751 -0.588830 0.605777 -0.471387 -0.4480459 -0.2675106 0.7382273 0.4274498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5751 5752 0.874759 0.242810 0.485238 0.0390590 -0.8809627 0.3714211 0.2905607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5752 5753 -0.460685 -0.220554 -0.660845 0.8219803 0.4522435 -0.2962842 0.1789968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5753 5754 0.292830 -0.307774 0.863833 -0.5983366 -0.3872315 -0.0114148 0.7013663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5754 5755 0.553545 -0.861696 -0.353000 0.4241344 -0.5037647 -0.5380615 0.5261377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5755 5756 0.727947 -0.364012 -0.619239 -0.0647866 0.2481043 0.2072542 0.9440830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5756 5757 0.776144 -0.436926 -0.261220 -0.4844975 0.1018814 -0.8683400 0.0294609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5757 5758 -0.499055 0.359049 0.749623 -0.1409739 0.0625152 -0.9217056 0.3559172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5758 5759 0.123804 -0.835675 0.358591 0.2713239 0.4543025 0.8457949 0.0679962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5759 5760 0.833126 0.222717 0.093022 -0.6551002 -0.0806864 0.4531460 0.5991595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5760 5761 -0.832757 0.300383 -0.809721 -0.0128750 -0.3250728 -0.1717545 0.9298722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5761 5762 -0.713324 -0.194978 -0.018040 0.7896870 -0.1233113 -0.3128057 0.5131679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5762 5763 -0.517801 -0.083265 0.791477 -0.5189209 0.4603767 0.7135057 0.0984076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5763 5764 -0.424852 0.863620 0.346079 0.0689076 -0.8845453 0.2925737 0.3566959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5764 5765 0.677770 0.835773 -0.446624 -0.2987647 0.6570004 -0.6815600 0.1206900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5765 5766 -0.914053 0.271740 -0.227322 -0.1518493 -0.1877000 0.4765620 0.8453397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5766 5767 -0.204088 0.962050 0.110133 0.1062185 -0.8655507 0.4207475 0.2500222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5767 5768 0.573327 0.662990 -0.552916 -0.2522673 0.3451777 -0.2033640 0.8808273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5768 5769 0.428610 0.947947 -0.003835 0.0782336 0.3372983 0.9370675 0.0448769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5769 5770 -0.101947 -0.862652 0.925502 -0.4613970 -0.4614004 0.7419613 0.1539998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5770 5771 -0.810774 -0.141116 0.512202 -0.4257391 -0.3414138 -0.8117843 0.2078199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5771 5772 0.962162 -0.052720 -0.509473 -0.2139495 -0.1110235 -0.9533465 0.1817413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5772 5773 -1.070842 0.262979 -0.103424 -0.6532414 0.2714624 -0.7065154 0.0204896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5773 5774 -0.206820 -0.021632 -0.917090 0.4086283 0.6808806 0.5736267 0.2009399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5774 5775 -0.117639 -0.938228 0.174085 0.4018315 -0.1277757 -0.8850112 0.1973829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5775 5776 0.232161 1.018436 0.225367 -0.4512768 -0.0526857 0.8710139 0.1868375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5776 5777 -0.004998 -0.903532 -0.206723 -0.1742354 -0.2032657 0.8105727 0.5208618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5777 5778 -0.913844 0.270393 -0.191631 -0.0553443 -0.0602476 0.1441774 0.9861643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5778 5779 -0.688644 0.848091 0.108350 0.1472251 -0.5643161 0.6262913 0.5173310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5779 5780 -0.318146 0.622135 0.748610 0.5342296 -0.1477283 0.5942417 0.5827966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5780 5781 -0.403952 0.947772 0.224128 -0.4208310 -0.2977291 0.4897325 0.7031506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5781 5782 0.731577 0.114169 0.578746 0.0410291 0.0365691 -0.9542977 0.2937606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5782 5783 -0.757261 0.323049 0.557098 -0.1200543 -0.4034131 -0.4935456 0.7610898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5783 5784 0.168702 -0.442385 0.972559 -0.0592109 0.0835364 0.8842783 0.4555960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5784 5785 -0.595614 0.383579 0.755942 0.1105916 0.4006167 0.6928538 0.5892617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5785 5786 -0.201649 1.055306 0.093335 0.0439684 0.4792924 0.8405354 0.2486883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5786 5787 0.434689 -0.333560 0.865129 0.3733003 0.4403063 0.7509358 0.3207377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5787 5788 -0.066576 0.739837 0.340765 -0.2228348 -0.2477838 -0.0500888 0.9415089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5788 5789 0.260267 0.578248 0.784222 0.8645525 -0.1287666 0.4404762 0.2048141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5789 5790 0.718444 -0.417567 -0.399007 0.4855539 0.2677105 0.0702184 0.8292393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5790 5791 0.526518 -0.537093 0.495420 0.1505987 0.1028891 0.5452385 0.8181986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5791 5792 -0.327264 -0.501973 0.662470 0.0084109 0.3931830 -0.7794037 0.4877153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5792 5793 0.164022 -0.681233 0.555601 0.4866599 -0.1591334 0.0938542 0.8538326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5793 5794 0.634087 0.000127 0.859741 -0.5942920 -0.0669158 -0.6596998 0.4551213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5794 5795 0.928833 -0.403030 0.646252 0.8716144 -0.0591896 0.3197347 0.3668169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5795 5796 0.877478 0.180889 -0.080074 -0.1257542 0.7541059 0.2030949 0.6117701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5796 5797 -0.245971 -0.282725 1.017009 -0.8991237 0.2362269 -0.2418800 0.2779702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5797 5798 0.339109 -0.215728 -0.826369 -0.4246904 -0.1394225 0.8794944 0.1633678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5798 5799 0.285536 0.467451 -0.785562 -0.2709977 0.7512151 0.0556016 0.5992868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5799 5800 -0.208179 -0.854684 0.502866 0.0906582 -0.6241728 0.1106871 0.7680741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5800 5801 -0.882527 -0.351172 0.305325 0.3182877 0.2968783 0.8197723 0.3721956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5801 5802 0.355588 0.782291 -0.340234 0.3575112 0.1041014 -0.3502465 0.8594626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5802 5803 -0.028320 0.723151 -0.783346 -0.2086019 0.0801205 -0.9579934 0.1797624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5803 5804 -0.466410 -0.140239 -0.798475 -0.0582883 0.5204829 -0.7591738 0.3864649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5804 5805 0.645894 0.479794 -0.651499 -0.4968884 0.7091310 0.0569856 0.4969787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5805 5806 -0.019688 0.005548 0.892668 -0.0697951 -0.5003051 0.5788100 0.6401581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5806 5807 0.685524 -0.582171 0.549386 0.2406936 0.4907926 -0.4592050 0.7002285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5807 5808 -0.050930 0.368354 0.780226 -0.2206082 -0.2535140 0.7487699 0.5713199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5808 5809 0.276783 -0.516361 0.674175 -0.7650621 -0.3464707 0.1276387 0.5275855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5809 5810 0.186169 -0.494187 -0.813782 0.3473259 -0.3126743 0.3898581 0.7934798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5810 5811 -0.866123 -0.612740 0.068343 0.5392385 0.0712094 0.7183072 0.4338039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5811 5812 -0.249181 0.691745 -0.556340 -0.7089844 0.1352740 0.4433892 0.5314584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5812 5813 0.587852 0.224160 0.702143 0.2906495 -0.4581296 -0.2788832 0.7923789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5813 5814 0.614416 0.725607 -0.288581 0.8366816 -0.1790178 0.3975029 0.3315237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5814 5815 0.041098 -1.028621 -0.222216 -0.6549370 0.6045248 -0.2866925 0.3513042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5815 5816 0.880060 0.067774 0.141330 0.0085582 0.0439312 0.9566975 0.2876223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5816 5817 -0.756063 -0.697785 0.133392 0.1441814 -0.3372928 -0.6176499 0.6956679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5817 5818 0.693784 -0.687200 0.491346 -0.1613978 -0.6495024 0.0454358 0.7416420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5818 5819 0.460573 -0.661621 -0.780310 0.6714098 -0.4142451 0.6133337 0.0378359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5819 5820 -0.560586 -0.807424 0.306093 -0.7518961 0.4436235 -0.3084036 0.3778064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5820 5821 0.442933 0.789438 0.520593 0.3736942 0.3221855 0.8696496 0.0160863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5821 5822 -0.069770 -0.196308 1.045154 -0.5347177 0.2928801 0.3103134 0.7293859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5822 5823 -0.775787 -0.662538 -0.024821 0.4011273 0.5943736 0.6887135 0.1071944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5823 5824 0.080676 -0.000931 -1.193644 0.6500562 0.5398623 0.2855722 0.4521328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5824 5825 0.181205 -0.886099 0.423289 -0.2517418 -0.1675716 -0.2097487 0.9298125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5825 5826 0.570944 -0.631765 -0.137052 -0.4432214 0.2458440 0.4134325 0.7564319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5826 5827 0.106462 -0.577544 -0.584643 0.4127258 -0.1170852 0.3825809 0.8182789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5827 5828 -0.437993 -0.831923 0.054845 0.6284760 0.0322602 0.4238511 0.6514042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5828 5829 -0.787346 0.449888 0.234951 -0.3634706 -0.0286293 0.7777020 0.5121025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5829 5830 0.560093 0.164142 1.021228 0.3261467 0.0360043 -0.8574873 0.3962922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5830 5831 -0.867337 0.320592 0.319841 0.2061047 0.6198688 0.6526790 0.3837885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5831 5832 0.700134 0.771787 -0.454736 0.6900276 0.1361046 0.6210401 0.3458997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5832 5833 0.391840 -0.685346 0.325568 -0.0286300 0.7265148 0.6217117 0.2912577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5833 5834 -0.631393 -0.002079 -0.713497 -0.2847082 0.5654000 0.6349160 0.4428834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5834 5835 0.941680 0.372062 -0.212228 -0.5235025 -0.4821708 0.1067663 0.6943035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5835 5836 0.318955 0.682618 -0.606118 0.6767718 0.1722183 0.2817398 0.6579844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5836 5837 0.747826 -0.695914 -0.381950 -0.7333348 -0.3795450 -0.5604701 0.0635527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5837 5838 -0.539412 0.619548 0.398828 -0.2172975 0.0258984 0.5114975 0.8309521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5838 5839 0.265093 0.626978 0.414741 0.2135441 -0.8889237 0.3954866 0.0883399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5839 5840 -1.007619 -0.531550 0.522347 -0.2327258 0.2147010 -0.8764924 0.3626338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5840 5841 -0.042284 -0.712049 0.865425 -0.6739658 0.6733134 0.1545482 0.2617901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5841 5842 -0.207725 -0.144237 -0.973823 0.5634717 -0.1919838 -0.6039443 0.5299935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5842 5843 0.559020 -0.692657 -0.383395 0.0483420 0.0207705 -0.4982541 0.8654331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5843 5844 0.923182 -0.097496 -0.036585 -0.4690949 -0.2003607 0.4378725 0.7403197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5844 5845 0.458615 -0.381096 -0.864349 0.4082852 0.3583271 -0.3996465 0.7383682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5845 5846 0.791841 0.044680 -0.058629 -0.2692737 -0.4295122 0.5104913 0.6945571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5846 5847 0.244605 -0.313789 -0.791702 0.5548165 0.3180641 0.7686987 0.0107790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5847 5848 -1.075085 0.153021 -0.109894 -0.5656505 0.0245654 -0.4584046 0.6850557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5848 5849 -0.717297 -0.492521 -0.418126 0.3282413 -0.5640702 -0.7566719 0.0391154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5849 5850 0.935310 -0.210338 0.008525 0.5372527 0.1825727 0.7776451 0.2707301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5850 5851 -0.311462 -0.100139 0.962784 0.5808370 0.1382376 0.7701062 0.2246225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5851 5852 0.863015 0.664279 -0.177321 -0.5939997 -0.1111144 -0.7384576 0.2991627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5852 5853 -0.537057 0.130747 0.954965 0.3872772 -0.3204119 0.8033902 0.3192440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5853 5854 1.012876 0.037079 0.129174 0.2022113 0.1483815 -0.9502884 0.1845139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5854 5855 -1.089418 0.256665 -0.081120 -0.3847209 0.4528242 -0.7762915 0.2105031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5855 5856 0.431668 -0.071086 -0.935765 -0.0172991 -0.0969846 -0.9717932 0.2142725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5856 5857 -0.473456 0.187186 -0.909115 -0.2751748 -0.0008246 0.6400346 0.7173798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5857 5858 0.425632 0.728786 -0.565690 -0.5987666 0.1373078 0.1708486 0.7703479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5858 5859 0.541955 0.679539 0.347851 0.2484609 0.9182904 -0.2171204 0.2187892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5859 5860 0.087044 -0.765776 -0.520138 0.7373833 0.0498140 -0.2536153 0.6240702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5860 5861 0.239335 0.930979 0.133266 0.1319221 -0.0937771 -0.9857511 0.0457947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5861 5862 -0.403106 -0.890999 0.205053 0.1826121 0.1651642 -0.7958936 0.5531066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5862 5863 0.689410 -0.424999 0.641103 -0.0359119 -0.1651288 0.5246240 0.8343935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5863 5864 0.164300 -0.773904 0.304399 -0.1745227 -0.6400710 -0.7139099 0.2240170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5864 5865 -0.125862 0.463624 -1.004684 -0.0644314 -0.4917098 -0.0459913 0.8671533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5865 5866 -0.821201 0.509955 -0.390768 0.0980837 -0.0904449 -0.1621420 0.9777061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5866 5867 -0.937572 -0.027854 -0.138680 -0.7128168 -0.0408119 0.6188266 0.3275365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5867 5868 -0.138393 0.306568 0.907492 0.7191113 0.5174316 -0.1107632 0.4504165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5868 5869 -0.322349 0.479407 -0.961965 -0.0048136 -0.0511064 -0.3682011 0.9283280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5869 5870 -0.778025 0.281615 -0.613904 0.4608927 0.4296874 -0.3814288 0.6763570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5870 5871 0.508183 -0.740406 -0.585900 0.3165048 -0.7880312 -0.1148519 0.5154033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5871 5872 0.043821 -1.134604 -0.129387 -0.3539011 -0.2087724 -0.2218653 0.8842759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5872 5873 0.117130 -0.665438 -0.863376 -0.2755516 0.5748272 -0.7447780 0.1973594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5873 5874 0.161281 0.944733 0.502687 -0.2254994 0.3672523 -0.6782511 0.5951900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5874 5875 -0.905283 -0.424566 0.162698 0.2418283 -0.0130640 0.8464674 0.4741744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5875 5876 0.243675 0.971844 -0.403622 -0.3023889 -0.3240729 0.7318469 0.5176271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5876 5877 0.883321 -0.308970 -0.351055 -0.1540559 -0.4654485 -0.8431264 0.2208218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5877 5878 -0.920665 0.232481 -0.211589 -0.4675392 0.3679292 -0.5654688 0.5712094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5878 5879 -0.104330 -0.137054 -0.856901 -0.5692078 0.3773931 0.7290736 0.0450407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5879 5880 -0.319266 -0.402554 0.971987 -0.6914851 -0.1421242 -0.0801405 0.7037233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5880 5881 -0.939870 0.061061 0.501799 0.3632188 0.1878778 0.5855551 0.6999280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5881 5882 -0.139426 0.959141 -0.308484 0.2993572 -0.2382663 -0.7153275 0.5847402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5882 5883 -0.848284 -0.848479 -0.180553 0.0638440 0.2201226 -0.6807651 0.6957218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5883 5884 0.647911 -0.726411 0.152384 0.0807788 -0.7852444 0.6119808 0.0484311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5884 5885 -0.629976 -0.402155 0.653137 0.4969885 0.6055881 -0.4756822 0.3999899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5885 5886 -0.758353 -0.612772 0.262720 0.2690233 -0.4955044 0.3332872 0.7556597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5886 5887 -0.222953 -0.152060 1.159487 -0.2019267 0.2514393 0.6765015 0.6620797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5887 5888 -0.822951 0.310845 0.615782 -0.0801734 -0.3595582 -0.6546670 0.6600767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5888 5889 0.132652 -0.305239 0.834126 -0.1697445 0.8791711 0.3605420 0.2612555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5889 5890 -0.474451 0.439209 -0.545741 -0.6900807 0.1664670 0.3918769 0.5852434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5890 5891 0.289302 0.969553 0.482149 -0.1377870 0.0747331 0.1176074 0.9806111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5891 5892 0.163146 0.778064 0.767853 -0.0532470 -0.9230380 0.3031944 0.2307352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5892 5893 0.146163 -0.099420 -1.085687 -0.2456432 0.3665135 0.3916662 0.8074187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5893 5894 0.814389 -0.017242 -0.506643 0.4401546 0.0139153 0.7798673 0.4448339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5894 5895 -0.447289 -0.839060 0.167872 0.3606106 -0.4479145 -0.1745741 0.7992850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5895 5896 0.349277 -0.331140 0.929367 -0.7478014 -0.5459367 0.0243636 0.3770312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5896 5897 0.224085 -0.244625 -0.962632 -0.7148011 0.0299887 -0.6981054 0.0284415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5897 5898 -0.991845 0.386614 0.260810 -0.2178325 -0.6199412 -0.7079902 0.2587891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5898 5899 0.671832 -0.404908 0.244724 -0.4837686 0.3066027 0.7745390 0.2684251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5899 5900 0.143863 -0.928175 0.029751 0.2896896 0.7434059 -0.5867041 0.1385852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5900 5901 -0.886852 -0.079886 -0.567299 -0.0616971 0.7614218 -0.1771940 0.6205100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5901 5902 0.922925 0.016487 -0.698405 0.1021249 -0.7030352 0.6546114 0.2584490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5902 5903 -0.810072 0.391209 0.027165 0.1870093 -0.5649146 0.8031333 0.0295956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5903 5904 0.883194 0.138204 -0.738205 0.6152793 -0.3980667 0.6320720 0.2519114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5904 5905 -0.796912 -0.673401 0.179374 -0.0948780 -0.8536654 0.5120417 0.0081766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5905 5906 0.683916 -0.687086 0.289849 0.3999895 -0.8592913 0.0808884 0.3083569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5906 5907 0.117850 -0.875052 -0.163554 -0.5248039 -0.2793508 -0.3980069 0.6986663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5907 5908 0.304730 0.175711 -1.025573 -0.3290427 -0.6247707 -0.7013011 0.0978220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5908 5909 -0.486069 -0.582074 0.156863 -0.0980875 -0.2093769 -0.8625232 0.4501043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5909 5910 0.976261 0.082391 -0.269646 0.3339856 0.4627278 0.4338206 0.6972347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5910 5911 0.204407 -0.319855 1.075275 -0.5707200 0.4321085 0.3008557 0.6301165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5911 5912 -0.734440 -0.857424 -0.298318 -0.6929807 0.2779677 0.5327210 0.3983968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5912 5913 0.263935 0.902134 -0.102531 -0.5094382 -0.0729340 0.3789709 0.7691127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5913 5914 0.765206 0.315847 0.766147 0.6917906 0.1352448 -0.0894362 0.7036589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5914 5915 0.501267 0.819716 -0.313080 -0.1402990 0.6124755 0.7459257 0.2208730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5915 5916 -0.322024 -0.719455 0.754973 0.2021008 -0.2269586 -0.7934669 0.5273095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5916 5917 0.840645 0.521161 0.635131 -0.5368635 -0.4340421 -0.7217552 0.0495423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5917 5918 0.363894 0.611939 0.776410 0.8446713 0.1179923 -0.0152930 0.5218949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5918 5919 0.333540 0.573035 -0.880202 0.0923748 -0.5587754 -0.8139772 0.1291436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5919 5920 -0.397258 0.012564 -0.866442 -0.2914021 0.3786668 0.7225273 0.4996505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5920 5921 0.294386 -0.609820 0.585755 -0.0864839 0.8321281 0.2798522 0.4709205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5921 5922 -0.910745 -0.468132 -0.480278 -0.8128174 -0.2879771 -0.2637384 0.4322489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5922 5923 -1.022472 -0.385617 -0.287706 -0.1248375 -0.9154917 0.2597655 0.2807354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5923 5924 0.551708 -0.153587 0.850386 -0.2307007 -0.4887704 0.7765912 0.3237079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5924 5925 -0.641038 -1.024824 0.004554 0.2215998 0.3245908 0.1562711 0.9061532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5925 5926 -0.900268 -0.578308 -0.069368 -0.6249047 0.6856611 0.3727550 0.0204104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5926 5927 0.558683 0.684344 -0.040079 -0.5883305 -0.5470641 0.5061381 0.3137074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5927 5928 0.658437 0.113390 -0.676348 -0.3672604 -0.0659446 -0.8621712 0.3426834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5928 5929 -0.713281 0.424829 -0.121268 -0.0942878 0.5676054 0.7328477 0.3631366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5929 5930 1.096163 0.303919 0.053999 -0.2457082 0.2911395 -0.9223838 0.0638235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5930 5931 -0.931364 -0.120402 0.340798 0.0162338 0.4081684 0.8548393 0.3199764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5931 5932 0.436542 0.837192 -0.217208 -0.1891009 -0.8048402 0.2376098 0.5099164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5932 5933 0.039026 0.834405 -0.518745 -0.6380937 0.1904535 -0.7424261 0.0732626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5933 5934 -0.984797 -0.572377 -0.119152 0.3286970 -0.0757836 0.6383659 0.6918844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5934 5935 -0.656976 0.689749 -0.091165 0.0850079 0.2681856 0.4309021 0.8574226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5935 5936 0.249170 0.802007 -0.337199 -0.1355832 0.7609307 0.6344093 0.0112459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5936 5937 -0.427432 -0.276039 0.933124 -0.2595250 0.0637938 0.7846921 0.5593169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5937 5938 -0.441719 0.315965 0.900020 -0.1456732 0.4166877 0.0565142 0.8955204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5938 5939 -0.956640 0.116573 0.202591 -0.2904073 -0.1836304 0.9351766 0.0859544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5939 5940 0.381993 0.972347 -0.244887 -0.4452797 0.0445388 0.1883067 0.8742327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5940 5941 -0.715284 0.692565 -0.275689 0.5946558 -0.0086850 0.3848469 0.7058342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5941 5942 -0.235747 0.201642 -0.883122 -0.1553758 -0.5248309 -0.8363601 0.0302106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5942 5943 -0.173216 -0.920504 -0.297046 0.0187130 -0.3056792 0.9151605 0.2620901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5943 5944 -0.389968 0.801967 0.233081 0.5194360 0.1905844 0.3252629 0.7668558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5944 5945 0.419905 0.468508 -0.774161 -0.0369083 0.3836397 0.1867490 0.9036499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5945 5946 0.876476 0.311629 -0.304076 -0.3144664 0.0042791 0.7152799 0.6240731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5946 5947 0.320523 -0.901438 -0.432263 -0.0477012 0.5734645 0.5316670 0.6214445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5947 5948 -0.369598 -0.839353 -0.410052 0.6510189 0.1101341 -0.6402356 0.3926108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5948 5949 0.835630 0.382774 0.660401 -0.0668865 -0.4295237 0.7706509 0.4659752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5949 5950 0.061077 -0.806348 -0.010935 0.2356069 0.1793884 -0.9527644 0.0674475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5950 5951 0.127479 0.833833 0.334772 0.1244856 -0.6341105 -0.7059910 0.2897996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5951 5952 -0.566990 0.333159 0.787064 0.2274014 0.1042373 0.5606984 0.7893292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5952 5953 0.007159 0.944987 0.409020 0.9016004 0.0554649 0.0592500 0.4248880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5953 5954 0.349188 -0.105295 -0.944816 -0.3950910 -0.0330959 -0.6625935 0.6354350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5954 5955 -0.248875 0.825423 -0.402776 -0.0730336 0.0931608 -0.9757086 0.1843364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5955 5956 -0.001007 -0.931727 -0.739284 0.2286451 -0.1539394 -0.9462819 0.1690406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5956 5957 0.522278 0.457581 -0.744379 -0.8903256 0.1488338 0.3447571 0.2575098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5957 5958 0.863357 -0.384915 0.336046 0.1068447 -0.7561876 0.4757464 0.4363828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5958 5959 -0.176341 -0.793315 -0.252109 0.0459784 -0.0861155 -0.9767513 0.1908586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5959 5960 0.577791 -0.173709 0.759221 -0.8590396 0.1950381 0.2449080 0.4050076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5960 5961 -0.835373 0.345719 -0.488868 0.2945663 -0.3500121 -0.6353139 0.6221724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5961 5962 -0.530542 -0.806046 0.384356 0.3974889 0.1243285 -0.0620050 0.9070283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5962 5963 -0.358415 -0.787435 0.539122 0.1450468 0.4981495 0.8420452 0.1475411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5963 5964 0.458413 0.845595 -0.312263 0.2759881 -0.2666538 0.9207085 0.0708672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5964 5965 -0.374374 -0.691502 -0.621024 0.1931739 0.1648673 0.4504173 0.8559362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5965 5966 -0.892875 -0.219193 -0.575327 0.3298223 0.2149670 -0.1782492 0.9017947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5966 5967 -0.326284 -1.072384 -0.369031 -0.6006900 -0.2094257 0.6823588 0.3601374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5967 5968 -0.340858 0.864824 -0.088977 0.3354249 -0.0966258 0.1155175 0.9299512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5968 5969 -0.368422 0.906895 -0.482896 0.3427752 -0.6478336 -0.6335072 0.2479627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5969 5970 -0.459778 -0.343844 0.782924 -0.0918554 0.6968301 0.6265634 0.3367622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5970 5971 -0.211828 0.672720 -0.541656 0.3677879 0.3659625 0.7717829 0.3676340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5971 5972 0.572097 -0.663803 -0.222919 0.3218734 -0.4207816 0.8280353 0.1835698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5972 5973 -0.515591 0.167493 0.732943 0.1716899 0.0040902 -0.1008965 0.9799621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5973 5974 -0.465783 0.399204 0.592362 0.7469629 -0.3202793 0.4776345 0.3336657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5974 5975 0.418432 0.431382 -0.675068 0.2452102 0.5410796 0.7345621 0.3279075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5975 5976 -0.009743 -1.017399 0.409648 0.2719784 0.5400026 0.7965080 0.0000019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5976 5977 -0.107321 0.555162 -0.952656 -0.9500608 -0.0636734 -0.1261669 0.2782304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5977 5978 -0.254747 -0.089897 0.793465 0.7107732 -0.3854708 0.1942345 0.5554158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5978 5979 0.717079 0.847529 -0.068724 0.4995362 0.5868387 -0.6012453 0.2111585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5979 5980 -0.551016 -0.667013 -0.287519 -0.3306153 0.7423384 0.4306125 0.3926831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5980 5981 -0.527676 0.253202 -0.533562 0.1327334 0.0732297 0.8719886 0.4654623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5981 5982 0.689034 0.172328 -0.686286 0.4550438 0.7517941 -0.0488368 0.4747165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5982 5983 0.674071 0.117551 0.785620 -0.5342108 -0.5505081 -0.0900176 0.6351822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5983 5984 0.888103 0.184479 -0.407960 0.2346939 0.2967790 0.7355844 0.5619222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5984 5985 0.009095 -0.867814 0.263910 0.1024866 0.1525830 0.9645959 0.1891287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5985 5986 -0.288780 0.739477 0.033258 0.0254200 -0.3061055 -0.8781786 0.3666819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5986 5987 -0.572740 -0.528736 0.617672 0.6593220 -0.6834070 -0.2714888 0.1566627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5987 5988 0.601045 0.715121 -0.255669 -0.5084900 0.0911263 0.6727156 0.5297052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5988 5989 0.825326 -0.799522 0.100727 0.0618546 0.3311778 -0.9066207 0.2540357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5989 5990 -0.279058 0.718868 0.524249 0.8858064 -0.2436641 -0.1831870 0.3498819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5990 5991 -0.866399 -0.069951 -0.617875 -0.8891712 0.2496159 -0.3121613 0.2227596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5991 5992 -0.744780 0.522296 -0.243420 0.7864709 -0.0104638 -0.6162917 0.0392250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5992 5993 -0.020290 -0.586646 0.810871 -0.0542605 -0.1606646 0.9029112 0.3949609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5993 5994 -0.294522 0.038416 0.816919 0.6290209 0.5497856 0.1784876 0.5198179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5994 5995 -0.071155 0.696238 -0.712500 -0.1971237 -0.3251171 0.5156670 0.7678077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5995 5996 0.390337 1.010726 -0.451299 0.2393131 -0.2248376 -0.4039721 0.8538055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5996 5997 -0.449226 0.574335 -0.782734 0.3935352 0.6459270 0.5266212 0.3880445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5997 5998 0.620181 -0.665034 -0.030454 -0.4385915 0.5809194 -0.6734555 0.1289490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5998 5999 0.157015 0.182773 0.992429 0.6956067 0.3053556 0.1901776 0.6218696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5999 6000 1.031860 -18.903272 1.694982 0.2075405 -0.2636976 -0.6366693 0.6942930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6000 6001 -1.231893 -0.109562 -0.181442 -0.1761797 0.0850973 -0.1462149 0.9697115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6001 6002 -0.871897 -0.315721 -0.164596 0.5522633 0.6451847 -0.5271734 0.0288130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6002 6003 0.380628 -0.688935 0.908818 0.5750501 -0.7840993 -0.0341363 0.2309555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6003 6004 0.541267 -0.225633 -0.772938 -0.4743651 -0.2227351 -0.4497694 0.7232388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6004 6005 -0.191083 0.957494 -0.600125 -0.2467646 0.0012334 0.8698183 0.4272256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6005 6006 0.820811 -0.398436 -0.268924 0.0807010 -0.5775138 0.6929894 0.4239468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6006 6007 -0.759327 -0.394816 -0.140291 -0.4949084 -0.2951284 0.7817954 0.2382454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6007 6008 0.341449 0.568198 0.860678 0.4377461 -0.5442805 0.0936054 0.7094893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6008 6009 0.613412 0.539319 -0.483496 -0.4240325 -0.1525219 -0.8907883 0.0585639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6009 6010 -0.832566 -0.280604 0.389930 0.2795265 0.2509807 -0.6205331 0.6883402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6010 6011 0.020536 -0.783076 0.445214 -0.5820784 -0.2393853 -0.7296396 0.2674050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6011 6012 0.691810 0.454801 -0.691608 0.7860882 -0.3108993 0.3934729 0.3613670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6012 6013 -0.106795 -1.022884 0.100458 0.7384780 -0.3113519 0.5928623 0.0788963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6013 6014 0.527226 0.711798 0.341164 0.1618285 0.5690467 -0.7124280 0.3774171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6014 6015 -0.820041 0.129961 -0.594973 0.2921539 -0.7871638 -0.1101749 0.5318654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6015 6016 -0.306684 0.107591 1.033904 0.0004073 0.3082549 -0.0031914 0.9512983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6016 6017 -0.809146 -0.134040 0.530534 -0.0377309 0.7825434 0.0083413 0.6213957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6017 6018 -0.284228 -0.058559 -1.019883 -0.5177446 -0.7112235 -0.4472820 0.1613707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6018 6019 -0.443621 -0.517878 0.386953 0.2963300 0.3709294 -0.6660604 0.5752943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6019 6020 0.925402 -0.060445 -0.126469 -0.4310818 0.3493036 0.2642301 0.7888840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6020 6021 0.630557 0.638186 0.122526 -0.3875461 -0.1412616 -0.5552866 0.7221565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6021 6022 -0.473885 0.528130 0.712939 0.0664811 0.6775942 0.0776263 0.7282997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6022 6023 -0.514573 0.779896 -0.274919 -0.6396223 -0.4320089 0.3479382 0.5321566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6023 6024 0.491840 0.234417 0.810614 -0.2309074 -0.5700837 0.6598222 0.4316493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6024 6025 0.059060 -0.841090 -0.221152 -0.3218796 -0.2558535 -0.3818711 0.8277119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6025 6026 0.224866 -0.371719 -0.940269 -0.2293010 0.8002834 -0.2782492 0.4791084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6026 6027 0.585636 0.232178 0.634374 -0.1429920 -0.2522400 0.9290242 0.2298745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6027 6028 -0.387674 -0.928075 0.169762 0.1998783 0.5680869 0.7652073 0.2275602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6028 6029 -0.084215 0.387595 -0.772521 -0.2967259 0.2708156 -0.5696776 0.7169938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6029 6030 -0.128539 0.685281 -0.751313 -0.5858840 -0.0444648 0.7735848 0.2373381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6030 6031 1.089141 -0.402648 0.144125 -0.3592430 -0.4164801 0.4691666 0.6909208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6031 6032 -0.205316 -0.661593 -0.817574 -0.1908962 -0.8257477 0.3667165 0.3836905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6032 6033 -0.850632 0.277903 0.572913 0.2447027 -0.2278652 0.4179023 0.8447223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6033 6034 0.006771 0.901969 0.694671 0.6824126 -0.4993738 -0.4772717 0.2390619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6034 6035 -0.887842 0.102753 -0.060619 -0.3433816 -0.4801627 -0.6656467 0.4565603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6035 6036 0.120413 -1.079809 0.005806 -0.4230894 -0.3808209 0.1193025 0.8134726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6036 6037 -0.526189 -0.744874 -0.535294 0.3410158 -0.2945439 -0.2299298 0.8626033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6037 6038 -0.307486 -1.031882 0.139282 -0.5203279 -0.0839398 -0.8081816 0.2627841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6038 6039 0.285656 0.876323 -0.444281 0.0614103 -0.4057862 0.8878063 0.2082457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6039 6040 -1.096993 -0.133368 0.220272 -0.2293737 0.7362812 -0.1789184 0.6109550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6040 6041 -0.995691 -0.337437 0.057318 0.5351919 -0.6600122 0.4919447 0.1895889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6041 6042 0.443266 0.939845 -0.008305 0.1269805 0.5029698 0.6335868 0.5739905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6042 6043 0.500284 -0.148320 0.937547 0.1992346 -0.7855135 -0.2822263 0.5134417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6043 6044 0.403062 0.400547 -0.818998 0.7598452 0.0090676 0.5883376 0.2764271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6044 6045 -0.560881 -0.858447 0.284149 0.3602048 -0.0348474 0.1007201 0.9267651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6045 6046 -0.732635 -0.369851 0.650802 0.7289418 0.0400467 0.6762176 0.0988433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6046 6047 0.677027 0.607590 -0.785743 -0.1366391 -0.1290136 0.9753743 0.1154564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6047 6048 -0.342719 -0.408838 -1.144885 -0.1565303 -0.4926926 0.4461489 0.7305501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6048 6049 -0.526321 0.708694 -0.073874 0.1604687 -0.2247144 0.4887044 0.8275997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6049 6050 0.053443 1.183391 -0.246856 -0.1400186 -0.3755280 -0.6213682 0.6732570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6050 6051 -0.733072 0.363196 0.437036 0.1100047 0.2252734 -0.8210743 0.5128234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6051 6052 0.053865 -0.939107 0.105171 -0.4283614 -0.6618055 -0.3661637 0.4944129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6052 6053 0.072446 -0.361259 -0.865344 -0.5610920 0.4715467 -0.6396415 0.2316855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6053 6054 -0.189663 1.132827 0.247533 -0.4906206 0.0219736 0.0277549 0.8706539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6054 6055 -0.073328 0.436478 1.072117 -0.0960262 -0.5611448 0.7608714 0.3114005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6055 6056 0.376949 -0.949255 0.055590 0.6481642 0.1782183 -0.7216920 0.1651729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6056 6057 -0.311614 0.969589 -0.037913 -0.1153919 -0.0374793 0.8039879 0.5821370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6057 6058 0.801784 -0.113720 0.138744 -0.1134048 -0.7237110 -0.6768926 0.0720976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6058 6059 -0.688834 0.349068 -0.035848 -0.7690055 0.1902492 -0.1689798 0.5864142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6059 6060 -0.031451 -0.698203 -0.841994 -0.3027407 -0.1253532 0.3196769 0.8890677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6060 6061 0.633942 -0.430853 -0.559540 0.6302446 -0.3905952 0.6303093 0.2300810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6061 6062 -0.633754 0.087288 0.842086 0.7958701 -0.1167250 0.5753560 0.1480932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6062 6063 0.710412 0.092084 -0.772948 0.2251029 0.1488666 0.9238895 0.2712852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6063 6064 -0.767264 -0.880989 -0.547740 -0.5264854 -0.6893126 0.2261926 0.4432812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6064 6065 -0.896836 -0.237422 0.622699 -0.3946175 0.2693673 0.0364455 0.8777186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6065 6066 -1.031451 -0.210246 -0.214481 0.1416290 0.2976108 0.8041792 0.4946361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6066 6067 0.271724 0.570538 -0.741943 -0.3890358 -0.4691871 0.6809831 0.4059268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6067 6068 0.564061 0.620324 -0.420628 0.7422766 0.1812197 0.1960163 0.6146239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6068 6069 0.813000 -0.692103 0.070511 -0.8932731 0.0546334 0.1131840 0.4315875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6069 6070 0.704623 0.296173 -0.775139 0.5773646 0.6891333 -0.4271374 0.0964315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6070 6071 0.302241 1.023883 -0.118988 0.2175244 -0.6981867 -0.1158280 0.6721624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6071 6072 -0.312193 0.676484 -0.635499 -0.2836514 0.5743667 -0.5484858 0.5374087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6072 6073 -0.451038 0.701849 -0.580402 -0.3989626 -0.5640513 0.7195876 0.0697761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6073 6074 1.034495 0.223804 -0.067355 0.6387127 0.1261716 0.5749468 0.4955431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6074 6075 0.262249 -0.523820 0.674763 -0.5191269 0.4169454 -0.1337849 0.7340064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6075 6076 0.205021 -0.993913 -0.199290 -0.3210842 -0.3605801 0.7663394 0.4238053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6076 6077 -0.813964 0.485641 0.037566 0.5993345 -0.3582732 -0.6411331 0.3184129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6077 6078 -0.224156 -0.138877 1.036731 -0.7745570 -0.3502877 -0.0861353 0.5195582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6078 6079 0.038966 -0.764941 -0.479663 0.6723362 0.0437395 0.4345919 0.5976461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6079 6080 -0.433253 0.826024 -0.549523 -0.2008940 0.4681458 -0.8385862 0.1930138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6080 6081 -0.888337 0.367746 -0.127726 0.6745753 -0.5549757 0.4307599 0.2267072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6081 6082 -0.297499 0.586907 -0.760122 0.0599533 -0.1684431 0.9749966 0.1319631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6082 6083 0.345593 -0.241305 -1.023325 0.3679079 0.4859958 -0.6568090 0.4439074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6083 6084 0.777036 0.770950 0.060294 -0.1353482 -0.5188127 0.2427529 0.8084462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6084 6085 0.482054 0.438016 -0.932532 -0.3062221 0.5402708 -0.7740273 0.1233584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6085 6086 -1.023266 0.301922 0.010270 -0.5089604 0.3667183 -0.6827467 0.3746116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6086 6087 -0.150149 -0.578266 -0.921056 0.8025313 -0.3124715 0.1311693 0.4910191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6087 6088 -0.516944 -0.334484 0.770480 0.2555676 0.3051819 0.3495484 0.8481539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6088 6089 -0.925609 0.465024 0.178946 -0.3779989 0.1903435 -0.8864625 0.1872708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6089 6090 0.450017 -0.673399 -0.692097 -0.1595039 0.4758517 0.4978599 0.7072901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6090 6091 0.227385 -0.936095 -0.546409 0.0239744 -0.8558712 -0.0540036 0.5138028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6091 6092 -0.656043 -0.802161 0.009053 0.1382966 0.3973667 0.8975278 0.1319760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6092 6093 0.231604 0.695935 -0.733815 0.0981636 -0.9698151 -0.0854627 0.2062008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6093 6094 -0.498292 0.522906 0.529043 -0.0925386 0.5838699 0.6960260 0.4075296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6094 6095 0.084263 0.905234 0.605267 -0.4247543 -0.0099812 0.6222045 0.6575300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6095 6096 0.671570 -0.503327 0.530243 -0.6342175 0.2949574 0.7146800 0.0009343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6096 6097 -0.559102 0.419911 -0.667621 0.2048035 -0.6494186 -0.0125710 0.7322247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6097 6098 -0.935215 0.302575 0.392398 0.0949735 0.9833636 0.1548409 0.0005816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6098 6099 0.997310 0.125033 -0.337531 -0.4880106 0.6634317 0.0079850 0.5671333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6099 6100 0.602941 0.858928 0.185685 -0.1140931 0.4628115 0.8184169 0.3209080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6100 6101 1.048063 -0.320124 -0.171919 -0.4989605 -0.1431297 -0.8318647 0.1963502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6101 6102 -0.450673 0.746590 0.255191 0.2597205 0.2165968 0.0533715 0.9395651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6102 6103 -0.429706 0.747264 -0.377431 -0.5988549 0.0174512 0.1150770 0.7923544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6103 6104 -0.260876 0.591880 0.714116 0.7395727 -0.4053266 -0.4655806 0.2682859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6104 6105 -1.108494 0.355290 -0.090846 -0.2106957 -0.0711653 -0.9569808 0.1863617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6105 6106 0.677360 -0.492022 -0.517054 0.5294512 -0.4138796 0.7251722 0.1500345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6106 6107 -0.434825 0.012066 0.854523 -0.4529677 0.3824711 -0.4899857 0.6391011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6107 6108 -0.313955 -1.044659 -0.029767 -0.7018036 -0.4041510 0.5733273 0.1242155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6108 6109 -0.475404 0.673542 0.580985 0.7207979 -0.3186312 -0.4368804 0.4336588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6109 6110 -0.834702 0.378979 0.259066 0.0533840 -0.5079989 -0.8128128 0.2800404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6110 6111 0.541085 -0.176798 0.536174 -0.8311208 0.0674012 0.4534164 0.3148157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6111 6112 -0.148281 -0.423828 -0.941715 0.0033811 0.1980095 -0.5763433 0.7928488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6112 6113 0.487479 -0.231469 -0.602926 0.1862632 0.1911508 -0.2718904 0.9245772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6113 6114 0.983576 0.437505 -0.510486 0.2092348 0.7301134 -0.2037877 0.6177586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6114 6115 0.244396 0.552577 0.686321 0.6128405 -0.2558539 -0.0682221 0.7445207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6115 6116 -0.081448 0.796117 -0.650807 -0.4102882 -0.4064445 0.5118323 0.6359986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6116 6117 0.973524 0.596102 -0.267017 0.7827015 -0.1070523 0.5778591 0.2049316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6117 6118 0.046666 -0.784476 0.547304 0.3634262 0.1961211 0.5452868 0.7294657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6118 6119 -0.704197 0.320403 0.581969 -0.2085042 -0.1198614 -0.5105426 0.8255335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6119 6120 -0.688110 0.558698 0.369944 0.5781718 -0.2574391 0.5960071 0.4941842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6120 6121 -0.505269 -0.661760 -0.608947 -0.0445300 0.1604679 -0.8204694 0.5468976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6121 6122 0.758362 0.224112 -0.447929 -0.3390878 0.2990070 0.8916913 0.0223826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6122 6123 -0.544529 -0.814185 -0.742682 0.3583982 0.1197360 0.8980346 0.2252731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6123 6124 -0.628210 0.225042 -0.737575 -0.8148267 0.2858977 0.4898729 0.1197689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6124 6125 0.259980 -0.101187 1.027143 -0.5669206 -0.8150683 0.1193270 0.0050667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6125 6126 -0.333901 -0.025463 -0.832134 0.1120311 -0.2567761 -0.2264933 0.9328536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6126 6127 -0.645429 -0.314739 -0.783908 0.3891764 -0.0136039 0.1767789 0.9039391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6127 6128 -0.955222 -0.527607 -0.118851 0.5608170 0.1127354 0.3664111 0.7338378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6128 6129 -0.942045 0.018239 0.043552 -0.5703695 -0.0662226 -0.5807430 0.5770882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6129 6130 -0.603646 -0.583028 -0.631999 -0.5022604 -0.5637602 -0.0649401 0.6524505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6130 6131 -1.000830 -0.309237 -0.089886 0.2093082 -0.0336890 -0.0924180 0.9728895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6131 6132 -1.119831 -0.414465 0.068010 0.6608792 -0.1148453 0.1950763 0.7155379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6132 6133 -0.713675 0.412521 0.178778 -0.2385506 0.6185259 -0.7428233 0.0934499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6133 6134 0.494965 0.059233 -0.873321 0.0851736 0.7445587 -0.5748551 0.3285109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6134 6135 0.252597 1.033857 0.284948 0.1539549 -0.6478347 0.7334291 0.1367111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6135 6136 0.044809 -0.486682 -0.879378 -0.2834215 0.7052140 -0.4510562 0.4678609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6136 6137 0.786379 0.520495 0.429591 -0.3819648 -0.1511751 -0.8850770 0.2188328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6137 6138 -0.279802 -0.349724 0.925188 0.0250536 0.2484275 0.9537494 0.1673861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6138 6139 0.127715 0.644760 0.813290 0.2519559 -0.5662410 0.3390891 0.7077485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6139 6140 0.248448 0.584991 0.672664 0.2072031 0.1918858 -0.8430254 0.4577717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6140 6141 0.412898 -0.809685 0.521529 -0.0588625 0.2869599 0.9218617 0.2536934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6141 6142 -0.632950 0.704386 0.021836 0.4300198 -0.1148562 -0.8678579 0.2207119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6142 6143 -0.084403 -0.845276 0.559003 0.2870698 -0.3845515 0.0035702 0.8773245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6143 6144 0.456012 -0.524018 0.721774 0.5037810 -0.4363652 -0.7367997 0.1136500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6144 6145 -0.409234 0.736383 -0.556844 0.1790759 -0.1400117 -0.1365156 0.9642054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6145 6146 -0.676661 0.380879 -0.453353 0.5815108 0.0614287 -0.7956313 0.1582484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6146 6147 0.702829 -0.599092 0.400845 0.3974510 0.0181777 -0.2949682 0.8687324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6147 6148 0.595628 0.324895 0.584752 0.0558778 0.4844861 0.7680347 0.4150585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6148 6149 -0.447721 0.000818 1.120701 0.1663539 -0.7681342 -0.5989070 0.1536443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6149 6150 0.432642 0.875578 0.109611 0.0099824 -0.8621717 -0.4336173 0.2617947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6150 6151 -0.646808 0.626768 0.213204 0.0127787 0.6346460 -0.2836095 0.7187675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6151 6152 -0.522201 0.268931 -0.622131 -0.6109299 -0.3167587 -0.6830417 0.2447095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6152 6153 -0.699712 -0.421094 -0.449811 -0.2030868 0.8081934 -0.1430029 0.5339751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6153 6154 0.703132 -0.261438 -0.627482 0.1695014 0.6297599 -0.6688583 0.3567917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6154 6155 -0.368489 0.920148 0.383991 -0.4831401 0.0688140 0.2999337 0.8196829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6155 6156 0.005202 0.217149 0.942005 -0.1878158 -0.0306164 0.9702690 0.1495523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6156 6157 -0.090650 -0.439941 0.766759 -0.2177930 0.4776935 0.4767007 0.7050756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6157 6158 -1.171664 0.127297 0.053368 -0.2326760 -0.2797426 -0.2845686 0.8869197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6158 6159 -0.482071 -0.657098 0.554879 -0.2619390 -0.2134049 0.9023352 0.2676519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6159 6160 0.313298 -0.614767 0.322200 -0.0815335 -0.3078612 -0.0409020 0.9470485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6160 6161 -0.545952 -0.197070 -0.830530 -0.4388064 -0.0979569 0.7490026 0.4866708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6161 6162 0.230021 0.690381 -0.358085 0.1664192 0.0482722 0.1079673 0.9789369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6162 6163 0.479184 0.431971 -0.641913 -0.0521093 -0.0951563 0.9766215 0.1855811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6163 6164 -0.361525 -0.321023 -0.747113 0.1230565 0.7957603 -0.5436802 0.2367160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6164 6165 0.508941 0.226182 0.731474 -0.5816627 0.3779624 0.5886359 0.4151152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6165 6166 -0.997927 -0.644754 -0.055301 -0.6053613 -0.4186784 0.2139164 0.6422506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6166 6167 -0.946563 -0.138193 0.322134 0.3957586 -0.2322015 0.0202001 0.8882846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6167 6168 -0.622110 0.216786 0.764028 0.3706859 0.3258863 0.1422481 0.8579951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6168 6169 -0.917272 0.849658 -0.199822 -0.3445384 0.7086476 -0.0085845 0.6156607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6169 6170 -0.308687 1.073944 -0.230108 -0.3534875 -0.8246265 0.3315812 0.2917046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6170 6171 0.903788 0.477692 0.227401 0.5744914 0.5630106 -0.4971531 0.3252960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6171 6172 -0.008170 0.718696 -0.877343 -0.3109670 -0.6984673 -0.5402840 0.3514771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6172 6173 -0.485775 -0.174005 0.747878 -0.8300899 0.2691898 -0.0727124 0.4829085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6173 6174 -0.295156 -0.303842 -0.717522 0.5573929 -0.3112189 0.1370763 0.7574074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6174 6175 -0.859700 -0.612630 -0.034958 0.7321429 -0.0885544 0.3766211 0.5606081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6175 6176 -0.626851 0.561407 0.191177 -0.2170152 0.3455977 -0.4771064 0.7783548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6176 6177 -0.883233 -0.133109 -0.491811 -0.5258584 0.1989281 0.8247969 0.0600886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6177 6178 0.781105 0.326461 0.652089 0.5447761 -0.1199066 -0.6790733 0.4771802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6178 6179 -0.650960 0.558541 -0.582539 0.5149953 -0.2780828 0.2082623 0.7836304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6179 6180 -0.516766 -0.027202 0.773333 -0.3670899 -0.0736470 0.4316482 0.8206710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6180 6181 0.172968 -1.134136 0.028332 -0.4070508 0.0694267 0.3534977 0.8393623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6181 6182 -0.386177 -0.619736 -0.650201 -0.0829654 -0.1791734 0.7317572 0.6523382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6182 6183 -0.776266 0.680344 -0.454246 0.2200871 -0.6415257 0.2428557 0.6935614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6183 6184 -0.441120 1.008365 0.279589 -0.1379887 -0.5453930 -0.6598918 0.4980445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6184 6185 -0.286685 -0.178390 0.827057 -0.8343844 0.4240468 -0.0293496 0.3508926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6185 6186 -0.125722 -0.525769 -1.006563 -0.0660979 0.2324234 0.9703495 0.0056807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6186 6187 0.261255 0.201563 -0.885843 -0.6142708 -0.5948855 -0.4172162 0.3077553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6187 6188 -0.854099 0.271095 0.708420 -0.2780771 -0.0796457 -0.5525266 0.7816931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6188 6189 -0.191159 -0.939818 0.398490 -0.6804288 0.4285833 0.1778647 0.5671835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6189 6190 -0.244634 -0.060380 -0.889576 0.6366400 -0.3330532 0.2343936 0.6548471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6190 6191 -0.781090 -0.616920 0.118270 0.0498330 0.3060497 -0.0982322 0.9456219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6191 6192 -0.599900 -0.640066 -0.376372 0.5516368 -0.5229536 -0.6191605 0.1971211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6192 6193 0.884555 0.154975 0.480686 -0.5259260 -0.6462175 -0.1190700 0.5400251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6193 6194 0.702419 0.584072 -0.640205 0.2439696 -0.3631850 0.2345180 0.8680880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6194 6195 0.218656 0.116064 -1.105182 0.3445517 0.2916095 0.5386891 0.7113804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6195 6196 0.038615 -1.119359 -0.530069 -0.5126900 0.3361218 0.6187279 0.4912707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6196 6197 0.340830 0.373477 -0.886562 -0.6714442 0.0173672 -0.2308101 0.7039799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6197 6198 -0.156764 0.954626 0.252282 0.4251102 0.3531665 -0.6308944 0.5445430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6198 6199 -0.681659 -0.185968 -0.860882 0.0072616 -0.3544539 -0.3810287 0.8538893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6199 6200 -0.545768 0.087003 0.931669 0.5481643 0.2936247 -0.7068739 0.3370901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6200 6201 -0.338115 -0.074331 -0.908541 -0.0470769 -0.6585816 -0.5211092 0.5408320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6201 6202 -0.648228 -0.880930 0.171781 -0.0628964 0.0185045 -0.5734792 0.8165925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6202 6203 0.634491 -0.956303 -0.099062 0.4722243 0.0275247 -0.3203762 0.8207348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6203 6204 1.168953 -0.219549 0.367796 -0.1631789 -0.8335899 -0.5134470 0.1219540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6204 6205 -0.570452 0.771126 -0.053166 -0.8214169 0.1101419 0.0370528 0.5583638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6205 6206 -0.471642 0.244644 0.735790 -0.2079670 0.0882252 0.9736282 0.0318445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6206 6207 0.169949 -0.130341 0.947265 0.1245931 -0.5185084 0.4206732 0.7339344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6207 6208 0.735817 -0.510213 0.244309 -0.3535194 -0.0854766 0.5118863 0.7782610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6208 6209 0.030093 -0.705950 -0.670558 0.3695959 -0.8069831 0.4316411 0.1608201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6209 6210 -0.026399 -0.042126 0.952479 0.4653579 -0.4511257 -0.3484656 0.6771258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6210 6211 0.277134 0.915131 0.142666 -0.7475970 -0.4300738 -0.4603243 0.2103255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6211 6212 0.726568 -0.423638 0.503324 -0.5318257 -0.1674720 0.2365738 0.7957056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6212 6213 0.475722 -0.835349 -0.525883 0.4964554 0.6320640 0.2884521 0.5204062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6213 6214 -0.601249 -0.505237 0.499522 -0.1204713 -0.2483179 -0.0670119 0.9588192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6214 6215 -0.205984 -0.534637 0.721255 0.4772259 0.2628372 0.4505884 0.7072073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6215 6216 -0.833693 0.728395 0.356390 0.0092100 0.6937338 0.7040431 0.1515650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6216 6217 0.859772 0.527024 0.663109 -0.2330516 -0.2188392 -0.2930654 0.9010599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6217 6218 0.548320 0.558163 0.593989 0.5367647 -0.1126106 0.7340282 0.4005061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6218 6219 0.947158 -0.557413 0.516314 -0.7688108 -0.0473132 0.3219283 0.5505030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6219 6220 0.959515 0.272791 0.177953 0.4425708 -0.5770989 0.0994910 0.6791093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6220 6221 0.738600 1.013422 -0.003634 -0.3931491 0.1150267 0.1767922 0.8949565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6221 6222 0.784374 0.292466 0.577319 -0.0602863 0.2427378 -0.0538593 0.9667177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6222 6223 0.193494 0.380123 1.013326 0.4831176 -0.1866955 0.7144615 0.4704114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6223 6224 0.759730 -0.089027 0.629959 -0.0594086 -0.2638643 -0.5315695 0.8026706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6224 6225 0.624153 0.784385 -0.242116 0.4900984 0.4558652 0.6796108 0.3001991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6225 6226 0.338972 -0.226023 0.944651 -0.3243337 0.9302172 0.0917724 0.1451945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6226 6227 -0.285464 -0.313565 -1.035748 0.3323044 -0.5979793 -0.3883944 0.6173689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6227 6228 0.012271 -1.029089 0.321512 0.0184992 -0.7266777 -0.2788273 0.6275768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6228 6229 0.728498 -0.576356 -0.294224 -0.0606356 0.5104285 -0.1782227 0.8390606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6229 6230 0.835019 -0.421531 0.537146 -0.4366310 0.2720225 0.3343363 0.7896685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6230 6231 0.145497 -0.964988 0.149063 0.4721519 -0.7575219 -0.0731075 0.4448466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6231 6232 0.796663 -0.400189 0.224664 -0.4847467 0.1247883 0.0681342 0.8630216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6232 6233 0.874189 -0.532814 -0.323677 0.3945262 0.5906367 0.2328181 0.6642989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6233 6234 -0.235458 -0.410971 0.719465 -0.8525103 0.0755056 0.1788407 0.4853257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6234 6235 -0.534327 -0.465107 -0.729322 -0.5036832 -0.1893342 0.7264280 0.4275022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6235 6236 0.483846 1.019275 0.128421 0.1358271 -0.1881563 0.8678928 0.4392155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6236 6237 0.665669 -0.805457 -0.179111 -0.1391500 0.2057386 0.5963340 0.7633444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6237 6238 -0.400106 -0.810020 -0.343963 0.0399750 -0.6056372 0.7402901 0.2890955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6238 6239 0.010046 0.460173 0.745048 -0.4198441 -0.6524123 0.5909747 0.2209933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6239 6240 -0.715075 0.187767 -0.722835 -0.6824607 -0.1988553 0.6883026 0.1447188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6240 6241 0.094698 -0.972586 0.324589 -0.1418456 0.7422264 0.6431248 0.1239769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6241 6242 -0.167645 0.103181 -1.010753 -0.3407873 -0.0350993 -0.8381611 0.4244030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6242 6243 -0.649893 0.181128 -0.657149 -0.0739935 -0.6109469 -0.1856019 0.7660423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6243 6244 -0.846998 -0.138163 0.539286 0.3143181 0.5047971 -0.0322692 0.8033323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6244 6245 -0.876043 -0.160889 -0.356325 0.2338612 0.4795956 0.2156878 0.8177872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6245 6246 -0.121490 -0.267096 -0.895599 0.5926986 -0.1270717 -0.6782623 0.4153569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6246 6247 0.920209 -0.562586 0.005505 -0.6273010 -0.3114933 0.6922883 0.1737881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6247 6248 -0.449973 0.699047 -0.750241 0.4213851 -0.1719281 0.3596487 0.8145724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6248 6249 -0.478432 0.354018 -0.788138 -0.9176137 0.1411684 0.1330271 0.3469300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6249 6250 -0.003842 0.412473 0.725446 0.6807638 -0.2569134 -0.6745523 0.1246411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6250 6251 -1.032306 0.183923 0.117934 -0.3645697 0.3720899 -0.3770081 0.7658348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6251 6252 -0.331490 -0.275306 -0.904209 0.8187848 -0.0378981 -0.5720909 0.0294471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6252 6253 0.630230 0.288972 0.724916 0.2465270 -0.0295232 0.5812000 0.7749577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6253 6254 0.665314 -0.107631 0.680781 0.1680385 0.1327648 0.2116286 0.9535984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6254 6255 0.397827 0.080297 1.132316 -0.5003789 0.2963801 0.1798833 0.7933611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6255 6256 -0.314885 -1.061766 0.203161 0.1569679 0.2842498 0.8898356 0.3205553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6256 6257 -0.305780 0.940502 -0.526708 -0.0407591 -0.2889461 0.2046672 0.9343234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6257 6258 -0.116787 0.824577 -0.051816 -0.0843570 0.0411265 0.4362674 0.8949097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6258 6259 0.870185 0.609431 0.159137 0.4895699 0.7291440 -0.2105643 0.4293403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6259 6260 -0.565975 -0.023802 -0.695921 -0.1234064 0.4276925 0.8537877 0.2699938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6260 6261 -0.332411 0.504369 -0.763970 -0.9264184 0.0077029 -0.1710295 0.3353186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6261 6262 -0.410830 0.191692 0.836637 0.0838193 0.6565532 0.0990247 0.7430386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6262 6263 -0.725179 0.173416 -0.203062 0.0878465 -0.1268541 -0.9435994 0.2929355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6263 6264 0.665075 -0.911791 -0.097605 -0.4682598 0.4595947 -0.7480174 0.0998770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6264 6265 0.285865 0.079362 0.970224 -0.4954159 -0.7607602 0.3819022 0.1730827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6265 6266 0.020258 -0.703952 -0.947138 0.2264553 0.1166422 -0.0790304 0.9637774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6266 6267 0.344835 -0.746261 -0.405167 -0.0158755 0.1208292 -0.4509047 0.8842133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6267 6268 0.871504 0.008476 -0.398092 0.2722589 0.6463735 -0.3623324 0.6138335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6268 6269 0.205906 0.821727 0.604263 0.7938089 -0.1307806 -0.5284915 0.2710360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6269 6270 -0.886744 -0.203191 -0.590947 -0.5486265 0.4863237 -0.0151463 0.6799035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6270 6271 0.088680 0.674735 -0.390335 -0.0212615 -0.0933382 0.0306353 0.9949359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6271 6272 -0.038468 0.811948 -0.588925 -0.2090004 -0.5424040 -0.7891811 0.1982674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6272 6273 -0.378889 -0.652662 0.591072 0.0135358 0.7655459 -0.4886158 0.4183430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6273 6274 -0.011771 -1.043833 0.008199 -0.3557589 -0.3062788 0.2426491 0.8489701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6274 6275 -0.516511 -0.892137 -0.307690 -0.0553572 -0.5726089 0.1713748 0.7998033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6275 6276 -0.791984 -0.569521 0.353658 0.1462037 0.4373728 0.6449634 0.6093863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6276 6277 -0.288551 0.767172 -0.418825 -0.7071839 0.3840192 0.5779667 0.1355531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6277 6278 0.059569 -0.523404 0.875578 0.1977335 -0.7429595 -0.5735449 0.2827701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6278 6279 0.268103 0.856692 -0.709432 -0.1143723 -0.1658815 -0.7919669 0.5763600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6279 6280 0.091110 0.919227 -0.110786 0.4294084 0.2464027 0.8678681 0.0412208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6280 6281 -0.490586 -0.056373 0.958009 -0.2422613 -0.1516704 -0.2529503 0.9242952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6281 6282 -0.033098 -0.426905 0.880840 -0.3214161 0.3095264 -0.8657387 0.2266751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6282 6283 0.533377 -0.123174 0.640072 0.8566142 0.2076053 -0.3780564 0.2831703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6283 6284 -0.021844 0.900933 -0.522361 0.5179326 0.4378799 -0.5785111 0.4531357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6284 6285 0.347667 -0.366710 -0.773319 0.3072556 -0.2596125 0.8346950 0.3761377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6285 6286 -0.978468 0.086171 -0.116938 -0.5796374 -0.5796722 -0.4489537 0.3555857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6286 6287 -0.136666 -0.912522 0.079460 0.1087663 -0.1241304 -0.9411869 0.2948369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6287 6288 0.731048 0.759342 -0.210164 0.1188052 -0.8033016 0.2043636 0.5466511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6288 6289 -0.435544 0.256402 -0.996368 -0.7171813 -0.1548904 -0.1592840 0.6605214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6289 6290 -0.578402 0.602018 0.375317 -0.2382359 0.3025365 0.6376078 0.6672118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6290 6291 0.267773 0.455350 0.743654 -0.4672503 -0.2687427 0.3928455 0.7450684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6291 6292 0.520348 -0.543143 0.617310 0.4677909 0.5965214 -0.6500719 0.0523495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6292 6293 -1.055082 0.258048 -0.010860 0.2307371 -0.5775996 0.6550086 0.4290720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6293 6294 0.376662 0.641004 0.062585 0.0681611 0.2690213 0.2314911 0.9324127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6294 6295 0.634796 0.507288 0.142446 0.2495809 0.4312686 -0.0197565 0.8667909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6295 6296 0.442124 0.710415 0.471244 -0.0642017 -0.1242431 0.8069057 0.5738858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6296 6297 0.605338 -0.747914 0.486264 -0.3727900 -0.2756204 -0.8603935 0.2116224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6297 6298 0.046561 0.977915 0.066376 -0.5240952 0.3185634 -0.2727952 0.7412316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6298 6299 -0.977030 0.158276 0.545504 0.1926066 -0.9210400 0.3260603 0.0909545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6299 6300 0.434396 0.647793 0.812107 0.6575011 0.3873539 0.3205323 0.5611669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6300 6301 -0.410245 0.422380 -0.746988 -0.4726795 -0.2327515 0.7701202 0.3596050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6301 6302 0.863747 0.561218 0.242803 -0.4707269 0.3395336 -0.7692863 0.2670797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6302 6303 -0.647436 -0.449226 0.553192 -0.5740889 0.5334536 -0.1842381 0.5932163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6303 6304 -0.312973 -0.502613 -0.971717 -0.1723096 0.8824759 -0.4374176 0.0145463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6304 6305 0.325634 0.604649 0.862497 0.0245759 -0.5881974 0.4372530 0.6798747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6305 6306 0.853981 -0.292091 -0.298103 0.1549938 -0.6049279 0.7682572 0.1407839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6306 6307 -0.989942 -0.093823 0.092724 0.1914517 0.0200522 0.1853031 0.9636425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6307 6308 -0.841991 0.342118 0.140924 -0.3289514 0.6213277 -0.6362177 0.3177576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6308 6309 0.066717 -0.006477 -1.019657 0.0134990 0.4254540 -0.2333931 0.8742621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6309 6310 0.846969 0.097224 -0.434519 -0.1440064 -0.2276129 0.8723242 0.4080503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6310 6311 -0.412264 -0.327339 -0.797969 0.1829745 -0.0364163 -0.5772606 0.7949619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6311 6312 0.406009 -0.708382 -0.520244 -0.6802815 -0.3892371 0.6201308 0.0339010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6312 6313 -0.213749 0.988422 0.092109 -0.1782575 -0.1731548 0.6751860 0.6945254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6313 6314 1.026946 0.006458 -0.029548 -0.5735636 -0.0127586 0.0364613 0.8182497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6314 6315 0.717240 -0.210152 0.030423 0.3101122 -0.1067881 0.0935959 0.9400354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6315 6316 0.972270 -0.271444 -0.270510 -0.5312365 -0.1168271 0.1510197 0.8254285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6316 6317 0.828425 -0.059387 -0.589961 0.1644101 0.8298619 -0.4569145 0.2748229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6317 6318 -0.143714 0.932480 0.685948 -0.0419763 0.6080747 -0.5061823 0.6101333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6318 6319 -0.915014 -0.166492 -0.502011 0.4091093 0.2415200 -0.8683791 0.1421809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6319 6320 -0.210473 -0.956016 0.210255 0.5413943 -0.3373097 -0.0221410 0.7698209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6320 6321 -0.871440 0.049457 0.341074 -0.3040854 -0.0447326 -0.8272735 0.4702655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6321 6322 0.650556 -0.604669 -0.144411 0.2479034 -0.1362396 -0.8060750 0.5198325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6322 6323 0.396794 0.869052 -0.341511 -0.3735107 0.5290866 0.5364045 0.5411352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6323 6324 0.615604 -0.321587 0.987682 0.8509767 -0.0180924 -0.3572502 0.3845563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6324 6325 0.073270 0.645600 -0.455352 -0.4905263 0.4940103 0.3702680 0.6150117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6325 6326 0.333515 0.310484 0.790423 -0.5318364 -0.2214777 0.5143627 0.6352391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6326 6327 0.275897 -0.942328 0.077741 0.5427277 0.1172919 0.8005613 0.2253683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6327 6328 -0.457317 0.733882 0.517570 -0.3577441 0.4484267 -0.8064374 0.1434970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6328 6329 0.218299 -0.762008 -0.586891 0.3198284 -0.5008322 0.7728354 0.2227158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6329 6330 -0.637476 0.584124 0.266168 -0.4280329 0.7134449 0.4178038 0.3649988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6330 6331 -0.107350 0.852247 0.407841 0.7859194 -0.2410575 -0.5635555 0.0814070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6331 6332 -0.662029 -0.844372 0.312146 -0.4755996 -0.1738294 0.8623026 0.0047563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6332 6333 0.132421 0.276916 0.961299 0.0575987 -0.6711873 0.6720607 0.3074482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6333 6334 0.714269 -0.789277 -0.319287 -0.1351496 -0.2421209 -0.8544724 0.4393052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6334 6335 0.395251 0.653847 -0.645309 0.0974118 -0.0674906 -0.6442711 0.7555599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6335 6336 -0.568772 0.204577 -0.678788 -0.3065955 -0.0801114 0.6046754 0.7307182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6336 6337 0.101783 0.933004 -0.629837 -0.5188160 -0.1066148 -0.7583858 0.3798871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6337 6338 -0.833217 -0.368364 0.494078 -0.3885583 0.4822498 0.1862854 0.7627289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6338 6339 -0.671098 0.340224 -0.811693 -0.1327312 -0.3301150 0.3667373 0.8595989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6339 6340 -0.615359 -0.632233 -0.419475 0.4961259 -0.4822563 0.4903095 0.5299855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6340 6341 -0.085567 -0.793583 0.695632 0.1289108 0.7460890 0.5795674 0.3013883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6341 6342 -0.490633 0.681010 -0.578517 -0.6422065 0.1766144 -0.1906458 0.7211327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6342 6343 -0.704651 0.825661 -0.015809 0.6228834 0.4042357 -0.5837832 0.3283397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6343 6344 0.106166 -0.819493 -0.265159 0.4251339 0.2764138 0.0799613 0.8581741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6344 6345 -0.007138 -0.797494 0.562518 -0.3111987 0.1992948 0.8511982 0.3726909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6345 6346 -0.649869 0.672883 -0.203344 -0.4681061 0.1962664 0.5009263 0.7010200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6346 6347 -0.138257 0.542571 0.792814 0.0142779 -0.1560168 0.0490677 0.9864316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6347 6348 0.211249 0.674691 0.579245 0.5039496 -0.3884847 0.2624022 0.7254374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6348 6349 0.671772 0.333825 -0.590922 -0.1753083 0.4276307 -0.3613506 0.8098301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6349 6350 0.318486 0.900325 0.179245 0.2497634 -0.3276016 0.3988107 0.8192957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6350 6351 0.757706 0.391124 -0.308681 0.4880824 0.4831129 0.7247220 0.0561743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6351 6352 -0.629603 -0.172511 0.817193 0.4411151 -0.0362112 0.8964649 0.0213734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6352 6353 1.106430 0.286818 -0.115697 -0.1133860 -0.3239194 0.8622400 0.3725077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6353 6354 -0.485552 -0.900947 -0.538182 0.0618604 0.3583155 0.9315226 0.0069974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6354 6355 0.590535 -0.001051 -1.016272 -0.7865168 0.4157871 0.3591294 0.2820255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6355 6356 0.855690 -0.475760 0.598561 0.6708390 -0.2025761 -0.6977397 0.1486512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6356 6357 -0.221928 0.543219 -0.862987 -0.1010942 -0.1563579 0.9824769 0.0084418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6357 6358 0.211467 -0.031757 -0.854621 -0.0772342 -0.2171972 0.7426312 0.6287759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6358 6359 -0.493242 0.107794 -0.906104 -0.1723035 -0.2233289 -0.4142811 0.8653363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6359 6360 -0.424899 0.662818 0.520119 -0.6201484 0.1374695 0.7719310 0.0253110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6360 6361 -0.617752 -0.270323 -0.856954 -0.5419289 -0.1293619 0.8293107 0.0426886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6361 6362 0.833634 0.315315 0.377291 0.1095367 0.2132857 0.1230353 0.9630022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6362 6363 0.618002 0.178848 0.630028 -0.3192947 0.0992402 0.8862036 0.3206954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6363 6364 -0.680636 -0.631563 0.115450 0.3217141 -0.9208487 -0.0109229 0.2200418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6364 6365 0.830730 -0.139858 0.143088 -0.6393785 0.5690258 -0.2698530 0.4411169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6365 6366 0.449732 -0.553782 0.760366 0.8106344 0.4375087 -0.3413017 0.1870058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6366 6367 -0.691785 0.694547 -0.396990 0.5410308 -0.2077352 0.5128907 0.6333047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6367 6368 -0.091046 0.555900 -0.811227 -0.5578565 -0.0315215 -0.1286870 0.8192937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6368 6369 -0.365673 0.731713 0.020390 0.2340895 0.3146137 -0.5979347 0.6990668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6369 6370 -0.651803 -0.433317 -0.686030 0.0323914 -0.5102885 0.8229176 0.2477157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6370 6371 0.239424 0.896417 0.143648 0.3393714 0.5742497 0.1562623 0.7284548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6371 6372 0.709828 0.873583 -0.051509 0.6394393 -0.3016567 -0.6342743 0.3127567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6372 6373 -0.563646 -0.344795 -0.420940 0.0075655 0.1548950 0.3588331 0.9204288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6373 6374 -0.320945 -0.210590 -0.828642 -0.1405768 -0.8116833 -0.5592450 0.0930242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6374 6375 0.231360 -0.990289 0.255352 -0.0093944 0.8022276 0.2970505 0.5177872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6375 6376 -0.613541 -0.850531 -0.257492 0.7623336 -0.4279491 -0.4021727 0.2719636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6376 6377 0.639629 0.592961 0.652956 -0.1351950 -0.9481322 -0.1121837 0.2649197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6377 6378 -0.386682 0.583486 -0.926813 -0.0678064 0.9839602 0.1170437 0.1162990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6378 6379 0.196826 0.355137 0.990068 0.0989337 -0.6480541 0.4489407 0.6071987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6379 6380 -0.062965 0.288776 -1.002090 0.0341874 -0.0182737 0.9450368 0.3246579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6380 6381 0.870636 0.166196 0.194251 -0.0235071 0.5414451 0.0669735 0.8377346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6381 6382 0.078188 0.163322 0.901602 0.4075384 -0.2811757 -0.1780375 0.8503854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6382 6383 0.433706 0.917300 0.085973 -0.6961835 0.5503307 -0.4602579 0.0250472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6383 6384 -0.442332 -0.595779 -0.566002 -0.4977337 0.6405450 -0.1278127 0.5706376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6384 6385 0.815996 0.559829 -0.646533 0.2576011 0.4794798 0.0436602 0.8377556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6385 6386 0.877932 0.070018 0.284721 0.5440794 -0.3160021 0.2839191 0.7235401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6386 6387 0.930984 -0.484308 -0.194213 -0.0481878 0.0682948 -0.3368507 0.9378408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6387 6388 0.919337 0.053385 -0.064458 -0.1954827 -0.7708543 -0.0970935 0.5984506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6388 6389 -0.119371 0.575721 -0.723240 -0.2644998 0.3205947 0.8843677 0.2124917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6389 6390 0.664756 -0.684132 -0.133612 0.0723572 0.6308387 -0.5636423 0.5283127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6390 6391 0.050543 0.198374 0.862178 -0.1325813 -0.0330712 -0.9775867 0.1601646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6391 6392 -0.050031 -0.154240 0.987895 0.1061020 0.4937391 0.3889310 0.7705172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6392 6393 -0.703579 0.480647 0.670366 0.6612790 0.5678251 0.4673844 0.1477723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6393 6394 0.311368 -0.295631 -0.722812 -0.2153345 0.5345400 0.3204010 0.7518253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6394 6395 0.501360 -0.556623 0.161414 0.1707446 0.2564003 0.9192617 0.2450776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6395 6396 -0.956932 0.435551 0.148666 -0.3036110 0.8261830 0.3367674 0.3344095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6396 6397 0.351648 0.803596 -0.284341 -0.4779091 0.6727885 0.5536156 0.1116617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6397 6398 -0.468561 -0.698936 0.471767 -0.6264728 -0.0710258 -0.6559732 0.4149535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6398 6399 0.691951 -0.161310 -0.581515 0.2888148 0.8860174 -0.0989403 0.3489556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6399 6400 2.061791 -7.279405 -17.478670 -0.0050591 -0.6845183 0.3484627 0.6402990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6400 6401 1.012088 0.056785 -0.111123 -0.2479290 -0.2607324 0.0632617 0.9308855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6401 6402 0.740647 -0.003184 -0.486803 0.0766442 0.3829162 0.1150637 0.9133790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6402 6403 0.876520 -0.294090 0.254178 0.3902317 -0.6275046 0.0827637 0.6686609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6403 6404 0.379906 -0.780317 -0.571985 -0.2537224 0.3253516 0.8839639 0.2199527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6404 6405 -0.190527 0.132707 -1.050574 0.6151286 -0.6515996 -0.4356315 0.0852056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6405 6406 0.540046 -0.569111 0.730882 0.1186049 0.7658035 -0.0746532 0.6276183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6406 6407 -0.910955 -0.201473 0.455308 -0.3308233 0.4342359 0.8377864 0.0104445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6407 6408 0.555799 0.917188 0.434265 -0.2483702 -0.1828160 0.8953489 0.3213111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6408 6409 0.087357 -0.977405 -0.032115 -0.2423890 0.4057729 0.8755848 0.0997359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6409 6410 -0.066781 0.587281 -0.751979 -0.8760485 0.0214456 0.2089224 0.4340858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6410 6411 0.274977 0.218288 0.772185 0.8790756 0.2118675 -0.4003252 0.1485869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6411 6412 -0.589647 -0.097861 -0.835165 -0.7460310 0.5471816 0.2279693 0.3034139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6412 6413 0.517641 0.761674 0.476569 0.5765800 -0.4273407 -0.5276767 0.4544147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6413 6414 -0.896325 0.232686 -0.420477 -0.3112090 -0.2740341 0.1679841 0.8943353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6414 6415 -0.611786 0.766275 0.172851 0.2646083 0.5807799 0.3276068 0.6966713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6415 6416 0.373489 0.529045 -0.513665 -0.7237514 0.2076460 0.6169669 0.2289516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6416 6417 0.649136 -0.606244 0.342247 -0.0282150 -0.3625638 0.4202927 0.8313275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6417 6418 0.160750 -1.075653 0.135512 0.0457172 -0.3425463 -0.7771046 0.5260041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6418 6419 0.723698 -0.057112 -0.655949 -0.9137415 0.3246089 0.1232474 0.2109871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6419 6420 -0.179773 0.126754 0.702829 0.6176015 0.3483672 -0.3844133 0.5911304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6420 6421 0.197832 -0.955152 -0.387394 0.0931449 -0.3498559 -0.9042335 0.2264656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6421 6422 0.303086 0.184021 -0.787012 0.2155906 0.6881313 0.2938894 0.6273954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6422 6423 0.758502 -0.396047 0.589967 0.2307610 0.6030776 0.6439998 0.4102572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6423 6424 -0.828587 0.008283 0.326955 -0.6079865 0.1279160 -0.4718134 0.6256054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6424 6425 -0.515629 -0.627869 -0.696351 -0.2537501 -0.6350303 0.5008171 0.5305937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6425 6426 -0.641160 0.434742 0.438515 0.1935954 0.2621527 -0.9444310 0.0429756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6426 6427 0.411320 -0.659376 0.604871 -0.2042252 0.6818353 0.2199831 0.6670832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6427 6428 -0.566155 -0.833267 -0.155686 -0.2916323 0.5857603 0.6757261 0.3394549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6428 6429 0.415476 0.394335 -0.735590 0.2407904 -0.4754717 -0.3992246 0.7460338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6429 6430 -0.727870 -0.340366 -0.804361 -0.0783457 -0.2320582 -0.7614959 0.6001125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6430 6431 0.045020 -0.771468 -0.703947 0.2440706 -0.7739576 0.4447099 0.3790147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6431 6432 -0.791780 -0.310934 0.764330 -0.5115787 0.1636087 -0.8432851 0.0197408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6432 6433 0.903664 -0.042470 -0.085648 -0.1790922 -0.0630143 0.1149707 0.9750574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6433 6434 0.746360 -0.307416 -0.377117 0.3612672 0.5585591 0.4597134 0.5883548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6434 6435 -0.236323 -0.508846 0.979352 -0.5284337 0.6577828 0.3996160 0.3583110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6435 6436 -0.792088 0.142256 -0.938013 -0.3791900 -0.2908672 -0.1795093 0.8598765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6436 6437 -0.865401 0.151019 -0.281130 -0.4589921 -0.3798573 0.5576765 0.5779547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6437 6438 0.141079 0.423724 0.853886 0.2245603 -0.8695078 0.3839613 0.2147149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6438 6439 0.030478 -0.462279 -0.729687 -0.3082861 0.3101374 -0.6405778 0.6312167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6439 6440 0.801604 -0.678567 -0.527014 0.4554438 0.3509365 -0.4836205 0.6599437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6440 6441 -0.324610 -0.425541 0.765365 -0.6900557 0.0064369 -0.5956847 0.4110249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6441 6442 0.866628 -0.382447 -0.239253 -0.1919690 0.9475807 -0.2549626 0.0152590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6442 6443 -0.834050 -0.374220 0.628735 0.6048707 -0.7398368 0.2829643 0.0818788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6443 6444 0.989218 0.490062 -0.635831 0.0976776 0.2308306 -0.5155369 0.8193888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6444 6445 0.115507 0.946176 -0.448821 -0.1288778 -0.1641536 -0.6683436 0.7139755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6445 6446 -0.998570 0.106721 -0.082847 0.3010008 0.4244916 0.8484333 0.0967801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6446 6447 0.954620 -0.038330 -0.588358 -0.0190178 -0.4531237 0.6051078 0.6543407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6447 6448 -0.652465 -0.175535 -0.593802 0.0834168 0.9669459 -0.2027846 0.1301369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6448 6449 0.655936 -0.312251 0.637706 -0.4039204 -0.7920940 0.3098864 0.3367579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6449 6450 -0.203158 -0.575909 -0.907210 0.6801344 0.5531761 -0.4439351 0.1852971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6450 6451 0.700891 0.167003 0.825035 -0.1966703 -0.9296712 0.0956264 0.2964587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6451 6452 0.049923 -0.011241 -0.945909 -0.1868549 0.6728290 -0.7026510 0.1366307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6452 6453 0.050217 1.016179 0.037922 -0.0344191 -0.6171097 -0.3150421 0.7202356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6453 6454 -0.466727 0.817930 0.546154 -0.0046237 -0.0137129 0.5623012 0.8268059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6454 6455 0.607060 0.712417 0.422974 -0.3607052 0.0358387 -0.9198318 0.1500563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6455 6456 -0.113329 -0.678670 0.899321 0.1032556 -0.7014386 -0.4993148 0.4980029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6456 6457 0.871945 0.344830 -0.346731 0.0471893 -0.0061721 -0.1119223 0.9925767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6457 6458 0.846639 0.666078 -0.326623 -0.5212854 0.4970704 0.6045660 0.3401213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6458 6459 0.093702 -0.855324 0.399506 -0.0296652 0.6171071 0.3852220 0.6854946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6459 6460 -0.341316 -0.665050 1.023579 -0.6925019 0.1793281 0.6812798 0.1553718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6460 6461 -0.253915 -0.644877 -0.737582 -0.3625353 -0.2400094 0.8317450 0.3452011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6461 6462 -0.061969 0.886707 0.083848 -0.0712787 -0.0209778 0.4043597 0.9115769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6462 6463 0.617806 0.827777 0.223224 0.6595383 -0.3602251 -0.6048897 0.2633546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6463 6464 -0.555221 -0.433875 -0.484565 0.3014109 -0.1197161 -0.0863597 0.9419987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6464 6465 -0.669085 -0.594670 0.054445 0.1006361 -0.3335577 0.1450853 0.9260464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6465 6466 -0.649321 -0.320839 0.521563 0.0002221 0.1607344 -0.9718804 0.1720839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6466 6467 0.824883 0.050439 0.531249 0.0774449 -0.4430298 0.8467730 0.2840818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6467 6468 -0.127333 -1.066524 0.643090 0.6093438 -0.1018613 -0.7844926 0.0538128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6468 6469 -0.399524 0.956215 0.428676 -0.4719670 -0.1901414 0.6216900 0.5954788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6469 6470 0.487909 -0.404885 0.621558 0.3295506 -0.3275697 -0.3906613 0.7946560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6470 6471 0.628195 0.695630 0.012934 -0.5412888 -0.1169648 -0.4230389 0.7171916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6471 6472 0.045609 0.602638 0.687727 0.5478433 -0.2251144 0.7090551 0.3826644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6472 6473 0.902421 -0.356609 -0.153262 0.5419077 0.2328682 -0.5289712 0.6101622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6473 6474 0.485146 0.779312 0.194085 0.4514079 0.6311989 0.6306025 0.0126247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6474 6475 0.108991 0.309288 1.028828 0.5419488 0.2884504 0.6285128 0.4775559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6475 6476 0.581363 0.580001 0.401270 -0.1396510 -0.1632732 0.6070565 0.7650633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6476 6477 0.771529 -0.470493 0.046189 0.5106398 -0.1435613 -0.4857991 0.6947203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6477 6478 0.814119 0.321171 -0.382014 -0.3077989 0.1998044 0.8869410 0.2804883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6478 6479 -0.157661 -1.009301 -0.372058 0.1390348 -0.1613608 0.4610754 0.8614183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6479 6480 -0.319535 0.918080 0.491174 0.0058947 -0.1103590 0.9757224 0.1890817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6480 6481 -0.762416 -0.573245 -0.199291 -0.1914690 0.0513731 0.9490965 0.2447780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6481 6482 0.408157 1.020262 -0.137810 -0.5056143 0.3376667 0.0616593 0.7915387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6482 6483 0.188091 0.458849 1.043483 0.8834040 -0.2144463 0.0814615 0.4086248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6483 6484 0.373074 0.469149 -0.853193 -0.6084566 0.7426163 0.2497619 0.1261765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6484 6485 0.035679 -0.458799 0.930750 -0.1515873 0.1818495 0.2352360 0.9426644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6485 6486 -0.501592 -0.743121 0.447070 0.3736742 -0.2366536 -0.6801328 0.5846213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6486 6487 0.488775 0.210286 0.738450 -0.5670866 -0.3565349 0.2556712 0.6970853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6487 6488 0.682935 -0.693695 -0.087868 0.6669012 0.1338007 -0.5755232 0.4539969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6488 6489 0.517193 0.660998 0.258849 -0.4323800 -0.3164526 0.8256010 0.1768847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6489 6490 -0.066399 -0.557961 -0.653002 0.3188362 -0.1363202 -0.7145380 0.6076148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6490 6491 0.805692 -0.272047 -0.397833 -0.3549472 0.6451867 -0.4778511 0.4789623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6491 6492 -0.039942 0.434466 1.045887 -0.0529942 -0.6492637 0.7291143 0.2098584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6492 6493 0.329403 -0.936813 -0.289276 -0.6052917 -0.1560909 -0.6518839 0.4293075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6493 6494 0.067742 0.917086 -0.355132 -0.8806677 0.0954756 -0.2226700 0.4070956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6494 6495 -0.341476 -0.055493 0.858028 0.2368466 -0.2143159 0.6634394 0.6766244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6495 6496 0.488211 0.352217 0.758349 -0.1954894 0.7641920 -0.5538175 0.2666097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6496 6497 -0.662970 -0.684277 -0.197433 0.4652641 0.3045289 0.7751629 0.2998567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6497 6498 -0.377303 0.439214 -0.800735 -0.1618789 -0.1817864 0.9682580 0.0567934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6498 6499 0.498803 -0.158866 -0.873548 -0.6725151 -0.0248259 -0.6355943 0.3783212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6499 6500 0.088943 -0.759372 0.848208 -0.5416202 -0.0530003 0.3063537 0.7810159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6500 6501 0.084813 0.227893 -0.918710 0.4075198 -0.0475898 0.0777444 0.9086356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6501 6502 -0.173047 -0.821989 -0.617869 -0.5506875 -0.1745098 -0.7942052 0.1884878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6502 6503 -0.629403 0.509686 -0.705279 -0.1237994 -0.8571186 -0.4329949 0.2500735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6503 6504 0.115453 -0.493597 0.826540 -0.0493721 -0.1192479 0.8751869 0.4662512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6504 6505 -0.253330 -0.121903 0.848256 -0.7183104 0.2093558 -0.5422386 0.3823319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6505 6506 0.563537 -0.813028 -0.267672 0.3090768 -0.0887526 0.6347881 0.7025942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6506 6507 -0.678931 -0.570393 0.180942 -0.1515814 0.9468179 -0.2490540 0.1361286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6507 6508 0.867235 -0.405783 -0.181342 -0.0860250 0.9211775 -0.3558596 0.1318927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6508 6509 -0.666277 -0.034466 0.901485 0.2857152 -0.6810447 0.5706866 0.3589731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6509 6510 1.127872 0.208796 0.148947 -0.4016815 0.0555297 -0.8426948 0.3541663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6510 6511 -0.201681 0.437531 0.881841 0.0723605 0.2693694 -0.6438628 0.7124920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6511 6512 -0.609181 -0.564871 0.127037 -0.7099693 0.4584098 0.1434035 0.5150140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6512 6513 -0.391736 0.345773 -0.773737 -0.3529807 -0.8387208 -0.0633357 0.4098056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6513 6514 -0.064216 0.351021 1.065393 0.7723711 0.1264032 0.0322268 0.6216322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6514 6515 -0.309070 0.866107 -0.540676 0.5909130 0.1952323 0.7820982 0.0320710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6515 6516 -0.268367 -0.909576 -0.063811 0.3312967 -0.1437305 -0.8937652 0.2660220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6516 6517 0.837442 0.473731 0.002647 -0.7035680 -0.3206615 -0.4003725 0.4918029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6517 6518 0.604757 0.525965 0.625180 0.8415149 0.3372602 -0.3776040 0.1884768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6518 6519 -0.178196 0.131408 -0.856788 0.3985886 0.3100690 -0.8622994 0.0377358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6519 6520 -0.421415 -0.355627 -0.836477 0.4914833 -0.0164433 -0.4665150 0.7352126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6520 6521 -0.221190 -0.034705 0.797664 -0.2133240 0.2882722 -0.7627835 0.5381016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6521 6522 0.184634 -0.680986 0.610231 0.4450136 0.5118522 -0.6704774 0.3007163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6522 6523 -0.447191 0.466938 0.708876 -0.5592365 -0.7938117 0.1757939 0.1619076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6523 6524 0.172800 -0.525503 -0.550724 0.4318000 0.3173200 -0.5807423 0.6128582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6524 6525 0.823585 0.311737 0.510206 0.5566047 -0.3301879 -0.6284565 0.4315202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6525 6526 -0.269831 0.209624 -0.989295 -0.1520330 -0.3242774 -0.8956627 0.2636635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6526 6527 0.015073 -0.685506 -0.448017 -0.0862803 -0.1210835 -0.9419075 0.3011724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6527 6528 0.418459 0.561726 -0.591009 -0.0736836 -0.1971775 0.9234401 0.3208586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6528 6529 -0.005904 -0.475496 -0.917689 0.4057147 0.5170536 -0.0909109 0.7481887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6529 6530 0.483714 -0.762541 0.408438 -0.0936944 -0.0955650 -0.1232103 0.9833148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6530 6531 0.745446 -0.721316 -0.350276 0.0756414 -0.4315411 -0.4278694 0.7905558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6531 6532 0.443613 -0.058648 -0.696929 -0.2464319 -0.3596087 0.8983313 0.0543480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6532 6533 -0.310075 0.538489 -0.735462 -0.8620244 -0.0777063 0.2746040 0.4188893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6533 6534 0.332567 0.195881 0.776005 0.5701582 -0.4983670 -0.6386691 0.1365715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6534 6535 -0.672279 0.453287 -0.206754 -0.4393713 0.7138647 0.4426619 0.3184346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6535 6536 0.434645 0.831613 0.495984 0.0544091 0.3800983 -0.9006474 0.2034677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6536 6537 -0.738336 -0.688165 -0.098636 0.5891380 0.2757987 0.7048021 0.2830290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6537 6538 -0.616989 0.460596 -0.818739 0.2286340 -0.2337159 0.5532672 0.7661585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6538 6539 -0.296357 0.658222 -0.860758 -0.0773160 0.3771137 -0.4899942 0.7821209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6539 6540 -1.005498 -0.324335 0.082209 -0.2170025 -0.5770999 0.0800146 0.7832390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6540 6541 0.669295 -0.741142 -0.100658 0.4371399 0.2663174 0.6201996 0.5944209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6541 6542 -0.904221 -0.214065 0.689569 0.5614165 0.5527867 0.1702241 0.5918295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6542 6543 -0.787179 -0.213411 -0.640960 -0.4836480 0.3267889 0.4159656 0.6973279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6543 6544 -0.036028 0.956815 -0.168090 0.3229031 0.1598749 0.3662325 0.8579320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6544 6545 0.926703 0.269428 -0.341288 0.1901910 0.0907247 -0.3857662 0.8982098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6545 6546 0.636065 0.515636 -0.522002 -0.8067633 0.0697577 0.4091790 0.4205228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6546 6547 0.970451 -0.645722 0.343584 -0.0269746 -0.4467189 0.3073595 0.8397885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6547 6548 0.397270 -0.816949 -0.289316 -0.3348022 0.5327320 0.2606353 0.7322386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6548 6549 0.474011 -0.562986 -0.533470 0.2028777 0.5125844 -0.6326688 0.5439008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6549 6550 0.800786 0.449714 0.535872 0.3849224 0.4706586 -0.5552983 0.5674144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6550 6551 -0.763564 0.956623 -0.348028 0.4939162 0.4345098 0.7526951 0.0264215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6551 6552 0.521321 -0.830805 -0.088303 -0.6235276 -0.2265770 -0.7326018 0.1522198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6552 6553 -0.354559 1.025946 0.024365 -0.3657154 -0.2830186 0.1532384 0.8733102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6553 6554 0.194314 0.649352 0.712266 0.4162429 0.5835993 0.4499666 0.5326197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6554 6555 0.571012 0.663804 0.358406 0.0574907 -0.4103218 0.5815333 0.7001070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6555 6556 0.979475 -0.336875 -0.517086 0.2628844 0.4073191 0.6315460 0.6050889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6556 6557 -0.255480 -0.621239 0.311625 0.2615943 0.1284433 0.4450287 0.8467705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6557 6558 -0.964946 0.039916 0.378039 -0.6207764 0.0824400 -0.5362779 0.5659031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6558 6559 -0.222145 -0.926215 -0.542398 0.4560098 0.5339145 0.4793449 0.5265158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6559 6560 -0.228197 0.751090 -0.902159 -0.0856367 0.0664175 0.9247805 0.3647412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6560 6561 -0.134655 -0.929255 0.369952 -0.1466095 -0.3648864 -0.4033904 0.8262202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6561 6562 0.637146 -0.776972 -0.481359 -0.4355108 -0.3700030 -0.1364767 0.8091985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6562 6563 0.231422 0.006138 -1.101437 -0.4747126 0.1529151 0.6973491 0.5147517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6563 6564 0.931178 0.125093 -0.447857 -0.5829103 0.2394611 -0.7431053 0.2250968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6564 6565 -0.488937 0.372177 0.772170 -0.0304806 -0.3970628 -0.7232465 0.5642044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6565 6566 0.273507 -0.096405 0.942125 0.6805588 -0.3753704 -0.3024013 0.5518063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6566 6567 0.256814 0.928143 -0.478777 0.4063117 -0.2641677 -0.2282273 0.8444161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6567 6568 -0.307363 -0.023731 -0.919043 -0.0012003 -0.6071349 -0.5268311 0.5948401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6568 6569 -0.779792 -0.628566 0.059035 0.5471115 -0.0863365 -0.4520349 0.6991991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6569 6570 0.144487 -0.102769 0.875360 0.4258588 0.1862213 0.8479145 0.2549644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6570 6571 0.128968 0.694227 0.543782 0.3711410 0.3040839 0.2549796 0.8395074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6571 6572 0.499683 0.900003 0.161486 -0.1674797 0.5603309 -0.4485551 0.6758537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6572 6573 -0.962549 0.429331 0.182646 0.1203078 -0.2363264 0.1915008 0.9449885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6573 6574 -0.362053 0.682524 0.190733 0.3744464 -0.0158816 0.0580296 0.9252947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6574 6575 -0.178875 0.910036 -0.329360 0.6777563 -0.3847256 -0.6241775 0.0550908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6575 6576 -0.157239 -0.737788 0.803017 0.6887209 -0.3046589 -0.4125694 0.5124774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6576 6577 0.443316 0.979446 0.209194 -0.4528306 0.0242584 -0.2580317 0.8530977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6577 6578 -0.185587 0.523409 0.790429 0.7693365 0.2618566 -0.5811350 0.0428327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6578 6579 -0.351246 -0.897738 -0.370254 -0.4227920 -0.0620017 -0.1522703 0.8911882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6579 6580 0.774945 -0.602607 -0.148884 -0.2485597 0.1150586 -0.2030715 0.9400753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6580 6581 0.211052 0.257439 0.914286 0.2086791 0.2014490 -0.1155632 0.9500087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6581 6582 -0.356560 0.640118 0.800727 -0.2172926 0.8006605 -0.4791449 0.2866125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6582 6583 -0.248370 -0.235271 -0.957818 -0.4660628 0.7714782 -0.4202938 0.1046897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6583 6584 0.303333 0.748846 0.621974 0.7614473 0.3293041 0.1618622 0.5343758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6584 6585 0.575415 0.314450 -0.694447 0.2233517 0.4053571 0.3213861 0.8261420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6585 6586 1.030519 -0.183269 -0.061985 -0.2537483 -0.5764549 -0.6985028 0.3397137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6586 6587 -0.518278 0.727639 -0.276511 0.5923590 -0.0067451 -0.2995530 0.7478859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6587 6588 -0.683578 -0.427737 -0.716066 -0.3147865 0.1150269 0.4484962 0.8285707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6588 6589 -0.433026 0.613753 -0.668022 -0.0010466 0.1471263 0.8695809 0.4713617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6589 6590 0.861484 -0.054291 -0.537172 0.2704657 0.7763113 0.3461384 0.4520810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6590 6591 0.024143 -0.493862 0.864346 -0.7094382 -0.4813335 0.5011951 0.1175538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6591 6592 -0.884540 -0.415047 -0.340545 0.3190084 0.7523990 -0.4254185 0.3887783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6592 6593 0.307603 -0.657446 0.377152 0.4337778 -0.3335776 0.6986522 0.4609207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6593 6594 -0.300451 -0.285316 0.777347 -0.5970255 -0.0636730 -0.7849928 0.1526188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6594 6595 0.961644 0.089210 0.121523 0.3844372 0.7099856 -0.5580824 0.1915007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6595 6596 -0.785312 0.714136 -0.357146 -0.7240950 -0.6420304 0.2385351 0.0811443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6596 6597 0.708862 -0.635606 0.500015 0.0774466 -0.5787404 -0.4242463 0.6921537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6597 6598 0.863259 0.211256 -0.441839 0.1083227 0.3078296 -0.6130669 0.7194832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6598 6599 0.239767 0.939356 -0.588351 0.0332715 0.3571407 -0.1623669 0.9192282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6599 6600 0.741638 0.154318 0.653698 -0.8188022 -0.0410129 0.2925753 0.4922200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6600 6601 -0.622553 0.427211 -0.726284 0.4436130 0.8080033 -0.3048633 0.2395757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6601 6602 0.843435 -0.391512 0.010811 -0.2317357 -0.8372637 0.1334270 0.4769542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6602 6603 -0.397690 -0.116856 -1.002484 0.0518678 -0.7756094 0.4493848 0.4402194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6603 6604 -0.505147 0.622668 0.644745 0.2738692 -0.4891809 -0.6022432 0.5683316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6604 6605 -0.566086 0.264826 0.680417 -0.9025368 -0.1768238 -0.1076624 0.3775837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6605 6606 -0.225482 -0.837857 -0.294977 0.0979869 0.6593696 0.5012493 0.5517059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6606 6607 -0.411106 -0.706005 -0.618213 -0.2642102 -0.3326059 0.7933847 0.4360126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6607 6608 -0.308490 1.024310 -0.019219 -0.2733346 0.3323708 0.2856299 0.8562905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6608 6609 0.225103 0.849233 0.513241 -0.6427206 -0.2504296 0.4027155 0.6016772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6609 6610 0.646076 -0.668960 0.269593 -0.1412858 0.0266054 0.8701339 0.4713783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6610 6611 -1.056915 -0.174775 0.065673 -0.3644106 -0.2416166 0.5095200 0.7410908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6611 6612 -0.577912 0.332220 0.553639 -0.6807131 0.5458902 -0.3614504 0.3286140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6612 6613 -0.405067 -0.445705 -0.659601 0.2025060 -0.5659445 0.5216157 0.6054876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6613 6614 -0.765541 0.465354 0.303223 0.1431717 0.4234908 0.6840496 0.5763970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6614 6615 0.772174 0.663420 0.051819 -0.5595228 0.1153514 0.7079238 0.4152977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6615 6616 0.426611 -0.978372 0.201879 0.0627116 -0.3627170 0.8662826 0.3377249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6616 6617 -0.741487 0.203332 0.790940 0.9422087 0.0082542 0.2586341 0.2127980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6617 6618 -0.284804 0.341248 -0.774912 0.1481770 -0.9431824 -0.2588181 0.1465053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6618 6619 0.044116 -0.151831 1.019882 -0.2003034 -0.4927129 0.4168349 0.7371304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6619 6620 0.771653 0.126654 -0.626787 -0.5668238 -0.2482492 -0.5770165 0.5330432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6620 6621 -0.697281 -0.670003 0.446942 -0.1867243 -0.3655575 0.6294567 0.6597621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6621 6622 -0.373816 0.265091 0.979047 0.6441122 0.0443466 -0.2327023 0.7273256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6622 6623 -0.745033 0.703598 -0.073449 -0.4206561 0.2871611 0.8061983 0.3010503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6623 6624 0.598421 0.060144 0.729305 -0.5068724 -0.4037376 0.2784466 0.7089032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6624 6625 0.942982 -0.716471 -0.441286 0.0534124 -0.6380294 -0.1317387 0.7567764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6625 6626 0.039902 -0.699565 -0.761675 0.2493118 0.0322163 -0.2292060 0.9403565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6626 6627 0.451431 -0.962172 -0.206408 -0.6909682 0.4301853 -0.5741263 0.0887839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6627 6628 0.530418 0.317812 0.659913 0.7447038 -0.0151861 -0.1027417 0.6592646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6628 6629 0.287080 0.672566 -0.561700 -0.3188467 -0.3761426 -0.6413416 0.5878219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6629 6630 -1.008080 -0.117127 0.237712 0.5682059 0.0184099 0.7663753 0.2991187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6630 6631 0.509396 0.456104 -0.694788 0.4663706 0.4252879 0.1394675 0.7630056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6631 6632 0.955981 -0.332887 -0.008667 -0.3810160 0.2989728 -0.0969351 0.8695089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6632 6633 0.861872 -0.218912 0.393303 -0.1745039 -0.0303581 -0.6255548 0.7598079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6633 6634 0.649196 0.677100 0.490404 0.1043161 0.3533275 -0.1669068 0.9145600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6634 6635 -0.067610 0.938083 0.654398 -0.0834512 0.3354139 -0.8179185 0.4599378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6635 6636 -0.725518 -0.629627 0.109951 -0.0743240 -0.1845598 -0.1190137 0.9727535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6636 6637 -0.630654 -0.499261 0.173064 -0.4439701 0.1026607 -0.0455349 0.8889758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6637 6638 -0.548932 -0.716382 -0.506782 -0.2398404 0.8239087 -0.4133610 0.3046042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6638 6639 0.970238 0.347871 0.200486 -0.2536090 -0.1410335 -0.8446368 0.4498675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6639 6640 -0.148645 0.494393 -0.969429 0.7794585 0.0010022 0.6246583 0.0473864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6640 6641 -0.384596 0.482624 0.497090 -0.1410453 0.8625332 -0.4857201 0.0147858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6641 6642 0.409612 -0.365798 -0.998460 -0.1096739 -0.6987945 0.6820199 0.1857598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6642 6643 -0.634329 0.883416 0.045597 0.5028262 0.1089937 -0.8461237 0.1391434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6643 6644 0.061277 -0.760944 0.127513 0.0196849 -0.4398981 -0.3799120 0.8134919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6644 6645 0.858540 -0.473952 -0.374827 0.5251121 -0.2784355 -0.6688317 0.4465368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6645 6646 0.544115 0.437029 -0.958701 -0.8238975 -0.3205133 0.2507956 0.3944181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6646 6647 0.649842 0.565199 0.282076 0.5868801 0.1332439 -0.4726935 0.6437225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6647 6648 -0.220173 0.598790 -0.803090 0.0733755 -0.4639591 -0.7886479 0.3967273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6648 6649 -0.266268 -0.888079 0.002848 -0.2251183 -0.5224143 -0.5854038 0.5776742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6649 6650 0.564934 -0.379719 -0.693784 -0.2274413 -0.1277508 -0.4669420 0.8449351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6650 6651 0.312502 0.530381 -0.701615 0.0804224 0.8588819 0.4431738 0.2438259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6651 6652 0.251828 -0.350392 0.650597 -0.6026575 0.3086218 0.1626531 0.7177051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6652 6653 -0.265917 -1.018255 -0.091607 0.0075137 -0.8633038 -0.0397981 0.5030569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6653 6654 0.253485 -1.150474 0.558419 -0.7179287 0.0169298 -0.2185688 0.6606962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6654 6655 0.306437 -0.053566 -0.957674 -0.4620831 0.5454474 0.3878284 0.5818552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6655 6656 1.070819 -0.343501 -0.115031 0.1033989 0.2938211 -0.7236174 0.6159185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6656 6657 0.189802 1.143208 0.118129 -0.3897714 -0.0123676 -0.7228640 0.5704323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6657 6658 -0.786100 -0.187272 0.459735 0.0445388 -0.1650113 -0.6694394 0.7229373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6658 6659 0.381596 -0.521586 0.634739 -0.3359180 -0.2790785 0.8049230 0.4017129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6659 6660 0.082559 -0.722489 -0.850098 -0.1243007 -0.3857615 0.5776543 0.7085569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6660 6661 0.315839 -0.286757 -0.742231 0.1668411 0.2624756 -0.9180912 0.2457218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6661 6662 0.249143 1.044750 -0.569470 0.1773625 0.5957531 0.4334763 0.6524715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6662 6663 0.991832 0.168990 0.128418 0.2136843 -0.0127429 0.9515023 0.2209525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6663 6664 -0.663117 -0.285888 0.598413 -0.0167741 0.1731212 -0.4050686 0.8975896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6664 6665 -0.213296 -1.135774 0.390161 -0.5304757 0.3681121 0.4750031 0.5978805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6665 6666 -0.538414 0.029271 -1.013812 -0.0867582 0.0903413 0.9800986 0.1540071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6666 6667 0.683047 -0.018231 -0.830374 -0.1898655 -0.0958163 -0.1991564 0.9566123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6667 6668 0.222030 0.552148 -0.957214 -0.1667587 0.0442981 0.6364914 0.7517366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6668 6669 0.938485 0.025571 -0.469746 0.2429976 0.4537716 -0.2232776 0.8277624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6669 6670 0.825933 0.323260 0.288771 0.3052215 -0.8360026 -0.3676188 0.2698071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6670 6671 -0.688434 0.084633 -0.636388 -0.1382593 0.2887099 0.8524965 0.4132561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6671 6672 0.971033 0.452561 -0.372361 0.2368953 0.0183273 -0.3962799 0.8868523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6672 6673 0.392288 0.711811 -0.504376 0.3086367 -0.0901425 -0.3731021 0.8702945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6673 6674 -0.219344 0.148264 -1.034097 0.4209585 0.8849577 0.1953955 0.0382673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6674 6675 0.251252 -0.289959 0.814524 -0.0448170 0.9667031 0.1312378 0.2150656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6675 6676 -0.616324 0.003131 -0.837864 -0.5465419 0.6571113 0.3050079 0.4200796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6676 6677 1.004362 0.459246 0.177580 -0.3529340 -0.5703766 -0.0081466 0.7416480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6677 6678 0.431276 0.766280 -0.380304 0.4915205 -0.2380134 -0.7806017 0.3040036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6678 6679 -0.430176 -0.630005 -0.636397 -0.2451239 -0.3639334 -0.1115653 0.8916389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6679 6680 -0.492109 0.677688 -0.066070 0.5716316 0.0695209 -0.2142723 0.7889814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6680 6681 0.393803 0.722010 -0.481135 -0.1569542 0.0589892 0.5452024 0.8213647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6681 6682 0.935803 0.011259 -0.230032 -0.7571899 0.3721396 0.4132832 0.3425968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6682 6683 0.639307 -0.699208 -0.074578 -0.8361604 0.0551510 0.5180850 0.1714120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6683 6684 0.312472 0.649201 -0.779405 0.3930351 0.0454385 -0.8059597 0.4403268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6684 6685 0.045290 -0.321046 -0.835273 0.3911641 -0.2258152 0.8817581 0.1360175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6685 6686 -0.624277 0.604120 -0.470628 -0.4609757 -0.3344737 -0.7291287 0.3794734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6686 6687 -0.432100 -1.109199 0.058257 -0.1198702 -0.3641823 0.4013899 0.8317984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6687 6688 -0.965128 -0.417495 0.469170 -0.2092943 0.3170611 -0.5611094 0.7354077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6688 6689 0.273879 -0.987217 -0.181130 -0.0271188 0.5179445 0.3465031 0.7816225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6689 6690 -0.142843 -0.849523 -0.255202 0.1245015 -0.5964393 0.1655141 0.7754770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6690 6691 -0.474939 -0.658418 0.369066 0.4241197 -0.3255080 -0.5740778 0.6201626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6691 6692 0.570435 0.305929 0.915459 -0.1144538 -0.4071110 -0.5124562 0.7473618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6692 6693 0.374626 0.918351 0.384192 0.1340331 0.3700775 -0.4355414 0.8095563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6693 6694 -0.539347 0.712633 -0.175437 0.5776398 -0.7251700 0.1772256 0.3302298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6694 6695 -0.507463 0.550900 -0.492666 -0.6090524 -0.1464118 0.1014786 0.7728653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6695 6696 -0.223587 0.569071 0.773824 0.8053428 0.1848280 -0.0807879 0.5574360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6696 6697 -0.347294 0.444858 -0.766160 -0.6710022 -0.7284068 -0.1185344 0.0716182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6697 6698 0.164135 -0.448561 0.703810 -0.5795696 0.5223186 0.1547973 0.6060694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6698 6699 -0.441467 -0.689356 -0.387220 0.6352025 -0.1141435 -0.6164391 0.4511007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6699 6700 0.595241 0.496492 -0.754901 0.2064672 -0.6418624 -0.6108827 0.4149774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6700 6701 0.168205 -0.735361 0.580338 -0.1747927 0.0590956 -0.7958783 0.5766568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6701 6702 0.746020 0.155785 0.338323 -0.0239727 0.7468094 -0.4037480 0.5279097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6702 6703 -0.982806 0.206836 0.312102 0.9088787 -0.3641296 0.1236751 0.1614113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6703 6704 -0.606655 0.725557 -0.511695 -0.6396751 0.4950420 -0.4343526 0.3963420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6704 6705 -0.905766 0.524655 -0.443763 -0.4498080 -0.4151066 0.7237338 0.3186985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6705 6706 0.556787 0.252960 0.561383 0.0312887 -0.8153943 0.5634104 0.1293132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6706 6707 -0.453374 -0.560451 -0.787576 -0.0581396 -0.6155117 0.6463444 0.4472182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6707 6708 -0.377749 0.656755 0.765323 0.6960371 -0.4730453 -0.3598165 0.4028555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6708 6709 -0.845053 0.510183 -0.206314 0.1714669 -0.7946758 -0.5796941 0.0551737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6709 6710 0.608226 0.206697 0.909414 -0.5885317 0.0984793 0.7996613 0.0668892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6710 6711 -1.046039 -0.142359 -0.176848 0.4728855 -0.3944560 -0.2229046 0.7557098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6711 6712 -0.619767 -0.252789 0.707392 -0.2839367 0.2384922 0.0809687 0.9251732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6712 6713 -0.718830 -0.527465 0.136843 0.4857193 0.2746377 0.3452813 0.7546070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6713 6714 -0.832734 0.415351 -0.304353 0.3286682 -0.2417360 -0.3991549 0.8211067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6714 6715 -0.900720 -0.641527 0.037869 -0.0583366 -0.8446044 -0.0017263 0.5322004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6715 6716 0.379566 -0.419031 0.665297 -0.0578516 0.5967504 0.7624843 0.2432277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6716 6717 -0.698985 0.567844 -0.518793 -0.1265924 0.4541221 0.4016880 0.7851078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6717 6718 0.304492 0.901398 -0.311191 -0.5519454 -0.1819682 0.8125323 0.0451126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6718 6719 0.514898 -0.474627 -0.758664 0.0230843 -0.6201588 0.7726360 0.1338049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6719 6720 0.439268 0.601967 0.662134 -0.2615182 0.0338992 0.4785860 0.8375049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6720 6721 -0.022003 -0.627011 -0.717961 0.2512899 -0.5295257 -0.1920421 0.7871313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6721 6722 -0.040627 -0.851734 -0.063272 0.4078668 -0.5660683 0.7163871 0.0009332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6722 6723 0.365486 0.602091 0.916912 0.6068131 -0.2028937 0.5371461 0.5496236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6723 6724 1.012809 -0.060664 -0.016853 -0.2641899 0.7284399 0.5345497 0.3373954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6724 6725 -0.419886 -0.773856 0.150027 0.3895243 -0.6347697 -0.1295289 0.6546454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6725 6726 0.624186 -0.217517 0.679362 -0.4720508 -0.2748252 -0.3776368 0.7476829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6726 6727 1.070733 0.066432 -0.165972 -0.3421455 -0.5212573 0.4819292 0.6156066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6727 6728 -0.033142 -0.374552 -1.034439 0.7473669 -0.0516029 0.3404574 0.5682153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6728 6729 -0.490482 -0.832228 0.170843 -0.6892472 0.4484350 0.5561860 0.1204224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6729 6730 0.133928 0.889808 -0.279019 0.1357895 0.0266888 -0.9449729 0.2964374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6730 6731 -0.501771 -0.770155 -0.336954 0.5782351 -0.2622218 0.3640265 0.6814459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6731 6732 -0.889271 0.274096 0.554311 -0.2916774 -0.3335100 0.8909795 0.0992518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6732 6733 0.388499 -0.285210 0.693430 -0.0722285 -0.7779515 0.1735155 0.5995556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6733 6734 0.425818 -0.815986 -0.586242 -0.4366339 0.1279334 -0.0347945 0.8898164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6734 6735 0.437831 0.061228 -0.929592 0.7791672 0.0484664 0.3715500 0.5024938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6735 6736 -0.051875 -0.904369 0.749180 0.1896624 0.6439068 0.6824428 0.2892820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6736 6737 -0.518796 0.605899 -0.371364 -0.1871836 0.1296399 0.6327520 0.7401221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6737 6738 0.794502 0.426117 0.080565 0.7886745 0.0391038 0.4328260 0.4348851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6738 6739 0.559065 -0.561234 0.299290 -0.1953246 -0.3495790 -0.0094699 0.9162713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6739 6740 -0.016808 0.765499 -0.717287 -0.6527194 -0.0355360 -0.3098997 0.6904033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6740 6741 -0.284465 -0.745577 0.443793 0.4237655 -0.2037156 0.8825653 0.0011114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6741 6742 0.765328 0.711348 0.376437 0.0918971 -0.0736787 0.7517774 0.6488121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6742 6743 0.805949 -0.658310 0.076304 0.5128950 0.3655341 -0.0335894 0.7760124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6743 6744 0.281683 0.112124 0.965028 0.5735228 -0.6961823 -0.0526912 0.4285153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6744 6745 0.271410 0.401205 -0.741930 0.1202393 -0.5249449 -0.4472366 0.7141112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6745 6746 -0.821141 0.303577 -0.529703 -0.3888094 -0.0299384 -0.1983385 0.8992178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6746 6747 -0.970268 0.005348 -0.276985 0.3860487 0.1443800 -0.7087260 0.5725629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6747 6748 0.292519 -0.990714 -0.060402 -0.4298043 -0.2494972 0.8619419 0.1003775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6748 6749 -0.480315 0.693369 0.130147 -0.2142755 -0.2152414 0.2070250 0.9299988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6749 6750 0.089042 0.775511 0.689876 -0.4811597 -0.3749326 0.2620217 0.7478339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6750 6751 0.847248 -0.177937 0.679903 0.2304813 -0.2045786 0.6431714 0.7009683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6751 6752 0.447644 -0.880701 0.539277 0.6292698 -0.6283287 -0.3411975 0.3046422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6752 6753 0.639166 0.315690 -0.583085 0.1258087 0.2852670 0.9401913 0.1372412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6753 6754 -0.597766 -0.600869 0.269712 0.5824188 0.5055511 0.2529768 0.5841311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6754 6755 -0.760262 -0.227910 -0.454577 -0.4749754 0.5949233 0.6481015 0.0207115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6755 6756 0.733686 0.137149 0.237312 0.0903646 0.6491809 0.4132641 0.6321481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6756 6757 -0.070529 0.117106 1.039110 0.6255666 0.3620337 0.6889896 0.0537707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6757 6758 0.819310 0.452313 -0.311382 0.8287653 0.3708418 -0.1118753 0.4038667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6758 6759 1.044236 0.126729 -0.117997 -0.8918762 0.4113972 -0.0311010 0.1853157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6759 6760 -0.020182 -0.263883 -1.023842 -0.3487434 -0.7252167 0.5935883 0.0095741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6760 6761 0.753054 0.112841 -0.333119 -0.3894348 -0.2887475 0.3680240 0.7934253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6761 6762 0.298211 -0.135288 -0.906150 0.0159474 0.3004807 -0.9111940 0.2813940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6762 6763 -0.129177 0.850388 -0.502686 0.0523549 -0.5870490 -0.6491515 0.4808687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6763 6764 -0.688915 -0.420740 0.475200 -0.3714400 -0.7405755 0.1571003 0.5374940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6764 6765 0.360529 -0.963530 0.403596 0.2736000 -0.1568435 0.5852915 0.7469786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6765 6766 -0.484503 -0.005690 0.770501 0.9417545 0.1247853 0.1304387 0.2837479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6766 6767 -0.406528 0.521829 -0.715996 0.2202101 0.5089526 0.2726831 0.7862053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6767 6768 0.781253 0.014642 -0.486993 0.0136984 0.4928816 -0.8334888 0.2493521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6768 6769 -0.479508 0.741798 -0.282692 0.3909874 -0.4177738 0.8052060 0.1556831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6769 6770 0.113702 -0.051859 -0.969242 -0.6036398 0.1753451 -0.2791608 0.7259080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6770 6771 0.218308 1.056236 -0.179605 -0.0721064 0.4681656 0.6083857 0.6367798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6771 6772 0.845769 0.001639 0.515060 -0.7691985 -0.4097725 -0.0864750 0.4826410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6772 6773 0.730789 0.319564 -0.671803 0.0575363 0.2853461 -0.5027321 0.8139580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6773 6774 0.371730 0.763340 -0.122673 0.5498258 0.3928652 0.3014067 0.6726831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6774 6775 0.756454 0.121524 -0.081931 -0.0519130 -0.4428739 0.1210968 0.8868502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6775 6776 0.303063 0.075191 -0.777661 -0.4004055 0.2919704 -0.6168549 0.6114889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6776 6777 -0.030931 0.861581 -0.035588 0.0282387 -0.4961386 -0.7598125 0.4192064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6777 6778 -0.637844 -0.251971 0.747360 -0.3625347 0.1965071 0.2460597 0.8771592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6778 6779 -0.930010 -0.072302 0.202486 0.3990374 0.1295974 0.1900441 0.8876130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6779 6780 -0.304640 -0.681933 0.693472 -0.1990980 -0.4519146 0.5592897 0.6658290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6780 6781 -0.396852 -0.805187 -0.722629 0.3944575 -0.1737143 0.8808432 0.1958108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6781 6782 -0.437522 0.819385 -0.181277 -0.0536771 -0.0511189 0.0090959 0.9972075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6782 6783 -0.341700 0.606585 0.122891 0.1605475 -0.7195552 -0.4086161 0.5380499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6783 6784 -0.552939 0.448505 0.647669 -0.1190043 -0.5985415 -0.7357941 0.2935867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6784 6785 0.460965 0.143916 0.827304 -0.8523226 -0.2921167 0.4304745 0.0539047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6785 6786 -0.140649 -0.203390 -1.024330 -0.5779567 0.2548055 -0.7718868 0.0723251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6786 6787 -0.722320 0.676935 -0.284207 -0.4213972 0.3396209 0.8114445 0.2205444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6787 6788 0.703706 0.082295 0.775254 0.4716708 0.4539827 -0.4076516 0.6365898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6788 6789 -0.723245 0.913629 0.207025 0.2112359 0.1696125 -0.6436782 0.7157440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6789 6790 -0.886854 -0.447169 -0.112714 0.0326046 -0.2881335 0.9524862 0.0931995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6790 6791 0.771595 0.550082 0.121855 -0.2598756 0.1137110 0.6567859 0.6986893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6791 6792 0.716086 -0.657552 0.632895 -0.1327629 -0.7776874 -0.2265130 0.5711990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6792 6793 0.154465 -0.198030 -1.025398 -0.6183788 0.1581537 -0.6648993 0.3879484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6793 6794 -0.426719 0.992368 -0.117835 -0.0334246 -0.0889110 -0.8947402 0.4363686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6794 6795 -0.456642 -1.046259 0.268336 -0.1090556 0.5545911 0.7739596 0.2855207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6795 6796 0.099897 0.465107 -0.772570 0.0774876 0.0467560 0.2615457 0.9609388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6796 6797 0.297079 0.282051 -0.951503 -0.8242627 -0.4042147 -0.3955037 0.0278971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6797 6798 -0.344229 -0.434636 0.774646 -0.2780408 0.0748510 -0.8290847 0.4792798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6798 6799 0.872702 -0.484116 0.577834 0.7085294 0.2685280 -0.6335713 0.1564167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6799 6800 9.943976 -14.695859 6.991434 0.4795910 -0.4382081 -0.2620267 0.7136583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6800 6801 -0.944746 0.122568 -0.129568 -0.1330393 -0.5620218 -0.7365089 0.3521175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6801 6802 0.779013 -0.477155 0.203264 0.1541408 -0.1835852 0.9570845 0.1628691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6802 6803 -0.623436 0.380809 0.718260 -0.1210923 -0.4018873 0.1230723 0.8992644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6803 6804 0.120485 0.270857 1.001655 -0.0364406 0.8613243 -0.3915758 0.3216534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6804 6805 -0.787703 -0.312815 -0.398674 -0.3437814 0.6772287 -0.6402757 0.1149895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6805 6806 0.551001 0.932579 0.119010 -0.1938488 0.2693351 -0.3562363 0.8734855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6806 6807 -0.199974 0.881681 0.417787 0.2591113 0.1607466 -0.1675587 0.9375212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6807 6808 -0.602890 0.701127 -0.049973 0.4198694 -0.1871329 -0.2478975 0.8527824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6808 6809 -0.925332 0.154103 -0.443813 -0.8502200 -0.4067498 -0.0259482 0.3331776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6809 6810 -0.482786 -0.738943 0.451609 -0.0407778 0.2240312 -0.8123995 0.5368001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6810 6811 0.862396 -0.599873 0.680740 0.4047849 0.4983943 0.6251810 0.4437352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6811 6812 -0.626695 0.395628 0.515640 -0.4397052 -0.1461865 -0.0596878 0.8841528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6812 6813 -0.359584 -0.497745 0.831357 0.3294335 0.5496055 0.6890847 0.3384814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6813 6814 -0.169914 0.845917 -0.414874 -0.0216094 0.0737375 -0.0618045 0.9951261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6814 6815 -0.031756 0.987554 -0.598064 0.3027367 -0.0716059 -0.6093495 0.7293259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6815 6816 -0.851787 -0.223914 -0.728451 0.1443488 -0.5463357 -0.4135234 0.7139181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6816 6817 -0.298192 -0.860421 0.382167 -0.1771415 0.5334560 -0.6775503 0.4743113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6817 6818 0.853281 -0.534108 0.263336 -0.2712175 0.1009128 0.8674800 0.4046432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6818 6819 -0.901142 -0.228440 -0.329735 0.2118304 0.3111180 0.9134265 0.1548727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6819 6820 -0.179600 1.044475 0.442863 -0.1852220 0.1588726 0.0827660 0.9662309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6820 6821 -0.952902 -0.304766 0.353715 0.8017111 0.2061169 0.3789451 0.4137338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6821 6822 -0.524988 0.653511 -0.874171 0.1256497 0.5963510 0.5841095 0.5360911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6822 6823 1.044833 -0.219959 -0.320741 -0.0576318 0.2771888 0.7572635 0.5885549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6823 6824 -0.142114 -0.879621 -0.018681 -0.0808671 -0.0899365 -0.8581964 0.4988696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6824 6825 0.978453 0.255584 -0.544156 -0.0579433 -0.0094393 -0.1173098 0.9913586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6825 6826 0.835787 0.368398 -0.283036 0.2436472 0.4325876 -0.8222939 0.2780947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6826 6827 -0.685058 0.323705 -0.636812 0.7789120 0.0902302 -0.2853105 0.5511374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6827 6828 -0.229386 -1.053636 0.011116 0.1353276 0.2093319 -0.8436324 0.4755533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6828 6829 0.742626 0.358139 0.158291 0.0924595 0.0353838 0.7865536 0.6095348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6829 6830 -0.075966 -0.928914 0.432456 0.3323957 -0.5170527 -0.2929909 0.7323427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6830 6831 0.818789 -0.310040 0.410131 -0.1772919 0.7055181 0.4948517 0.4753248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6831 6832 -0.724665 -0.602580 0.151725 -0.1782165 0.3303008 0.8296354 0.4133344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6832 6833 -0.061259 0.884662 -0.196283 -0.6343356 0.4363257 -0.3658279 0.5228845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6833 6834 -0.947730 0.184168 0.323059 0.7039456 0.0362556 0.4258196 0.5672952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6834 6835 -0.359539 0.610562 -0.833084 -0.6332249 -0.1696144 -0.1607893 0.7378374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6835 6836 -0.533305 0.525753 0.383277 0.6942087 -0.1084326 0.3037299 0.6434787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6836 6837 0.047338 0.557832 -0.901344 0.0808861 -0.7896270 -0.5239447 0.3089152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6837 6838 -0.506183 -0.477274 0.831109 -0.0804402 -0.9464926 -0.2454002 0.1935454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6838 6839 0.690597 -0.370364 -0.592386 -0.7443851 -0.5190073 -0.4199885 0.0114821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6839 6840 0.177467 0.877774 -0.369342 0.4597939 0.6158997 -0.4835994 0.4187944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6840 6841 0.445671 0.547237 0.604057 -0.7093149 0.6616419 0.2152576 0.1129890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6841 6842 -0.644487 -0.441178 -0.525036 -0.2825599 0.0136504 0.6810860 0.6753484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6842 6843 -0.117396 0.624257 -0.175361 0.1490084 -0.0060256 -0.9535620 0.2616865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6843 6844 -0.211829 -1.019435 -0.322362 0.1048673 0.2212020 -0.8337025 0.4949875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6844 6845 0.769413 0.604790 0.037803 -0.3684058 0.5260821 -0.1268249 0.7559300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6845 6846 0.019503 0.088310 1.067034 0.9017170 -0.3753541 -0.0122082 0.2141650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6846 6847 0.397676 0.440548 -1.063005 0.2477802 0.3087711 -0.4416102 0.8051371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6847 6848 0.406144 0.158940 -0.841725 -0.7849525 -0.3282025 -0.1024752 0.5153946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6848 6849 0.220448 1.037416 0.103674 0.3124324 -0.0642256 -0.1035514 0.9420924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6849 6850 0.042243 1.060429 -0.383199 -0.4716768 0.1480727 0.3040175 0.8143518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6850 6851 0.537978 0.584494 0.741576 -0.2855789 0.1817733 -0.9364406 0.0920984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6851 6852 -0.314782 -0.690416 0.729054 -0.1233926 -0.0674926 -0.8389064 0.5257900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6852 6853 1.035188 0.010280 0.287926 -0.5123143 0.0242368 0.1079765 0.8516383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6853 6854 0.708870 -0.424708 0.205991 -0.4765419 0.2243042 0.8458805 0.0841528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6854 6855 -0.571546 0.102492 -0.748680 -0.8598390 -0.2911997 0.3034082 0.2895223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6855 6856 -0.084229 0.178505 0.947222 0.5952919 0.7109761 -0.0954154 0.3619896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6856 6857 -0.381624 0.621448 -0.693922 0.1219168 0.2686194 -0.4809022 0.8256591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6857 6858 0.009345 -0.210871 -0.919665 -0.3870964 -0.3551082 0.6474065 0.5521951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6858 6859 -0.057478 1.018553 -0.408469 -0.0162624 -0.6013522 -0.5705731 0.5590683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6859 6860 0.038324 -0.962622 0.088876 0.5134414 0.2761896 -0.0824024 0.8082741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6860 6861 1.038120 0.224207 0.100074 -0.5103708 -0.3748218 0.5789378 0.5136743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6861 6862 0.127778 -0.340971 -1.104441 -0.4369332 0.6390444 -0.3427009 0.5322291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6862 6863 0.596046 0.718857 0.270271 0.0529156 0.2298972 0.6937357 0.6804984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6863 6864 0.472900 -0.511835 0.734537 -0.2219756 -0.5113151 0.7486244 0.3589502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6864 6865 -0.754847 -0.432745 0.240811 0.3860958 0.3447622 -0.4839474 0.7055948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6865 6866 -0.086917 -0.763552 0.608015 0.6541755 0.1405586 -0.7128395 0.2101369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6866 6867 -0.511089 0.814333 0.411874 -0.0921550 -0.2047515 0.9540304 0.1985203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6867 6868 0.767375 -0.449743 0.248218 -0.0918744 -0.3613896 -0.0948341 0.9230185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6868 6869 0.823928 -0.343531 -0.233992 -0.1729400 0.7971656 -0.0696844 0.5742498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6869 6870 0.187011 -0.365571 0.875597 0.2142681 -0.2769312 -0.5606251 0.7503985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6870 6871 0.878095 0.555431 0.440381 0.5010359 -0.0074613 -0.1739935 0.8477226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6871 6872 0.519679 0.535711 -0.541076 -0.0897188 0.6051451 0.5551683 0.5635052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6872 6873 0.312733 -0.210727 0.940454 -0.3465185 0.6357574 0.6823924 0.1003898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6873 6874 -0.688201 0.244076 -0.516746 0.0611783 0.2446568 -0.7102516 0.6572237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6874 6875 0.024312 -0.605392 -0.808536 -0.5377027 -0.6636012 0.5181286 0.0452992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6875 6876 -0.017805 0.899812 0.670993 -0.0511784 -0.9191216 0.3894767 0.0300700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6876 6877 0.158271 -0.013112 -0.919046 0.0754258 -0.3035116 0.9478950 0.0607185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6877 6878 -0.319543 0.572093 -0.670744 -0.5329676 -0.3338071 0.3521560 0.6931843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6878 6879 0.323683 0.897754 0.407616 -0.2091013 -0.3507359 0.6518190 0.6390563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6879 6880 -0.179181 -0.429045 -0.770828 0.0172855 -0.4453961 0.4599339 0.7679742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6880 6881 0.325657 0.807432 0.646818 0.0648545 -0.2498349 -0.4025752 0.8782424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6881 6882 -0.274022 0.910811 0.255343 0.2399463 -0.2368037 -0.8163693 0.4689253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6882 6883 -0.771460 -0.373094 0.414939 -0.7524174 -0.3467255 0.0061005 0.5600109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6883 6884 -0.357154 -0.839886 -0.079737 -0.4694196 -0.3108375 -0.7127296 0.4183801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6884 6885 0.101222 -0.165759 -1.061993 -0.2918118 0.7591864 0.4381637 0.3827460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6885 6886 0.691342 -0.558647 0.365708 0.1790001 -0.7225581 -0.4658693 0.4783665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6886 6887 0.403002 0.127399 -1.030123 -0.3039579 0.2884975 0.0826613 0.9041824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6887 6888 0.833741 0.579667 -0.231288 -0.5258066 0.0960918 0.4319509 0.7264380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6888 6889 1.069282 -0.297892 0.066802 0.4258020 0.6476028 -0.6274609 0.0748076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6889 6890 -0.832299 0.624056 -0.048081 -0.6867928 -0.4908290 0.4933327 0.2098223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6890 6891 0.573945 -0.299564 0.528262 0.1445928 0.9883095 -0.0483057 0.0019336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6891 6892 -0.936611 -0.206178 -0.451069 0.2286313 0.8521715 0.1647569 0.4408929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6892 6893 0.494055 -0.656201 -0.349168 0.5189681 0.3807809 -0.1369814 0.7529370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6893 6894 0.574196 -0.185741 0.864015 0.1342093 0.1117892 -0.9294591 0.3249565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6894 6895 -0.515677 0.570221 0.572440 0.3076227 0.3774024 0.8571561 0.1679855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6895 6896 1.134498 0.034752 0.230677 -0.1433773 -0.8635820 -0.2244896 0.4281047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6896 6897 -0.373049 0.654987 -0.599937 0.7455455 0.1099505 0.6468022 0.1171312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6897 6898 -0.491828 -0.779342 -0.601260 0.5680347 -0.3187534 -0.1895753 0.7347068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6898 6899 0.111041 -0.575895 0.935379 -0.0767631 0.6346517 0.7365943 0.2208020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6899 6900 -0.422110 -0.635055 -0.639044 0.4528846 -0.1584008 0.4739081 0.7383873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6900 6901 0.102523 -0.270447 0.965792 0.6009322 0.1775523 0.7528310 0.2014970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6901 6902 0.678212 0.827254 0.327751 -0.1799634 0.8343150 -0.2449509 0.4599246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6902 6903 -0.728306 0.302787 0.430776 -0.0504108 0.3360694 -0.2506663 0.9064670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6903 6904 -0.964092 -0.084399 -0.346523 0.0546608 -0.0183584 0.9954912 0.0753151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6904 6905 0.998078 0.128708 -0.546584 0.3005234 0.2578345 0.6001701 0.6949841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6905 6906 0.108880 -0.894462 0.297812 -0.6390188 0.0736023 -0.6558815 0.3950407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6906 6907 0.869494 0.378765 0.098690 -0.2420541 0.3004290 0.6764636 0.6273350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6907 6908 0.131017 -0.896478 0.367292 0.7267020 -0.2700028 -0.1756066 0.6067661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6908 6909 0.802483 0.379977 0.395391 -0.5697606 -0.3603270 0.6823997 0.2826091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6909 6910 -0.176544 -0.737458 -0.640194 0.0874391 0.8360149 -0.2187090 0.4955804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6910 6911 0.738049 -0.411005 0.429333 0.2064623 0.2200672 -0.6173050 0.7265523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6911 6912 0.321332 0.640791 0.744042 0.5344392 0.4587787 0.5823518 0.4059104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6912 6913 1.001620 0.484048 0.251982 -0.0840073 0.4931027 0.8312634 0.2424740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6913 6914 -0.522039 -0.399511 0.581773 -0.2584282 0.1507118 0.4497775 0.8415468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6914 6915 -0.845038 0.161984 0.373252 0.8277983 0.3618789 -0.1807843 0.3887295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6915 6916 -0.760127 -0.719848 -0.342129 -0.2356505 -0.6791452 -0.6235153 0.3073421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6916 6917 0.307489 -0.764440 -0.459627 0.4938699 0.4919185 -0.1436155 0.7024836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6917 6918 0.394528 -0.514028 0.876958 -0.0911297 -0.3917755 0.4560516 0.7938666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6918 6919 0.330899 -1.063168 0.113778 -0.1092388 0.5029198 0.6040755 0.6084664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6919 6920 -0.349438 0.912675 0.186677 0.3795021 -0.6532699 -0.3642714 0.5445392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6920 6921 -0.278328 0.530135 -0.734172 0.7461092 0.1597081 0.5218838 0.3813813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6921 6922 -0.410873 -0.954931 -0.436674 -0.0494233 -0.3985932 0.8643387 0.3026539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6922 6923 -0.227718 0.845410 0.512999 0.8561648 -0.0241641 -0.4141898 0.3079687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6923 6924 -0.791407 -0.458075 -0.535757 -0.2424139 -0.5130356 0.6845319 0.4576527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6924 6925 -0.199052 0.540603 0.528589 0.3544060 0.7411334 -0.3157686 0.4747713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6925 6926 -0.543061 0.424703 -1.213370 -0.2775356 -0.2257391 0.8999986 0.2490350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6926 6927 0.646632 0.288214 -0.333328 -0.6764801 -0.2453432 -0.6924222 0.0522766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6927 6928 -0.256407 -0.161164 0.857233 -0.1418520 0.0665111 -0.7938980 0.5875205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6928 6929 0.299067 -0.317690 0.517838 0.1072220 0.1635569 -0.4635351 0.8642267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6929 6930 0.452577 -0.093869 0.895633 0.2295517 0.6124920 -0.6887495 0.3127039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6930 6931 -1.065055 -0.326957 0.006562 0.4683863 -0.3954418 0.0391589 0.7891177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6931 6932 -0.408564 0.305800 0.938187 -0.1329317 0.4612140 0.1917791 0.8560559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6932 6933 -0.734407 0.242319 0.376610 0.1153838 0.1993928 -0.9718604 0.0491571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6933 6934 0.718629 -0.479444 0.416125 0.1695752 -0.7718406 -0.4840522 0.3757657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6934 6935 -0.070968 0.241921 -0.991430 -0.2223931 -0.2884983 0.1633440 0.9168581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6935 6936 -0.438373 0.578909 -0.661965 -0.1332737 0.4945794 -0.1113814 0.8516006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6936 6937 0.075010 0.683488 -0.874572 -0.5290917 -0.2741004 -0.0917165 0.7978214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6937 6938 -0.164090 1.023918 0.455119 0.3205022 0.1963035 0.2818841 0.8827710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6938 6939 0.339302 1.020378 0.072661 -0.1963902 -0.2738858 0.1018753 0.9359695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6939 6940 -0.822607 0.367205 0.535407 -0.1858542 0.3365255 -0.7805615 0.4928819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6940 6941 0.961405 -0.040621 -0.209686 0.2728624 0.3058276 -0.8208422 0.3977860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6941 6942 -0.555165 0.833035 -0.163668 -0.5649363 0.1099011 -0.1164629 0.8094474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6942 6943 -0.741728 0.468151 0.397884 0.4799783 -0.4141471 -0.2220225 0.7408164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6943 6944 -0.569435 0.695374 0.371927 0.5566881 0.5377467 0.3069414 0.5538175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6944 6945 0.444113 0.262692 -0.947040 -0.0915887 0.4544596 0.8177524 0.3411144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6945 6946 0.152545 -1.055961 -0.110032 -0.2963757 0.3824088 -0.8533207 0.1943419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6946 6947 0.426079 0.593941 0.355601 -0.6369631 -0.5148982 0.5734067 0.0190415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6947 6948 -0.179967 -0.237513 -1.161401 0.0856142 0.0677381 -0.9837191 0.1427535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6948 6949 0.233535 0.286943 -0.716928 0.4303464 -0.4696172 0.7570549 0.1453603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6949 6950 -0.907883 0.127680 -0.421737 0.0378528 -0.2331206 -0.3780211 0.8951659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6950 6951 -0.739236 -0.695710 -0.165232 0.6284522 0.5385281 0.1657224 0.5362568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6951 6952 -0.803249 -0.442391 -0.192519 -0.4781196 -0.2014054 -0.6634912 0.5390889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6952 6953 -0.099752 -0.713459 -0.873562 0.3313330 0.3986282 0.8516100 0.0779391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6953 6954 -0.589087 -0.137584 -0.871010 -0.9260519 -0.0261395 0.3311662 0.1790907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6954 6955 0.090759 0.423455 0.746712 0.1249403 0.9014725 -0.3019847 0.2838002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6955 6956 -0.414202 -0.198663 -0.828896 0.3141854 0.5641983 0.1781270 0.7424545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6956 6957 0.463903 -0.611691 -0.497580 -0.5441395 -0.4202284 0.6494891 0.3247832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6957 6958 -0.415889 0.912574 -0.343034 -0.3627967 0.1255507 -0.9033574 0.1912094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6958 6959 -0.081309 -0.934190 -0.516191 -0.6097115 0.3063525 -0.7257692 0.0875162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6959 6960 0.907694 -0.114104 -0.317587 0.3639330 -0.1167288 -0.9184874 0.1015288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6960 6961 0.343294 0.953447 -0.364684 0.2680225 -0.2400960 0.5990438 0.7153071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6961 6962 0.458814 -0.211578 -0.871711 -0.7292717 -0.1206427 0.4146723 0.5307118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6962 6963 0.415184 0.651078 -0.498596 0.6087335 0.2022361 -0.1393939 0.7543960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6963 6964 0.789728 0.067814 -0.695207 -0.0078769 -0.0647798 0.3643752 0.9289630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6964 6965 0.561407 -0.220025 -0.681847 -0.1540833 -0.3191762 -0.9263561 0.1274727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6965 6966 -0.785284 0.138329 -0.824030 -0.8226063 -0.2481118 0.2357771 0.4540578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6966 6967 -0.410216 0.292370 0.980865 0.9299000 -0.0740966 -0.2440102 0.2650560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6967 6968 -0.793554 0.185425 -0.792232 -0.8094847 0.5172740 0.0449249 0.2741239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6968 6969 -0.253929 0.698114 0.514265 0.0123553 -0.6169759 0.2084660 0.7587688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6969 6970 0.667044 0.731623 0.277491 0.2406350 0.1248948 0.8325912 0.4829989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6970 6971 0.385943 -0.823300 0.590269 -0.5744438 -0.1020646 -0.7908722 0.1847114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6971 6972 0.367317 0.771352 0.210187 0.6653763 0.4416973 0.1007008 0.5933273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6972 6973 0.787569 0.505332 -0.346610 -0.1579207 0.5329641 0.7666212 0.3214067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6973 6974 -0.419742 -0.910287 0.251335 -0.4749478 0.5115285 0.7130043 0.0662416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6974 6975 0.482562 0.646691 -0.604062 -0.2205906 -0.1169660 0.9167372 0.3118519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6975 6976 0.212048 -0.584419 -0.660030 0.0131647 0.1981039 -0.0568714 0.9784412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6976 6977 0.432747 -0.614472 -0.781229 0.5991680 -0.3591138 0.6915974 0.1836518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6977 6978 -0.786129 0.158937 0.636242 0.7660662 -0.3458801 0.5226757 0.1425472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6978 6979 0.546791 0.133278 -0.788018 -0.0083574 -0.1790264 0.8001965 0.5723332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6979 6980 0.891485 -0.631632 -0.043187 0.4428581 -0.3258515 -0.2227660 0.8050297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6980 6981 0.163955 1.128628 0.217520 0.1830856 0.0313456 0.9680111 0.1686763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6981 6982 0.079612 -0.969527 -0.018546 0.0908010 -0.3450707 -0.0975328 0.9290687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6982 6983 0.526897 -0.816112 0.352635 -0.2817506 0.6290889 0.7009280 0.1832042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6983 6984 -0.407599 -0.087585 -0.874076 0.1577544 -0.4189944 0.2511456 0.8581859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6984 6985 -0.897503 0.243736 -0.302299 0.0027866 -0.5212474 -0.5976300 0.6092059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6985 6986 -0.074519 -0.910685 0.508697 0.0854773 0.5431754 0.5814774 0.5996150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6986 6987 -1.024799 0.348932 -0.082098 -0.1994303 -0.2196479 -0.9456997 0.1327948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6987 6988 0.741565 -0.557882 -0.311447 0.2360523 0.5059603 0.4183971 0.7163989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6988 6989 -0.225437 -0.936346 0.599053 -0.4345789 -0.3058099 -0.4037339 0.7447284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6989 6990 0.225460 -0.783377 -0.436816 0.5996268 0.4098502 -0.6063953 0.3236592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6990 6991 0.411706 0.877385 0.469632 0.1221629 -0.2299223 0.4704906 0.8431196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6991 6992 0.928957 0.212361 -0.070171 -0.7172735 -0.1083422 0.4079845 0.5543729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6992 6993 0.552933 -0.300757 -0.664637 0.3968246 -0.0528069 -0.8248780 0.3991465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6993 6994 0.495125 0.410478 -0.831311 -0.0916178 -0.1807635 -0.4623080 0.8632508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6994 6995 -0.414260 0.411231 -0.652815 -0.1460053 -0.8526400 -0.3053470 0.3980586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6995 6996 -0.253713 -0.251848 0.955948 -0.4858156 0.3013452 0.0445098 0.8192638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6996 6997 -0.762791 -0.580253 -0.118764 0.2543038 -0.3194043 0.2997460 0.8622429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6997 6998 -0.753950 0.073264 0.741044 0.3842847 0.3924099 0.6473543 0.5284620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6998 6999 0.286667 0.797616 -0.447725 -0.1710481 0.2795069 0.2256288 0.9174476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6999 7000 0.505888 -0.784860 0.518522 0.1747128 -0.4102186 -0.2963996 0.8445966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7000 7001 -0.189950 -1.093193 0.348914 -0.0448845 0.3774440 0.9247022 0.0211484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7001 7002 0.136591 0.769289 -0.325220 0.0028828 0.3034081 -0.7192567 0.6249840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7002 7003 -0.812997 0.414684 -0.603083 0.3289390 -0.3539401 -0.6656658 0.5686955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7003 7004 -0.061177 -0.896830 0.079903 -0.1822336 -0.0606959 -0.6683797 0.7185927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7004 7005 0.967502 0.071976 -0.173580 0.1951173 0.0858592 -0.9479410 0.2365697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7005 7006 -0.851217 0.427180 -0.455947 0.3535751 -0.0410392 -0.0548270 0.9328957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7006 7007 -0.775939 0.143678 -0.712068 0.0193578 0.3473268 -0.7316383 0.5862548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7007 7008 0.313665 -0.329342 -0.642149 0.0659775 0.1145515 0.2233481 0.9657332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7008 7009 0.397035 -0.662749 -0.638215 0.2533199 -0.2683449 -0.2585100 0.8927444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7009 7010 0.522028 -0.877299 -0.380026 0.6888583 -0.1940591 0.5563780 0.4222071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7010 7011 -0.439080 -0.285848 0.993315 -0.5965339 0.4386325 -0.6682593 0.0719600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7011 7012 0.925156 -0.249345 -0.254451 0.3255618 -0.0035075 0.3413623 0.8817420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7012 7013 0.399328 -1.082379 0.317499 -0.8358673 0.2396302 0.4938119 0.0072853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7013 7014 0.283567 0.813172 -0.619252 0.0300635 -0.8295912 -0.3812008 0.4068914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7014 7015 -0.925955 0.282526 0.496744 -0.2818398 -0.2459648 0.8977889 0.2324708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7015 7016 0.575986 -0.350487 0.812706 0.6013281 0.0002462 -0.7172179 0.3521406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7016 7017 -0.560816 0.779074 -0.077880 0.0238567 -0.0364394 0.6961397 0.7165839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7017 7018 0.697733 0.656958 -0.076838 -0.4592896 0.2988204 -0.7562086 0.3576422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7018 7019 -0.931696 -0.003404 0.608865 -0.6328200 0.1056155 -0.5358853 0.5488271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7019 7020 0.440168 0.589014 -0.659053 0.2614525 -0.2728456 0.9134230 0.1511826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7020 7021 0.519663 -0.842797 -0.174091 0.1403814 0.3398059 0.5457639 0.7529719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7021 7022 -0.566720 -0.676306 0.063012 -0.5983564 0.0321389 -0.1348067 0.7891539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7022 7023 -0.364517 -0.448089 -0.727067 -0.1925657 -0.4206825 -0.4663858 0.7539423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7023 7024 -0.428937 -0.582440 -0.687323 0.1180412 0.6360896 -0.0342814 0.7617618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7024 7025 0.436051 -0.838505 -0.700412 0.4446822 0.6538662 -0.6114625 0.0288148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7025 7026 -0.420558 0.787333 0.384862 0.5165325 -0.3624287 0.6705743 0.3900895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7026 7027 0.686965 0.026268 -0.722572 -0.3113285 -0.2958940 -0.5702142 0.7002693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7027 7028 -0.279128 0.804681 -0.433796 -0.5749556 0.3136629 -0.4316179 0.6202802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7028 7029 -1.016355 0.271788 0.137358 0.8778151 -0.2109340 0.4033946 0.1490644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7029 7030 -0.599047 0.096986 -0.701604 -0.5052037 0.1529423 -0.0050457 0.8493247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7030 7031 -0.598479 0.701188 -0.250819 0.3014243 0.4311609 0.4782846 0.7031980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7031 7032 0.681127 0.323300 -0.681857 -0.2371210 0.2296671 -0.5232996 0.7856107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7032 7033 -0.025882 0.913607 0.039218 0.5351891 -0.2876331 -0.6174253 0.4996256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7033 7034 -0.814065 -0.263614 -0.109463 0.1299194 0.1822170 0.9585475 0.1763649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7034 7035 0.705072 0.657037 -0.560912 0.5340402 0.2651143 0.1352620 0.7913404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7035 7036 1.042303 -0.219235 -0.238364 -0.4449499 0.0799575 -0.6236838 0.6376871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7036 7037 0.393229 1.019099 0.409145 0.5018980 -0.3234545 0.5475954 0.5861866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7037 7038 0.808090 -0.373932 -0.788849 0.2683344 -0.1202506 0.7177933 0.6311174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7038 7039 -0.541704 -0.868932 -0.201335 -0.6859434 0.0745287 -0.6447321 0.3290100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7039 7040 0.935706 -0.343002 -0.172524 -0.4552361 0.6546137 0.2801735 0.5345501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7040 7041 -0.468123 -0.405684 -0.706573 -0.4240264 -0.5348605 -0.0579114 0.7285411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7041 7042 -1.053502 -0.171521 -0.007496 0.5489932 -0.3234596 0.7583991 0.1371539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7042 7043 0.442073 0.462054 -0.696934 0.3189327 0.5232974 -0.1746294 0.7706791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7043 7044 0.936805 0.511170 -0.025423 -0.3198476 0.0787418 0.7660862 0.5519141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7044 7045 0.413715 -1.034804 -0.153829 -0.0404416 -0.2966118 0.7748481 0.5567732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7045 7046 -0.994356 0.059049 -0.015149 0.1006253 -0.3119423 0.8877915 0.3230987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7046 7047 0.848086 0.689254 -0.019280 0.2265039 -0.0961954 0.7215831 0.6471169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7047 7048 0.443028 -0.856191 0.073531 -0.3093497 -0.1223128 0.5298210 0.7801487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7048 7049 -0.480136 -0.496764 -0.580495 0.1450710 -0.4532925 0.4943189 0.7274126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7049 7050 -0.693988 0.379824 0.621257 -0.1749452 -0.0000551 0.9176804 0.3567307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7050 7051 0.747041 0.289172 0.580457 -0.4860326 0.5772090 0.6103897 0.2408870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7051 7052 -1.037952 -0.246710 0.050783 0.1018583 0.6553235 0.6766222 0.3199350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7052 7053 0.538015 0.222050 -0.741165 -0.5522168 -0.0850778 -0.5430531 0.6268267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7053 7054 -0.191126 0.957928 0.199812 -0.4389606 -0.0954312 0.8906580 0.0702483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7054 7055 0.070327 -0.921177 0.423605 0.2234452 0.0153784 0.8488134 0.4789067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7055 7056 -0.596385 0.467017 0.548356 -0.2015435 0.3084440 0.9191205 0.1394991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7056 7057 0.247599 0.165053 1.200736 0.6857640 0.0436084 0.3612414 0.6303417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7057 7058 0.900980 0.501406 0.078635 0.7943333 -0.1338845 -0.5804218 0.1192476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7058 7059 -0.096690 -0.469153 -0.793585 0.4290354 0.7158789 -0.1735509 0.5228060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7059 7060 -0.370943 0.424862 0.751580 0.4575352 -0.1588217 -0.6988037 0.5264130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7060 7061 -0.097357 -1.045649 -0.050497 0.5461296 0.5174492 -0.3984205 0.5246426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7061 7062 -0.074511 -0.151368 1.048682 0.8515231 -0.0921180 -0.3701555 0.3597326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7062 7063 -0.565927 0.803953 -0.280630 0.4259630 0.7036734 -0.4654364 0.3267542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7063 7064 0.685306 -0.229936 -0.477499 0.5875189 -0.2375135 -0.2516248 0.7315011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7064 7065 0.633700 -0.581138 -0.493519 -0.0247981 0.0033754 0.8340971 0.5510496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7065 7066 -0.800786 -0.636165 -0.552800 0.1462055 0.7248975 -0.1934950 0.6447537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7066 7067 0.496444 -0.787137 -0.657237 0.0909951 0.1699124 -0.9740051 0.1190117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7067 7068 -0.295098 0.962312 -0.140158 -0.5659324 0.6199847 0.1451545 0.5237076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7068 7069 -0.441636 0.609787 0.495649 0.7197966 -0.0338576 -0.5787748 0.3817935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7069 7070 -0.990982 -0.240171 -0.118420 0.1524193 -0.4329009 0.3062456 0.8340136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7070 7071 -0.312890 0.312763 0.673139 -0.2071804 0.7308247 0.5729496 0.3077341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7071 7072 -0.059993 1.162184 0.102593 0.4833855 -0.7138522 -0.4973811 0.0967755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7072 7073 -0.719653 0.019112 0.729457 -0.9754687 0.1320774 0.0349265 0.1726164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7073 7074 -0.690592 -0.006145 -0.690531 0.1686298 0.2769848 -0.5056153 0.7994977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7074 7075 0.136570 -0.696694 -0.621928 0.2023270 0.4045582 -0.4473804 0.7715227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7075 7076 1.128917 -0.235687 0.354270 -0.5077808 -0.0146346 0.8372693 0.2022982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7076 7077 -0.952687 -0.287352 -0.673904 -0.5396880 -0.5879704 0.5592795 0.2241294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7077 7078 0.427019 0.464036 0.993020 0.5967358 0.5108868 -0.6187805 0.0034246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7078 7079 -0.658760 -0.462493 -0.677838 -0.2704048 -0.0262475 0.2879874 0.9182895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7079 7080 -0.170578 0.794045 0.313953 0.0355727 0.1313873 -0.9888640 0.0601662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7080 7081 -0.498395 0.160874 0.839549 0.4273148 0.1280447 0.5858495 0.6765995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7081 7082 0.262848 0.914228 0.041031 0.0355142 0.5407421 0.8401822 0.0207496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7082 7083 -0.043742 -0.576090 0.770204 -0.6489417 -0.0150505 0.7606713 0.0052285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7083 7084 -0.713630 0.578567 0.267126 -0.1345716 0.0178638 0.1433850 0.9803122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7084 7085 -0.816734 0.592863 0.216553 0.5040414 0.4645016 -0.4588259 0.5653842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7085 7086 -0.469535 -0.814401 -0.723981 -0.3471888 -0.3069953 0.1519200 0.8730029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7086 7087 -0.897214 0.044008 -0.371080 -0.0271492 0.7986955 -0.3603764 0.4811208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7087 7088 0.810054 0.095096 -0.496551 0.0183914 -0.1519470 0.0512276 0.9868888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7088 7089 0.601151 0.044150 -0.841826 0.6063888 -0.6194780 0.3268387 0.3764520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7089 7090 -0.563751 -0.632120 0.428181 -0.0390176 0.2194962 -0.9197105 0.3231590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7090 7091 0.977927 -0.353600 0.362781 -0.0634885 -0.1907192 0.1280383 0.9711857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7091 7092 0.898161 -0.468455 0.201955 -0.1315335 -0.5520334 0.6405281 0.5173798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7092 7093 -0.821293 -0.440807 -0.401078 -0.4367288 0.0261122 -0.8699616 0.2274929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7093 7094 0.473987 0.300944 -0.915762 -0.1585307 -0.8410121 -0.4664653 0.2235548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7094 7095 -0.779170 -0.448181 0.547526 0.0704652 -0.3615307 -0.7896217 0.4907420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7095 7096 0.964598 -0.074994 0.495554 -0.3303634 0.2856538 0.2321439 0.8691209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7096 7097 0.241949 -1.042689 0.454232 -0.2061471 -0.6360198 0.4891698 0.5600848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7097 7098 -0.599908 -1.104775 -0.116857 -0.0832445 0.0791762 -0.8069387 0.5793544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7098 7099 1.047155 -0.341155 -0.083272 0.1831165 0.2838207 0.3154960 0.8867787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7099 7100 0.880691 0.182619 -0.430980 0.0621609 -0.0177112 0.8974766 0.4363005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7100 7101 0.827303 0.094430 -0.691617 0.8296856 0.1300120 0.5410309 0.0447691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7101 7102 -0.202872 -0.247136 0.948268 -0.0381061 0.1233529 0.2110507 0.9689116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7102 7103 -0.518976 -0.075900 0.778761 -0.6834709 -0.6611270 -0.2753714 0.1412421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7103 7104 0.599728 -0.320661 -0.614611 -0.0375435 0.7882978 -0.2033424 0.5795075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7104 7105 0.727998 -0.197464 0.606173 -0.1139244 -0.5755258 -0.4296251 0.6864500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7105 7106 0.645535 0.669875 -0.338021 -0.0455153 -0.2168652 -0.7288369 0.6478384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7106 7107 -0.998501 0.581212 0.036146 -0.1848607 0.5537009 -0.7191729 0.3768716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7107 7108 0.019394 -0.086179 -0.847497 0.2139005 0.0244627 0.9576314 0.1912857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7108 7109 -0.687563 -0.187675 -0.816250 -0.2391602 -0.5583872 0.3283012 0.7233425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7109 7110 -0.634811 0.693742 0.440866 -0.6168021 -0.1231687 -0.2684906 0.7295872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7110 7111 -0.468354 -0.585141 0.691843 0.1145054 0.8597433 0.2697949 0.4182590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7111 7112 -0.280464 0.097011 -0.867618 -0.1462347 -0.3085673 0.2977578 0.8914830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7112 7113 -0.752713 0.712695 -0.538711 -0.4310345 0.0838711 0.8959311 0.0669506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7113 7114 0.901572 -0.493857 0.218425 0.3307785 -0.4545361 -0.8186177 0.1176757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7114 7115 -0.334204 0.313394 -0.801905 -0.0024907 0.2764274 0.5233112 0.8060565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7115 7116 0.567485 0.215194 -0.812788 0.6865708 0.3561096 0.1603553 0.6132639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7116 7117 0.877719 -0.648767 0.301780 -0.6903634 0.1149190 0.5687311 0.4321307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7117 7118 -0.313465 -0.334823 -0.962335 -0.1446670 0.0425811 0.2489780 0.9566965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7118 7119 -0.147985 0.104581 -1.078415 0.5134577 -0.4448626 -0.2968500 0.6710726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7119 7120 -0.910972 0.385539 0.424941 -0.3097107 -0.2830622 -0.5999747 0.6811647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7120 7121 -0.555141 0.363206 0.862602 0.1383988 0.3111052 0.8937128 0.2921245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7121 7122 0.744855 0.392331 0.571624 0.4504622 -0.4614392 -0.7481380 0.1563559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7122 7123 -0.952007 0.073866 -0.269963 -0.4839448 0.5383284 0.3195290 0.6114746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7123 7124 -0.046143 0.836580 -0.366735 -0.2825412 -0.7120689 0.0564434 0.6402676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7124 7125 0.297891 0.912990 0.331877 0.5730665 0.3359893 -0.3337361 0.6688244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7125 7126 -0.289146 0.472648 -0.704868 0.3405937 -0.8752638 -0.3432615 0.0089892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7126 7127 0.191147 -0.361587 0.952036 -0.5414169 0.4649065 0.3060643 0.6301225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7127 7128 -0.926279 -0.555186 0.012689 -0.0227744 -0.1171103 -0.4876717 0.8648369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7128 7129 -0.261150 -1.017758 -0.094961 0.6858129 -0.0179698 -0.3275123 0.6496718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7129 7130 0.356424 -0.071554 0.859680 0.3629176 -0.6923381 0.2908814 0.5516763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7130 7131 0.760305 -0.550532 -0.520456 -0.2044519 0.2802229 0.9378760 0.0079477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7131 7132 -0.338273 0.128816 -0.822296 0.5148851 -0.3903167 0.7110345 0.2774459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7132 7133 -0.829908 0.679610 -0.437671 -0.6330654 0.3774755 -0.4052031 0.5408797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7133 7134 -0.915591 0.461282 -0.477508 0.2543536 0.3205480 -0.1763831 0.8952331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7134 7135 -0.385280 -0.336549 -0.901067 0.4857029 -0.0750676 -0.0868729 0.8665510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7135 7136 -0.361186 -0.892403 -0.315074 0.4529002 -0.5766154 -0.3039582 0.6082807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7136 7137 0.726327 -0.428644 0.550796 0.0524902 0.6623348 0.3290715 0.6710211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7137 7138 -0.936415 -0.206480 0.444709 -0.0451948 -0.0997209 -0.8473997 0.5195449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7138 7139 0.679518 -0.597514 0.416658 -0.1270977 -0.6880687 0.7142626 0.0153826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7139 7140 -0.285746 -0.646639 -0.889540 0.5731906 -0.4221060 0.6538224 0.2565060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7140 7141 -0.960325 -0.667671 0.150088 -0.3913961 0.2880469 0.3446951 0.8031335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7141 7142 -0.822319 0.400844 -0.491771 -0.5905474 -0.3878998 0.5663314 0.4243304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7142 7143 0.457214 0.292823 0.669762 0.0941267 0.2657718 -0.4650435 0.8391901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7143 7144 -0.658443 0.732371 0.563606 0.1917109 -0.7747050 0.0068678 0.6025213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7144 7145 0.527318 0.883901 0.176915 0.2181765 -0.2679948 0.5098355 0.7878106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7145 7146 0.872958 0.036063 -0.441684 -0.4262812 0.1031515 -0.8956327 0.0740692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7146 7147 -0.811346 0.266479 0.423237 0.3809806 0.0601438 0.8775633 0.2848143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7147 7148 0.770166 0.460628 -0.360135 0.1980733 -0.4854876 0.2756629 0.8056542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7148 7149 0.099834 -0.401575 -0.847540 -0.5516230 -0.3034476 -0.7687787 0.1122985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7149 7150 -0.950274 -0.084141 -0.288857 0.2461638 -0.7669598 -0.2105635 0.5539306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7150 7151 0.334530 0.075786 0.913783 -0.5983243 -0.4780660 -0.6410669 0.0499408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7151 7152 0.808977 0.568131 -0.048758 0.4572700 0.0913291 0.2645561 0.8441405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7152 7153 0.838530 -0.053826 -0.337393 0.0196334 -0.1334713 -0.0181408 0.9906921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7153 7154 0.815896 -0.386032 -0.574872 -0.4182915 -0.1104358 -0.6298425 0.6450850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7154 7155 -0.074355 0.851655 -0.039214 -0.5381432 0.6754998 -0.0791469 0.4978329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7155 7156 -0.677447 0.588666 0.567803 0.7874899 0.2237435 -0.5060132 0.2715679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7156 7157 -0.438884 -0.858161 0.061906 -0.3359679 -0.4082083 0.8008955 0.2811726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7157 7158 -0.001100 0.542882 0.839499 0.5726676 -0.6745179 0.4650736 0.0279995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7158 7159 -0.100015 -0.575798 -1.024004 -0.0499244 0.5939377 0.6057106 0.5271245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7159 7160 -0.694421 0.491607 -0.925611 -0.3616079 -0.3926797 0.3390208 0.7746659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7160 7161 0.839718 0.013112 0.829570 0.0834881 -0.5599377 -0.0694740 0.8213847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7161 7162 0.950723 0.220737 -0.313582 0.4187639 0.2718644 0.8662592 0.0179343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7162 7163 -0.847782 -0.073175 0.538368 0.4658619 -0.1402881 0.7465160 0.4538786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7163 7164 0.510313 0.812575 -0.474939 -0.4205372 0.1069977 -0.5600954 0.7056863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7164 7165 -0.627792 0.750447 0.672039 -0.7979217 -0.0140398 -0.2985768 0.5234269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7165 7166 -0.444334 -0.914272 -0.061112 -0.6056646 0.5053156 -0.5862579 0.1847380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7166 7167 1.033376 0.357333 0.285575 0.4650933 -0.6475908 0.4011807 0.4509639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7167 7168 -0.256275 -0.568820 -0.696621 0.5945599 0.5183395 0.3600471 0.4981855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7168 7169 -0.793193 -0.628768 0.051727 -0.0914653 0.1730865 -0.7025861 0.6841403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7169 7170 0.663743 -0.519105 -0.214396 0.1974516 -0.3433761 -0.0421980 0.9172377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7170 7171 0.329515 -0.644933 -0.459798 -0.3906488 -0.2497110 0.8689877 0.1729113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7171 7172 -0.406248 0.731539 -0.529127 0.4964416 0.3523390 -0.4164325 0.6752680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7172 7173 0.042540 -0.533509 -0.781250 -0.2763732 -0.6430467 -0.1752881 0.6923748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7173 7174 -1.013357 0.025557 -0.282539 -0.0168851 -0.4863328 0.7079835 0.5118151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7174 7175 0.322090 0.912843 0.280259 -0.3849123 -0.0475941 0.7963468 0.4641219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7175 7176 0.396819 -0.882703 0.377570 -0.0524740 -0.1746217 0.7395174 0.6479720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7176 7177 -0.828273 -0.456212 0.376256 -0.0217941 -0.0104363 0.9996859 0.0066470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7177 7178 0.741154 0.230004 0.463866 0.6069673 -0.1307779 -0.2473382 0.7438493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7178 7179 0.540269 0.633825 -0.473563 -0.3883676 0.1982885 0.4665141 0.7695563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7179 7180 0.317765 1.089958 -0.559137 -0.1824557 0.4162653 0.7817482 0.4269694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7180 7181 0.736858 0.687254 -0.158014 -0.3247561 -0.5012309 0.7656100 0.2390446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7181 7182 -0.056120 -0.072414 -1.123279 -0.1819573 -0.7694346 0.5640152 0.2382199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7182 7183 -0.366471 0.931985 0.458337 0.0057289 -0.8653332 0.4261407 0.2637608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7183 7184 0.689420 0.322379 -0.711301 0.2972520 0.3192897 -0.6525343 0.6195921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7184 7185 0.267951 0.662872 -0.597267 -0.4258921 0.2266590 0.2160987 0.8488480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7185 7186 0.707884 0.700991 0.123919 -0.0458920 0.4110866 0.9089366 0.0523063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7186 7187 -0.708354 -0.538464 0.425133 -0.3538538 0.3756074 0.8462853 0.1323172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7187 7188 0.128922 0.906927 0.325023 -0.5113020 -0.1491156 -0.4248605 0.7320030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7188 7189 -0.120031 0.137489 0.828662 0.4206152 -0.8096637 0.3626955 0.1896824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7189 7190 0.890717 -0.290313 -0.745308 0.3406626 -0.2429947 0.0923904 0.9035301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7190 7191 0.312763 -0.735258 -0.443269 -0.4665335 -0.3718230 -0.7900617 0.1410554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7191 7192 -0.650444 0.521861 -0.733217 0.3156905 0.4397749 0.1174576 0.8325510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7192 7193 0.379807 -0.077205 -0.944747 0.1898935 -0.7166646 -0.6185936 0.2601426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7193 7194 -0.435246 -0.847350 -0.113721 -0.0596938 -0.1745338 -0.7271813 0.6611974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7194 7195 0.739306 -0.631745 -0.313644 0.5800375 -0.5294193 -0.3499884 0.5106660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7195 7196 0.513671 -0.579625 -0.638847 0.8036146 0.4690620 0.3420276 0.1311544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7196 7197 -0.473900 0.423000 0.637018 -0.2340951 -0.6358828 -0.6697294 0.3038340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7197 7198 0.904691 0.127591 0.767130 -0.1467938 -0.5988962 -0.7858173 0.0476025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7198 7199 -0.752754 0.501835 0.178516 -0.0760377 0.5824265 0.6906942 0.4218284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7199 7200 -10.318166 -14.712357 -6.889311 -0.3889532 -0.4224440 0.3136914 0.7562104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7200 7201 0.844590 -0.026255 -0.048181 -0.4234955 0.3544960 0.2210524 0.8038159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7201 7202 0.702014 -0.753551 0.319078 0.3922609 0.2369213 -0.1180592 0.8809437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7202 7203 0.397348 0.027159 1.100850 -0.1786049 0.0058253 0.9664366 0.1845717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7203 7204 -0.608848 -0.222944 0.652005 0.4932495 0.7327678 0.4685796 0.0137659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7204 7205 0.432412 0.133906 -0.746300 -0.5983238 0.1950807 0.3235860 0.7065722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7205 7206 0.975027 0.190492 -0.413596 0.6005119 0.5368036 0.4469623 0.3891683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7206 7207 0.050121 -0.265616 0.905868 -0.6181633 -0.0646996 -0.2324973 0.7480863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7207 7208 0.576280 -0.916427 0.064817 0.6441684 0.3455540 -0.6785517 0.0721604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7208 7209 -0.524952 1.070035 -0.096423 0.0697547 -0.5264029 -0.0144661 0.8472455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7209 7210 -0.257880 1.025441 0.504688 -0.2818912 0.4831680 -0.2836044 0.7788803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7210 7211 -0.867547 0.429205 0.193188 0.1520671 -0.0076850 -0.2957275 0.9430598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7211 7212 -0.744830 -0.089738 0.202435 -0.1574566 0.3478826 -0.9161039 0.1222241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7212 7213 1.034290 -0.101601 0.146241 -0.6187292 -0.2439199 -0.5338071 0.5222330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7213 7214 0.458541 0.942900 0.283912 0.4252683 -0.1227903 -0.5879496 0.6770411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7214 7215 -0.883777 0.373903 -0.438538 -0.1237922 -0.0515848 -0.3070832 0.9421860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7215 7216 -0.933164 -0.151299 -0.154298 0.1856302 0.3322613 0.8719260 0.3080405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7216 7217 0.583334 0.055081 -0.938968 0.2348306 -0.8309198 0.5031879 0.0350559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7217 7218 -0.811914 0.539703 0.398281 0.1923493 -0.2671843 0.7032185 0.6301572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7218 7219 0.700860 0.568187 0.032138 0.4897958 -0.5495675 -0.6205853 0.2700916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7219 7220 -0.169955 -0.893239 0.382926 -0.7879652 0.0032468 -0.0186652 0.6154282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7220 7221 0.881540 -0.471279 0.037103 0.6358810 -0.0821666 -0.6472913 0.4122109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7221 7222 0.450148 0.642357 -0.787088 -0.1360918 0.2827461 -0.6633305 0.6793573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7222 7223 -0.674303 0.758926 -0.566280 -0.0001572 -0.1598907 -0.9687227 0.1897664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7223 7224 0.189141 -0.774837 0.017143 -0.5411168 0.3490809 -0.6981900 0.3128351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7224 7225 0.590775 0.757800 0.360522 -0.2287067 0.0536045 0.2023507 0.9507229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7225 7226 0.643071 0.314862 0.485018 0.2565934 0.7629651 -0.4159197 0.4231487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7226 7227 -0.814321 0.134677 -0.065098 0.8364852 -0.4694682 -0.1377231 0.2468288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7227 7228 -0.947182 0.391674 0.276911 -0.1573936 0.5174871 -0.2885275 0.7900546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7228 7229 -0.680269 -0.191280 -0.528804 0.1180719 0.3944215 0.7625591 0.4989933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7229 7230 0.257434 0.101936 -0.958376 0.0286049 -0.0167869 0.9759347 0.2155257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7230 7231 -0.141160 -0.337659 -0.904404 -0.4311157 -0.3483363 0.7855952 0.2750295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7231 7232 0.475312 0.902814 -0.246279 -0.1122162 -0.2319912 0.5957864 0.7606748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7232 7233 0.777913 -0.107483 -0.271648 -0.4462847 -0.1812843 0.4009146 0.7792519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7233 7234 0.477034 -0.235213 -0.672774 0.3618752 0.1181710 -0.8650743 0.3266932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7234 7235 0.318165 0.134261 -1.047825 -0.5460255 0.0693370 0.7195094 0.4235030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7235 7236 0.907995 0.180939 -0.403360 0.5283553 0.2655927 0.7786259 0.2098640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7236 7237 -0.409965 -0.018419 0.727036 -0.8088741 0.2830172 0.3392761 0.3879636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7237 7238 -0.862932 0.598446 -0.392037 0.0877154 0.3936192 -0.2076601 0.8912055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7238 7239 -0.438400 -0.120836 -0.959426 0.1323039 -0.0872153 -0.8567155 0.4908439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7239 7240 -0.304942 -0.963015 0.111326 0.8286529 -0.2582843 0.4753411 0.1437864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7240 7241 0.492319 -0.172822 -1.080104 -0.5194886 0.0872241 -0.0088677 0.8499676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7241 7242 0.521334 0.888732 -0.505829 -0.2399436 0.8211077 0.1134336 0.5053137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7242 7243 0.087399 0.592172 0.889722 0.5590042 -0.1734108 0.6557302 0.4769286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7243 7244 0.996399 -0.061860 -0.097003 -0.0212411 0.1652573 0.9722696 0.1641058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7244 7245 -0.920992 -0.181449 -0.092990 0.6827946 0.2032730 -0.6600345 0.2383824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7245 7246 0.085796 -0.249049 0.865185 0.0393401 -0.1476964 0.0055241 0.9882346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7246 7247 0.392418 -0.386483 0.796276 -0.6872608 0.0588295 0.7240156 0.0036191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7247 7248 -0.674272 0.465101 -0.492528 -0.4301731 -0.3697221 0.7015494 0.4313758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7248 7249 0.497375 0.264813 0.496984 0.8347087 -0.1382078 -0.5137509 0.1421972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7249 7250 -0.437575 -0.106621 -0.765463 0.9772478 0.0885651 -0.1927183 0.0016351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7250 7251 -0.024898 0.328590 1.138452 -0.1970626 -0.7686892 -0.0307288 0.6077327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7251 7252 0.878508 0.036820 -0.014186 0.2191431 -0.4411288 0.8616014 0.1225755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7252 7253 -0.796736 -0.500265 0.044817 -0.4837946 0.3207320 0.6047289 0.5453226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7253 7254 -0.321362 0.917873 0.063762 0.5673029 -0.3244512 -0.5018683 0.5665924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7254 7255 -1.011945 -0.210346 0.014931 -0.6670038 0.3813396 -0.2440663 0.5917074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7255 7256 -0.522178 0.274361 -0.817358 0.3732343 0.5607502 -0.5615028 0.4805934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7256 7257 0.816770 -0.265872 -0.560510 -0.3367491 0.1299708 -0.9322016 0.0266044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7257 7258 -0.951987 0.406874 0.175385 0.3687112 -0.0946748 -0.2404207 0.8929090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7258 7259 -0.891936 0.072012 0.273612 -0.5499174 -0.2564595 -0.7848231 0.1259847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7259 7260 0.740124 0.573925 0.170827 0.4046629 -0.3080295 0.6994457 0.5021370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7260 7261 0.980606 0.412787 -0.046846 -0.2296447 0.6876778 -0.6022063 0.3342307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7261 7262 -0.870747 0.332392 0.275502 0.8529197 0.1937055 -0.4447000 0.1929976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7262 7263 -0.531336 -0.740321 0.219385 -0.6116273 0.2704590 0.5254886 0.5259522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7263 7264 -0.595138 0.779052 -0.609627 0.4032960 -0.1134741 0.6721992 0.6104295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7264 7265 0.062992 0.253314 -1.130180 0.0503419 -0.0807621 0.9665207 0.2382873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7265 7266 -0.053208 -0.031534 -0.994463 0.0541359 -0.4513415 0.7136368 0.5329941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7266 7267 -0.483955 0.686504 -0.494343 0.4920957 -0.6770786 -0.4757566 0.2702999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7267 7268 -0.373313 0.035025 0.892925 -0.0559196 -0.5094673 -0.5937015 0.6203504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7268 7269 0.838244 0.387685 0.639891 0.2881369 -0.7138563 -0.0987071 0.6305896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7269 7270 0.285957 0.331564 -0.955699 -0.6007897 0.0258719 0.1321474 0.7879845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7270 7271 0.487368 0.767252 0.007379 0.6065711 0.3261103 -0.4930718 0.5316050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7271 7272 0.178841 0.250244 -0.852087 -0.2328103 0.4924955 0.7207199 0.4287311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7272 7273 0.845848 -0.591245 -0.378933 0.3182420 0.2676945 0.7788531 0.4695206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7273 7274 -0.921215 -0.235447 0.309611 -0.0865834 0.5564539 -0.1880952 0.8046630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7274 7275 -0.445492 -0.351477 -0.798414 0.2909825 0.7373544 -0.5425341 0.2780188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7275 7276 0.657178 0.113493 0.725412 0.2451821 -0.8753897 0.0251803 0.4158660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7276 7277 0.278665 -0.093177 -0.976804 0.2305867 0.3929691 -0.8862863 0.0830766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7277 7278 0.174988 0.842492 -0.463072 -0.7252154 -0.6004303 -0.0277331 0.3358229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7278 7279 0.314643 0.522269 0.678682 0.5705861 -0.3872977 0.7023524 0.1764460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7279 7280 -0.884954 -0.231719 0.466113 -0.7374387 0.1947558 -0.1999138 0.6150519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7280 7281 -0.880423 -0.162171 0.673472 -0.3329745 -0.7144510 0.6147694 0.0273184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7281 7282 0.330801 -0.840881 0.317367 0.5672069 -0.6963856 0.0516086 0.4366463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7282 7283 1.028610 -0.454618 0.011175 -0.4409348 0.1540066 -0.8691081 0.1628175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7283 7284 -0.219682 0.395790 0.754904 0.5431754 0.5047778 -0.5973845 0.3054367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7284 7285 -0.728705 -0.546569 -0.328893 0.5693626 -0.1804092 0.2553655 0.7603073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7285 7286 -0.974909 -0.153967 0.435602 0.1393390 -0.1373828 -0.0327412 0.9801217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7286 7287 -0.880566 0.094274 0.613495 0.2497403 0.9384437 0.2022685 0.1266515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7287 7288 0.423762 -0.056914 -0.767618 -0.1986327 0.0560080 0.5000572 0.8410416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7288 7289 0.569604 -0.319271 -0.812732 0.3084880 0.7110788 -0.1297312 0.6183622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7289 7290 0.724971 -0.156332 0.789660 0.5377342 -0.3311285 -0.4265017 0.6475277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7290 7291 0.479590 0.876067 -0.457725 -0.3528235 0.3832418 0.7264116 0.4482939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7291 7292 0.467539 -0.965492 0.503711 -0.3999048 -0.3078805 0.4935848 0.7082795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7292 7293 -0.346272 -0.775534 -0.475080 -0.4750460 0.4205424 -0.6404583 0.4327685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7293 7294 0.693527 0.373525 -0.402692 0.2634065 -0.2538076 0.2695223 0.8908178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7294 7295 0.492191 -0.218301 -0.856108 0.7861037 -0.1033313 0.6026937 0.0901324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7295 7296 -0.658909 0.107215 0.476062 -0.3077879 0.8201585 -0.1602852 0.4548794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7296 7297 -0.093938 -0.018000 -0.958131 0.0476962 -0.2126458 0.2866294 0.9329257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7297 7298 -0.601378 0.166975 -0.666919 0.2751534 -0.1086575 -0.7127110 0.6360246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7298 7299 0.167152 -0.920734 -0.226301 0.3585124 -0.1919317 0.7976881 0.4453368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7299 7300 -0.116963 -0.758867 0.584226 -0.2773034 -0.7567429 -0.5035853 0.3111989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7300 7301 -0.640190 0.171550 -0.454296 -0.3505979 0.5346338 -0.4217284 0.6429565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7301 7302 -0.130018 0.086685 -0.816134 -0.8403090 -0.3500920 -0.1447654 0.3877620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7302 7303 -0.617196 0.277628 0.790578 0.8247887 0.3434343 0.3364130 0.2976622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7303 7304 0.370008 0.128058 -1.039541 0.0669814 -0.5066368 0.4776747 0.7146045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7304 7305 -0.565066 0.387490 -0.937872 0.1422798 0.5671929 0.7921601 0.1747314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7305 7306 0.670857 -0.692709 -0.166621 -0.2391107 0.0194870 0.0833079 0.9672157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7306 7307 0.499064 -0.561397 -0.572790 0.4914736 0.2357382 -0.8278208 0.1326422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7307 7308 0.515515 0.918036 -0.284464 -0.3097548 -0.1264344 -0.5307227 0.7787167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7308 7309 -0.567898 0.700610 0.387298 0.4868118 -0.1119284 -0.8209601 0.2766059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7309 7310 -0.404466 -0.514736 0.721237 -0.6689926 -0.1371994 0.7301240 0.0233276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7310 7311 -0.664360 0.393422 0.785534 -0.1067094 -0.6902393 0.3126001 0.6437888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7311 7312 0.902887 0.176267 0.806055 -0.1098565 0.3705578 -0.3014360 0.8716391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7312 7313 -0.109063 0.252924 0.984308 -0.1480667 0.1038929 0.9394648 0.2910126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7313 7314 -0.044634 -0.295575 0.913789 -0.2957117 0.0332366 0.6423973 0.7062405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7314 7315 -0.413659 -0.090005 0.952684 0.1421072 -0.1173852 -0.9696581 0.1605908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7315 7316 0.301556 0.145029 0.880004 -0.4908583 -0.7996955 0.0426730 0.3431097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7316 7317 0.322837 0.085147 -0.997432 0.2709176 -0.3079328 0.4530630 0.7915270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7317 7318 -0.512798 -0.309981 -0.510776 0.7550266 -0.2330954 0.2999205 0.5344615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7318 7319 -0.733981 0.307608 0.443866 -0.7627681 0.5359442 -0.0247329 0.3610220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7319 7320 -0.483903 0.570328 0.745442 0.3775563 -0.4713494 -0.4913343 0.6275919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7320 7321 0.488775 0.680930 -0.484120 -0.2947784 0.7604142 -0.5758334 0.0573749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7321 7322 -0.952968 0.281118 -0.209758 0.4831402 -0.5507613 0.5960006 0.3286651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7322 7323 0.023137 0.927790 -0.429761 0.2494448 0.6010118 -0.2002194 0.7324441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7323 7324 0.538460 0.468162 -0.443442 -0.5860299 -0.5761690 0.5211576 0.2302022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7324 7325 0.790654 0.538646 -0.764688 0.0129236 0.2218132 -0.7894341 0.5722113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7325 7326 -0.627701 0.656967 -0.497113 0.0105325 -0.0848941 -0.1686733 0.9819528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7326 7327 -0.845357 0.424257 -0.434997 -0.6277696 0.2922371 0.1442843 0.7068839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7327 7328 -0.482330 0.827444 0.030266 -0.3008392 -0.3012795 0.1469629 0.8928205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7328 7329 -0.152552 0.472987 0.822740 0.5823676 -0.6141418 -0.0512957 0.5301383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7329 7330 0.046273 0.773245 -0.723991 -0.5046720 0.4315344 0.5614533 0.4938162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7330 7331 0.683192 -0.227307 0.704184 0.1065357 -0.8820014 0.3595447 0.2853966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7331 7332 -0.148951 -0.769392 -0.601048 0.0691700 0.1469216 -0.9859567 0.0389731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7332 7333 0.339800 0.954702 -0.352013 0.3103492 0.3055545 0.8256254 0.3586956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7333 7334 0.256501 -0.911568 0.125726 0.3248280 0.6457453 0.3545656 0.5931129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7334 7335 -0.800878 -0.321838 0.598375 -0.2350007 -0.7607723 -0.6003846 0.0744214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7335 7336 0.835279 -0.006688 -0.668444 -0.0448444 0.3710735 -0.1147294 0.9203970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7336 7337 0.888134 0.295923 0.182123 0.1739580 0.0265944 0.9500275 0.2578354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7337 7338 -0.581296 -0.692318 0.677173 -0.3715284 0.7128120 0.1451277 0.5768914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7338 7339 -0.191634 -0.314040 -0.874020 -0.0037110 0.4901711 -0.1490069 0.8587872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7339 7340 0.565863 0.185656 0.782349 -0.2059014 -0.1281822 0.5056871 0.8279218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7340 7341 -0.235623 0.278579 0.842909 -0.0787805 -0.3168707 -0.5595405 0.7617749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7341 7342 0.238735 0.086546 0.860185 -0.1460167 0.5572753 -0.0900833 0.8124090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7342 7343 -0.920730 0.003075 0.777940 -0.3863349 -0.1119559 -0.9140786 0.0516859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7343 7344 0.973108 -0.088796 -0.000059 -0.1677489 0.4898171 0.8535704 0.0579398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7344 7345 -0.810682 -0.355466 -0.253921 0.4888789 -0.0435462 0.6383030 0.5930181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7345 7346 -0.684046 0.611288 -0.287251 0.1358483 -0.3704320 -0.2970495 0.8695326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7346 7347 -0.950502 -0.310019 0.064578 -0.0362115 0.3478747 -0.0244077 0.9365235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7347 7348 -0.713801 -0.087600 -0.357787 0.1331802 -0.0152371 -0.7801603 0.6110489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7348 7349 0.693576 -0.751446 -0.255949 0.3136750 -0.3840066 -0.6898894 0.5274463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7349 7350 0.597828 0.047804 -0.707670 -0.2883885 -0.4716114 -0.7254280 0.4100841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7350 7351 -0.871381 0.126471 -0.288620 -0.8651636 -0.1965649 -0.0219451 0.4608389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7351 7352 -0.933025 -0.313227 0.441035 0.4198610 0.0753122 -0.8962493 0.1215811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7352 7353 0.206268 -0.014563 0.953902 0.0557623 -0.1233820 0.7619302 0.6333481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7353 7354 0.082521 -0.512540 0.985694 0.2226191 0.5497198 -0.0257715 0.8047264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7354 7355 -0.926957 -0.205566 0.533295 -0.3650491 0.5596677 0.1908414 0.7190903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7355 7356 -0.683215 0.122634 -0.705454 -0.6501769 -0.1901423 0.4318594 0.5954942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7356 7357 -0.122108 0.913565 0.578107 0.2754162 -0.7418024 0.1502003 0.5927183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7357 7358 0.686548 0.646485 -0.572309 -0.5315413 0.7152268 -0.0035123 0.4537644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7358 7359 -0.184934 0.106953 1.107727 -0.2855357 -0.7740040 0.2551463 0.5042693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7359 7360 -0.573414 -0.140653 -0.934310 -0.5485662 -0.4700349 0.4646774 0.5120715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7360 7361 0.618363 -0.453882 0.807488 -0.2762960 -0.3276739 0.8771645 0.2165014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7361 7362 -1.120029 -0.488393 0.328310 -0.2193845 0.0611386 0.4835571 0.8451657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7362 7363 -0.772969 0.566940 0.178662 0.2063202 0.0050208 0.9744857 0.0882293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7363 7364 0.884126 -0.409245 0.076348 0.3278502 0.4659341 0.7768308 0.2682415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7364 7365 -0.792980 -0.123386 0.615920 0.1015973 0.4593438 0.6409786 0.6064881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7365 7366 0.075226 0.966292 -0.290143 0.2825177 0.3865163 -0.8689887 0.1250900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7366 7367 0.202381 -0.625967 -0.871102 -0.7665675 -0.1099773 0.5677774 0.2791203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7367 7368 0.484934 0.799100 -0.188679 -0.8144748 0.0206861 -0.1702426 0.5542746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7368 7369 0.254947 -0.228767 0.789928 -0.1949312 -0.4681768 -0.3067646 0.8054240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7369 7370 0.911823 -0.040506 0.141333 -0.4940173 -0.2256522 0.8377061 0.0572401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7370 7371 -0.691991 -0.036288 -0.657045 -0.4071266 0.2570489 -0.4328991 0.7620841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7371 7372 -0.471780 0.454311 -0.906312 -0.1849585 -0.2783847 0.5109223 0.7919916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7372 7373 0.177420 0.898005 -0.544166 0.2560516 -0.8066657 0.2115606 0.4888458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7373 7374 -0.698996 0.532755 -0.274849 0.1938686 -0.1684677 -0.9581717 0.1262562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7374 7375 0.575774 -0.894643 0.217796 0.9690717 -0.2193663 0.0122605 0.1123751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7375 7376 0.729734 0.390231 -0.110642 0.0691612 -0.4888542 -0.8539698 0.1642373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7376 7377 -0.962997 -0.203450 -0.196136 0.3611625 0.3307756 0.6520313 0.5787957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7377 7378 -0.121387 0.700659 -0.774581 0.1419866 -0.5997944 -0.3379017 0.7112727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7378 7379 -0.989122 -0.279253 0.105832 -0.0278179 0.1946265 0.6650154 0.7204868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7379 7380 -0.951083 -0.371761 0.299419 -0.0364699 0.3453994 -0.7811170 0.5188694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7380 7381 0.625564 0.406347 0.792414 0.0594116 -0.2278270 0.8682600 0.4366803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7381 7382 -0.032794 -0.831355 0.526049 -0.4328255 -0.1374645 0.8855202 0.0980793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7382 7383 -0.478769 0.862487 0.342366 0.0731953 -0.8400018 -0.3622826 0.3972289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7383 7384 0.417585 0.785095 0.657837 0.1928653 0.6948466 0.4459949 0.5301696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7384 7385 0.076036 0.898652 0.509311 0.0190615 -0.1480068 0.9530332 0.2635495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7385 7386 0.314537 -0.851208 0.299315 0.0750493 0.3280714 0.8867310 0.3169304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7386 7387 -0.948754 0.172738 -0.193148 0.5430975 0.1529595 -0.5787019 0.5888570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7387 7388 -0.258365 -0.830846 -0.034371 -0.4900120 -0.3896141 0.6909982 0.3614010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7388 7389 -0.646459 0.512923 0.404934 -0.4263264 0.1418480 -0.1054218 0.8871365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7389 7390 -1.130176 0.025294 0.306435 0.0643802 -0.8315030 0.5508600 0.0317984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7390 7391 1.024244 -0.230662 -0.001551 -0.5094521 -0.2061999 -0.8351085 0.0231085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7391 7392 -0.594077 0.451086 0.590401 -0.2035016 -0.4226962 -0.8824813 0.0337915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7392 7393 0.741790 0.266473 0.650209 -0.6135070 0.3154116 0.6804676 0.2471608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7393 7394 -0.806210 -0.718615 -0.289383 -0.1324129 0.3599539 0.9231754 0.0254410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7394 7395 0.573596 0.288402 -0.660718 0.3969266 0.4789271 0.0365775 0.7821382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7395 7396 0.965989 0.013575 -0.029177 -0.4642956 0.1866189 0.4610288 0.7328407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7396 7397 0.577491 -0.925520 0.152220 0.4681578 -0.5713437 -0.4588147 0.4938459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7397 7398 0.766046 -0.237474 -0.369463 -0.6478338 0.4234425 -0.0092069 0.6331848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7398 7399 0.799513 -0.115095 0.485151 -0.2795185 -0.3035368 0.5559141 0.7215915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7399 7400 -0.813303 0.061245 -0.323169 0.4342520 -0.0522759 -0.6270961 0.6445486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7400 7401 -1.088626 -0.010714 -0.066896 0.0549316 0.2403362 -0.9670848 0.0629919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7401 7402 1.097602 -0.022603 0.114343 0.3354329 0.3893001 -0.8019793 0.3045642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7402 7403 -0.495864 0.799745 -0.296698 -0.0015127 -0.0115941 -0.0075876 0.9999029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7403 7404 -0.496228 0.903890 -0.383560 0.2521431 -0.3926204 -0.8731247 0.1411605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7404 7405 0.096253 -0.820939 0.545194 0.0975870 -0.1642255 0.9309853 0.3110839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7405 7406 -0.519425 0.164936 0.838734 0.0978818 0.7962582 -0.4906187 0.3401254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7406 7407 -0.273125 -0.806892 -0.831311 0.0349650 -0.6774202 0.4692427 0.5654119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7407 7408 -1.029560 0.181867 0.624787 -0.5711872 0.1097510 -0.1996010 0.7885806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7408 7409 -0.572764 -0.675093 0.015556 0.2343122 0.1813980 -0.9546373 0.0293279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7409 7410 0.609084 0.299100 0.749211 -0.5057459 0.2112483 0.2895448 0.7847031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7410 7411 0.026641 -0.843327 0.601514 0.0156098 0.1022563 0.6888766 0.7174601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7411 7412 -0.783638 0.063902 0.754745 -0.4491497 0.3758598 0.2201679 0.7800770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7412 7413 -0.886490 0.389469 -0.036032 -0.3346578 -0.4346088 -0.8356020 0.0298108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7413 7414 0.891015 -0.374873 -0.408622 -0.3696627 -0.0453772 -0.6489315 0.6634593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7414 7415 0.622715 0.876804 -0.178126 -0.3299532 0.5722971 0.6563982 0.3643463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7415 7416 0.083613 -0.386198 0.626631 0.2477539 -0.8628937 -0.1219985 0.4232598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7416 7417 0.949703 -0.096636 -0.431138 -0.7365424 -0.0953251 -0.5235951 0.4174526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7417 7418 -0.078782 0.948449 0.452230 -0.3356531 0.1296112 -0.9317839 0.0481316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7418 7419 0.213270 -1.135315 0.037940 -0.2180042 -0.0840853 0.8511825 0.4699918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7419 7420 0.033653 -0.574130 -0.833820 0.4191331 -0.3485621 -0.3860885 0.7441556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7420 7421 0.688854 0.491583 -0.634935 0.4433649 0.0016458 0.6022669 0.6638520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7421 7422 0.374445 -1.189799 -0.047984 0.5762090 0.2681789 -0.1640098 0.7544296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7422 7423 -0.023763 -0.349445 0.967622 -0.4334732 -0.4195794 -0.6512298 0.4603844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7423 7424 1.004211 0.363500 0.199276 0.2057905 -0.4030164 -0.6909621 0.5637371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7424 7425 -0.591368 0.707930 -0.473884 0.4849001 -0.0917930 -0.8688737 0.0387867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7425 7426 0.727592 -0.722386 0.269370 0.0953013 -0.7408608 -0.4323119 0.5051231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7426 7427 0.122215 -0.040287 -1.001270 -0.0140913 0.3078275 -0.1901243 0.9321461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7427 7428 0.763622 0.132265 -0.432599 -0.6596134 0.0434827 -0.5810162 0.4748048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7428 7429 -0.175098 0.801304 0.732593 -0.5176421 -0.1570584 -0.7085770 0.4530981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7429 7430 0.244516 -0.841029 0.607442 -0.2845925 0.0649758 0.2690589 0.9178195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7430 7431 -0.456497 -1.092176 0.010742 -0.2145674 0.0976512 0.9392452 0.2494864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7431 7432 -0.128623 0.891335 -0.160102 0.1788452 0.1833840 -0.6584082 0.7077311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7432 7433 -0.748127 -0.358531 -0.785654 -0.1798251 -0.2317958 0.9545278 0.0530122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7433 7434 1.000933 0.330674 -0.107115 -0.0354907 -0.7493532 -0.1868331 0.6342741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7434 7435 -0.341384 0.684097 -0.843198 -0.0622072 0.0539984 0.9907444 0.1078885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7435 7436 0.587352 -0.436485 -0.738939 0.7031746 0.0491371 -0.5111600 0.4917789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7436 7437 1.031019 0.274921 -0.036131 0.0331357 -0.2080023 0.1430634 0.9670419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7437 7438 0.958234 -0.119538 -0.344567 -0.4066967 -0.3091440 0.2796277 0.8129183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7438 7439 0.568276 -0.012033 -0.951976 0.3328533 -0.5640144 0.7490515 0.1000911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7439 7440 0.441453 0.920256 0.395208 0.2633534 0.2179059 0.8529598 0.3944890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7440 7441 -0.733419 -0.350695 0.610065 0.2084309 -0.1020069 -0.9245852 0.3021480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7441 7442 0.592999 -0.047470 0.916766 0.3070839 0.1674717 0.4606859 0.8157335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7442 7443 0.219049 0.139715 0.961287 -0.8369685 -0.5254211 -0.0723787 0.1348243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7443 7444 0.328152 -0.166831 -0.902635 -0.5225389 -0.1937599 0.8302923 0.0049977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7444 7445 0.586027 0.538204 -0.677764 -0.3055009 -0.4908392 0.2915537 0.7620646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7445 7446 0.395173 0.930281 -0.575794 -0.5259823 0.4690598 -0.0869268 0.7041089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7446 7447 0.115785 0.770650 0.668929 0.1234734 -0.0968796 -0.2249708 0.9616428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7447 7448 -0.361181 0.554408 0.473066 0.2412195 0.4608858 -0.0824747 0.8500561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7448 7449 -0.603573 0.888712 -0.433083 -0.0430377 0.0721374 0.6288144 0.7730048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7449 7450 0.557304 0.727136 -0.276376 0.2283208 -0.6930550 0.0300523 0.6831114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7450 7451 -0.310629 0.521156 -0.857954 0.5826257 0.4800215 0.6189163 0.2169545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7451 7452 0.076126 -1.110719 0.049057 0.3835657 0.7298629 0.1271397 0.5513738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7452 7453 -0.581877 -0.662143 0.154509 -0.3199719 -0.2216399 0.9203606 0.0378171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7453 7454 0.321845 0.560309 1.071761 0.2503686 0.6438965 -0.7182642 0.0825197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7454 7455 -0.578713 -0.714466 -0.339705 0.1962098 0.3393466 0.7646548 0.5115159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7455 7456 -0.344537 0.171341 -0.935035 -0.0596636 -0.5016689 -0.8462022 0.1694414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7456 7457 0.100410 -0.866982 -0.223932 0.3285262 0.6506163 -0.6730068 0.1258206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7457 7458 -0.159775 0.400388 0.812115 0.8659531 -0.3163499 0.3473198 0.1715135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7458 7459 0.562065 0.016548 -0.922299 0.4071773 0.4388508 0.7147354 0.3616211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7459 7460 0.539578 -0.297512 -0.892370 0.1084216 0.4657225 0.4660964 0.7443799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7460 7461 0.804623 0.233877 0.547879 0.0207858 -0.6375739 0.6857892 0.3503720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7461 7462 -0.449203 -0.930710 -0.488994 -0.1226550 0.5927913 0.4578269 0.6511135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7462 7463 -0.150998 -0.266785 -0.998865 0.3417235 -0.2202397 0.6285718 0.6630362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7463 7464 -0.950100 -0.171879 -0.307638 -0.3560050 0.2605609 -0.7117179 0.5466498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7464 7465 0.215620 -0.244355 -1.078277 0.4832908 -0.1775320 -0.5735965 0.6371024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7465 7466 0.671977 -0.539319 -0.622760 -0.4087032 -0.1627097 -0.8880796 0.1334242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7466 7467 -0.588263 0.713180 -0.275090 0.4161597 0.3212706 0.8472774 0.0756125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7467 7468 0.616183 -0.682504 -0.157361 0.1725809 0.5082100 -0.0305533 0.8432111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7468 7469 0.316236 -0.751264 0.533651 0.4319497 0.0179456 0.6372577 0.6379655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7469 7470 -0.434588 -0.096936 0.853343 -0.4508873 0.6932692 0.4950180 0.2665252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7470 7471 -0.712256 0.557726 -0.421365 -0.0524404 -0.1732484 -0.8015478 0.5698738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7471 7472 -0.496037 -0.965569 -0.053839 0.7434588 0.5739667 0.0234036 0.3424670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7472 7473 -1.037851 -0.255231 0.382258 -0.3458691 -0.7550966 -0.2747278 0.4844877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7473 7474 0.662992 -0.685212 -0.226013 -0.2180821 0.5683581 -0.5026509 0.6138007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7474 7475 0.524233 -0.310087 0.751518 0.4173647 0.2854272 -0.5049770 0.6995258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7475 7476 -0.343709 0.763553 0.555799 0.7079386 0.3330043 -0.5675614 0.2565251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7476 7477 -0.508938 -0.845861 -0.238877 -0.4448074 -0.7049679 0.2929940 0.4683175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7477 7478 -0.685872 0.074781 0.580398 0.0742371 0.0185927 0.1606698 0.9840368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7478 7479 -0.741775 0.196788 0.571222 0.5635608 0.1439299 0.4066337 0.7045087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7479 7480 0.597549 0.536919 0.496321 0.1350410 0.6073856 0.7706484 0.1376503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7480 7481 -0.439701 0.670283 -0.456271 -0.3939810 0.2306752 -0.7857794 0.4172753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7481 7482 -0.680407 -0.060952 -0.684526 -0.0055918 -0.3302414 -0.8376776 0.4349778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7482 7483 0.267355 -0.716842 -0.574725 -0.3191979 -0.0979521 -0.9120357 0.2381364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7483 7484 -0.149024 0.904954 -0.549114 -0.1954649 0.0600123 0.2444544 0.9478576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7484 7485 0.098288 0.833741 -0.167754 -0.6193272 -0.1344547 0.7578820 0.1548246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7485 7486 0.352881 -0.884468 -0.305640 0.6280104 0.3308145 -0.4231065 0.5631569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7486 7487 0.221357 0.217511 0.779928 -0.6263036 -0.5432505 0.5062489 0.2373494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7487 7488 0.076909 -0.442285 -0.855419 -0.3416912 -0.7971348 0.4294178 0.2518406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7488 7489 -0.542315 0.516141 0.804209 0.0583500 0.3221001 0.1213237 0.9370845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7489 7490 -0.705759 0.767473 0.297379 0.4170905 -0.5340411 -0.2479313 0.6923624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7490 7491 -0.918436 0.571478 0.586735 0.4389031 0.4980408 -0.1334191 0.7358796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7491 7492 -0.552106 0.117254 -0.839418 -0.4037474 -0.2037347 0.1847433 0.8725538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7492 7493 -0.496431 0.905633 -0.076636 -0.3070200 -0.3652432 -0.6583632 0.5821461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7493 7494 -0.582957 -0.584412 0.682455 -0.0060935 0.1535377 0.4271963 0.8910064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7494 7495 -1.042659 0.118693 0.339206 -0.3099676 0.6493969 0.2073308 0.6627350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7495 7496 -0.319956 0.648704 -0.546844 -0.4428712 -0.1790607 0.8364238 0.2686961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7496 7497 0.913846 -0.154411 0.310623 -0.2633962 0.1547636 0.2378816 0.9219995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7497 7498 0.566819 -0.624368 0.328052 -0.2687356 0.6660687 0.5191724 0.4632425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7498 7499 -0.638518 -0.719150 -0.534242 -0.0830539 -0.9003759 0.1766176 0.3888850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7499 7500 0.812517 -0.706063 -0.243478 -0.1683254 -0.0434336 -0.7730829 0.6100188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7500 7501 -0.656788 0.049111 -0.802732 -0.0551497 -0.5828226 -0.7683568 0.2586585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7501 7502 0.320005 -1.081911 0.073146 -0.7152039 0.0970659 0.1200085 0.6816594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7502 7503 0.312747 0.063507 -1.061322 0.3508383 0.0659359 -0.0548570 0.9324997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7503 7504 0.481531 -0.600005 -0.661803 0.4202417 -0.1970380 -0.5407447 0.7015469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7504 7505 0.794697 -0.425894 -0.313380 -0.5790011 0.4528646 -0.3956821 0.5505517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7505 7506 0.551702 0.338996 0.814207 0.5552023 0.3035019 -0.6692258 0.3895816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7506 7507 -0.804497 0.291296 -0.564442 -0.2909241 -0.4194597 -0.5300705 0.6770834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7507 7508 -0.610937 -0.662155 0.321502 0.3527714 0.1742773 0.3354236 0.8559619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7508 7509 -1.019728 0.267511 0.280550 0.5560032 -0.0760181 -0.7427314 0.3652831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7509 7510 0.115342 -0.605381 0.775096 -0.1708678 -0.0771862 0.5859124 0.7883864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7510 7511 -0.538927 -0.550133 0.831441 -0.5339267 0.6643747 0.2551369 0.4565454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7511 7512 -0.333037 0.251450 -0.932146 0.6626557 -0.4683231 -0.4664055 0.3521743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7512 7513 -0.148523 -0.564311 0.509954 0.2184144 0.2251316 0.9374820 0.1507925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7513 7514 0.079878 0.995607 0.247155 -0.0304121 0.4657382 0.7542069 0.4618820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7514 7515 0.635709 0.133890 0.689288 -0.4153271 -0.2153317 -0.4518724 0.7595703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7515 7516 0.808104 0.171329 0.227795 0.5064526 -0.1398279 0.8361055 0.1577391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7516 7517 -0.063263 -0.484734 0.847081 -0.1652661 -0.0256773 -0.2653320 0.9495403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7517 7518 0.530006 -0.608648 0.422971 0.0664623 -0.1354793 -0.9842536 0.0920491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7518 7519 -0.375149 0.934496 0.207840 -0.0160457 -0.4927021 -0.8567323 0.1516475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7519 7520 -0.654752 0.576032 0.140478 0.8881874 -0.1024502 0.4339003 0.1111648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7520 7521 -0.814311 -0.234557 0.310604 0.7848536 -0.1882956 0.3547959 0.4718787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7521 7522 -0.507089 0.940532 0.034738 -0.3121025 0.0074648 -0.5818124 0.7510198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7522 7523 -1.091425 -0.194701 0.206141 0.2309073 -0.3854784 -0.6495093 0.6133725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7523 7524 0.352404 -0.422088 0.836180 0.1388501 0.0736636 -0.9831552 0.0932744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7524 7525 -0.371590 0.443933 0.560010 -0.1301648 -0.0702543 -0.1698326 0.9743092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7525 7526 -0.340622 -0.041384 0.838938 0.6665098 0.2248708 -0.3606130 0.6124998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7526 7527 -1.089905 0.308233 -0.013172 -0.4272497 -0.5782828 -0.6794034 0.1464848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7527 7528 0.746603 -0.519453 -0.258209 0.1926970 0.4682926 0.4314352 0.7466147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7528 7529 -0.333057 -0.775050 0.669665 0.0026198 0.4059306 -0.8002328 0.4414080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7529 7530 0.505517 -0.208032 0.815250 0.2392189 -0.7067183 0.3884233 0.5407873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7530 7531 0.397016 -0.762079 -0.168102 0.0594913 0.8824220 0.1054608 0.4546099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7531 7532 -0.177275 -0.793217 0.380694 -0.0580817 -0.1661297 -0.8219716 0.5416549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7532 7533 0.996709 -0.004922 -0.032640 -0.1275272 0.7923205 -0.5899299 0.0891501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7533 7534 -1.001469 -0.032629 -0.003113 0.0616226 -0.8643205 0.4037745 0.2934601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7534 7535 0.798103 0.173531 0.508454 -0.6892346 -0.4470074 0.5636560 0.0862087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7535 7536 -0.405388 0.260154 -0.932369 0.2482230 0.3378998 -0.8698692 0.2598780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7536 7537 0.920681 0.262722 -0.542342 0.4412568 0.1719297 0.7865050 0.3964119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7537 7538 -0.520632 -0.875296 0.489473 -0.1823807 -0.5246467 -0.8025331 0.2177698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7538 7539 0.747883 0.418187 -0.668043 -0.1179778 -0.5517346 0.7632701 0.3147837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7539 7540 0.483347 -0.641666 -0.619228 -0.3582719 -0.9124676 -0.0045758 0.1975427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7540 7541 -0.276778 0.201906 -1.138289 0.6024057 -0.2688783 0.3274547 0.6764505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7541 7542 -0.995015 -0.351809 0.031741 -0.0947188 -0.2356418 0.0429912 0.9662572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7542 7543 -0.901480 -0.333313 0.541897 0.6842604 -0.1270421 0.5960106 0.4005238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7543 7544 0.107896 1.010861 -0.498532 0.6893582 0.2591931 0.5845359 0.3404732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7544 7545 0.261215 -0.852343 -0.113942 0.3242587 -0.2861385 0.5170449 0.7386783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7545 7546 -0.589520 -0.536506 0.449301 0.7912303 0.2715277 0.0632196 0.5442707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7546 7547 -0.800954 0.519386 0.057329 -0.8012510 0.0856465 -0.5910923 0.0356579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7547 7548 -0.382105 -0.419582 -0.846689 -0.4551348 0.6713239 0.0081696 0.5849016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7548 7549 1.053216 0.227826 -0.285313 0.8076014 -0.1474804 0.2862426 0.4940594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7549 7550 0.566350 -0.782478 -0.087444 -0.6496890 -0.0500993 -0.7446375 0.1446003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7550 7551 0.258801 0.972499 0.420639 -0.4051736 0.6053910 0.1517822 0.6680556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7551 7552 -0.465894 0.237688 0.762902 0.7467668 0.1315873 0.2799657 0.5887643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7552 7553 -0.091228 0.583340 -0.500970 -0.6683378 -0.1476666 -0.0598173 0.7265955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7553 7554 -0.173371 0.653205 0.661989 0.0013748 -0.5747990 0.5202853 0.6315912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7554 7555 1.179866 -0.251291 -0.238180 0.3005970 0.2280656 0.6330912 0.6758869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7555 7556 0.201144 -0.727595 0.555166 -0.5602532 -0.3560190 -0.7114980 0.2305155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7556 7557 0.502110 0.738302 -0.417428 -0.5765877 -0.2607128 -0.7392802 0.2303047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7557 7558 -0.459142 -0.265624 0.654924 -0.1088501 -0.1934347 -0.6232432 0.7498684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7558 7559 0.400330 -0.836669 0.573426 -0.2674582 -0.7509409 -0.0279247 0.6031368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7559 7560 -0.504898 -0.651808 0.533195 -0.3518397 0.5401494 -0.7615788 0.0666722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7560 7561 0.382388 -0.688679 -0.436685 0.6288833 -0.1182521 -0.6691426 0.3778497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7561 7562 1.059111 0.328354 0.130134 0.3376104 0.6279297 0.7012289 0.0012293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7562 7563 -0.702193 0.042772 0.714909 0.1095388 0.5045577 0.4745536 0.7128966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7563 7564 -0.118944 0.979231 -0.077592 0.3410767 0.4198850 -0.8183148 0.1942274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7564 7565 0.071855 -0.500234 -0.707727 0.3188574 -0.2140333 0.7443523 0.5463144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7565 7566 -0.891529 -0.080098 0.000175 -0.0782694 0.7210633 0.6643517 0.1804948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7566 7567 0.872242 0.273271 -0.324744 -0.1178059 -0.6719342 -0.4107905 0.6048780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7567 7568 -0.617745 0.714426 -0.296823 -0.7167706 0.5965040 -0.0752561 0.3532130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7568 7569 -0.484542 0.677001 0.384317 0.5202771 0.3831902 -0.7076725 0.2857913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7569 7570 0.010658 -1.018573 -0.299521 -0.1220963 -0.1081222 0.8780159 0.4499891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7570 7571 -0.861297 0.558019 -0.166411 0.4995076 0.3128943 -0.6195617 0.5183942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7571 7572 -0.066188 -1.084474 -0.191102 0.1497371 -0.3420080 -0.9276440 0.0092671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7572 7573 0.150161 0.591573 -0.863312 -0.7284682 -0.5095152 -0.4518164 0.0747682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7573 7574 -0.311666 -0.367415 0.923148 0.1101615 0.4101197 0.9040827 0.0479654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7574 7575 0.416938 0.730572 0.350017 0.7874234 -0.2422068 -0.5520223 0.1287311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7575 7576 -0.721739 -0.444488 -0.155159 -0.7160417 0.4081451 0.2665550 0.4996502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7576 7577 0.253682 0.908731 -0.547267 -0.6010303 -0.6869527 -0.0816665 0.4002363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7577 7578 0.578619 0.626576 0.895594 -0.0698475 0.2812516 0.5721917 0.7672128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7578 7579 0.135813 0.023322 0.801899 -0.0478603 -0.2179765 0.0163857 0.9746421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7579 7580 -0.387126 0.622699 0.442936 0.5549561 0.1991523 -0.0261856 0.8072647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7580 7581 -0.355892 -0.590233 -0.702336 -0.1533702 0.1557306 0.9438216 0.2478436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7581 7582 0.059970 0.816908 -0.735259 -0.4795862 -0.4494286 -0.7368737 0.1582026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7582 7583 -0.305938 -0.823992 0.417669 -0.3913627 0.0360738 -0.9017709 0.1798420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7583 7584 0.844912 0.532544 -0.039671 0.6120145 -0.0218459 0.6420132 0.4612809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7584 7585 0.494247 -0.987366 0.449218 0.1342794 0.6964659 0.5349907 0.4590091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7585 7586 -0.818516 -0.114069 -0.302304 0.3109342 -0.3119607 -0.7367619 0.5130130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7586 7587 0.208257 -0.773823 0.451840 -0.7505991 0.0000009 0.1707140 0.6383241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7587 7588 0.030430 -0.478664 -0.805333 0.6114773 -0.3842936 0.6177457 0.3111337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7588 7589 -0.885632 0.582282 0.347026 0.1918924 0.2745828 0.5318481 0.7777655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7589 7590 0.183968 0.874640 -0.194534 -0.3553608 0.6163382 0.0122934 0.7026342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7590 7591 -0.122650 0.716510 0.685906 0.0709063 -0.1524854 -0.2995154 0.9391544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7591 7592 -0.652864 0.370571 0.685676 0.4597124 0.3277480 0.8250677 0.0225647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7592 7593 0.971525 -0.238220 -0.073657 0.1849869 -0.7053623 -0.4724942 0.4949678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7593 7594 -0.167140 0.312970 -0.978742 0.7020707 -0.3049287 -0.5581010 0.3203724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7594 7595 0.387540 -0.683914 0.363250 0.2248824 -0.4698530 -0.8535111 0.0135971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7595 7596 -0.151042 0.656528 -0.720571 -0.1137547 -0.4594149 -0.7817589 0.4060183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7596 7597 -0.549343 -0.735916 0.150726 0.1728010 -0.1378764 -0.8806609 0.4190064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7597 7598 0.845454 0.002568 0.429614 0.3583789 -0.0684214 0.8023481 0.4723564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7598 7599 0.205030 -0.843196 0.577807 -0.0149899 -0.1132973 0.9906969 0.0738832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7599 7600 4.869460 -11.000408 -14.732640 0.4518950 0.2400324 -0.5606455 0.6510391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7600 7601 -1.066470 -0.010954 0.187794 -0.1377992 0.5184250 -0.1116185 0.8365335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7601 7602 -0.405911 -0.356406 -0.836273 0.7745506 0.1747207 -0.4239089 0.4357123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7602 7603 0.474266 -0.702004 0.545954 0.0788931 0.0006443 0.9590168 0.2721436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7603 7604 -0.670951 0.398100 0.709248 -0.5625406 0.7402340 -0.1353614 0.3424602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7604 7605 -0.329399 0.458260 -0.713256 -0.4031224 -0.6450060 0.5924630 0.2654187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7605 7606 0.599455 0.651600 0.220798 -0.4126385 0.5887818 -0.5344836 0.4442891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7606 7607 -0.846986 -0.047909 0.486399 0.1104449 -0.6773535 0.6871620 0.2383328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7607 7608 1.138041 0.017969 0.366853 -0.2802254 -0.6971668 -0.1717827 0.6371208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7608 7609 0.452066 0.426377 -0.719539 0.3783844 0.1889839 0.0745505 0.9030795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7609 7610 0.646704 -0.012722 -0.971162 0.6626988 0.1285312 -0.4723997 0.5666998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7610 7611 0.957736 0.105237 -0.166277 0.2209744 -0.3193857 -0.5027494 0.7722733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7611 7612 0.136986 0.317930 -0.744986 0.1656920 -0.9562051 0.0050951 0.2412301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7612 7613 -0.721531 0.074059 0.551155 -0.1573603 -0.1295752 -0.8725607 0.4439436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7613 7614 0.445264 -0.558540 0.451337 -0.3166271 -0.6910480 0.1480223 0.6326843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7614 7615 0.096814 -0.669844 -0.542481 -0.2033434 0.0002925 -0.6670315 0.7167429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7615 7616 0.612808 0.205773 -0.866344 -0.6880525 0.2851687 -0.4328231 0.5078649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7616 7617 -0.199116 0.759812 0.474411 -0.1829499 0.0146907 -0.9100239 0.3717122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7617 7618 -0.217548 -0.799909 0.352952 0.4405945 0.5209906 -0.1914939 0.7055320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7618 7619 -0.665506 -0.523113 0.684718 -0.4036414 -0.7001497 -0.5862563 0.0562823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7619 7620 -0.007518 1.097228 0.190109 -0.0816518 0.0541041 0.0512918 0.9938686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7620 7621 -0.921516 -0.167118 0.724748 0.0503666 0.4034772 0.6055167 0.6841190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7621 7622 -0.565059 0.860104 -0.087300 0.2604542 -0.3265263 0.7372824 0.5309979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7622 7623 0.506784 0.080628 -0.834491 0.0458880 0.8445447 0.0759819 0.5280769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7623 7624 0.561837 0.078739 0.707084 0.5122681 0.0702121 -0.7385260 0.4327019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7624 7625 -0.818598 0.689972 -0.064622 -0.3006136 -0.8041763 0.4183930 0.2964444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7625 7626 0.957351 0.337867 0.360643 -0.2858973 -0.0163405 -0.7199912 0.6321459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7626 7627 0.151673 0.708333 0.538623 0.3896743 0.1835738 -0.3917064 0.8130318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7627 7628 -0.697279 0.564598 -0.219431 -0.0279574 0.1776969 -0.4899842 0.8529699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7628 7629 -0.739978 -0.276290 -0.354594 -0.0972188 0.1641054 0.8398578 0.5081898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7629 7630 0.433028 0.691724 -0.607424 -0.2692289 -0.4818426 -0.6947879 0.4611001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7630 7631 -0.989256 0.016495 0.113041 -0.4939468 -0.2729024 0.1310208 0.8150917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7631 7632 -0.757037 -0.294144 0.600302 0.5956772 -0.1943690 0.6651914 0.4060908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7632 7633 0.606960 0.819275 -0.197355 0.2015353 0.4013340 0.4700120 0.7598706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7633 7634 1.057868 0.009109 0.293229 -0.3497989 -0.5297689 0.6368108 0.4375587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7634 7635 -0.572273 -0.429498 -0.715706 0.3287931 0.4221211 -0.8441534 0.0333757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7635 7636 0.538665 0.756111 0.170601 0.2090127 0.0559063 0.9667097 0.1366038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7636 7637 -0.339410 -1.002553 0.610511 0.0155767 0.4852885 -0.4766087 0.7328687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7637 7638 0.371150 -0.838723 0.303555 -0.1387002 -0.5580025 0.2009204 0.7931119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7638 7639 -0.095543 -0.943744 -0.330993 -0.2825471 0.7282741 0.3564619 0.5125611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7639 7640 -0.571125 0.451918 -0.590274 -0.4251352 -0.2876905 0.7435755 0.4284738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7640 7641 0.271121 -0.748623 0.652368 -0.2030349 0.6667729 0.7168046 0.0195433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7641 7642 -0.531496 0.606449 -0.779768 -0.2980122 0.1344252 -0.0974576 0.9400110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7642 7643 -0.418973 0.845555 -0.333058 -0.6040531 -0.1368347 -0.5684643 0.5415204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7643 7644 -0.844315 -0.284890 0.282695 0.5348041 -0.1658266 0.6198559 0.5497862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7644 7645 0.066154 1.094157 0.112152 0.6284554 0.0425911 0.3760433 0.6795743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7645 7646 0.345514 0.076289 -0.847352 -0.2608639 0.8300480 -0.0367716 0.4915466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7646 7647 0.370652 0.162147 0.881694 -0.7938536 0.5837283 0.1686502 0.0247983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7647 7648 -0.401026 -0.256166 -0.849427 0.4526873 -0.4234074 -0.7089991 0.3363341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7648 7649 0.698141 -0.678149 0.021326 0.6083476 -0.1448843 0.0760480 0.7766198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7649 7650 0.640666 -0.386843 0.738283 -0.3209248 0.2995076 -0.8066816 0.3956859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7650 7651 0.320378 0.095009 1.005856 -0.0784383 0.7360280 -0.5841111 0.3330532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7651 7652 -0.720362 -0.684931 0.204568 0.3804462 0.7377415 -0.1930024 0.5232096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7652 7653 -0.042267 -1.165613 0.043847 0.1786766 -0.5387111 -0.5874962 0.5768130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7653 7654 0.961426 -0.385345 -0.332138 0.6914113 0.3683588 0.5906829 0.1932769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7654 7655 -0.400771 -0.033166 0.864594 -0.0361156 0.8289821 0.4840096 0.2778832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7655 7656 0.034361 0.936282 -0.439980 -0.4252852 -0.2686687 -0.7520316 0.4259086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7656 7657 -0.642943 -0.309835 0.486445 0.3450441 0.5391314 -0.4737492 0.6048501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7657 7658 -0.222598 -0.780479 0.458423 -0.4711873 -0.4627811 0.7484877 0.0598525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7658 7659 -0.526334 0.222282 0.819155 0.2702404 0.3314388 -0.5471995 0.7195076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7659 7660 0.225983 -0.733949 -0.707927 0.7452803 0.2463221 -0.0209178 0.6192294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7660 7661 1.028732 -0.150858 -0.005883 -0.1468883 -0.8615730 -0.4042124 0.2696816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7661 7662 -0.748391 0.462299 -0.322061 0.3654302 0.3989125 0.3901286 0.7450700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7662 7663 0.253789 -0.050974 -1.063833 -0.8560586 -0.0908156 -0.3512505 0.3681566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7663 7664 -0.575924 0.434405 0.553751 0.1957038 0.7911190 -0.1631640 0.5560650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7664 7665 -0.589165 0.211840 -0.823551 0.2795894 -0.4621381 0.7507478 0.3803103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7665 7666 -0.423960 0.961531 -0.476877 -0.5145795 -0.2438756 -0.5395479 0.6201780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7666 7667 -0.963752 -0.293778 0.555513 0.4391436 0.2554396 0.8150504 0.2785614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7667 7668 0.533036 0.759042 -0.362413 0.3813635 -0.3803386 0.8024058 0.2570005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7668 7669 -0.585878 -0.724090 -0.537363 -0.1965884 0.1924598 -0.9594857 0.0608228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7669 7670 0.546414 0.742390 -0.533255 0.2119970 -0.1313850 -0.5459963 0.7998020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7670 7671 -0.433144 0.442068 -0.911979 -0.5167447 -0.5864059 -0.0503216 0.6217482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7671 7672 -0.640893 0.394543 0.568918 -0.6524905 0.0541374 -0.5302221 0.5386926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7672 7673 -0.066944 -0.833915 -0.191979 0.3347009 0.2812845 -0.8458949 0.3054770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7673 7674 0.573610 0.553841 0.506482 -0.0416223 -0.8549417 0.3608455 0.3703145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7674 7675 0.235740 0.203148 -1.028319 0.0914132 0.7605424 -0.3293884 0.5520164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7675 7676 0.749664 0.452283 0.274923 -0.5731358 -0.0874015 -0.1606085 0.7987999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7676 7677 0.930253 0.361220 0.424403 0.3568637 -0.4371245 0.2402959 0.7898281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7677 7678 0.885476 -0.271096 -0.214049 -0.1355783 0.3202230 0.3211300 0.8808809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7678 7679 0.772217 -0.674190 0.035705 -0.3888476 -0.0996722 0.7797712 0.4804371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7679 7680 -0.403631 0.727248 0.167842 -0.5788666 -0.3887959 0.6944225 0.1775629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7680 7681 -0.301212 -0.469197 -0.744435 0.0628208 -0.6945045 0.6932799 0.1818792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7681 7682 0.102323 0.699257 0.604974 0.6018327 -0.4882367 0.4533486 0.4403377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7682 7683 0.587541 -0.538862 -0.763569 0.1838912 -0.2448195 -0.6888953 0.6570166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7683 7684 0.080245 -0.182172 -1.013310 0.5589783 0.5178318 0.6466725 0.0347591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7684 7685 -0.683850 -0.550310 0.283136 -0.6138738 0.2518609 0.6546532 0.3621523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7685 7686 -0.499629 0.779308 0.176745 -0.7814377 -0.5783074 0.1448760 0.1841920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7686 7687 0.835463 -0.811531 -0.110668 0.4037583 0.4174220 -0.7493424 0.3181574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7687 7688 -0.324740 0.895827 0.571828 0.0569927 -0.1608048 0.9764585 0.1319939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7688 7689 0.369341 -0.934925 0.092907 0.4666342 0.1085746 -0.8614134 0.1686151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7689 7690 -0.085904 1.052088 0.016194 0.4510582 -0.3286863 -0.7973861 0.2295371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7690 7691 -0.386150 -0.732714 0.346263 -0.5755604 0.4644722 -0.1761523 0.6495892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7691 7692 -0.109586 -0.525036 -0.976969 0.0907913 0.4259433 -0.5634239 0.7020561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7692 7693 0.830082 0.219932 -0.323001 0.0075526 -0.1010177 0.1135023 0.9883601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7693 7694 0.862907 -0.209374 -0.471047 0.6966808 0.3897447 0.3388446 0.4979149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7694 7695 0.673887 -0.260467 0.862657 0.2633845 -0.6660680 -0.6945227 0.0679715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7695 7696 -0.275399 0.851219 -0.548322 -0.1921255 0.6543479 0.7310574 0.0217152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7696 7697 0.350094 -0.254956 0.920852 0.5050266 -0.3711436 -0.7485534 0.2164910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7697 7698 -0.482460 0.963231 -0.387542 -0.1544831 -0.1438839 -0.9768781 0.0337861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7698 7699 0.240371 -0.955171 -0.159237 0.0107812 -0.4071766 0.7679588 0.4942977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7699 7700 -0.296507 -0.156567 -0.910437 0.6989204 0.0949334 0.6897162 0.1636752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7700 7701 -0.200734 -0.413687 0.733154 -0.0513100 -0.0373112 -0.1834316 0.9809832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7701 7702 -0.134635 -0.331857 0.969771 0.1300580 0.1095326 0.9606535 0.2196188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7702 7703 0.040808 0.629127 0.641475 -0.4312130 -0.1615839 -0.8476058 0.2636483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7703 7704 0.332248 -0.564765 0.631774 -0.6457144 0.4257836 -0.2721052 0.5724683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7704 7705 0.659475 -0.774320 -0.081104 -0.5788237 -0.1305467 0.7250617 0.3495801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7705 7706 -0.453858 0.395165 -0.819522 0.2416579 -0.4557984 0.3340156 0.7888491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7706 7707 -0.914893 0.458434 -0.399629 -0.3246636 0.5771737 0.6998687 0.2676712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7707 7708 0.764677 0.503730 0.459294 -0.3306071 -0.0309411 -0.6352994 0.6972347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7708 7709 0.054778 0.296118 0.898060 0.3290965 0.3883881 0.5580036 0.6553489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7709 7710 0.354286 0.721569 0.551007 0.3497503 0.1464606 -0.9138005 0.1455769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7710 7711 -0.839338 -0.508621 -0.186477 -0.3807963 -0.1620718 -0.7178583 0.5598271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7711 7712 0.405031 -0.404704 -1.066843 0.6164960 0.6658461 -0.1192946 0.4029273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7712 7713 0.286374 -0.054193 0.783089 -0.2670865 0.1893359 0.9406704 0.0891964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7713 7714 -0.896364 0.437173 0.772045 -0.2739997 -0.2334157 0.7294606 0.5816601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7714 7715 0.072844 0.042588 0.962803 -0.2020745 -0.6656472 0.6197038 0.3633826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7715 7716 0.111852 -1.026146 -0.169998 0.2651941 0.4585026 -0.8112164 0.2477406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7716 7717 0.243424 0.545971 0.755074 -0.0513248 -0.9525254 0.1510211 0.2593332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7717 7718 0.317103 0.234522 -1.128002 0.3120064 0.1021560 0.7993427 0.5032568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7718 7719 -0.187827 -0.689289 -0.707732 -0.2813597 0.2718576 -0.7360685 0.5523887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7719 7720 -0.307176 -0.325130 -0.715120 -0.0732171 -0.8594117 0.4384269 0.2526510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7720 7721 0.494086 -0.548457 0.397080 0.7693183 0.2977161 -0.5512178 0.1251935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7721 7722 -0.502077 0.757715 -0.521778 0.2827281 -0.5723522 -0.0970897 0.7635780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7722 7723 -0.773843 0.629803 0.184359 -0.0262478 0.3543143 -0.6304779 0.6901232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7723 7724 -0.353376 -0.748306 -0.506526 0.4466491 -0.5683705 0.2492493 0.6444645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7724 7725 -0.438109 -0.317897 0.917516 -0.2959186 -0.7554248 -0.2985090 0.5026510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7725 7726 0.995156 -0.314949 -0.094734 -0.7656587 -0.0151658 -0.6175319 0.1794188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7726 7727 0.262402 0.548288 0.820730 0.3772272 -0.0030145 -0.7829017 0.4947277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7727 7728 -0.816300 0.131576 0.398794 0.0251837 -0.1290886 0.2461392 0.9602695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7728 7729 -0.688504 0.837994 0.520314 0.1604217 0.9668461 0.1426592 0.1382817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7729 7730 0.822069 0.556937 -0.390200 -0.2595367 -0.0585074 -0.6551763 0.7070796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7730 7731 -0.628420 0.736056 0.023125 -0.0281589 -0.2776743 -0.3791679 0.8822334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7731 7732 -0.849236 0.114750 0.576437 0.4554756 0.5438326 0.0389721 0.7037537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7732 7733 -0.844850 0.010790 -0.692128 0.6192605 -0.4615753 0.1004137 0.6272016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7733 7734 -0.958060 -0.078403 0.468468 -0.1971469 0.5827873 0.6164493 0.4914085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7734 7735 -0.094704 0.844123 -0.270573 -0.6127016 0.1795196 0.2536822 0.7266463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7735 7736 0.319356 0.569187 0.923615 0.1473685 -0.6858087 -0.3077011 0.6428600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7736 7737 0.259326 0.724395 -0.134518 0.4788270 0.4412299 -0.6484235 0.3944462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7737 7738 0.109006 0.175581 -0.981211 -0.1941216 -0.5511348 -0.8113678 0.0157998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7738 7739 -0.309295 -1.047303 -0.099521 0.2900880 0.6115826 0.4619120 0.5731082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7739 7740 0.342928 -0.765512 0.422244 -0.6672586 0.0190037 0.1869771 0.7207249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7740 7741 0.775768 -0.760177 0.183928 -0.0272287 -0.6806696 0.7204659 0.1299090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7741 7742 -0.591830 -0.294860 0.639653 0.7276346 -0.4026730 0.4936111 0.2544611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7742 7743 0.507785 0.891284 -0.326549 0.3402909 -0.7335025 0.5346068 0.2457066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7743 7744 -0.800294 -0.050362 -0.533690 0.6325312 -0.2035734 -0.1501682 0.7320599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7744 7745 -0.660917 -0.599747 0.267846 -0.4599329 -0.1836630 0.1534169 0.8550982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7745 7746 -0.773837 -0.654061 0.032896 0.2120635 0.8970325 -0.3855385 0.0414948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7746 7747 0.581107 -0.533188 0.551045 0.5432540 -0.7261012 0.2990584 0.2970120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7747 7748 0.647746 -0.737378 0.289410 -0.4988262 -0.0752960 -0.4909684 0.7102485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7748 7749 0.787309 0.293791 -0.153636 -0.3885971 0.2371465 -0.3536111 0.8171371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7749 7750 0.214304 0.720099 0.445993 -0.2960007 0.4789313 -0.7949652 0.2259176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7750 7751 -0.415936 -0.813133 0.146252 0.1897179 0.1290255 0.6703605 0.7056744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7751 7752 -0.632181 0.515960 -0.240400 0.1559194 -0.0089366 -0.8564219 0.4920882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7752 7753 0.049314 -1.169140 0.116947 -0.6238962 0.0644900 0.5090727 0.5894401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7753 7754 -0.452064 0.257622 -0.570187 0.0960746 -0.5984001 0.6457317 0.4644541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7754 7755 -0.080198 1.003635 -0.094122 -0.4945818 0.3581997 -0.5396822 0.5795041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7755 7756 -1.046219 0.134944 0.213758 0.3512474 0.8904826 -0.2848052 0.0505174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7756 7757 0.555298 -0.769920 -0.080908 0.7858277 0.1365744 -0.5408787 0.2669690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7757 7758 0.579150 0.925132 -0.157679 0.1049715 -0.6076796 0.1194210 0.7781035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7758 7759 0.017458 0.612357 -0.692940 -0.1888244 -0.1838559 -0.7062140 0.6571181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7759 7760 0.078484 0.699206 -0.434020 -0.3540486 -0.6093068 0.3758658 0.6017638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7760 7761 0.124558 -0.213568 -0.912641 0.5864902 0.5558928 0.1164036 0.5774622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7761 7762 0.187513 -0.852327 0.276528 -0.4442680 0.6587181 0.6064338 0.0308929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7762 7763 0.033068 0.270536 -0.961966 -0.5870414 0.3803000 0.7077350 0.0993250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7763 7764 0.763997 -0.733758 0.195468 0.2078591 -0.4446389 -0.6790851 0.5458335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7764 7765 0.320757 0.394660 -0.850882 0.1846757 0.5493839 0.3655571 0.7283133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7765 7766 0.991244 -0.313527 0.044904 -0.0865140 0.1058916 0.6500005 0.7475304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7766 7767 -0.225690 -0.885760 -0.026246 0.2293950 -0.0687078 0.2275345 0.9438672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7767 7768 -0.572116 -0.766058 0.620963 -0.6974208 -0.1996428 -0.6195905 0.2997577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7768 7769 0.494227 0.097896 -0.943060 0.2163553 0.1176015 0.7681531 0.5910170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7769 7770 -0.217510 -1.108664 -0.414863 0.2775275 0.2249229 -0.8087867 0.4671747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7770 7771 0.932102 0.262627 0.375253 -0.3117926 -0.3686094 0.8382052 0.2536230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7771 7772 -0.434871 -0.708479 -0.619202 0.2952720 0.6187578 -0.7009227 0.1966233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7772 7773 0.600927 0.284254 0.587441 0.1950938 0.2253629 0.2030060 0.9327050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7773 7774 0.529156 0.172888 0.656071 0.0181238 -0.6735898 -0.2734482 0.6864214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7774 7775 0.676384 0.825374 -0.497248 -0.1850137 0.3276445 0.8609477 0.3423275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7775 7776 0.099858 -0.841964 0.135079 -0.2192444 -0.5438325 0.5419798 0.6020266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7776 7777 -0.614695 -0.694074 0.226541 0.2557627 0.4686872 0.0626728 0.8432021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7777 7778 -0.859555 -0.267267 -0.411598 -0.3165721 0.1528904 0.8803774 0.3183431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7778 7779 0.468052 0.797329 -0.303498 -0.7626157 0.0434507 0.5418298 0.3506419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7779 7780 0.354183 0.139542 0.846701 0.4736687 -0.3274324 0.7316373 0.3648737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7780 7781 0.126765 0.090557 -0.871565 0.0265587 -0.8591849 -0.3064237 0.4089016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7781 7782 -0.771525 -0.696786 0.309904 0.2969591 -0.5120901 -0.7970682 0.1194205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7782 7783 0.681468 0.767784 0.104796 -0.3139443 0.4637978 0.7153893 0.4177903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7783 7784 -0.150752 -0.633009 0.725029 -0.7255511 -0.3682093 0.0862135 0.5749476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7784 7785 -0.592247 -0.658046 -0.701947 0.2398403 0.3211511 -0.4923884 0.7725880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7785 7786 0.800179 -0.746705 0.010091 0.3812202 -0.1922078 0.5002282 0.7533253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7786 7787 -0.092068 -1.106844 0.328324 -0.6759851 0.1587867 -0.0568931 0.7173521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7787 7788 0.084941 -0.309705 -0.745522 0.5035738 0.7329412 -0.4053149 0.2119682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7788 7789 0.405698 0.330891 0.921819 0.2787692 0.2575494 -0.5643410 0.7331270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7789 7790 -0.790715 0.343014 0.307711 0.4665308 0.7780147 -0.2566747 0.3334071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7790 7791 0.208714 -0.605791 -0.877660 -0.1419141 -0.4719743 -0.1968873 0.8475470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7791 7792 -0.537159 -0.357934 -0.814747 0.0716223 0.3726451 0.3464049 0.8579100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7792 7793 0.025524 -0.748525 -0.809404 -0.6606550 -0.3141016 0.6815890 0.0176508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7793 7794 0.413972 0.779855 0.177802 -0.0453740 -0.0863750 -0.7886898 0.6070000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7794 7795 -0.886195 0.230932 0.492233 -0.4409474 -0.1432899 -0.2222824 0.8576852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7795 7796 -0.524432 -0.858098 0.293257 -0.1703992 0.5763313 -0.2500437 0.7591340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7796 7797 -0.071771 -0.757505 -0.180772 -0.0755728 -0.1930133 -0.2486775 0.9461470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7797 7798 0.158531 -0.988542 -0.420029 -0.0742895 0.0568591 0.7942440 0.6003537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7798 7799 -0.793189 0.030997 -0.566987 0.9425816 -0.0875268 0.0734839 0.3138139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7799 7800 -0.427477 -0.183993 -0.974993 0.3764457 -0.7748391 -0.4881278 0.1401582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7800 7801 -0.552468 -0.629517 -0.466504 -0.1362466 -0.2736578 0.3227624 0.8957526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7801 7802 -1.104479 0.035726 0.236409 -0.7599554 -0.0787354 -0.5087291 0.3968164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7802 7803 -0.390158 -0.626391 -0.735767 0.4512648 -0.3862175 0.2855385 0.7521063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7803 7804 -1.036224 -0.403149 0.280423 0.8246041 0.5057873 0.1676963 0.1899610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7804 7805 -0.366497 -0.293109 -0.498475 0.6320739 -0.2497410 -0.5794516 0.4498309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7805 7806 0.684252 -0.582806 0.547835 -0.4590390 -0.6395699 0.4250920 0.4466881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7806 7807 -0.424068 -0.618643 -0.477051 -0.2772833 0.3789213 -0.2409659 0.8493928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7807 7808 0.275190 -0.140460 -0.804044 -0.0605761 -0.4909760 -0.0289333 0.8685827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7808 7809 -0.773765 -0.177391 -0.723639 0.8342049 0.3897182 -0.1484526 0.3608098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7809 7810 -0.197488 -0.931737 0.601164 0.0597310 0.6197317 0.7824303 0.0129495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7810 7811 0.104105 0.780745 -0.665205 0.0116916 -0.4929129 -0.8007012 0.3402612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7811 7812 -0.990330 -0.654040 0.173273 -0.5626913 -0.4913984 -0.6343761 0.1986782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7812 7813 0.102529 -0.289891 -1.010698 -0.2220597 0.5413249 0.4697871 0.6610271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7813 7814 0.654786 -0.590227 -0.597841 0.8468715 0.0104360 0.0621007 0.5280561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7814 7815 0.702312 -0.103122 0.742625 0.2899524 0.0790817 -0.7342746 0.6086990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7815 7816 -0.184155 0.795597 0.531459 0.5834445 -0.6783988 0.1261728 0.4283084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7816 7817 -0.194324 0.475502 -0.909930 0.0373665 0.2073486 0.9549529 0.2089864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7817 7818 0.305832 -0.649969 -0.712759 0.3388802 -0.0467820 0.6169217 0.7087872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7818 7819 -0.902198 -0.544275 -0.124331 0.1627335 0.0059571 -0.5148642 0.8416633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7819 7820 0.522164 0.195565 0.674446 -0.1594266 0.2220783 -0.7940418 0.5429198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7820 7821 -0.736788 -0.180025 -0.567963 0.8840678 0.1659932 -0.3973960 0.1815128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7821 7822 -0.107377 -0.056962 0.972345 -0.9764935 0.0243182 0.0150397 0.2136418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7822 7823 -0.063745 -0.162684 -1.009653 0.7497749 -0.3029242 -0.3391572 0.4806734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7823 7824 0.358883 -0.701832 0.386205 -0.6341533 -0.0602442 -0.7175601 0.2816517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7824 7825 0.706668 0.587105 -0.200006 -0.1854493 0.5140396 -0.5724422 0.6112952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7825 7826 -0.809850 0.576024 0.262993 0.3268679 -0.6646507 0.4239160 0.5212408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7826 7827 0.509853 0.771062 -0.501678 0.5973691 -0.4676349 0.4744812 0.4464699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7827 7828 -0.552974 -0.511443 -0.784699 -0.2258824 0.5868087 -0.4457252 0.6371512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7828 7829 0.772346 0.314020 -0.488333 0.1714356 0.6105271 0.5187802 0.5733529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7829 7830 0.036644 -0.736476 0.718826 -0.0604633 -0.7195512 -0.4560660 0.5201865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7830 7831 0.853209 0.209096 -0.452279 0.3683601 -0.1074475 -0.5288925 0.7569932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7831 7832 0.228238 0.357215 -0.851337 -0.1489868 0.4071511 -0.1488789 0.8887441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7832 7833 0.794765 0.727123 -0.325343 -0.1174774 -0.8561332 -0.4798230 0.1516738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7833 7834 -0.698194 0.517306 0.468617 0.2869282 -0.1944321 0.8742925 0.3398248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7834 7835 0.805977 0.022841 -0.103717 0.0468139 0.0446633 -0.2549555 0.9647856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7835 7836 0.810037 0.859959 0.225185 0.3881299 0.4201814 0.3564266 0.7387576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7836 7837 0.769850 0.268830 0.501710 -0.2785291 -0.1735073 -0.5808650 0.7449245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7837 7838 0.087360 0.796907 0.852957 -0.3464649 -0.7628533 0.4728368 0.2728410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7838 7839 0.352475 -0.314633 -0.823362 0.9251874 -0.0467732 0.1636634 0.3391975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7839 7840 -1.096828 -0.573621 -0.141710 -0.0383040 0.6744938 0.5375190 0.5046427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7840 7841 0.836938 -0.561400 0.178649 0.7196107 -0.0447305 0.6928808 0.0087057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7841 7842 0.083217 0.311134 0.887705 0.7287423 0.2465376 0.4608714 0.4424381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7842 7843 0.816984 0.584182 -0.236462 -0.0287524 0.2385709 -0.7221485 0.6486592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7843 7844 -0.673775 0.781841 -0.270588 0.0855578 -0.6914475 0.1798025 0.6944431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7844 7845 -0.074823 1.131306 0.190129 0.2193744 0.4915636 0.3842891 0.7500413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7845 7846 0.599499 0.882723 0.104742 -0.1389425 0.1763014 0.2709435 0.9360568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7846 7847 0.909977 0.248294 0.440831 -0.6149547 0.1978613 -0.4968758 0.5794792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7847 7848 0.189006 -0.143820 1.025244 0.2057046 -0.2446774 0.7270293 0.6076569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7848 7849 0.349975 -0.674789 0.825858 0.3806701 -0.7433509 -0.4657984 0.2924921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7849 7850 0.178717 0.436302 -0.789002 -0.8670870 -0.2732531 -0.3160929 0.2712529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7850 7851 -0.228938 0.137598 1.020803 0.4972106 0.3846361 -0.3370762 0.7008683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7851 7852 -0.879430 0.553387 -0.142726 0.5399826 0.3175639 0.7586823 0.1788102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7852 7853 0.494231 -0.301499 -0.860844 -0.7306424 0.4894854 -0.0473462 0.4736286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7853 7854 0.822615 0.153726 0.526569 0.6830811 -0.4352808 0.4673140 0.3543283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7854 7855 0.558595 -0.782459 0.013836 -0.0631222 0.0099284 0.0441527 0.9969792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7855 7856 0.447283 -0.914752 -0.200295 -0.0993538 -0.0807942 -0.0914095 0.9875452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7856 7857 0.646584 -0.689552 -0.626524 -0.0656443 -0.1994230 -0.2216759 0.9522506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7857 7858 0.527231 -0.334296 -0.651449 -0.5036769 0.3389361 0.5877151 0.5348110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7858 7859 0.404039 -0.467798 -0.855239 -0.5549553 0.2088879 -0.7804478 0.1982214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7859 7860 -0.243561 -0.435805 0.878722 -0.1076209 0.7382072 0.6568094 0.1098605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7860 7861 -0.750722 -0.372498 -0.822622 0.1683516 -0.4405823 -0.1830024 0.8625863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7861 7862 -0.541026 -0.878861 0.326379 -0.3539185 0.4556426 0.4654377 0.6711925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7862 7863 -0.638939 0.286234 -0.755640 0.4297585 -0.1494151 -0.8756468 0.1619427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7863 7864 0.929072 -0.778120 -0.123808 0.3961240 0.0241469 -0.6953603 0.5991467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7864 7865 0.578973 0.940475 -0.213979 -0.5271792 -0.5041767 0.2325781 0.6432692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7865 7866 0.681365 0.538985 0.015608 0.3876272 0.1026240 -0.7181095 0.5687989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7866 7867 -0.556735 0.530685 -0.897879 -0.3728261 -0.0773723 0.1411927 0.9138265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7867 7868 -0.198200 1.041113 -0.006470 0.0283688 0.2111859 0.7937127 0.5697507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7868 7869 1.091296 -0.255531 0.300319 -0.0809986 -0.2215091 0.9654427 0.1108755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7869 7870 -1.002320 -0.100798 0.129578 -0.4021023 -0.1889254 0.8237892 0.3521253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7870 7871 0.471075 0.308523 0.848379 -0.4292495 0.2891961 0.5611566 0.6459209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7871 7872 -0.329493 -0.485782 0.670386 0.3535757 -0.4856883 -0.3964068 0.6942282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7872 7873 0.584335 0.392281 0.804817 -0.4198051 -0.0046323 0.6012145 0.6799142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7873 7874 0.145480 -0.745707 0.419658 -0.6987411 -0.3826044 0.5666293 0.2104901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7874 7875 -1.102885 0.067208 -0.206905 -0.3212584 -0.6469676 0.6088221 0.3279659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7875 7876 0.624104 0.431340 0.673877 0.1959454 0.6354137 -0.7452960 0.0488733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7876 7877 -0.802842 -0.538519 -0.204162 0.2822872 -0.4096465 0.0121663 0.8673844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7877 7878 -0.620790 -0.144823 0.649503 0.4904019 -0.7034920 0.2183658 0.4657481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7878 7879 0.780524 0.470700 0.348959 0.6209775 0.6660272 0.3674519 0.1891397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7879 7880 -0.315560 -0.449015 1.018546 0.3045930 -0.7108900 -0.6011973 0.2010481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7880 7881 0.896049 -0.587696 -0.127351 -0.5252330 0.1865594 -0.2331683 0.7968428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7881 7882 1.188060 -0.062360 0.025532 -0.3827962 -0.1975605 0.8244426 0.3670576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7882 7883 -0.517186 -0.504903 -0.529152 -0.6137712 0.0089214 0.7021705 0.3607795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7883 7884 0.370738 1.024089 0.213623 -0.7922318 0.0782285 0.3301345 0.5072083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7884 7885 0.452810 -0.567933 0.541850 0.5071011 -0.4747894 -0.6997116 0.1668149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7885 7886 -0.201295 0.849699 -0.601875 0.5061736 0.7464130 0.3218184 0.2882514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7886 7887 0.685998 -0.673123 0.435359 -0.3640328 -0.8779128 -0.2929602 0.1045162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7887 7888 -0.670988 0.154549 -0.729472 -0.1153904 -0.1710967 -0.3622260 0.9089572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7888 7889 -0.822551 -0.165405 -0.256331 -0.2848084 -0.7845526 -0.3013406 0.4610371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7889 7890 0.077167 -0.713747 0.707434 -0.7177737 -0.2524779 -0.4848777 0.4312186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7890 7891 0.786542 0.308327 -0.725296 0.0348787 0.6627037 0.3879652 0.6396016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7891 7892 0.705641 -0.379536 0.609944 0.5407600 -0.1004115 0.1695088 0.8177793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7892 7893 0.608037 0.124155 0.658175 0.1579809 0.6869891 0.6897349 0.1653895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7893 7894 -0.601763 0.715122 0.685694 -0.3846034 -0.5657788 -0.6215879 0.3815797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7894 7895 0.585993 -0.444204 0.637690 -0.1399839 0.1734491 0.5344996 0.8152485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7895 7896 -0.407798 -0.847554 0.426656 -0.6512736 0.3875599 -0.0746921 0.6481213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7896 7897 0.107284 -0.395288 -0.923360 0.2701393 0.0417415 0.5761798 0.7702592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7897 7898 -0.680480 -0.466623 -0.663552 0.8957105 -0.1023211 -0.2707759 0.3375108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7898 7899 -0.069736 -0.185096 1.050817 0.6401148 -0.6262877 -0.0677225 0.4398073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7899 7900 -0.477296 -0.509552 -0.799060 -0.1938423 0.8738940 0.3598075 0.2631975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7900 7901 -0.005880 0.153656 -1.020604 -0.8173773 -0.0160933 -0.2443867 0.5214504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7901 7902 -0.255684 0.806276 0.576415 -0.3070396 0.1931071 -0.6129451 0.7019506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7902 7903 -0.839967 -0.477335 0.347383 0.1460072 0.3186669 -0.0822832 0.9329324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7903 7904 -0.819566 -0.561494 0.057888 -0.1349372 -0.5610646 0.8118472 0.0888961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7904 7905 0.498532 0.139537 0.788929 0.4780536 0.5488629 0.1008863 0.6782597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7905 7906 -0.126253 0.834734 0.275693 0.1978054 0.1069938 -0.9537311 0.1995552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7906 7907 -0.301806 -0.889045 0.257778 0.2563869 -0.1889589 -0.0808850 0.9444670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7907 7908 0.005126 -0.786345 0.732813 -0.6678044 0.0796506 -0.0206934 0.7397735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7908 7909 -0.080396 -0.828066 -0.567609 -0.8224294 -0.1041830 -0.4726057 0.2989977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7909 7910 -0.558194 0.856518 0.008210 0.1334239 0.7119076 -0.3109997 0.6153575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7910 7911 0.363265 0.312773 -0.719471 -0.3545576 -0.5603623 -0.7041808 0.2537959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7911 7912 -0.802392 -0.418161 0.371843 0.7294390 -0.0166957 -0.1903596 0.6568129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7912 7913 -0.486778 0.222670 0.659605 -0.7903901 -0.1609932 0.3424207 0.4817809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7913 7914 -0.547358 -0.524345 0.623718 0.5792960 -0.1383607 0.2220830 0.7719791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7914 7915 -0.425867 0.711700 0.550036 -0.4177685 -0.2723654 -0.8666289 0.0155184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7915 7916 0.825585 -0.221504 0.444721 0.2524611 0.8373625 0.3966337 0.2788712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7916 7917 -0.927671 0.448719 0.170503 -0.1825546 0.4753311 -0.1334592 0.8502487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7917 7918 -0.698315 -0.032675 -0.623271 -0.5717924 0.6750903 0.3472473 0.3110078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7918 7919 0.607266 0.757957 0.296280 -0.3308474 -0.5144614 -0.5821473 0.5356995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7919 7920 0.843979 0.314235 -0.248933 -0.0305864 0.1730215 -0.9807736 0.0849186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7920 7921 0.035555 0.870206 -0.409308 -0.6371256 -0.3955161 -0.4164522 0.5140092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7921 7922 -0.331085 0.169364 0.858834 0.5028181 -0.0710544 0.4726696 0.7202143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7922 7923 0.314930 0.842105 0.214328 0.0525192 -0.5596015 -0.5670350 0.6021289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7923 7924 -0.669624 0.732905 0.309337 -0.6772372 0.6817568 -0.1016476 0.2573428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7924 7925 -0.714303 0.542835 -0.304536 0.6660423 0.3469675 -0.4641354 0.4696590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7925 7926 0.170174 -1.004393 -0.007456 0.8296691 -0.2486387 -0.0054108 0.4997987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7926 7927 0.362532 -0.016380 0.800908 -0.3464807 -0.1064387 -0.7036860 0.6111039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7927 7928 0.483520 -0.004756 0.819172 -0.2446549 -0.2652636 0.9252315 0.1171578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7928 7929 -0.682628 -0.695908 0.441708 -0.0024890 0.1227329 0.7965510 0.5919771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7929 7930 -0.464248 0.974092 0.119711 0.5807329 -0.1885763 0.4187075 0.6722145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7930 7931 0.135969 0.633150 -0.860226 -0.4763164 0.0344288 -0.4160242 0.7738612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7931 7932 -0.552298 0.836126 -0.206834 0.2843749 -0.3250406 0.6989241 0.5700742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7932 7933 0.504160 0.290321 -0.774582 0.1213759 0.9084689 -0.2397806 0.3200895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7933 7934 -0.071574 0.763170 0.643732 -0.8101211 0.2204430 0.5411618 0.0474617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7934 7935 -0.837178 -0.416568 -0.155460 -0.1310596 0.3058510 0.1392856 0.9326725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7935 7936 -0.780068 -0.075939 -0.978329 -0.1895140 0.3259545 0.1523915 0.9135726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7936 7937 0.126241 0.409392 -0.970068 -0.5040475 -0.6600130 -0.4037191 0.3838356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7937 7938 -0.637122 0.008156 0.660067 -0.2687795 0.6341381 -0.4839072 0.5398706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7938 7939 -0.168276 -0.814418 -0.616039 0.1489338 0.1969606 0.9121744 0.3270520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7939 7940 -0.955767 -0.014917 0.682355 -0.0390497 0.5587353 -0.1815100 0.8082970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7940 7941 -0.290701 -0.402458 0.815459 -0.0991605 0.4146624 0.6491827 0.6299080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7941 7942 -0.975511 0.474355 -0.179668 -0.7494824 0.3853780 0.5014868 0.1956296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7942 7943 -0.284742 0.392655 0.803600 0.2663179 0.9451621 -0.1845999 0.0408193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7943 7944 0.208240 -0.079502 -0.921943 -0.0055582 0.4300651 -0.6311757 0.6454691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7944 7945 0.503620 0.925934 -0.284610 -0.2235636 0.4961232 -0.8205998 0.1746341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7945 7946 -0.923860 -0.091480 -0.257867 0.1506027 0.2975681 0.9318397 0.1429924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7946 7947 0.943992 -0.068106 -0.503485 -0.0237686 0.5448630 0.8291544 0.1227285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7947 7948 -0.694100 -0.539525 -0.129879 0.0659658 0.7233728 -0.5912416 0.3504479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7948 7949 0.897234 -0.497296 0.254314 0.7221531 0.0256784 -0.6020030 0.3397468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7949 7950 0.176320 0.862651 -0.536162 -0.4846429 -0.3707199 0.6766759 0.4120651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7950 7951 0.805959 0.129213 -0.382091 0.6242743 0.3224547 -0.3648120 0.6109147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7951 7952 1.001046 0.552391 -0.237331 0.1836649 0.4027897 -0.6541067 0.6133287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7952 7953 -0.324490 0.904921 -0.446681 -0.3901281 0.3467224 0.7031468 0.4828749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7953 7954 0.454485 0.213416 0.631674 -0.1836595 0.4123747 0.5682313 0.6879894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7954 7955 -0.471221 -0.541387 0.774949 -0.2702925 -0.3266725 -0.3810269 0.8216115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7955 7956 0.596405 -0.699381 0.103415 -0.1009671 0.0190850 -0.9539095 0.2819540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7956 7957 -0.123723 1.118650 0.136534 0.1699394 0.3152582 0.1237620 0.9254274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7957 7958 0.045412 1.041831 -0.055929 -0.1880535 -0.2548022 0.7125000 0.6261434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7958 7959 0.885172 -0.203273 -0.115931 0.4429594 0.1849334 -0.4593417 0.7473900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7959 7960 -0.002905 0.072417 1.040783 0.5454596 -0.6995457 -0.2883089 0.3605381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7960 7961 0.430019 0.144436 0.234037 -0.6543118 -0.4891804 0.0268315 0.5760718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7961 7962 0.929870 -0.036274 -0.440698 0.7332279 -0.2633431 0.2263183 0.5846429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7962 7963 0.315338 -0.811913 0.189361 -0.0507849 0.0018918 -0.9467592 0.3179062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7963 7964 0.563618 0.808559 -0.079639 -0.3626958 -0.6242779 0.4620853 0.5149817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7964 7965 0.807865 0.085416 -0.582324 -0.1911015 0.7017525 -0.1439015 0.6710559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7965 7966 0.143652 0.394133 0.927194 0.1601409 -0.3031160 0.3899685 0.8546345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7966 7967 0.818539 0.011327 0.339056 0.2473669 0.2934383 -0.5125826 0.7680903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7967 7968 0.106342 0.855400 0.508428 -0.5667192 -0.7121692 0.3480377 0.2247536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7968 7969 0.697084 -0.119637 -0.763167 0.4866077 -0.7268392 0.2249784 0.4293045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7969 7970 -0.635407 -0.757245 0.253678 0.3667777 0.5478600 0.7254932 0.1974415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7970 7971 -0.010214 0.462166 -1.012455 -0.8203387 0.3825230 0.4137358 0.0976897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7971 7972 0.770456 -0.506696 0.698359 0.6000081 0.4574218 -0.3169202 0.5747322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7972 7973 -0.678859 0.680547 0.497266 0.2623154 -0.3526500 0.0574729 0.8963958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7973 7974 -0.172692 1.025106 0.101239 -0.5850451 -0.3251181 0.2430029 0.7021182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7974 7975 0.595896 0.139236 0.868330 -0.0529112 0.1351670 -0.4860205 0.8618088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7975 7976 0.119030 0.475618 0.841846 0.0333446 -0.9572694 0.2787237 0.0695446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7976 7977 -0.057829 -0.305250 -1.076756 0.4102242 -0.2085108 0.4070036 0.7890421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7977 7978 -0.633575 -0.534941 -0.423297 -0.3055823 0.3626374 0.4476780 0.7580884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7978 7979 -0.256377 0.562789 -0.879982 -0.6135710 0.4005063 0.4260223 0.5306886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7979 7980 0.091653 0.820140 -0.437776 -0.0771776 -0.1019408 0.9790530 0.1584516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7980 7981 0.709890 0.523170 -0.313616 0.1502727 -0.3843121 0.8683173 0.2752226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7981 7982 -0.468007 -0.458401 -0.773849 -0.1626064 -0.1221838 0.1712973 0.9639956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7982 7983 -0.797234 0.008346 -0.684241 -0.3465682 -0.3921929 0.5648044 0.6380213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7983 7984 -0.293620 0.867124 0.349818 0.1244309 0.4391562 -0.2424605 0.8560793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7984 7985 -0.641592 0.627587 -0.480682 -0.1014830 -0.2677465 0.3544435 0.8901589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7985 7986 -0.089153 0.861615 0.067044 -0.3388844 0.0996608 0.6149890 0.7049920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7986 7987 0.768132 0.126818 0.699685 -0.4371426 0.1586474 0.8190030 0.3361121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7987 7988 -0.881228 -0.575574 -0.027518 0.0092840 0.1011295 -0.9831851 0.1517687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7988 7989 0.977441 0.338855 0.041491 0.3161338 -0.1270236 -0.8059624 0.4840960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7989 7990 -0.448640 0.448243 -0.621427 0.3230555 -0.6934802 -0.6420499 0.0499222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7990 7991 0.362930 -0.351457 0.948079 -0.1027541 -0.2059549 -0.8027237 0.5501443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7991 7992 0.453682 0.646811 0.313187 0.0931769 -0.3779575 -0.5959174 0.7023878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7992 7993 -0.418606 1.024232 0.230979 -0.0821481 -0.1185058 -0.9613531 0.2345383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7993 7994 -0.198227 -0.848085 0.501427 -0.2375920 0.3943352 0.8640654 0.2035699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7994 7995 -0.399010 0.844318 -0.337779 0.4755622 0.2253792 0.6768935 0.5146456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7995 7996 0.515437 -0.459971 -0.635965 0.1450589 0.4195211 0.8743792 0.1960128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7996 7997 -0.667625 -0.412674 -0.628837 0.0891083 0.0316817 0.9748015 0.2020348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7997 7998 0.409757 0.617683 -0.771420 -0.6908772 0.3383052 -0.5998665 0.2199964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7998 7999 -0.894371 0.189442 0.241419 0.1533242 -0.6490938 0.2383416 0.7059478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1 38 -0.980152 -0.031146 0.495738 0.2233971 0.3678427 0.6900835 0.5818680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1 781 0.222140 0.654266 0.706161 -0.0294402 0.1307301 -0.9706259 0.1998209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2 782 -0.819732 0.722755 0.076240 0.0978694 -0.5556737 0.0794744 0.8217860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3 36 0.723257 -0.751325 0.241178 0.4063752 -0.0577266 0.7495501 0.5193280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4 35 0.632055 0.212594 0.310261 -0.1563891 0.0708051 0.9800708 0.0999514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4 784 -0.597965 0.908906 0.437975 -0.3778678 -0.6349233 -0.6599596 0.1361676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5 34 0.570406 0.090593 -0.748002 -0.2444139 0.5037691 -0.6086704 0.5621377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6 786 -0.429427 -0.484117 0.552674 -0.4163578 -0.0753545 0.8779188 0.2241126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7 32 -0.010545 -0.814751 -0.414210 0.3207925 -0.1184293 0.1035603 0.9339925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7 787 0.217724 -0.230407 0.691741 -0.0450775 0.3504757 -0.9063662 0.2315928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 8 31 0.931845 0.692819 -0.109549 -0.0799459 -0.1853198 0.9782865 0.0471239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 8 788 -0.410799 0.530884 0.506106 -0.2409866 -0.4845017 0.7653859 0.3483790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 9 30 0.640442 -0.102217 0.591625 -0.2726638 0.7892938 -0.4975030 0.2348628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 9 789 -0.286451 -0.760303 0.274749 0.1459838 -0.4822183 -0.1771074 0.8454509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 10 29 0.502190 0.659940 -0.192515 -0.0441288 0.5592243 -0.5120350 0.6504929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 10 790 0.772321 -0.453592 0.121625 0.1627631 -0.2523423 0.9348633 0.1893729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 11 28 0.527160 -0.013546 0.885339 -0.2002245 -0.6439757 -0.4418494 0.5915864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 11 791 -0.816573 0.068355 0.583678 -0.1116764 -0.5752720 -0.1743744 0.7913179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 13 26 -0.478059 0.752462 -0.441716 -0.2975394 -0.3143084 -0.7970865 0.4211100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 13 793 0.957338 0.656743 0.170037 -0.7609956 -0.1280213 -0.5878146 0.2428378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 14 25 0.047521 -0.562357 0.727596 0.6581744 -0.0519446 0.7316443 0.1697199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 14 794 0.753534 0.376319 0.581407 0.2189724 0.7122221 0.4418043 0.4995996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 15 24 0.321945 -0.199058 1.039528 -0.4272273 -0.3701075 0.3815145 0.7313986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 16 23 -0.450952 0.814196 0.404475 -0.1442508 -0.5833822 -0.7402728 0.3014186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 16 796 0.900803 0.166790 0.742193 -0.2561721 0.6274154 -0.4071839 0.6123128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 17 22 0.010047 0.132171 -0.919659 -0.2910056 0.1650510 0.8293492 0.4474974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 17 797 -0.805512 0.607274 0.156083 -0.0084194 -0.0934349 -0.0357668 0.9949471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 18 798 0.143877 0.012016 1.002535 0.5253620 0.0996892 -0.0168201 0.8448514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 19 799 -0.142299 0.398144 0.897288 -0.4644587 -0.4162689 0.5385115 0.5665718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 20 59 1.046807 -0.416657 0.437702 0.1401166 0.4803738 -0.7171003 0.4851551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 20 760 -0.485029 -0.790899 -0.178470 0.4135897 -0.2675883 0.8144324 0.3066594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 21 18 -0.942472 0.142845 -0.469395 -0.1197374 0.1257986 0.7012086 0.6914797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 21 58 0.830977 -0.122101 0.484697 0.0976144 -0.6285665 -0.0972227 0.7654563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 21 761 -0.437821 0.430457 0.760343 0.1789525 0.7736248 0.6078120 0.0067237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 22 57 0.616070 -0.121245 -0.727992 -0.7258729 -0.3934171 -0.5298793 0.1938024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 23 56 0.501708 -0.337192 0.768978 -0.3687710 0.6797038 0.6340405 0.0018103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 23 763 -0.142979 0.979498 0.304647 0.2139662 0.0741680 -0.9151514 0.3334898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 24 55 0.360698 -0.947711 -0.080488 -0.1801568 0.5017891 -0.5598950 0.6342466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 25 54 0.524011 0.836511 0.290351 0.4689776 -0.4044053 0.7814343 0.0766606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 25 765 0.651832 -0.549176 0.696239 0.1259400 0.2197988 -0.9596365 0.1221696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 26 53 -0.523811 -0.971597 0.125429 0.0780618 0.4901064 0.6960339 0.5188824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 26 766 -0.688451 0.587644 0.642562 -0.7470676 0.0203115 0.6421991 0.1704631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 27 52 0.053923 0.171152 1.066166 -0.3021483 -0.8587058 0.3823533 0.1585458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 27 767 -0.882694 -0.569696 0.015352 0.1405691 0.4061398 -0.5688212 0.7012369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 28 51 0.636027 0.601745 -0.432638 0.1261886 -0.2581216 -0.8193989 0.4960193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 28 768 0.609783 -0.585070 0.658737 -0.6133756 0.0759394 -0.7487404 0.2395651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 29 50 -0.449583 0.784616 -0.082211 -0.4352629 -0.2943168 -0.5465453 0.6520829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 29 769 0.328867 0.316282 0.983248 0.1112527 -0.5019003 -0.6262076 0.5861595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 30 49 -0.609068 -0.741885 -0.000218 -0.1944322 0.9136507 -0.3231448 0.1517102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 30 770 0.912595 -0.380166 0.217456 -0.0494105 0.9586486 -0.1628314 0.2281170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 31 771 0.510882 -0.874757 0.437494 0.3262805 0.7509040 -0.5637107 0.1091531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 32 772 0.555551 0.114039 0.950731 -0.2006674 0.4066418 0.6003433 0.6587586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 33 6 0.700032 -0.838561 0.274955 0.3678259 0.3184115 -0.8728766 0.0374782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 33 46 -0.618239 0.688011 -0.195992 -0.2224562 -0.1302709 -0.8728967 0.4142392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 33 773 -0.368833 -0.016697 0.887673 -0.0192300 0.3087582 -0.9159720 0.2555265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 34 45 -0.097657 0.931790 0.343620 -0.5007178 0.4018623 -0.7196094 0.2644819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 34 774 0.626393 -0.299142 0.744015 0.5887871 -0.0982448 -0.5227919 0.6085773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 35 775 0.199849 -0.725397 0.690253 0.3481573 -0.0505286 0.4696408 0.8097351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 36 776 1.000107 0.702709 0.307968 0.4878988 -0.1607306 0.7751548 0.3677709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 37 2 0.311840 0.704573 0.160691 -0.1156080 0.3205986 0.9280814 0.1500541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 37 42 -0.322720 -0.770116 -0.336554 0.4671926 -0.6027593 0.6333819 0.1312998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 38 41 -0.200936 0.822873 -0.652282 -0.5194368 0.7484062 -0.2092741 0.3553561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 38 778 0.539523 0.557541 0.689901 -0.4210415 -0.0557110 0.1421370 0.8941014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 39 0 0.826268 -0.353034 -0.105246 0.3019944 -0.4016484 0.3941023 0.7695202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 39 779 -0.302836 -0.771964 0.317983 0.2795673 -0.2070200 0.6645876 0.6612928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 40 79 -0.399977 0.909137 0.415882 0.5217060 0.4386010 -0.7196602 0.1324435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 40 740 -0.215935 -0.469193 0.779686 0.4509749 -0.3403126 0.3576456 0.7435715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 41 78 -0.621568 0.691775 0.325411 0.5450542 -0.3868860 -0.2767849 0.6903805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 41 741 -0.820786 -0.577848 0.017805 0.6609189 0.5541555 -0.3286651 0.3848080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 42 77 0.283717 0.519861 0.671607 -0.5105206 0.3368967 -0.7560501 0.2329325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 43 36 -0.878040 -0.321803 0.395105 -0.5362844 -0.5553233 -0.6355866 0.0066864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 43 76 1.027108 0.569419 -0.424931 -0.5587764 0.2199322 -0.2223445 0.7680897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 44 75 0.366284 0.822088 -0.412804 -0.1428729 -0.8257503 -0.5357849 0.1032389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 44 744 -0.175923 0.556307 0.821077 0.3099784 -0.2447952 0.2143104 0.8933419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 45 74 -0.420019 -0.671390 -0.260002 -0.2470586 0.6313666 -0.6727552 0.2962072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 45 745 0.541577 -0.569652 0.737922 0.0974777 -0.5246237 0.7696074 0.3506742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 46 73 -0.448536 -0.960780 -0.004560 -0.0699554 0.5713217 0.5643097 0.5918211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 46 746 0.606150 -0.205618 0.695568 0.6235017 -0.2683646 0.7341791 0.0143884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 47 32 0.397754 -0.292641 -0.806607 0.3615203 0.3490206 -0.8099677 0.3023906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 47 72 -0.316421 0.304702 0.728499 0.4870311 0.4057892 -0.5518668 0.5418292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 47 747 -0.682688 -0.678724 -0.005475 0.0135390 -0.4817382 -0.2881883 0.8274615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 48 31 -0.667374 -0.160433 0.720944 0.2088761 0.0217842 0.9351042 0.2854407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 48 71 0.508976 0.334361 -0.755174 -0.1931219 0.6102180 0.7677546 0.0298455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 48 748 0.200369 0.792216 0.307184 -0.9005124 -0.2206552 -0.1459174 0.3451042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 49 70 0.811640 -0.340242 0.123604 0.0223300 0.2153273 -0.7042134 0.6761797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 49 749 -0.467270 -0.792655 0.570573 0.4795932 0.2355515 -0.8349383 0.1318480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 50 750 0.761244 0.068336 0.828318 -0.1173682 0.3083990 -0.9301077 0.1612900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 51 68 -0.877853 0.080180 -0.304345 -0.0976419 -0.0858063 -0.9184610 0.3735409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 52 752 0.423119 -0.728755 0.524847 -0.6927886 0.2091997 -0.6901289 0.0012469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 53 66 -0.639755 0.472418 -0.475437 -0.1942146 -0.7619203 -0.6139470 0.0694784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 54 754 0.326591 -0.159633 0.812277 -0.6202767 0.0822088 -0.7799844 0.0110806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 55 64 0.661279 -0.356137 0.589956 -0.3949180 0.2436854 0.8826978 0.0741738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 55 755 -0.697819 -0.409618 0.656809 -0.0094354 0.3490590 -0.7494618 0.5624729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 56 63 -0.384317 0.606720 -0.427483 -0.8771296 0.0296782 0.4183926 0.2339026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 56 756 -0.541165 0.435859 0.716670 0.0808022 0.0521374 -0.3495636 0.9319646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 57 62 -0.726368 0.459766 0.465251 0.0138241 0.4270023 -0.0423874 0.9031507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 57 757 0.697042 0.688952 0.446893 0.0991898 -0.4358653 -0.7156300 0.5367090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 58 61 0.668177 -0.055740 -0.686904 -0.7665932 -0.1252814 -0.4911582 0.3942120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 59 759 0.696347 -0.265101 0.539392 -0.0215380 0.1776524 -0.5503089 0.8155586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 60 99 -0.075895 0.763094 -0.883178 0.0599933 -0.9406089 -0.3229683 0.0857152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 60 720 -0.746033 0.442371 0.560932 -0.3886083 -0.2001653 0.8986017 0.0378466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 61 721 0.640080 -0.366327 0.752386 -0.3285738 0.8263130 -0.2349104 0.3925087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 62 97 -0.744068 0.471889 -0.129802 0.3318885 -0.1165105 0.8573387 0.3758266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 62 722 0.028636 0.435563 0.763546 -0.1586793 0.2503440 0.8088249 0.5078888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 63 96 0.072132 -0.133548 1.036756 0.4141384 -0.2295753 0.2736892 0.8371850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 63 723 -0.735553 -0.367943 0.041669 -0.8081418 -0.2180968 0.5211116 0.1666832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 64 95 -0.951529 0.109464 -0.425352 0.0907647 -0.3760991 -0.2178049 0.8960314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 65 54 1.016601 -0.381636 -0.302779 0.2851639 0.3153957 -0.6632541 0.6158742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 65 94 -0.654829 0.490443 0.164560 0.6669592 -0.4698478 0.4893730 0.3080951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 65 725 -0.278322 -1.022678 0.391728 0.2681803 -0.2827285 -0.8746186 0.2884203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 66 93 0.440022 -0.564439 0.473032 0.0627068 -0.5810303 -0.7814870 0.2185172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 66 726 -0.148799 0.499957 0.667133 0.1687416 0.3023599 -0.2412852 0.9065794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 67 52 -0.852609 0.083202 0.694584 0.1880236 -0.3590272 0.1433602 0.9028812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 67 727 0.301100 -1.079762 0.232252 0.3781076 0.0052501 0.8576126 0.3485795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 69 50 0.567229 -0.208586 0.892532 -0.6776155 -0.6218054 -0.2304432 0.3179484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 69 90 -0.494785 0.137109 -0.829695 -0.2481313 -0.1413589 -0.5522103 0.7832703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 69 729 -0.069017 1.211317 0.227153 0.0155173 -0.0443343 -0.9975730 0.0513988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 70 730 0.592680 -0.491858 0.431833 0.2181073 -0.6020505 0.7384709 0.2112466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 71 88 -0.424100 -0.974592 -0.242221 -0.0593477 0.4057467 0.8833947 0.2268507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 71 731 -0.546480 -0.064192 0.801032 0.0346554 0.3300454 -0.5135308 0.7912997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 72 87 -0.641312 -0.465324 -0.374761 0.2002511 -0.2559831 0.9094254 0.2594563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 72 732 0.166267 -0.495965 0.788174 0.1994004 0.3526662 -0.3451090 0.8466202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 73 733 -0.872683 -0.056098 0.606738 -0.0961291 -0.5836583 0.7673073 0.2476724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 74 85 1.183700 0.270391 0.342391 0.1426587 0.4494214 0.1529966 0.8684820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 74 734 -0.025563 -0.750181 0.786077 0.2346432 -0.6712022 0.5752645 0.4043524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 75 84 -0.361608 -0.013365 0.738785 0.2736354 0.1216536 0.9477071 0.1103417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 75 735 0.433661 0.913080 0.312173 -0.6441279 0.4876731 -0.1361239 0.5733624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 76 83 0.545328 0.339560 0.848153 -0.0860382 -0.5825024 0.1280207 0.7980596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 76 736 0.009200 -0.764387 0.504647 0.4970410 0.3240538 0.1650792 0.7878377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 77 737 0.762502 0.096994 0.738859 0.4677820 0.5880463 -0.0418213 0.6585078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 79 739 -0.823488 -0.346938 0.431683 -0.7779988 -0.2259285 0.5788387 0.0928439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 80 119 0.906533 0.253596 -0.058702 0.6741397 0.2092119 0.0651592 0.7053512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 80 700 0.122376 -0.666997 0.690124 0.3758925 -0.2380308 0.7947341 0.4128486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 81 78 -0.946931 0.082981 0.535876 -0.4313986 -0.3196028 -0.7998851 0.2682035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 81 118 0.881154 -0.220308 -0.515379 -0.9238211 -0.0492507 -0.3617960 0.1150329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 81 701 0.693808 0.799211 0.719006 -0.3941486 0.4830350 0.0012390 0.7818712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 82 77 0.645146 0.346685 0.811644 -0.0270661 -0.6583939 -0.5450539 0.5183639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 82 117 -0.656277 -0.271195 -0.780759 -0.1725455 0.7682258 0.5806327 0.2071782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 82 702 -0.822653 0.394614 0.452925 -0.7448450 -0.3963078 0.5341511 0.0531858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 83 116 0.938956 0.300098 -0.138165 0.4399687 0.4599617 0.3263126 0.6988439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 83 703 0.401943 -0.723712 0.134925 -0.0761423 0.4179190 0.0969232 0.9000844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 84 115 0.818546 0.246096 0.214510 0.4566746 -0.3790161 0.2965034 0.7482519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 84 704 -0.071056 -0.688629 0.464164 -0.3206895 0.2752236 -0.8287974 0.3667495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 85 114 0.332528 0.031568 0.996964 -0.8461965 0.1445643 0.4723976 0.1997326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 85 705 -0.954425 -0.391024 0.685303 -0.4712512 -0.4244596 0.6136737 0.4702776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 86 73 0.875285 -0.208344 -0.337266 0.5550193 0.5495770 0.0572179 0.6218077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 86 113 -0.909702 0.271028 0.483285 0.3649296 0.1800672 0.1118291 0.9065850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 86 706 -0.070674 -0.977035 0.182005 0.7602226 -0.2717969 0.1269644 0.5762535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 87 707 -0.108585 -0.057268 1.104055 -0.1121168 0.4963465 0.6683216 0.5426013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 88 111 0.128120 0.541198 -0.771391 -0.8066593 -0.3267146 -0.0270055 0.4917611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 88 708 0.217840 0.808929 0.560786 -0.0874841 -0.6043485 -0.2418883 0.7540553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 89 70 -0.787428 -0.338323 -0.314286 -0.5561655 -0.3564386 -0.6012288 0.4496170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 89 110 1.114189 0.278919 0.408799 0.0667306 -0.4750393 0.8152725 0.3243693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 89 709 -0.505418 0.399083 0.783524 0.0403245 0.4927747 0.8058227 0.3258787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 90 109 -0.622707 -0.527478 -0.699695 -0.5080083 0.3912515 0.4833588 0.5959984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 90 710 -0.751793 0.084631 0.783861 0.1512888 -0.4314925 -0.2435750 0.8553345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 91 68 0.008910 0.118511 -0.902411 -0.8138858 0.0009004 -0.3246658 0.4818519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 91 108 0.022097 -0.137079 1.044015 -0.0796251 -0.3829569 -0.8874820 0.2436793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 91 711 -0.395121 0.706958 0.088586 -0.7044274 -0.2467132 -0.2025394 0.6339498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 92 67 0.395619 0.728011 -0.785895 -0.4952055 -0.3024880 -0.7395065 0.3411784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 93 106 0.056537 0.862281 -0.594888 -0.3149779 0.0872613 0.7892555 0.5198558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 94 105 -0.014587 0.601018 -0.623247 -0.6749750 0.6632010 -0.1410137 0.2910125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 94 714 0.527180 0.529909 0.634576 0.4941615 0.3093164 0.8072470 0.0920874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 95 104 -0.955204 -0.131691 0.544264 -0.3639164 0.5404495 0.6497546 0.3915331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 95 715 0.135076 0.791884 0.470122 -0.5510460 -0.6215994 -0.3314778 0.4473086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 96 103 0.746941 0.592310 0.664245 0.1157367 -0.1178284 0.4059054 0.8988672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 96 716 -0.835994 0.434123 0.573424 -0.2963148 -0.4799729 -0.4262633 0.7071938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 97 102 0.637810 0.264801 -0.696625 0.3180790 -0.2845204 0.1385816 0.8936828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 97 717 0.676251 -0.663052 0.201193 0.0156502 0.5397710 -0.2473708 0.8044937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 98 61 -0.485351 -0.758124 0.556085 -0.4982528 -0.6549679 -0.2940649 0.4860937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 98 101 0.447704 0.683583 -0.576984 0.0978416 0.9008792 0.4228934 0.0022162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 98 718 -0.495304 0.714158 0.440321 0.3467359 -0.2988320 -0.7935380 0.4009626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 100 139 -1.018976 0.019006 -0.608903 0.1690785 -0.2842238 0.2934980 0.8969326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 101 138 -0.291577 0.088699 0.862284 0.1764306 0.5181320 0.0806698 0.8330089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 102 137 -0.144601 -0.293910 -0.789740 0.8015712 0.1371185 0.3676142 0.4511562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 102 682 0.883652 -0.467337 0.274884 0.1259134 -0.3408515 0.6944662 0.6210336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 103 136 0.859420 -0.091346 0.538215 -0.5964870 -0.0018310 -0.4084644 0.6909100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 103 683 -0.287837 0.718469 0.610707 -0.6734342 -0.0791981 -0.7344791 0.0274679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 104 135 -0.064834 1.082252 -0.137402 0.7141602 -0.1722935 -0.3480295 0.5823793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 104 684 -0.323936 0.012547 1.083133 0.2170259 -0.2719367 0.8943715 0.2811578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 105 134 -0.558060 0.524593 0.765035 -0.0096623 -0.9429124 -0.0776068 0.3237282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 105 685 -0.693944 -0.615292 -0.009737 0.9438938 -0.0251847 -0.3141429 0.0987144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 106 133 0.947519 -0.256394 0.065761 -0.0726143 0.0817580 0.1436885 0.9835631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 106 686 -0.020821 -0.352858 0.911199 -0.4524354 0.6415244 -0.6194734 0.0011661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 107 92 0.572530 0.640123 -0.036333 0.6080307 0.5616830 -0.2531291 0.5007359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 107 132 -0.688840 -0.633936 -0.196815 -0.1006707 0.2089554 -0.6047337 0.7619056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 107 687 0.367790 -0.452488 0.701225 0.3956190 -0.0895516 0.6785218 0.6124331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 108 688 0.118832 -0.802028 0.620522 0.5723102 0.0557194 0.2337019 0.7840534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 109 130 0.544293 0.500600 -0.514090 0.0896438 -0.6949957 0.1992474 0.6850149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 109 689 -0.740975 0.755059 0.336177 0.1110997 -0.5263312 0.2589340 0.8022378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 110 129 -0.538238 -0.819550 -0.369101 0.3969578 0.5184753 0.6236809 0.4296859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 110 690 0.673655 -0.550322 -0.007588 -0.5385131 0.2951484 -0.5629197 0.5531839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 111 128 -0.106220 0.720424 0.794212 0.1669706 0.5316737 -0.5226698 0.6451823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 111 691 0.782819 -0.466478 0.440653 0.5882847 -0.0893910 0.7958980 0.1116998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 112 87 0.549475 0.794940 -0.300519 0.0209626 0.2586698 0.9606777 0.0987365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 113 126 -0.711109 0.401281 -0.380968 0.7208626 0.2268978 0.1225385 0.6433186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 114 125 -0.462557 -0.729836 -0.875403 -0.3948890 0.0498916 -0.5602843 0.7263986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 114 694 -0.823140 0.499404 0.308425 0.1289909 0.1218366 0.8106227 0.5580395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 115 124 0.741305 -0.200808 -0.406935 -0.1729090 -0.2623894 0.9475604 0.0581680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 115 695 0.523800 -0.083057 0.836665 -0.0082722 -0.4578059 0.7461541 0.4833213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 116 696 -0.755503 -0.177467 0.803077 0.0418518 -0.1659515 0.6019231 0.7799981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 117 122 0.987265 -0.390391 -0.215633 -0.9608648 -0.0144140 0.1310072 0.2436557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 117 697 0.415814 0.955306 0.164865 0.0915177 -0.9079398 -0.3853959 0.1368936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 118 121 0.390574 0.542967 0.761100 0.3867780 -0.1513937 0.0672376 0.9071724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 118 698 0.668596 -0.545108 0.140490 0.9751423 0.1590628 0.0928576 0.1231824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 119 699 -0.171369 0.516084 0.645732 0.5477450 -0.3963877 -0.4657546 0.5708983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 120 159 0.149765 1.014790 -0.198692 0.3226094 -0.4051936 -0.8339940 0.1902508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 120 660 -0.878924 0.353196 0.743090 0.0595506 -0.6458351 -0.6732816 0.3550248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 121 158 0.551751 0.913171 0.098956 0.0293466 -0.0751607 0.7136909 0.6957981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 121 661 0.665141 -0.670555 0.473261 0.3612069 0.5845468 0.5506364 0.4739558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 122 157 0.838420 0.451712 -0.188399 0.4942316 0.5275377 -0.6320713 0.2791503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 122 662 0.582140 -0.779838 0.336241 -0.1021517 -0.9760936 0.1917665 0.0056534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 123 116 0.934152 -0.308149 0.128007 -0.4659682 -0.5150617 0.6912535 0.1993832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 123 156 -0.733652 0.350436 -0.392309 0.0907865 0.3526719 0.0042905 0.9313227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 124 664 -0.625113 -0.352650 0.527103 -0.5943676 -0.5914230 0.3081847 0.4494087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 125 665 -0.761558 -0.739781 0.112846 0.6079792 -0.4799021 -0.3930296 0.4955633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 126 153 -0.554656 -0.500079 -0.556096 -0.1040157 -0.1978454 -0.3051753 0.9256922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 126 666 -0.662196 0.836874 0.018064 -0.3437580 0.0588589 0.4224675 0.8365926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 127 112 -0.330876 -0.169648 0.941080 0.3881706 0.6757295 0.6243945 0.0533356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 127 152 0.088744 0.029433 -0.796888 0.5948045 0.7523850 0.1000576 0.2647884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 127 667 0.702145 0.657459 0.236306 0.0913598 0.1694691 0.9773163 0.0882411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 128 668 -0.128334 0.236055 1.005269 0.2277835 -0.1402779 0.8202439 0.5056053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 129 669 -0.835239 -0.028725 0.746134 0.8172340 -0.2991235 -0.4157252 0.2642468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 130 149 -0.539336 1.053453 -0.768709 -0.3779455 -0.0000296 0.8705800 0.3150359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 130 670 0.429047 0.789951 0.326268 -0.6180301 0.5688903 -0.2331023 0.4899653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 131 148 -0.771814 -0.506648 -0.482860 0.5620252 -0.7462753 0.1556799 0.3208809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 131 671 0.514305 -0.747151 0.296379 0.0757708 -0.1312304 -0.1838842 0.9711972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 132 147 0.477012 -0.701563 -0.341867 0.3644701 0.1144367 0.7114318 0.5898565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 132 672 0.380692 0.098604 0.933109 0.1751606 0.2733971 -0.5132381 0.7944555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 133 146 0.918801 -0.201999 0.106583 0.2503046 0.5786720 -0.7127949 0.3072619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 133 673 -0.136258 -0.375196 0.805049 -0.3388172 0.4633405 0.8084735 0.1299580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 134 674 0.573378 -0.821976 0.262984 0.1355043 0.4683279 -0.3416307 0.8034899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 135 144 -0.808811 -0.321304 -0.823337 -0.4531479 -0.3816510 0.3278510 0.7358758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 135 675 -0.453889 0.930175 0.178934 0.0070462 -0.8501470 0.0645298 0.5225288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 136 143 0.884998 0.332603 0.445105 -0.1243001 0.2484263 -0.6561840 0.7016099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 136 676 -0.415158 -0.630192 0.629206 0.1890109 -0.2084811 -0.9065722 0.3145431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 137 142 -0.505164 -0.631302 0.539579 0.2003053 -0.0865869 0.3521001 0.9101681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 137 677 0.383275 0.345614 0.834620 -0.2260336 0.1577540 0.2862639 0.9176467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 138 141 -0.659407 0.253715 -0.282055 -0.6731383 -0.2253282 -0.4667282 0.5275196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 138 678 0.171512 0.692752 0.623214 0.0588481 -0.5186254 -0.7729077 0.3608023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 139 679 -0.239775 0.180625 0.953884 -0.1362655 -0.6853371 0.6471370 0.3048909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 140 179 -0.240680 0.718155 0.654294 -0.1281179 -0.5238951 0.4077400 0.7367957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 140 640 -0.668140 -0.462256 0.211974 0.0464846 -0.5402899 -0.4451093 0.7126035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 141 178 -0.592666 -0.777128 0.108373 -0.0464906 -0.1961026 0.2392498 0.9498115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 141 641 0.446250 -0.227008 0.695431 0.1012144 -0.0167000 -0.0632187 0.9927135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 142 177 -0.532728 0.137936 0.857261 -0.5220007 -0.1272576 -0.3615580 0.7619689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 142 642 0.769569 0.234191 0.603272 0.3663487 0.0703805 -0.5451367 0.7507737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 143 176 -0.082180 0.397842 0.690784 0.2859281 -0.2254037 -0.8740045 0.3217988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 143 643 0.206857 -0.697681 0.551198 0.6312436 -0.3865878 0.5823927 0.3360061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 144 644 0.541207 0.393111 0.810073 -0.4234483 -0.0805875 0.0065159 0.9023053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 145 134 0.731820 -0.721953 0.209081 0.0145610 -0.7242606 0.5897488 0.3569747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 145 174 -0.976787 0.717488 -0.148068 -0.6001316 -0.1160658 0.6649015 0.4292747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 145 645 0.015742 -0.113063 1.146919 0.0121052 0.5719947 -0.6390251 0.5141230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 146 173 -0.617146 0.641370 0.368620 0.3724752 0.0762955 -0.9224273 0.0675950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 146 646 -0.484004 -0.481333 0.650948 0.0155409 0.1664246 -0.2536130 0.9527548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 147 172 -0.811272 -0.332565 0.245464 0.3297415 -0.3393915 -0.8168563 0.3298936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 148 171 0.011951 0.457093 0.905181 -0.2634601 0.7483188 -0.5879403 0.1579050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 148 648 0.633353 -0.452734 0.168136 0.4776306 0.4936034 -0.7086451 0.1613902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 149 170 1.017451 -0.162564 0.010890 -0.2824449 0.6964554 -0.5224387 0.4027810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 149 649 -0.145323 -1.008293 0.237679 0.3154903 0.0582781 0.2500418 0.9135363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 150 129 -0.055823 -0.885607 0.210475 -0.0010404 0.4800806 -0.7654626 0.4284722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 150 650 0.997944 -0.021584 0.475106 0.4768811 0.4816943 -0.3825607 0.6278553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 151 651 -0.860434 -0.262189 0.675321 -0.3425685 0.1314414 -0.1785321 0.9129602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 152 167 0.324735 -0.390193 0.945558 -0.9541960 -0.1937495 0.0614754 0.2195264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 152 652 0.364507 0.953298 -0.004058 -0.0277178 -0.6789012 -0.4002379 0.6149264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 153 166 -0.584724 -0.711197 -0.493796 -0.2639516 -0.1802064 0.5313935 0.7845229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 153 653 -0.919215 0.359549 0.505021 -0.1142918 0.6126365 0.7805852 0.0479644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 154 165 -0.877463 -0.284691 -0.608389 0.1373734 -0.0525639 0.5594057 0.8157394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 154 654 -0.170484 -0.809457 0.336708 -0.0110633 -0.0553693 -0.9787748 0.1970072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 155 124 -0.588578 -0.692564 -0.324576 0.2026907 0.8352036 -0.4719758 0.1964442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 155 164 0.728749 0.586265 0.385231 0.2330963 0.4983473 -0.6311766 0.5467469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 156 163 -0.343024 0.459932 -0.832963 -0.3465914 -0.4260483 0.3267314 0.7691579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 157 162 0.072502 0.862300 -0.444391 -0.4724992 0.2423602 -0.4756065 0.7012877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 157 657 -0.544312 0.523428 0.800724 -0.7448880 -0.2163243 0.3815724 0.5027406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 158 161 0.852003 -0.815659 0.000209 0.1097555 -0.1263766 -0.4717120 0.8657196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 158 658 -0.497898 -0.663605 0.504230 0.1708125 -0.7927130 0.1666082 0.5609553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 159 659 0.206496 0.128531 0.942301 0.0200881 -0.6297285 -0.6995508 0.3371457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 160 199 1.030310 -0.009366 0.501673 0.3053670 0.1262127 0.1056124 0.9379059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 160 620 -0.238313 -0.648006 0.731337 0.4901018 -0.1268787 0.3374543 0.7936162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 161 621 0.368695 -0.582650 0.739723 -0.1441527 0.3517879 -0.8791329 0.2873860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 162 197 -0.823479 0.202968 0.247327 0.7870678 -0.5892073 0.0177501 0.1817800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 162 622 -0.722658 -0.970781 0.079713 0.8970809 0.0814386 -0.3213237 0.2921722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 163 196 -0.243172 0.942904 -0.033908 -0.4460027 0.0631731 0.6061895 0.6554579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 163 623 -0.721023 -0.254192 0.616644 0.1138004 -0.1680411 0.7632908 0.6133505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 164 195 -0.744751 0.522422 -0.366636 -0.2550557 0.3415798 -0.0435721 0.9035327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 164 624 -0.261607 0.200577 0.968616 -0.4184696 -0.6167719 0.3789775 0.5484995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 165 194 -0.499568 0.625143 -0.283428 0.5575482 -0.6417635 -0.1290390 0.5105179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 165 625 -0.765243 -0.362179 0.509265 0.2816048 -0.1956882 0.3679488 0.8643024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 166 193 -0.841690 0.311421 -0.279009 -0.3971629 0.6567722 0.4180417 0.4859558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 166 626 -0.252118 0.418221 0.904393 0.3751949 0.1073257 -0.0467764 0.9195227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 167 192 -0.015212 -0.089337 -0.881586 -0.3424856 0.5453776 -0.4985605 0.5802622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 167 627 0.811387 -0.373918 0.306946 -0.1376014 0.1725882 -0.6840951 0.6951929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 168 151 -0.465144 1.073639 -0.017940 -0.0440380 0.5428379 -0.2456553 0.8018984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 168 191 0.340779 -0.789963 0.002574 -0.1062897 0.0935154 0.8085204 0.5711848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 168 628 0.153104 0.179259 0.943900 0.2709908 0.5163191 0.7013146 0.4100444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 169 150 0.006241 -0.854967 0.351705 -0.0181910 -0.7396603 0.1311554 0.6598258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 169 629 -0.696313 0.251514 0.336896 -0.2797639 -0.5154570 -0.5505890 0.5940438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 170 189 -0.494485 -0.201890 0.765452 0.3896131 0.5825429 0.3582650 0.6168400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 170 630 0.744808 -0.576960 0.318631 0.3218357 0.5611879 -0.7461196 0.1574658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 171 188 -0.204942 -0.947564 -0.599303 0.0158300 -0.3801359 -0.7818736 0.4938823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 171 631 -0.285810 -0.497982 0.699798 0.6769710 -0.5620544 0.0239133 0.4745876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 172 187 0.598663 0.374986 0.833025 -0.1378814 -0.2317965 -0.7128163 0.6474195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 172 632 -0.720386 0.543784 0.326207 -0.1077013 -0.6102742 -0.6065620 0.4980445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 173 186 0.112944 -0.787389 0.659231 0.1427027 -0.2835220 0.4269804 0.8467225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 173 633 0.114962 0.681942 0.913680 -0.3879061 0.2013034 0.7961082 0.4185899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 174 185 0.357021 0.102487 0.908092 -0.1142662 0.2675998 -0.6466561 0.7051025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 174 634 -0.722591 -0.469502 0.377959 0.3858062 -0.5878180 -0.1317639 0.6987573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 175 635 -0.526804 -0.809191 0.114250 0.6188740 0.0280156 0.4134507 0.6672845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 176 183 -0.731090 -0.054752 0.985759 0.0413094 0.0080663 0.9986000 0.0320401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 176 636 0.125889 1.001801 0.038096 -0.8768671 0.4549168 0.0948856 0.1230918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 177 182 -0.200024 -0.972371 0.145244 -0.4058971 -0.3085896 -0.7599916 0.4030296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 177 637 0.748179 0.164485 0.590509 0.2048359 0.0383089 -0.0595056 0.9762345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 178 638 0.492137 -0.547843 0.567233 -0.0018735 0.6934466 -0.7204278 0.0105832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 179 639 -0.389296 -0.116127 0.848324 -0.3508473 0.3872772 -0.7796341 0.3450988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 180 600 0.809415 -0.455675 0.626681 0.0550082 -0.8913367 0.4499922 0.0002086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 181 178 -0.615126 0.472860 0.661092 0.2368019 -0.8375685 0.3291919 0.3661100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 181 218 0.703026 -0.536102 -0.773905 0.5829681 0.4107734 -0.6911915 0.1169092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 181 601 -0.108502 -0.762507 0.398746 -0.1944503 0.4333123 -0.8542865 0.2112442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 182 217 0.584641 0.498774 -0.641753 -0.2540605 -0.0511609 0.5229448 0.8120127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 182 602 0.188802 0.654569 0.880044 0.0235964 0.0196205 -0.4069298 0.9129438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 183 216 0.557729 -0.089171 0.605338 -0.0268997 -0.2978112 0.5764916 0.7604224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 183 603 -0.096423 -1.162021 0.243443 0.7373150 -0.5196652 0.1363243 0.4095489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 184 175 -0.042130 0.844599 -0.478390 -0.7705323 0.0179564 0.0208968 0.6368051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 184 604 -0.664897 0.355311 0.736940 0.0797914 0.0434245 -0.4729810 0.8763770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 185 605 0.453601 -0.830261 -0.047079 0.9873477 -0.1361388 0.0321847 0.0746649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 186 213 -0.366206 -0.538870 0.697924 -0.0467924 -0.5287658 -0.8463659 0.0433817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 187 212 0.103184 0.543515 0.637391 0.8558220 -0.0006965 0.1014460 0.5072247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 187 607 -0.364897 -0.627502 0.680585 -0.6215368 0.0722415 0.7523997 0.2058346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 188 211 0.601141 -0.176228 -0.976022 0.3548020 0.2829846 0.4749211 0.7539796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 188 608 0.872560 0.531583 0.471284 -0.2224300 0.4241517 0.8433712 0.2436088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 189 210 -0.496231 0.849398 -0.409044 -0.1589826 -0.5347863 0.8224540 0.1108945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 189 609 -0.632252 0.069591 0.733593 0.2007328 0.4434904 0.8719963 0.0514303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 190 169 0.747083 0.416634 0.324278 -0.3881281 0.1821498 0.7477241 0.5070372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 191 208 -0.920091 -0.404242 0.006586 0.1198165 -0.2250539 -0.9666886 0.0225353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 191 611 0.049477 -0.051716 0.917016 -0.0724888 0.4502311 0.2512652 0.8537582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 192 207 0.176901 0.860146 0.017968 0.0933277 0.6110929 0.6230315 0.4792569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 192 612 0.546659 -0.156040 0.905850 -0.0471794 0.7074349 0.0287758 0.7046148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 193 613 -0.748854 0.446219 0.025058 0.5570233 0.0758439 -0.6643292 0.4925845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 194 614 0.483597 0.751195 0.569429 -0.2750593 0.3290401 -0.8920849 0.1423359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 196 203 0.661456 0.183297 0.753340 -0.4956201 -0.5285717 -0.6250980 0.2902156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 196 616 -0.710188 0.536679 0.445800 0.1404367 -0.5194475 0.1221924 0.8339789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 198 161 -0.167681 -0.618773 -0.616809 0.4751015 -0.1792088 0.4688020 0.7227638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 199 619 -0.498141 -0.213734 0.863078 0.0127301 0.3472615 0.4427762 0.8265571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 200 580 0.765527 -0.148774 0.750040 0.7193806 0.3622184 0.4515642 0.3839000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 201 581 0.345775 0.815839 0.760451 -0.1543003 0.2845303 0.6651265 0.6729344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 202 197 -0.192079 0.886857 -0.273342 0.2229861 0.3680184 0.8790592 0.2051695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 202 237 0.340095 -0.914794 0.217605 -0.2823076 -0.1968182 0.5594511 0.7540421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 203 583 0.861578 -0.589528 0.078838 0.2320404 -0.8675281 0.4030316 0.1764025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 204 195 0.393441 0.183181 -0.860883 0.5247989 0.4736293 0.2535334 0.6602895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 204 235 -0.446704 -0.026200 0.883566 -0.5849864 0.6638582 -0.4623778 0.0573574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 205 194 -0.815741 -0.371033 -0.634860 0.1186699 -0.4672283 -0.8679471 0.1195114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 205 234 0.685527 0.535647 0.522621 0.2392665 -0.1988870 -0.5855745 0.7485306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 206 193 0.054073 0.762027 -0.341367 0.6143055 -0.2871840 -0.6659221 0.3109692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 206 233 0.036468 -1.044831 0.218970 0.1176796 0.2761744 -0.3896058 0.8706816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 206 586 0.143569 0.135233 1.039764 -0.5667826 -0.4768078 0.0582581 0.6693413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 207 232 0.322197 0.099421 0.885701 -0.3942862 -0.2596413 0.6283801 0.6182743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 207 587 -0.730096 0.586758 0.373004 -0.0124326 -0.4862030 -0.8621655 0.1418544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 208 231 0.846636 -0.017152 0.023614 0.6381341 -0.4648904 -0.5291224 0.3109523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 208 588 0.092804 0.663927 0.825671 0.1559558 0.1434275 0.7740538 0.5966130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 209 190 0.048736 1.013802 -0.050662 -0.3179549 -0.2676956 0.3591224 0.8356284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 209 230 -0.046713 -1.104795 0.003946 -0.0042166 0.4940262 0.7894759 0.3642090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 209 589 -0.812941 0.025858 0.671310 -0.5225787 -0.3311105 0.7825818 0.0695914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 210 229 0.750128 0.149799 -0.772250 0.3831281 -0.2857130 0.3238785 0.8165070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 210 590 0.294079 -0.774336 0.408201 0.4255300 -0.1539463 0.6521275 0.6082388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 211 228 0.169532 -0.899838 -0.030390 0.3279370 0.6048574 0.3793750 0.6186109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 211 591 0.747043 0.172944 0.773062 0.4825704 -0.0525772 0.7901024 0.3742990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 212 227 0.140572 0.440566 -0.906376 -0.8394283 -0.0172560 0.3913440 0.3767124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 213 593 -0.849543 0.413132 0.333120 0.1783263 -0.8655548 -0.0952111 0.4582024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 214 185 -0.120059 0.350481 -0.759419 -0.0091166 0.3920579 -0.9175849 0.0651572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 214 225 0.381928 -0.700527 0.856368 0.0950222 -0.0851853 -0.2282932 0.9651925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 214 594 -0.288120 0.386566 0.737815 0.1860224 0.4990391 0.5554302 0.6386336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 215 184 0.700381 -0.344683 0.649813 0.0046441 -0.5397364 -0.7335411 0.4130139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 215 224 -0.814897 0.438602 -0.484578 -0.6858855 0.3427037 0.3626487 0.5297180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 215 595 0.316726 0.775205 0.209839 -0.7167030 0.4924644 0.0745066 0.4881234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 216 223 0.327977 -0.821739 0.092864 0.6205824 -0.5223410 -0.4192803 0.4077271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 216 596 -0.889185 -0.411127 0.311029 0.5039392 -0.0047512 -0.8378356 0.2098910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 217 222 0.755415 -0.044513 -0.787677 0.2866954 0.2713176 0.8354521 0.3823771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 217 597 0.794570 -0.313936 0.712224 0.4015119 -0.2295912 -0.4507139 0.7635005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 218 221 0.410274 0.819515 -0.007529 -0.5544624 0.2032011 0.6465923 0.4829070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 218 598 -0.663039 0.393880 0.786945 0.0864043 -0.5381489 -0.3196649 0.7750770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 219 180 -0.678580 0.714465 -0.259571 -0.5688897 -0.1822784 -0.7623300 0.2489821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 219 599 0.038887 0.594134 0.884976 -0.2206408 0.4761054 0.8495035 0.0546357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 220 259 0.483127 0.276011 0.716684 -0.2779677 -0.8964911 0.3359986 0.0783747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 220 560 -0.067022 -0.931651 0.558573 0.5434464 -0.1001902 -0.6337383 0.5412982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 221 258 0.458207 -0.921264 0.522960 0.2535446 -0.1219488 -0.2526326 0.9257540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 221 561 -0.564878 0.185185 0.752691 0.6690125 -0.5455522 -0.5046427 0.0114391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 222 257 -0.516962 -0.709470 0.025314 0.1001731 -0.7118682 0.1031778 0.6874324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 222 562 -0.365540 0.447634 0.828558 -0.0611587 -0.8796924 -0.4023674 0.2459703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 223 256 0.986485 0.277651 -0.562492 -0.4213606 0.1613564 -0.8824751 0.1328799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 223 563 0.397024 0.660191 0.604292 0.5392621 0.3402687 0.7531961 0.1615833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 224 255 -0.251999 0.805130 0.405847 0.0058798 -0.5559129 0.3810632 0.7387266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 225 254 0.701051 -0.242488 0.779950 -0.6865404 0.3839109 0.6124865 0.0783259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 225 565 -0.558658 0.442557 0.782767 0.1891638 0.3125385 -0.5593780 0.7440652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 226 213 0.869703 0.211053 -0.055720 -0.4553591 0.6284956 0.5144236 0.3647050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 226 253 -0.923674 -0.169556 0.144165 -0.3208460 0.0370203 0.8844292 0.3368567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 226 566 -0.054822 0.714337 0.894810 -0.6094533 0.2509820 0.7265165 0.1942896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 227 252 0.951550 0.151028 0.285902 0.2690150 0.6438423 -0.6417481 0.3182099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 227 567 -0.224727 -0.751046 0.676231 -0.1012720 -0.2625130 0.4625612 0.8407544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 228 568 -0.124537 0.545987 0.833189 -0.5215507 -0.3635767 -0.5371791 0.5542883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 229 250 0.024801 -0.911145 -0.428446 0.2981047 -0.5446376 0.7571634 0.2029954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 229 569 0.337778 -0.560554 0.693650 0.4315097 0.4066772 -0.7917541 0.1467602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 230 249 -0.507978 0.275636 -0.762041 -0.7240491 0.2433606 0.5069374 0.3994283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 230 570 0.514296 0.936981 0.173296 -0.4856909 -0.4496493 -0.5323910 0.5277118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 231 571 -0.773417 0.563661 0.075215 -0.7400036 0.2203205 0.4975924 0.3952914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 232 247 -0.144240 -0.768231 0.120933 -0.1755353 0.4933097 -0.4928420 0.6949386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 232 572 0.181805 0.032824 0.816759 -0.0414147 0.5966473 0.1593229 0.7854381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 233 573 -0.562716 0.228680 0.714410 -0.2028559 -0.6692604 0.6423483 0.3135740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 234 245 -0.049253 1.028630 -0.206960 0.0466845 -0.1862446 -0.9808518 0.0326069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 234 574 -0.058651 0.069929 0.865355 -0.3723159 -0.1362717 -0.9179704 0.0118851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 235 575 0.916740 0.036898 0.568528 -0.4587949 0.2785807 -0.6741923 0.5073113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 236 203 0.308618 -0.120709 -1.001259 0.4052173 -0.3853660 0.2795958 0.7804602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 236 243 -0.331209 0.286644 0.860727 -0.0598030 0.8363032 -0.3845340 0.3862047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 236 576 0.800374 -0.289034 0.431257 0.6634679 -0.0118036 0.2722838 0.6968017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 237 242 -0.715461 -0.618669 -0.258826 0.5934591 0.0658882 -0.4477974 0.6655392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 237 577 -0.196221 -0.301108 0.862566 -0.0244170 -0.0222508 -0.8221363 0.5683314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 238 201 -0.704896 -0.603073 0.537433 0.7729294 0.3022049 0.0955542 0.5496560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 238 241 0.421908 0.497585 -0.533563 0.1736418 -0.1175253 0.2674263 0.9404890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 238 578 0.872007 -0.496230 0.099042 -0.6629807 0.3814353 -0.4339529 0.4760763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 239 200 0.336664 -0.820355 0.512869 0.4284520 0.1249132 0.6729351 0.5899016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 240 540 0.328556 0.831758 0.383554 -0.5834168 0.0484527 -0.1105259 0.8031570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 241 278 0.410455 0.060909 -0.853102 0.6750925 -0.1878049 0.7044393 0.1128926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 241 541 0.667917 -1.083691 0.222514 -0.4801377 -0.1839855 -0.8538731 0.0807330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 242 277 -0.026126 -0.597306 0.670461 -0.2449108 -0.8179943 -0.5177227 0.0535467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 242 542 -0.506665 0.592210 0.545180 -0.2930306 -0.1789923 0.4664459 0.8151828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 243 276 -0.218231 -0.508211 -0.743571 -0.0143673 -0.6157480 -0.4731306 0.6299170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 243 543 -0.872672 -0.333322 0.429719 -0.0075113 -0.4169146 0.8594346 0.2958005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 244 235 -0.816791 0.186866 0.396469 0.0278552 -0.3171228 -0.0820499 0.9444178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 244 275 0.855749 -0.266883 -0.305702 -0.1666892 0.5476794 0.2919651 0.7661712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 244 544 0.407594 -0.024823 0.943594 0.4927389 -0.1307220 0.6284856 0.5874742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 245 274 0.229455 -0.941980 0.196314 -0.4239944 0.5532089 0.0641794 0.7141916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 245 545 0.174535 0.167002 0.838521 -0.3466276 0.1405843 -0.0814368 0.9238254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 246 233 -0.670597 0.611340 0.373241 0.5647950 0.0054696 0.2090404 0.7982974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 246 273 0.748974 -0.670153 -0.310116 0.3639919 0.3931809 -0.7603705 0.3670904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 246 546 -0.566144 -0.959825 0.501116 0.9645172 -0.0854071 -0.1789815 0.1742922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 247 272 0.811264 -0.656058 -0.016162 -0.3497560 -0.1844029 -0.4776277 0.7845624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 248 271 0.521294 0.434270 -0.912834 0.1100251 0.1724583 0.5490855 0.8103442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 248 548 0.425051 0.617606 0.601358 -0.2301704 0.3514504 -0.5198625 0.7438059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 249 549 0.126821 -0.786933 0.393464 0.0582063 -0.3811855 0.0685646 0.9201133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 250 269 -0.328252 0.773399 0.442554 -0.0704411 0.3216820 0.8961611 0.2974122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 250 550 0.140361 -0.406454 0.908061 0.1119369 -0.2687916 -0.8822181 0.3700168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 251 268 0.819317 -0.468983 0.408712 -0.1128217 -0.0308748 -0.4083679 0.9052920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 251 551 -0.725261 -0.062258 0.688181 -0.2469782 -0.3253974 -0.5685978 0.7140132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 252 267 -1.034563 0.230423 -0.098064 -0.6415601 -0.3940558 0.4234543 0.5037927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 252 552 -0.526334 -0.371246 0.846803 0.1746458 -0.0604299 0.7232876 0.6653586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 253 553 -0.081664 -0.620949 0.537856 0.6353933 0.1611614 -0.6508783 0.3829618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 254 265 -0.572618 0.191330 -0.872926 -0.6824599 0.0983962 0.6764298 0.2588618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 254 554 -0.720944 0.604043 0.332376 -0.4330593 -0.6865890 -0.3040334 0.4986169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 255 264 0.959426 0.389625 -0.215391 0.0017194 -0.7836200 0.5655830 0.2570071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 255 555 0.389667 -0.715295 0.743985 0.5225322 0.2889482 -0.1627599 0.7854797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 256 263 -0.949594 -0.192141 0.141727 0.5411476 0.6666625 -0.4885149 0.1551570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 256 556 0.057114 -0.995600 0.279565 -0.0367163 -0.0239471 -0.3794034 0.9241924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 257 262 0.079664 -0.645350 0.764383 -0.7206904 -0.1007062 -0.6858798 0.0056912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 257 557 0.886527 0.559158 0.309927 -0.1520375 -0.2035710 -0.1856148 0.9492052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 258 558 -0.655292 0.243192 0.795285 -0.7340874 -0.4175861 0.5253607 0.1036041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 259 559 -0.263212 -0.871879 0.101574 0.7776510 -0.0836654 -0.3312714 0.5277483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 260 299 0.533680 -0.855787 -0.351721 -0.4161164 -0.2436270 0.3695278 0.7943187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 260 520 0.566573 0.026220 0.863343 -0.0613030 -0.2603848 -0.9634850 0.0117654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 261 298 0.453871 0.497691 -0.815449 0.0099670 0.6201682 0.6398093 0.4538018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 261 521 -0.583444 0.972996 0.148454 -0.0735126 -0.1989080 0.6843127 0.6976730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 262 297 0.661955 0.648401 -0.140678 -0.2509901 0.1511950 -0.6172890 0.7301358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 262 522 0.349775 -0.181078 0.796505 0.4363443 0.3906099 0.0167733 0.8103988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 263 296 -0.088872 -0.963181 -0.083859 0.1517826 -0.0052942 -0.0773693 0.9853669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 263 523 -0.837316 0.102613 0.658862 0.2511477 -0.0390314 0.7113799 0.6552404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 264 524 -0.301915 -0.913393 0.086261 -0.3900459 0.2716134 -0.8740614 0.1005333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 265 525 -0.386409 -0.019840 1.171039 -0.3904374 0.3158286 -0.8194893 0.2761307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 266 293 -0.222271 -0.334572 0.832482 -0.0467138 0.1370883 -0.6892520 0.7098988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 266 526 0.418251 0.929409 0.373130 0.1780702 0.3959238 0.3297112 0.8383471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 267 292 -0.114604 -0.033912 0.940800 0.5434634 -0.2650589 0.0510426 0.7948497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 267 527 -0.735811 -0.608965 -0.086101 -0.0616613 -0.7468428 0.6534131 0.1071220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 268 528 -0.180689 -0.818961 0.549168 -0.1316208 -0.0335185 -0.8988305 0.4167208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 270 289 -0.615968 0.750001 -0.106499 -0.3087489 -0.5818171 0.5831778 0.4754646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 270 530 -0.266384 -0.277495 0.926174 -0.6170109 -0.4669358 0.6280408 0.0826634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 271 288 0.527047 -0.549137 -0.578653 0.7618012 0.5227345 0.3620881 0.1236921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 272 287 0.873543 0.417709 -0.173502 0.2105071 0.1889375 -0.9198278 0.2718570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 272 532 0.588502 -0.735483 0.014011 -0.6924239 0.2838624 -0.6322900 0.2004510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 273 286 -0.040608 0.903623 0.042962 -0.1496001 -0.1344136 -0.8852753 0.4193334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 273 533 -0.034212 -0.043951 1.048562 -0.2157072 -0.2845779 0.9312407 0.0726404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 274 285 0.208599 -0.805553 -0.570007 -0.7091173 -0.0137419 0.6820326 0.1783125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 275 284 0.561626 -0.806253 0.359367 0.1927711 0.1406791 -0.1303398 0.9623202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 275 535 -0.630345 -0.374858 0.640867 0.0480128 -0.6313812 -0.4592477 0.6230121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 276 283 -0.166547 -0.785283 -0.197797 0.6624888 0.5430244 0.4935172 0.1505783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 276 536 0.901656 -0.355910 0.580168 -0.1364543 0.1078624 0.0284893 0.9843446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 277 282 -0.108964 0.459442 -0.956513 -0.0108390 -0.3829322 -0.7674362 0.5140887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 277 537 0.879746 0.513721 0.222183 -0.3333203 0.8330900 0.3068976 0.3172892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 278 281 -0.807354 -0.048847 0.460297 -0.0575361 -0.4797420 0.8732816 0.0625820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 278 538 0.098416 0.466448 0.721431 -0.2799536 0.0143714 -0.8902225 0.3590590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 279 240 0.054775 0.779445 0.461172 0.0941779 0.0417254 0.9637076 0.2462869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 279 539 -0.397481 -0.564832 0.667485 -0.0541161 -0.8571896 0.2206242 0.4621930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 281 318 0.773568 -0.085003 0.574292 0.8567866 0.3082778 -0.4121951 0.0312543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 281 501 -0.352575 -0.895032 0.129542 0.2724809 -0.6806045 0.6800398 0.0088034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 282 502 -0.755803 0.733153 -0.091944 -0.3486649 0.2663714 0.3269882 0.8369933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 283 316 -0.843629 -0.113802 -0.515867 -0.8365222 0.3629834 0.2958295 0.2845321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 283 503 -0.062370 1.032425 0.404581 -0.3344684 0.2146754 0.1852829 0.8987300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 284 504 -0.768682 -0.485069 0.489311 -0.5535418 -0.5368794 0.2326331 0.5926499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 285 314 0.222769 0.815614 -0.431780 0.1133434 -0.6622135 0.2183625 0.7077742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 285 505 -0.296500 0.650717 0.811883 -0.5806579 -0.0321508 0.8040239 0.1238882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 286 313 -0.796250 -0.538576 0.378689 0.0988013 0.5009143 -0.8237831 0.2463829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 287 507 0.149586 0.984529 0.269646 -0.1473233 0.1934448 -0.0612296 0.9680526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 288 311 -0.780125 0.359166 0.701805 0.6221594 0.4218826 0.5796541 0.3145377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 288 508 0.365256 1.051602 0.103540 -0.5447373 0.2601583 -0.7143535 0.3539464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 289 310 0.630936 0.415980 0.328833 -0.0950632 -0.3573464 -0.1050377 0.9231650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 289 509 0.058273 -0.748303 0.715069 -0.1897222 0.2444957 0.9508787 0.0075598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 290 269 0.776380 -0.765024 -0.285766 -0.1430904 0.4663115 0.8728362 0.0153534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 290 309 -0.780791 0.527475 0.294201 0.0885701 0.4085807 -0.8965413 0.1463927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 290 510 0.432525 0.067319 0.803080 0.3149815 -0.3036846 0.8222404 0.3639822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 291 268 -1.097115 -0.225655 0.073294 0.1693571 0.2894548 -0.0014639 0.9420892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 291 308 1.053761 -0.048792 0.067627 0.1840495 0.4989000 -0.7980586 0.2834203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 291 511 0.065741 -0.714796 0.531978 0.6357040 0.5742150 -0.1319484 0.4987456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 292 307 0.552813 0.837801 0.322765 0.5304803 0.4947926 -0.6563384 0.2073423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 292 512 -0.499585 0.096866 0.849366 -0.0245936 0.3033776 -0.7858161 0.5383775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 293 306 0.424567 -0.165354 0.858137 -0.4300590 -0.4395203 -0.0995782 0.7822758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 293 513 -0.727121 0.494500 0.092423 -0.0243261 -0.5003699 0.3536401 0.7899221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 294 265 0.235423 -0.360021 0.871103 -0.2695960 0.7832195 0.1811444 0.5301622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 294 514 0.774324 0.579245 -0.049607 0.4088548 0.7866121 0.3837812 0.2584398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 295 264 -0.187533 -0.507431 -0.701224 -0.2499969 0.8856065 -0.2473262 0.3033684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 296 303 0.105794 -1.079807 0.135378 -0.0767879 -0.0351160 -0.6088609 0.7887705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 296 516 -0.794073 0.042601 0.704383 0.0361179 0.3190247 0.9199765 0.2248599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 297 517 0.456848 -0.179845 0.872381 -0.0410056 -0.3175048 0.1015189 0.9419146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 298 301 0.397974 -0.793304 0.287927 -0.7046428 -0.3895091 -0.4793215 0.3493024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 298 518 0.508835 0.599217 0.455626 0.1979791 0.1366150 0.6217623 0.7453538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 299 519 0.698931 -0.788179 0.128346 0.7988104 -0.1474681 -0.3232956 0.4854225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 300 480 -0.345645 -0.686573 0.640375 0.5949313 0.0885389 0.6978377 0.3888961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 301 338 0.175476 0.637244 -0.442718 -0.2109222 0.4371353 -0.2245155 0.8449955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 301 481 0.608907 0.257686 0.668732 0.0153018 0.1151365 -0.9817375 0.1506685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 302 337 0.067719 0.728104 -0.753010 0.5674359 -0.6221911 0.0599336 0.5360062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 303 336 1.002195 -0.069814 0.302133 -0.1078488 -0.4893474 0.1125464 0.8580449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 303 483 -0.385798 -0.528568 0.714537 0.5285541 0.4970976 -0.6702320 0.1559280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 304 295 -0.545840 0.379477 -0.586416 -0.2339841 0.0250682 -0.8784699 0.4158288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 304 335 0.705392 -0.136079 0.629019 -0.5084147 -0.1341089 0.2877092 0.8004703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 304 484 -0.712122 0.016632 0.873949 0.3509675 -0.6026894 0.3087237 0.6467433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 305 294 0.740697 0.240979 0.799772 0.4630875 -0.0459641 0.8675898 0.1752860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 305 334 -0.732851 -0.081817 -0.559194 -0.0506130 -0.5601717 -0.8209525 0.0984024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 305 485 -0.368897 -0.102381 0.873732 0.4123767 0.1164380 -0.5433901 0.7218829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 306 333 0.740508 -0.522426 -0.204220 0.0689438 0.5857832 -0.4290361 0.6841293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 306 486 0.076090 -0.358763 0.805212 0.1566455 -0.1645925 0.1863158 0.9558546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 307 332 -0.165786 -0.071127 -1.085177 0.3535117 -0.8034405 -0.0666555 0.4744153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 307 487 -0.596357 -0.799663 0.347606 0.7172215 -0.3926438 -0.3082585 0.4862107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 308 331 -0.863986 0.660110 -0.318588 -0.5775405 -0.2086993 0.0935579 0.7836699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 308 488 -0.225062 0.001745 0.781976 -0.2647207 -0.5585205 -0.0288617 0.7855856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 310 329 0.889795 0.402448 -0.157338 0.7793566 0.6001644 0.0296167 0.1775639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 310 490 0.307529 -0.847912 0.262327 0.5861942 -0.1383090 0.0700935 0.7951942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 311 328 0.600382 0.257455 -0.504879 0.3552450 -0.5621187 0.7244159 0.1817835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 311 491 0.789117 -0.232533 0.647195 -0.3953089 -0.2741219 -0.8766899 0.0017102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 312 287 -0.018935 0.409155 0.956388 0.2829080 0.0176172 0.9516800 0.1181434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 312 327 0.131005 -0.480452 -0.933046 0.4424097 -0.0406231 0.0360593 0.8951666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 312 492 -0.152907 -1.002238 0.498001 0.3418104 -0.2699835 -0.0553769 0.8984476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 313 326 0.645844 -0.443632 0.546919 0.4707847 0.5563793 -0.6600268 0.1821223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 313 493 -0.727189 -0.649055 0.259622 -0.6025524 -0.2847966 0.5449177 0.5088085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 314 325 -0.339431 0.580465 -0.767006 -0.5541147 0.7836027 0.0785337 0.2697335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 314 494 1.019850 0.390931 -0.069872 0.1766080 0.7362374 -0.1320441 0.6397878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 315 284 -0.102665 0.052022 -1.037062 -0.4444836 0.0868373 -0.6488401 0.6114737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 315 324 0.090963 -0.061178 1.152615 -0.6569046 0.0318920 -0.7072304 0.2593924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 315 495 0.033540 0.899650 0.025969 -0.7098177 0.5379250 0.1201744 0.4385814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 316 323 -0.419499 0.763874 0.529541 0.4277572 -0.1703874 -0.7921117 0.4006882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 316 496 -0.538805 -0.587152 0.414936 -0.0198661 0.0788177 -0.9237121 0.3743648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 317 322 0.960782 0.144727 0.227049 -0.4774697 -0.3978924 0.7752325 0.1127778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 317 497 -0.221355 0.771510 0.847309 0.5759339 -0.1924301 -0.7690105 0.1997337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 318 321 -0.100643 0.476637 -0.980182 0.3522886 -0.0743299 -0.5714812 0.7374124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 318 498 -0.755449 0.527243 0.456675 -0.2404655 -0.3479456 -0.2019517 0.8833605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 319 280 0.631794 -0.606456 -0.079726 0.3114030 -0.0749530 0.4899079 0.8108024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 321 358 -0.210187 -0.451612 -0.706711 0.3178040 -0.0343418 -0.0819778 0.9439814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 321 461 -0.821876 -0.146733 0.519174 0.3337765 -0.6538239 -0.6025255 0.3131622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 322 357 -0.821907 -0.148885 -0.850548 0.4162716 -0.1892527 0.7278157 0.5110634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 322 462 0.034646 -0.902217 -0.054090 0.9100893 -0.1018209 0.3918142 0.0886096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 323 356 -0.980757 -0.288497 0.386779 -0.3901503 -0.1398465 0.8530629 0.3170322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 323 463 0.080316 0.379712 0.738829 -0.0400897 -0.3128603 0.0296154 0.9484905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 324 355 0.880147 -0.307365 0.259305 0.7499229 -0.5352744 -0.2774596 0.2722372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 324 464 -0.146863 -0.978791 0.282467 0.6467756 0.1335174 0.4903507 0.5686920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 325 354 0.064625 0.826353 0.824115 0.6010742 0.1313718 -0.4907687 0.6169257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 325 465 -0.701487 -0.514602 0.577352 0.1623634 0.3410784 -0.1654224 0.9110099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 326 353 -0.918564 0.337638 0.308514 0.7313004 0.2734357 0.4804632 0.3994844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 327 352 0.281459 -0.864770 -0.287991 -0.1099350 -0.8059465 0.3439596 0.4691017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 327 467 -0.085443 -0.357912 0.835067 -0.3316357 0.1995628 0.3188404 0.8651782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 328 351 -0.980784 -0.143521 -0.342627 0.2399704 -0.2264659 0.0090074 0.9439525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 328 468 -0.007805 -0.744942 0.730151 0.0845374 0.3952649 -0.3258378 0.8546630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 329 350 0.578103 0.674502 0.192070 -0.0983590 -0.8398996 -0.5126244 0.1486960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 329 469 -0.798444 0.708110 0.065002 0.3730692 -0.1342316 -0.8081203 0.4355949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 330 309 0.276199 -0.417602 -0.900085 0.0276336 -0.7015666 0.6971647 0.1449210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 330 349 -0.357876 0.268862 0.888457 -0.6667685 0.5439116 -0.4717431 0.1924536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 330 470 0.694927 -0.708072 0.328257 0.0274688 -0.5486621 0.7437630 0.3808306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 331 471 -0.116371 -0.874679 0.281450 0.6122164 0.1867552 -0.4963359 0.5864846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 332 347 -0.738596 -0.402001 0.648966 -0.6775160 0.0799496 -0.4000255 0.6120129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 332 472 0.891615 -0.053840 0.450950 0.4746510 0.3498029 -0.3919352 0.7062090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 333 473 -0.634995 -0.555847 0.427666 -0.2740431 0.1840691 0.9387067 0.0992409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 334 474 0.692377 0.686566 0.050633 -0.4837471 0.3128965 -0.8017714 0.1588934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 335 344 0.489516 -0.878401 -0.340644 0.6431214 0.0273472 0.3579526 0.6764000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 335 475 -0.581355 -0.559767 0.701293 -0.0933089 -0.6148742 0.5350787 0.5717640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 336 343 0.496460 -0.301405 -0.795577 0.0827794 -0.7390057 0.6672002 0.0431516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 336 476 0.205209 -1.015443 0.389716 -0.6075472 -0.2675050 0.7233584 0.1899478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 338 341 0.269250 1.034724 -0.000854 0.4420395 0.2419508 -0.4605120 0.7307459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 338 478 0.015647 -0.019927 0.836727 -0.0500867 -0.6210748 -0.7808946 0.0442836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 339 479 -0.079757 0.358420 0.993328 -0.2809646 -0.4731612 0.5275300 0.6472167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 340 379 -0.273291 0.203519 0.803242 0.5235190 0.1429492 -0.5625411 0.6237315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 340 440 -0.666168 -0.602244 -0.093620 0.3066549 0.1994293 -0.1585293 0.9170928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 341 441 -0.857309 0.193942 0.464404 -0.3691862 0.3166021 0.5633902 0.6678743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 342 337 -0.644315 -0.803474 -0.129671 0.4678105 -0.8756602 -0.0539875 0.1070419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 342 377 0.490518 0.876717 0.082063 -0.3965361 -0.8471693 -0.1729459 0.3084689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 343 443 -0.107815 -0.374013 1.064295 0.2440819 -0.4441563 0.0842829 0.8579310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 344 375 -0.302998 -0.356256 0.918138 -0.0196989 0.0021712 0.2772395 0.9605964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 345 334 1.000868 -0.606208 0.617453 0.4937176 0.7374043 0.4327782 0.1586850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 345 374 -0.895882 0.204232 -0.513985 -0.4250811 0.1948875 0.7209402 0.5114394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 345 445 0.090448 0.707566 0.648746 -0.5652683 0.0772949 -0.5723041 0.5890375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 346 446 0.689783 0.643130 0.300697 -0.1143003 0.1920077 -0.9732212 0.0539343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 347 372 0.346086 -0.775332 -0.572809 0.8762896 0.3360037 0.3408904 0.0548807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 348 331 0.710487 -0.597583 0.516137 -0.7042103 -0.3258893 0.0367397 0.6297096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 348 448 -0.537062 0.190326 0.895945 -0.3979594 -0.7187407 0.0688374 0.5659519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 349 370 0.060568 -0.830013 -0.558414 -0.3844343 0.6202712 -0.5779293 0.3653378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 349 449 0.698772 -0.607043 0.489784 0.6694372 0.4311422 -0.2825842 0.5348985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 350 369 -0.805435 0.740335 0.528100 -0.4883823 0.2654018 -0.6887437 0.4654855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 352 452 0.501744 -0.889307 -0.161658 -0.1357727 0.4330969 -0.8901554 0.0402033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 353 366 -0.222620 -0.023107 -0.922965 -0.4411240 -0.4355840 -0.7547927 0.2143928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 353 453 0.081106 0.983666 0.010868 -0.4626498 0.7869307 0.2451312 0.3265056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 354 365 -0.757423 0.390901 -0.368583 0.2778755 0.3898579 -0.8648234 0.1512498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 354 454 -0.374113 -0.204769 0.774491 0.3226466 -0.0715989 -0.1215105 0.9359530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 355 364 0.642287 -0.496079 -0.891100 0.2744285 0.3207685 0.6131962 0.6676728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 355 455 0.535663 0.770950 0.222076 -0.4144981 -0.6047541 -0.6504645 0.1983927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 356 363 -0.050889 0.316701 0.932695 0.3531086 -0.4224391 -0.7744915 0.3114841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 356 456 -0.286099 -0.884155 0.385670 0.2058282 -0.9606407 0.1601745 0.0956470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 357 362 -0.766807 0.821006 -0.482051 0.0095869 -0.4664736 -0.4371724 0.7688893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 357 457 -0.323123 0.308108 0.868048 -0.2582546 -0.6326571 -0.3126952 0.6597510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 358 361 -0.218094 -0.680571 -0.318196 0.4821565 -0.4845418 -0.1093325 0.7216584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 358 458 -0.682042 -0.125205 0.573438 -0.5922962 -0.5920252 -0.0849754 0.5398802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 359 459 -0.814707 -0.602596 0.229503 -0.2378858 -0.4800427 0.3758587 0.7561082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 360 399 0.721047 0.417593 -0.391672 -0.2037383 -0.1387578 0.1418184 0.9587098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 361 421 -0.033249 0.746888 0.696773 -0.4950369 0.5319704 0.6637540 0.1771344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 362 397 -0.790238 -0.264460 0.185332 0.2236308 0.6681032 -0.0780236 0.7053649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 362 422 0.456734 0.204958 1.065389 0.2866679 0.1942486 0.5936222 0.7264308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 363 396 -0.701980 0.522146 0.394642 0.4397294 0.5358667 0.7161426 0.0813919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 363 423 0.889972 0.592666 0.084404 -0.9646101 -0.0015737 -0.2608657 0.0383912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 364 395 -0.308984 -1.029185 -0.034863 -0.1402788 0.2361793 -0.1097196 0.9552501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 364 424 0.567228 -0.181522 0.545797 0.3145006 0.5807465 0.1274963 0.7399781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 365 394 0.897340 -0.236166 -0.198558 -0.2949135 -0.0474638 -0.1365508 0.9445248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 365 425 0.008897 -0.741208 0.651231 0.8587321 -0.0988043 0.0736654 0.4973835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 366 393 -0.708393 -0.736414 -0.273243 0.1756070 0.1553205 -0.3119810 0.9207093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 367 352 0.592939 0.059621 0.647776 -0.2173897 -0.6789859 -0.1725602 0.6796638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 367 392 -0.699279 -0.070946 -0.556203 -0.0858705 0.1850982 -0.9789550 0.0034679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 367 427 -0.277765 -0.709104 0.559538 0.1926692 0.1339432 -0.4565775 0.8581811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 368 351 -0.867602 0.233323 -0.051661 0.0618689 -0.7231915 0.6865401 0.0427672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 368 391 1.171388 -0.179484 -0.068653 0.0823707 -0.0654510 -0.8589326 0.5011647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 368 428 -0.110358 -1.034142 0.385716 0.2772844 -0.8201943 0.2024628 0.4576062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 369 390 -0.379706 -1.059904 -0.309682 -0.2202221 0.0602015 0.2438179 0.9425661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 369 429 -0.080662 -0.427528 0.926167 -0.4672182 0.0810924 0.6032898 0.6412274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 370 389 0.459828 0.809981 0.307757 0.0536227 0.0418124 -0.6690492 0.7401010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 370 430 0.131568 -0.578776 0.739269 0.6667654 -0.2699275 0.5521149 0.4215829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 371 348 0.592820 -0.614445 -0.372312 0.5820861 0.1832509 -0.0295536 0.7916574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 371 388 -0.711790 0.488692 0.362278 0.7921943 0.2068508 -0.0110175 0.5740379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 371 431 -0.278644 -0.740907 0.807996 -0.2524065 0.2069241 -0.7223679 0.6096376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 372 432 0.658550 0.947987 0.265972 -0.4270336 0.1419363 -0.8087070 0.3788000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 373 346 -0.347954 -0.194240 0.752884 0.6714799 0.6410546 0.3344730 0.1621468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 373 386 0.422604 0.097975 -0.934164 0.0947442 0.1059429 0.5705347 0.8088818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 373 433 0.542044 0.743496 0.326331 -0.5004029 -0.0693713 0.2941031 0.8113494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 374 434 -0.087925 -0.186401 0.978903 -0.3993102 0.3375314 0.2229050 0.8227620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 375 384 -0.640941 -0.175479 0.901834 0.3250754 -0.4561047 -0.5294849 0.6371344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 375 435 0.139288 0.895447 0.304679 0.1824068 0.4082959 0.1234189 0.8858838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 376 383 0.613857 0.486063 -0.657061 -0.7579060 0.3860921 -0.1007275 0.5161060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 376 436 0.183752 0.486255 0.779898 0.1622700 -0.1966559 0.9604596 0.1118582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 377 382 0.204413 0.818029 0.180688 -0.2811901 -0.0268552 -0.0001971 0.9592762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 377 437 0.815904 -0.334559 0.502843 -0.8162546 0.3876184 -0.2370206 0.3567936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 378 341 0.603238 0.792728 0.375613 0.3389682 0.3923513 0.7495825 0.4114452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 378 381 -0.580079 -0.811376 -0.084212 0.1165187 -0.2006105 0.1173208 0.9656162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 378 438 0.774844 -0.729391 0.360808 -0.2400123 0.7352006 -0.6337565 0.0150594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 379 439 0.347655 -0.475528 0.997244 0.1329072 0.3275581 0.9288029 0.1112049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 381 401 0.565933 -0.759463 0.180146 0.1401335 0.3322346 -0.7634199 0.5358851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 382 402 0.816640 -0.532417 0.294365 0.5107682 0.6196068 0.5276321 0.2771419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 383 403 -0.495906 -0.787574 0.182526 0.0154186 -0.8167981 0.5656880 0.1122503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 384 404 -0.715717 0.774138 0.105526 0.6811125 -0.1193061 -0.7158229 0.0972081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 385 374 -0.887827 -0.092938 -0.512487 -0.6099483 -0.3156704 -0.4707585 0.5538065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 385 405 -0.259058 0.990600 0.101104 -0.9199706 0.3116755 -0.1050887 0.2132342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 386 406 0.926608 -0.425386 0.369082 -0.5469247 0.5914945 -0.5465101 0.2287667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 387 372 0.796776 0.019316 -0.686490 0.4919187 -0.0196140 -0.1896810 0.8495013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 387 407 0.869694 0.144593 0.655567 0.0622527 0.3315124 0.3120124 0.8881849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 388 408 -0.588797 0.847811 0.520430 0.4081454 -0.8589174 -0.2632894 0.1623481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 391 411 0.798347 0.511406 0.300925 0.0827253 0.0237138 0.5694427 0.8175140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 392 412 0.449689 0.273777 0.885957 -0.8341588 -0.0315260 -0.4032287 0.3749559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 393 413 -0.004154 -0.318590 0.972522 0.0093732 0.0674731 0.6151122 0.7854912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 394 414 0.364448 -0.916545 0.142623 0.0615751 0.8965585 -0.0328361 0.4373936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 395 415 0.371959 -0.249231 0.956081 0.0248727 0.1844092 0.8836869 0.4295021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 396 416 0.112938 0.113491 1.118278 -0.6884356 -0.1439355 -0.1873438 0.6857414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 397 417 -0.693369 0.583111 0.295723 -0.2216588 -0.2354312 0.8552270 0.4050016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 398 361 -0.860496 0.262138 -0.267041 -0.1565411 0.3434442 0.1725998 0.9098078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 398 418 0.218694 0.673009 0.373661 0.1570145 0.0672265 0.0604768 0.9834478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 399 419 0.599077 -0.732029 0.342826 -0.6687722 0.0811550 -0.7335092 0.0901218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 400 380 0.062837 0.087806 -1.279539 -0.4374052 -0.1548585 -0.3689997 0.8053165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 400 439 0.078904 -0.905404 0.083881 0.3450207 0.3751441 0.5121164 0.6913497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 400 1180 -0.010832 -0.006946 1.059421 0.5318997 0.0124333 0.3239401 0.7822985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 401 438 -0.380899 0.764317 -0.499881 -0.3847618 0.1368610 -0.7661491 0.4962287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 401 1181 0.150581 0.683565 0.554289 -0.3216685 -0.4689740 -0.7182551 0.4008771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 402 437 -0.629442 -0.522055 -0.408125 0.2205728 0.0013303 0.9745217 0.0406610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 402 1182 -0.681072 0.635238 0.521371 0.0392885 -0.2671145 -0.9455865 0.1815830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 403 1183 0.525381 -0.436847 0.836674 -0.3121611 0.7483304 -0.5784979 0.0888667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 404 435 0.818603 0.056568 0.688320 0.8270797 -0.2078043 0.1785381 0.4907960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 404 1184 -0.498625 -0.452661 0.802888 0.5459324 -0.2621340 -0.7800123 0.1575578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 405 434 -0.524243 0.677838 0.040473 0.5128906 0.3802899 0.0068579 0.7695945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 405 1185 -0.999259 -0.549656 0.208044 0.6687898 -0.5461413 0.3941094 0.3148455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 406 1186 0.242182 -0.840757 0.569986 -0.2339320 0.1334254 -0.0288508 0.9626220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 407 432 0.587056 -0.418503 -0.259492 0.2967457 0.3737348 -0.8596445 0.1824161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 407 1187 0.237618 -0.090900 0.826682 -0.1798362 -0.1293835 0.6615908 0.7163913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 408 431 -0.252647 -0.006990 -1.101401 -0.5187981 -0.3124710 0.6549644 0.4519204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 408 1188 -0.228530 0.786970 0.043144 -0.7561173 -0.2300291 -0.1693722 0.5888007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 409 389 -0.899653 -0.516772 0.020423 0.7230291 0.4795751 0.4799282 0.1300214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 409 430 -0.696102 0.999779 0.171556 -0.2852397 0.2314415 0.0727840 0.9272409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 409 1189 0.722104 0.571085 0.114046 -0.2442861 0.4942469 0.5016088 0.6666580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 410 390 -0.856337 -0.326353 -0.373341 -0.1148273 0.1845154 0.8097500 0.5450446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 410 429 -0.379453 0.727368 0.361568 -0.1470730 -0.0170106 0.9844597 0.0944425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 411 1191 0.614022 -0.652221 0.315795 -0.0373915 -0.4987128 0.8188297 0.2817896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 412 427 0.054992 -0.276194 -0.785885 -0.3651497 0.6887209 -0.6205504 0.0851257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 412 1192 0.720190 -0.629346 0.299506 -0.3450745 -0.0239141 -0.9373385 0.0418112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 413 1193 -0.264793 0.055929 0.928617 0.3037428 0.0949576 0.3505226 0.8808276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 414 425 -0.058864 -0.158274 -0.945507 0.3551659 -0.1570463 0.9003915 0.1961858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 414 1194 -0.478485 -0.927980 0.098535 0.1129308 -0.1963254 -0.2404193 0.9438758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 415 424 0.762094 -0.392356 0.589282 0.3457268 -0.1739654 -0.4977088 0.7762055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 415 1195 -0.654171 0.030398 0.856662 0.2595351 -0.2784425 0.1633767 0.9101754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 416 1196 0.469253 -0.875230 -0.006689 -0.1208361 -0.3297502 0.9356714 0.0343877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 417 422 0.069229 -1.195264 0.024749 -0.0155371 0.2060257 -0.2735315 0.9394107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 417 1197 0.855589 0.006191 0.487963 0.4811001 0.2993372 -0.0018039 0.8239761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 418 421 -0.783159 0.221944 -0.570089 0.2892587 -0.7077536 -0.6174128 0.1849746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 420 360 -0.810167 0.533826 -0.006845 0.5816368 0.0367397 0.2093115 0.7851991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 420 459 -0.442906 -0.716872 -0.481119 -0.0439091 0.8885179 -0.4175838 0.1850179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 420 1160 0.726040 -0.556728 0.088467 0.4428552 0.3848655 0.6998265 0.4074318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 421 458 0.653678 -0.275723 0.657905 -0.4585573 -0.0709503 -0.6274851 0.6252630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 421 1161 -0.892672 0.148684 0.519237 0.2641223 -0.6484416 -0.4287559 0.5709039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 422 1162 0.577348 0.272843 0.950418 -0.4753960 -0.6899248 -0.5416888 0.0676437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 423 416 -0.304009 -0.669287 -0.426868 -0.6180427 0.6612173 -0.1168325 0.4088581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 423 456 0.209769 0.699552 0.616399 -0.3432369 0.1122022 -0.1615544 0.9184222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 423 1163 0.651421 -0.724922 0.267985 -0.0566611 0.6746687 0.3699198 0.6362162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 424 1164 -0.498044 0.388799 0.734363 -0.4993646 0.5019206 0.5159774 0.4821598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 425 454 -0.837114 0.338225 -0.712885 -0.2004287 0.7843104 0.5431079 0.2229783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 425 1165 0.195961 0.900160 0.416968 -0.6221887 -0.0511107 0.6649395 0.4100297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 426 1166 -0.599986 -0.095080 0.851654 -0.3079659 -0.5696344 0.4824437 0.5898489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 427 1167 -0.052843 -0.351881 0.861039 -0.1104712 -0.0649093 -0.9909663 0.0396065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 428 411 -0.610104 -0.682325 -0.547119 -0.6071073 0.5262595 -0.3342784 0.4926760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 428 451 0.419320 0.776400 0.778332 0.4184163 -0.1515146 0.7715493 0.4546238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 428 1168 0.813072 -0.741280 0.404634 0.2985841 0.5165636 -0.6678711 0.4449244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 429 1169 -0.750542 -0.431212 0.169245 -0.3115251 -0.7692463 -0.0696962 0.5534931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 430 1170 0.774248 0.181191 0.608175 -0.1841679 0.3029957 0.8825723 0.3087748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 431 448 0.495176 0.892334 -0.078000 0.6956778 -0.3278066 0.3407641 0.5407912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 431 1171 0.865244 -0.491955 0.265583 0.2862486 0.0631289 -0.8970077 0.3308378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 432 447 -0.304791 1.039354 0.055688 -0.8340950 0.1781467 0.5148207 0.0866548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 432 1172 -0.676514 -0.192593 0.545420 0.0958869 -0.5309409 -0.6805253 0.4957749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 433 406 0.653229 0.730634 -0.493322 -0.4073289 0.5532729 -0.0963751 0.7201972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 433 446 -0.594806 -0.566782 0.642340 -0.2212071 0.7018046 0.2830184 0.6151734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 433 1173 0.958547 -0.305870 0.455425 -0.3376253 -0.1354428 -0.9131727 0.1837931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 434 445 -0.258962 0.232344 -1.032477 0.5920297 0.7211467 -0.3508962 0.0794998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 434 1174 -0.757866 -0.674395 0.143428 -0.7215413 -0.4555690 0.5162694 0.0728075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 435 444 0.827533 -0.159801 -0.247023 0.1426524 0.7996191 0.5212435 0.2618487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 435 1175 0.270905 1.014442 -0.057058 -0.2401384 -0.3942011 -0.6025338 0.6510700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 436 403 -0.601860 -0.334964 -0.495090 0.0950677 0.1274786 -0.3929294 0.9057140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 436 443 0.615995 0.489297 0.434523 0.5762064 -0.5663476 0.5743240 0.1318655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 437 442 0.644247 0.573163 -0.442728 0.0950298 0.6965208 -0.6742790 0.2262210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 437 1177 0.868089 -0.431745 0.145334 0.3840149 0.7360731 -0.2075389 0.5173553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 438 441 -0.881960 -0.316264 -0.358896 0.6822812 0.1140197 0.0771085 0.7180154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 439 1179 -0.055885 0.797998 0.816970 -0.4275515 -0.3226673 0.3279144 0.7781759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 441 1141 -0.313094 0.423933 0.659739 -0.5729834 0.6148404 0.3096629 0.4447136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 442 342 0.874509 -0.069570 -0.605616 0.7641669 -0.1819640 -0.3341903 0.5208214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 442 477 -0.312275 0.600944 -0.473609 -0.1941611 -0.7649004 0.3264370 0.5202573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 443 476 -0.073177 -0.923260 -0.187604 0.3733624 0.8530249 0.0336556 0.3630652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 443 1143 0.688141 0.126779 0.824888 -0.2887350 0.1683198 -0.6917311 0.6401630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 444 344 -0.158021 -0.695140 -0.786565 0.0588553 0.7813914 0.5217077 0.3373198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 444 475 -0.688675 -0.288104 0.556316 -0.2880622 -0.0585742 -0.9551557 0.0355922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 444 1144 0.194743 0.547277 0.925050 0.0325046 -0.4079546 0.8648573 0.2907548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 445 1145 -0.248408 -0.823757 0.712492 -0.0146006 -0.3885960 0.9190619 0.0640719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 447 347 0.859987 -0.652113 -0.203476 -0.1894216 -0.0694330 0.9324533 0.2997155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 447 472 -0.450239 -0.987932 0.639460 0.4331405 -0.8520051 -0.2912267 0.0407880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 448 471 0.181706 -0.452581 -0.946219 0.2136538 0.4890051 -0.4839828 0.6935321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 448 1148 0.856702 -0.728405 0.161519 0.0888315 0.7080243 -0.7004623 0.0127735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 449 430 0.276863 -0.472067 0.840582 -0.3661024 -0.4722843 0.1490510 0.7878454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 449 470 -0.481373 0.252445 -0.788768 -0.6919084 0.2427302 -0.3797778 0.5640156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 449 1149 -0.205334 1.019443 0.364798 -0.1505210 -0.0180727 -0.6860414 0.7115926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 450 350 -1.045678 0.709285 -0.385604 0.8175609 -0.0617690 0.2512380 0.5144495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 450 469 0.507485 0.759231 -0.263067 0.0401670 0.3472351 0.5116822 0.7848539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 450 1150 0.538171 -0.409537 0.407021 -0.6005699 0.4380780 -0.4325275 0.5102190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 451 468 0.839716 -0.461483 0.193523 0.0134207 0.3311087 -0.6887785 0.6448031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 451 1151 -0.438101 -0.230965 0.980006 -0.2540879 0.2551763 0.1942063 0.9124737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 452 427 0.906660 0.014988 0.514963 -0.5343824 -0.0865324 0.5475944 0.6380345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 452 467 -0.925431 -0.147947 -0.238164 -0.7719473 0.0746960 0.5831709 0.2417223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 452 1152 -0.325249 0.560322 0.931350 0.0236773 0.2746095 0.3778886 0.8838717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 453 426 0.770180 0.068774 0.484297 -0.1059974 -0.0671074 -0.4739341 0.8715776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 453 466 -0.833318 -0.008528 -0.653181 0.1242146 -0.3568896 0.1724557 0.9096481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 454 465 1.008307 0.006828 0.291804 -0.7784972 0.0924744 0.1848403 0.5926421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 455 424 -0.980691 -0.086440 -0.261534 0.0539586 -0.0175218 -0.4645190 0.8837440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 455 464 1.105943 -0.088254 0.344028 0.4722530 -0.4470348 -0.7122777 0.2641923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 455 1155 -0.169301 0.684856 0.855500 -0.0407741 -0.2307820 0.2849457 0.9294531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 456 1156 0.760314 -0.712595 0.136292 0.4482451 -0.5916510 0.4313426 0.5128051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 457 422 -0.619267 0.031912 0.908869 0.4560677 0.2638180 0.2692585 0.8061651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 457 462 0.533840 -0.161664 -0.670006 0.5870950 0.1593269 -0.2943796 0.7370719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 457 1157 0.806203 0.060649 0.656221 0.7704953 0.1328734 0.2078659 0.5877698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 458 461 0.788491 0.267815 0.419619 0.2622832 0.1377596 -0.7405700 0.6031466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 459 1159 -0.677305 -0.327044 0.712872 -0.1008043 0.4965370 -0.5381806 0.6735363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 460 1120 0.461509 0.323225 0.851055 0.4259271 0.2749765 -0.1367122 0.8510486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 461 498 -0.666451 0.915945 -0.062320 0.1722783 0.2909868 0.9365932 0.0918701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 461 1121 0.709324 0.480854 0.611244 0.0638239 0.2940047 0.9172108 0.2611743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 462 497 0.905053 0.071920 -0.062862 -0.6793923 0.4450761 -0.3245528 0.4847667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 462 1122 0.184599 1.069882 0.070975 -0.5423791 -0.0135323 0.5943487 0.5936257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 463 456 -0.317451 -0.355088 0.828566 -0.9268144 0.2070962 -0.2772326 0.1458365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 463 1123 0.641518 0.013149 0.516584 -0.0344767 0.2794298 -0.2205291 0.9338615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 464 495 -0.298924 0.148421 -0.983061 -0.8621943 0.2086459 0.3048114 0.3466668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 464 1124 -0.584189 0.551820 0.324354 0.3742091 0.0574313 -0.7936691 0.4761918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 465 1125 -0.704851 -0.587061 0.153598 0.7497443 -0.4895825 0.3160472 0.3135389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 466 326 0.000767 -0.679188 -0.477633 -0.0894584 -0.1262974 -0.9853730 0.0713181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 466 493 -0.966612 0.070379 0.020098 -0.4678082 0.5375102 0.6934220 0.1067904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 466 1126 0.170562 0.811286 0.644846 -0.0010726 0.0646087 -0.4825759 0.8734672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 467 492 -0.033703 0.441914 0.870933 0.2227447 -0.3998816 -0.3216927 0.8288506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 467 1127 -0.733990 -0.527721 0.311169 0.0589718 0.4642027 -0.8661617 0.1755052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 468 1128 0.027693 -0.765753 0.586253 0.2086730 0.7802636 -0.4530186 0.3773838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 469 490 0.704685 -0.212973 0.217711 -0.0160295 0.3597599 -0.8771143 0.3177836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 469 1129 -0.432874 -0.574025 0.563477 0.7946847 0.2480558 -0.5480754 0.0809813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 470 489 -0.843121 0.647138 -0.107057 0.0070247 -0.5609181 -0.2594297 0.7861410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 470 1130 -0.675103 -0.757798 0.563801 -0.2717166 0.6642800 -0.6261536 0.3046866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 471 488 0.814419 0.005377 -0.018225 -0.2489721 -0.4458777 0.4242848 0.7477890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 471 1131 0.185185 0.452656 0.911856 0.1492998 -0.6507483 -0.7410679 0.0710960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 472 1132 0.089749 0.925824 0.389558 0.4386950 0.4181980 0.7792708 0.1593556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 473 446 -0.591887 -0.049025 0.623929 0.2500946 -0.0548383 -0.9625934 0.0886534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 473 486 0.789983 0.219445 -0.547127 -0.5270587 -0.2861881 -0.5374813 0.5928064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 473 1133 0.065238 0.911603 0.546162 -0.6733128 -0.1453405 0.1493837 0.7093733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 474 445 0.166657 0.684754 0.757111 0.4316361 0.4971113 -0.6576214 0.3662032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 474 485 -0.116258 -0.675865 -0.731907 -0.6604093 -0.3163702 0.6126181 0.2974365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 474 1134 -0.804907 -0.466167 0.573317 0.0961334 0.3834096 -0.8519982 0.3432994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 475 1135 0.082582 -0.452357 0.771708 -0.1065994 -0.7509316 0.6440829 0.0994766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 476 483 -0.585841 -0.971540 0.313556 0.0813912 -0.4345391 -0.3765011 0.8141241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 476 1136 -0.593929 0.602990 -0.075709 -0.7421203 -0.5541126 0.3253575 0.1906809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 477 482 0.330826 0.820937 0.212996 0.1384920 0.4769164 -0.2407350 0.8339169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 477 1137 0.828318 -0.348839 0.468004 0.1589431 0.6519222 -0.5907712 0.4480222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 478 441 -0.081744 -0.148791 0.959294 -0.0409358 -0.7428258 -0.5300670 0.4068944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 478 481 0.203453 0.246274 -1.016520 -0.5958663 0.6135379 0.0204557 0.5177800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 478 1138 0.443226 0.910434 0.215429 -0.0205401 0.3075349 -0.2801691 0.9091236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 479 440 0.297356 0.578463 0.554639 -0.1256043 0.7364542 0.0828902 0.6595362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 479 1139 0.494516 -0.541714 0.430448 0.1458575 0.3443967 -0.7101777 0.5964597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 480 519 -0.168675 0.204134 1.115322 0.3004572 0.8075903 0.3639774 0.3536155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 480 1100 -0.123953 0.963396 -0.073234 -0.3631500 0.0185234 0.6086471 0.7052146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 481 518 0.424074 0.564420 0.561760 -0.0876995 -0.7626818 0.0894767 0.6345228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 481 1101 -0.872798 0.092042 0.609608 -0.2379645 0.4638357 0.8504827 0.0700601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 482 517 -0.246270 1.089407 -0.196465 0.5218073 -0.1526659 0.8358389 0.0760494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 482 1102 0.143288 0.320198 0.787498 -0.4651251 -0.3028794 -0.7150302 0.4250347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 483 1103 -0.762885 -0.144607 0.541343 0.5948947 -0.3460505 -0.2211761 0.6909634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 484 515 -0.424543 0.758103 0.164764 -0.0636839 0.6710866 0.7380007 0.0306943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 484 1104 0.849232 0.700608 0.196257 -0.2371921 0.7250932 0.0586843 0.6438446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 485 514 -0.273877 1.028031 0.170411 0.4514445 -0.4136346 -0.1463995 0.7769630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 486 513 -0.190007 0.843557 0.168313 0.3293604 -0.1534706 -0.1310860 0.9223800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 487 472 0.189845 -0.847567 0.749385 0.2976085 0.4631605 0.1110955 0.8273870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 487 512 -0.055002 0.895513 -0.640048 -0.3912623 0.0335037 0.7718700 0.5000080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 487 1107 0.412651 0.541290 0.588048 -0.3819879 0.1888642 0.5447056 0.7222958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 488 511 0.021281 -0.492644 -0.662549 0.2485574 0.4774453 0.6855267 0.4902226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 488 1108 0.700457 -0.463739 0.474060 0.7957371 0.1276375 0.2938657 0.5139593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 489 309 -0.405847 0.639165 -0.399248 0.0694261 0.2749743 0.5046711 0.8153994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 489 510 -0.718866 0.203748 0.843172 0.0145743 0.2700324 -0.1581155 0.9496682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 489 1109 0.498369 -0.568585 0.498745 -0.3545766 -0.3137608 -0.8807967 0.0051748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 490 1110 0.815801 -0.013674 0.819718 -0.6917799 0.1803759 -0.4154694 0.5623969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 491 468 -0.779641 -0.830426 0.308329 -0.6847276 -0.0150587 -0.3407081 0.6440803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 491 508 0.641519 0.611273 -0.548872 -0.2937612 0.2798838 -0.5335261 0.7421047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 491 1111 -0.213187 0.668706 0.586543 0.3271195 0.3721246 0.4893019 0.7177045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 492 507 0.437550 0.940296 0.545248 0.1930016 0.2433714 0.9276364 0.2073923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 492 1112 0.294804 -0.502957 0.867494 0.3415922 0.2987909 0.4788723 0.7514786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 493 506 0.447794 0.554514 0.556993 -0.4848476 -0.4572813 0.0342294 0.7447449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 493 1113 -0.671765 0.085730 0.610007 -0.4693138 0.1409472 0.3954809 0.7768354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 494 465 0.876704 0.314654 -0.272065 -0.2365851 0.2060838 -0.8334627 0.4548592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 494 1114 -0.294671 0.731896 0.470559 -0.7499393 0.1662351 0.5860284 0.2579297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 495 504 0.523196 0.648309 0.784216 -0.1925914 -0.0312777 -0.2821719 0.9393132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 495 1115 -0.791310 -0.012371 0.498453 -0.0381954 0.0786958 -0.0589823 0.9944190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 496 463 -0.425631 -1.006983 0.228210 0.4204083 -0.0222281 0.0787109 0.9036412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 496 503 0.395340 0.788212 -0.182349 0.5367214 0.4064199 0.6583928 0.3365589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 496 1116 0.807279 -0.167485 0.548493 0.4149537 0.7903901 -0.2260589 0.3898644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 497 502 0.518561 -0.047605 0.514861 0.2137523 -0.0393617 0.5468500 0.8085268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 497 1117 -0.649229 -0.202056 0.534338 0.6386335 0.0703368 -0.5181769 0.5645287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 498 501 0.888513 -0.558249 0.133379 -0.1140995 -0.2703270 -0.7609691 0.5786456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 499 319 0.143996 0.795492 -0.365091 0.3569372 0.3637827 -0.7403996 0.4382538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 499 1119 -0.033192 -0.799385 0.221692 -0.3698888 -0.4788279 0.5918470 0.5325628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 500 280 -0.489073 0.178855 -1.065187 -0.4109794 -0.2107035 -0.7859648 0.4110466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 500 539 -0.434985 0.921730 0.033472 0.3229530 -0.4648867 0.5715012 0.5941112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 500 1080 0.306741 0.142104 0.847179 -0.5046963 -0.1649797 0.7509020 0.3926951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 501 538 0.355962 1.087486 -0.254304 -0.3800601 0.3415450 -0.6158840 0.5996568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 501 1081 0.618705 0.051179 0.725252 0.1057643 -0.5736982 -0.7783723 0.2319931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 502 537 0.235145 -0.221677 0.747450 -0.7443354 0.3703696 0.5386525 0.1365456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 502 1082 -0.150243 0.995381 0.370502 0.4245895 0.3232133 0.8423871 0.0751056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 503 1083 -0.033613 0.651212 0.741350 -0.3338656 0.3966751 -0.8550570 0.0077607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 504 1084 -0.589272 -0.695983 0.530789 -0.0051305 -0.6735356 0.7322502 0.1006632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 505 494 0.365443 -0.695159 -0.496945 0.6966673 -0.2414871 -0.6396675 0.2171729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 505 534 -0.650259 0.856905 0.527575 0.0572982 -0.0250729 -0.9138782 0.4011419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 505 1085 -0.399666 -0.598443 0.635467 -0.2554197 -0.8503917 0.2305817 0.3980288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 506 286 -0.057091 0.658783 -0.653124 0.3722740 -0.0655646 -0.3148894 0.8706078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 506 533 1.053746 -0.002841 -0.109187 0.1864205 0.6418890 -0.4008778 0.6265165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 506 1086 0.217924 -0.500890 0.667084 0.2487678 -0.1237634 0.9351873 0.2195951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 507 532 0.591738 -0.420628 0.723049 -0.2651872 -0.7876874 -0.2669639 0.4878059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 507 1087 -0.214890 0.866736 0.479836 -0.1321444 -0.2247061 0.6953787 0.6696966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 508 531 -0.104367 0.847808 0.186519 0.5589608 -0.3670525 0.1191269 0.7339238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 508 1088 -0.860361 -0.483879 0.397224 -0.3428578 0.2151724 0.8952805 0.1860702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 509 490 -0.925696 -0.052677 0.284708 0.3329683 0.7109435 0.6194271 0.0012097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 509 1089 -0.155082 0.973375 0.012209 -0.7870028 0.5699840 0.1358543 0.1931022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 510 529 -0.896275 -0.214132 0.484957 0.3718013 0.3391640 0.7090785 0.4939021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 511 528 -0.303247 -1.013950 -0.366673 0.0226893 -0.6914199 -0.6410235 0.3324342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 512 527 0.962306 0.043215 -0.013689 0.0156599 0.1897445 -0.7159078 0.6717349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 512 1092 -0.134416 -0.941191 0.530042 0.5129902 -0.7048389 0.4532803 0.1859575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 513 526 -0.651019 0.730440 -0.209395 0.4464264 0.4648340 0.6581185 0.3892465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 513 1093 0.552696 0.356288 0.890889 -0.2131238 -0.2802861 0.4378892 0.8272067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 514 525 -0.330407 0.789361 -0.557942 0.0376491 -0.3871716 0.8453654 0.3661121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 514 1094 0.080291 0.643792 0.815945 0.0008597 0.5164719 0.3766213 0.7690334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 515 295 0.871328 -0.259216 -0.418271 -0.4138753 -0.7392115 0.4383989 0.3001332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 515 1095 -0.778162 0.146951 0.524766 -0.2311783 0.2496439 0.9400321 0.0239629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 516 483 -0.571115 0.820773 -0.253663 -0.3930521 0.5849465 -0.3504607 0.6168671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 516 523 0.526185 -0.787511 0.330482 -0.1795878 -0.2851922 -0.3504113 0.8738567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 517 522 0.044906 -0.759998 -0.873547 0.5485390 0.4963454 0.4634445 0.4878169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 517 1097 0.967588 -0.583624 0.193862 -0.6566224 0.3027292 -0.3417152 0.6003605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 518 521 0.792299 0.357300 -0.712982 -0.8617076 -0.1517423 -0.4669056 0.1281932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 518 1098 0.744119 -0.373530 0.470309 0.3964210 0.3301439 0.7792558 0.3558312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 519 1099 0.730707 0.763011 0.296544 -0.1368301 -0.1243643 -0.0408203 0.9819087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 520 559 0.496126 -0.576451 0.585516 0.1731753 -0.4137691 -0.8884898 0.0969085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 520 1060 -0.562608 0.298931 0.785274 -0.1726090 0.6337080 0.7428836 0.1293994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 521 1061 0.648370 0.610326 0.336686 0.2478532 0.2483535 0.9279977 0.1253384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 522 1062 -0.225371 0.493433 0.593334 -0.6140390 0.2457451 0.6424423 0.3870832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 523 556 0.737505 -0.080248 -0.485243 -0.7617625 -0.2995059 0.2828185 0.5000278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 523 1063 0.233638 0.852568 0.300245 -0.5071826 -0.4917479 -0.5431637 0.4537875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 524 515 0.090616 0.368593 -0.816399 -0.0835375 -0.0020044 -0.8594683 0.5043131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 524 555 -0.151937 -0.498635 0.922465 -0.0877724 0.5410496 0.0100924 0.8363369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 526 553 0.833871 -0.506475 -0.403814 -0.0214759 0.5469474 -0.1712372 0.8191856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 526 1066 0.483496 0.656090 0.839847 -0.0899744 -0.6004388 -0.7444394 0.2778271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 527 552 0.208799 0.775331 0.246914 -0.1426132 -0.1517196 -0.9515874 0.2261065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 527 1067 0.651303 -0.055099 0.662182 0.2866661 0.3551415 0.8176753 0.3508621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 528 551 0.612270 -0.618608 -0.655051 0.2931216 -0.1170078 0.7001953 0.6404026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 528 1068 0.818141 0.321346 0.493302 0.3973272 0.6849279 -0.3000726 0.5319410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 529 269 0.419146 -0.455793 -0.519381 0.4065762 -0.2540564 -0.2737160 0.8338049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 529 550 0.240039 0.766974 -0.627183 0.1118161 -0.2075545 0.3572316 0.9037720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 529 1069 -0.550923 0.530936 0.716809 -0.4477872 -0.4049139 0.5386173 0.5877268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 530 509 0.659771 -0.896566 0.420053 -0.0066151 0.0766992 0.8630149 0.4992782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 530 549 -0.765008 0.646998 -0.249582 0.0994743 -0.0511149 -0.4619530 0.8798247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 530 1070 -0.742051 -0.725143 0.239304 0.4505842 0.5047865 -0.4500269 0.5827866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 531 271 0.322798 -0.749831 -0.782808 -0.3297084 -0.5701365 -0.1629981 0.7346212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 531 548 -0.054157 0.797464 -0.613193 0.4374297 -0.4012915 -0.7806270 0.1955556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 531 1071 -0.157628 0.553441 0.858808 0.2199255 -0.5117229 -0.8134610 0.1674921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 533 546 -0.177185 0.723708 0.659115 0.8122203 -0.2454590 -0.4993254 0.1752775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 533 1073 -0.537550 -0.661143 0.703264 0.5147996 -0.1665454 -0.4227667 0.7269885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 534 274 -0.644043 -0.232142 -0.678703 -0.2323089 -0.0392353 0.9539939 0.1854423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 534 545 -0.159921 -0.824699 0.574035 0.1211522 0.0570037 0.9002518 0.4142698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 535 504 0.660181 -0.135285 -0.906770 -0.0511778 0.0958886 0.8016878 0.5877779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 535 544 -0.408858 0.082473 0.974796 0.7185492 0.0827100 0.4858468 0.4907128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 535 1075 0.904863 -0.311294 0.676992 0.4423539 -0.0216689 0.7975858 0.4095245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 536 503 -0.228566 -0.715175 -0.600222 0.3940614 0.0597391 0.9047754 0.1500941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 536 543 -0.042772 0.838391 0.637979 -0.6368921 0.2230542 -0.7348073 0.0683621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 536 1076 0.595183 -0.645466 0.605880 0.3002718 0.6617153 0.0823368 0.6820486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 537 542 -0.562269 0.024156 -0.844375 -0.1526980 -0.3420949 0.8619659 0.3415688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 537 1077 -0.857223 -0.499070 0.604996 0.5692015 0.3740099 -0.4733323 0.5586438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 538 541 -0.865292 0.376856 0.323820 0.2046718 0.5064632 0.8109777 0.2095703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 538 1078 -0.042562 -0.283409 0.854943 -0.2676272 0.6804567 -0.4519737 0.5109541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 539 1079 0.796571 -0.518239 0.332322 0.0832624 0.0824570 0.7171303 0.6870169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 540 579 0.742883 -0.690674 -0.317915 0.2209910 0.2008208 -0.3138920 0.9012801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 540 1040 0.484987 -0.161288 0.726912 0.0231719 -0.4493938 -0.6733998 0.5865501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 541 578 1.027682 0.199559 0.002574 -0.5306501 -0.2452682 0.4518466 0.6738610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 541 1041 -0.050662 1.043913 0.292916 0.3920677 0.2680323 0.8108751 0.3419403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 542 577 0.563559 0.951325 -0.364831 -0.3092089 -0.0301248 -0.7005479 0.6424290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 542 1042 0.401774 0.019436 1.064321 -0.1405135 0.5560619 -0.2780064 0.7705606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 543 576 0.141206 -0.745605 0.093330 0.0605206 -0.1105905 0.1411870 0.9819232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 543 1043 0.530601 0.287703 0.671261 0.1683390 -0.2139547 -0.9286371 0.2520288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 544 575 0.207155 0.990267 -0.504877 0.3717098 0.1109976 0.8601133 0.3312349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 544 1044 0.706667 0.373267 0.791637 -0.1266960 0.3448365 -0.8942974 0.2554763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 545 574 -0.313842 0.783468 0.363671 0.3260002 -0.4898002 -0.0136294 0.8084763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 545 1045 -0.155030 -0.387578 0.794396 0.6632416 -0.3827800 -0.1448001 0.6265964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 546 573 -0.980262 -0.382539 -0.176819 -0.0275625 0.0614523 0.9377835 0.3406258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 546 1046 -0.422531 1.082912 0.134091 -0.8251946 0.1465013 -0.3153854 0.4451104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 547 247 -0.440743 -0.481597 -0.664946 -0.2748924 0.2362402 -0.7093611 0.6045093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 547 532 -0.468786 -0.642797 0.775171 0.0798142 -0.1074988 0.2724243 0.9528162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 547 572 0.339909 0.669134 -0.734759 -0.2180764 0.5027887 -0.1480259 0.8232464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 547 1047 0.135428 0.686107 0.808430 0.3308702 0.1661463 0.8521918 0.3697153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 549 570 -0.983148 -0.161314 -0.463755 -0.1650579 0.2779238 -0.9463078 0.0039670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 549 1049 0.266543 -1.032814 0.629396 -0.3520042 0.6650215 -0.4630273 0.4684498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 550 569 0.281341 0.460182 -0.661297 0.2729635 -0.4117107 -0.7908954 0.3612058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 551 568 -0.786081 -0.595586 -0.096722 0.4917742 -0.5016032 0.5559186 0.4444175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 551 1051 0.478234 -0.642309 0.462261 0.3453250 0.6487436 -0.1293003 0.6657055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 552 567 -0.036614 -0.786252 0.326722 -0.6323002 0.0318267 0.7451504 0.2096051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 552 1052 -0.331312 0.528190 0.864520 -0.6354256 -0.2525490 0.7145522 0.1478799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 553 566 0.778426 0.018667 0.668201 -0.8287062 0.0880281 0.4857613 0.2636911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 554 525 -0.808377 -0.311417 0.395575 -0.0891697 -0.1705584 0.1152712 0.9745107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 554 565 0.802927 0.307865 -0.483103 -0.2037977 -0.1408057 0.8531613 0.4590817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 554 1054 0.783977 -0.426171 0.593096 0.4456982 -0.2138660 0.8421417 0.2154340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 555 564 -0.935372 -0.479374 0.250390 -0.7008957 -0.3086795 0.0526662 0.6408498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 556 1056 0.844671 -0.591753 0.083486 -0.1069408 0.6227071 -0.3856398 0.6723701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 557 522 0.516964 -0.608583 0.584125 -0.3319748 -0.3263862 -0.6969589 0.5454476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 557 562 -0.599436 0.754643 -0.428642 -0.2704361 -0.3203995 0.0308438 0.9073352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 558 561 0.296247 0.001102 0.971080 -0.0273956 0.0301040 0.8451839 0.5329235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 558 1058 -0.391738 -0.824032 0.112204 0.4282345 0.7775263 -0.1256803 0.4430264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 559 1059 0.223860 0.309848 1.044737 0.5091995 0.0399084 0.8353964 0.2030666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 560 599 0.669004 -0.925686 0.012742 -0.0808789 0.3075172 -0.2687337 0.9092161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 561 598 -0.148557 -0.337010 0.854968 -0.2833834 -0.6200522 0.1463840 0.7167991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 562 597 -0.684335 0.612562 0.360426 -0.2817814 -0.2108356 -0.1630744 0.9217127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 562 1022 0.843346 0.538002 0.013934 0.6379994 0.7200926 0.2441417 0.1217299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 563 556 -0.572006 -0.224732 0.835927 -0.3765039 -0.0526249 0.1575034 0.9114099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 563 1023 0.869115 0.047598 0.614064 -0.5408598 0.4426080 0.4159857 0.5818287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 564 224 -0.376322 0.691808 -0.473039 0.1547405 0.6130566 -0.2163417 0.7439175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 564 595 -0.842918 -0.467598 -0.077665 0.2621606 0.7579663 -0.1996734 0.5629293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 565 594 -0.025114 -0.440960 -0.722292 -0.6011697 0.4596837 0.6424982 0.1203408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 565 1025 -0.817900 -0.521607 0.079169 0.4671588 -0.2913563 0.6562236 0.5159891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 566 593 -0.036240 -0.747997 -0.802400 0.4723217 -0.6884794 -0.4374850 0.3339388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 566 1026 -0.680706 -0.310360 0.458255 0.1161958 0.3737086 -0.2059260 0.8969029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 567 592 -0.854633 0.603158 0.116833 0.0679019 -0.3953997 0.8969291 0.1859209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 567 1027 -0.357779 -0.696826 0.724809 0.3409932 -0.4262577 0.7482509 0.3770259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 568 591 -0.013897 0.677743 0.571585 0.4949125 -0.3812421 0.7366852 0.2588649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 568 1028 0.621435 -0.551596 0.399752 0.8320323 0.3068096 0.1836084 0.4241203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 569 590 -0.390985 -0.588546 -0.291769 -0.5144437 0.0380802 0.8468844 0.1291683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 570 589 0.716613 0.401019 -0.416875 -0.3479404 -0.0321886 0.7676620 0.5372117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 571 1031 -0.348701 0.289130 0.735741 -0.3558740 0.3247656 -0.8668097 0.1285375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 572 587 0.578568 0.655699 0.357898 -0.1323289 -0.3814838 0.8340540 0.3759162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 572 1032 -0.925254 0.216534 0.663711 0.1038637 0.4674148 -0.8776300 0.0223913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 573 1033 0.914970 -0.651635 0.441903 0.8883373 0.0253146 0.1873197 0.4184822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 574 585 -0.009768 0.992312 -0.007727 -0.6647282 -0.4801332 -0.5109713 0.2579085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 574 1034 0.816390 0.112265 0.579077 -0.1297972 0.2965941 -0.6377146 0.6989311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 575 584 -0.050312 -1.030832 -0.240261 0.3886760 -0.5325722 0.5764432 0.4827122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 576 1036 0.658999 0.020286 0.719757 -0.1268111 0.4178843 0.2966946 0.8492726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 577 582 -0.785040 0.622068 0.152478 -0.0966454 0.0836550 -0.9903012 0.0544519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 577 1037 0.323195 -0.005023 1.131236 -0.1384368 0.7283686 -0.6079881 0.2840158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 578 581 0.419092 -0.439778 -0.784397 -0.2149327 0.3387401 -0.7079936 0.5812093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 578 1038 0.883365 -0.118509 0.676049 -0.0140337 0.0574164 0.8898340 0.4524400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 579 239 0.235649 -0.128175 -0.998641 0.2595204 -0.0824855 0.5382810 0.7975581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 580 619 0.379230 0.470515 -0.728300 0.2230339 0.0063230 -0.6513368 0.7252422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 580 1000 0.460923 0.806111 0.780458 -0.7142974 -0.0593064 -0.4134952 0.5615014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 581 1001 -0.110269 -0.132214 0.986620 0.3394044 -0.4803073 -0.7819875 0.2064103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 582 202 0.238092 0.005469 -0.970763 0.3193485 0.0802426 -0.9091646 0.2549460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 582 617 0.826217 -0.513431 -0.067580 0.4999305 -0.5028693 -0.6354365 0.3056343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 583 616 0.517433 -0.237093 0.690336 0.3859082 0.0909081 -0.9179624 0.0124760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 584 204 -0.937285 0.470071 -0.380357 0.4826367 -0.8351954 0.2526826 0.0752459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 584 615 -0.332903 0.085056 0.946299 0.5188443 0.7775063 -0.0159496 0.3550073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 584 1004 0.856976 -0.390792 0.202654 0.1334189 -0.0569011 0.9246634 0.3520784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 585 205 -0.555425 -0.567638 -0.160069 -0.4088834 0.7244411 0.2780498 0.4802997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 585 614 0.222113 -0.366116 0.769531 -0.2153984 0.2690275 0.9319570 0.1126230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 585 1005 0.567268 0.760937 -0.088345 -0.4925427 -0.2029751 -0.8135021 0.2332747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 586 573 -0.377361 -0.738375 -0.479443 0.3755382 -0.1957010 0.0750668 0.9027941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 586 613 0.261758 0.809846 0.640962 -0.0367040 0.1725863 0.6150076 0.7685262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 586 1006 0.829093 -0.746671 -0.036094 0.5793142 0.1667146 -0.0626838 0.7954068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 587 612 0.448167 -0.932035 -0.470105 -0.1238652 0.6500877 0.4690735 0.5848191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 588 571 -0.117878 -0.803183 0.548794 -0.1691647 -0.1162071 -0.9238820 0.3229881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 588 611 0.329652 0.743266 -0.408607 -0.2064371 0.6514194 0.5865865 0.4346870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 589 610 0.405841 -0.661817 -0.646647 0.1552459 0.1015302 0.6897570 0.6998754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 589 1009 -0.163181 -0.636952 0.826945 0.6440791 -0.4784712 0.3524949 0.4816377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 590 609 0.269058 1.130517 0.039035 0.1119014 -0.6186570 -0.2808623 0.7251607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 590 1010 -0.049893 -0.106503 0.988033 -0.2248837 -0.3644764 0.6715520 0.6046505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 591 608 0.697089 -0.588890 -0.463415 0.1155041 0.6909711 -0.6779477 0.2227209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 591 1011 0.412785 -0.338870 0.836294 -0.3090957 0.2007189 0.0576710 0.9278178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 592 212 -0.275375 -0.228252 -0.816407 0.3504404 0.6700069 0.3556331 0.5493700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 592 1012 0.344147 0.290876 0.953826 0.4192242 -0.0797805 0.0966453 0.8991918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 593 606 0.645727 -0.761170 0.142919 -0.4501726 -0.4718224 -0.7214817 0.2327927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 594 605 0.894508 -0.078831 -0.256839 0.3802527 0.6289050 0.2253231 0.6396217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 594 1014 0.299375 0.991545 0.136689 -0.4014424 0.3875526 -0.4576079 0.6922731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 595 604 0.326396 -1.125596 -0.296325 -0.5600132 -0.2112991 0.5957481 0.5355578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 596 563 -0.131362 0.938759 -0.109933 -0.3771652 -0.3288826 -0.6565678 0.5643593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 596 603 0.179689 -0.934878 0.221193 0.3766202 -0.0587289 0.7910224 0.4785307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 596 1016 -0.060256 0.199185 0.969477 0.2004691 -0.2487434 0.5338262 0.7829230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 597 602 -0.452940 0.192251 0.910142 -0.3416975 0.0071222 -0.4568967 0.8212415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 597 1017 0.634477 0.926105 0.098904 0.0373162 0.2641834 0.0960143 0.9589556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 598 601 0.548506 -0.762567 0.056920 -0.0507125 -0.1788202 0.0562327 0.9809635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 598 1018 0.299035 0.445363 0.821748 0.1033174 -0.3419888 -0.9139238 0.1926459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 600 639 0.179575 -0.300688 1.009053 -0.0664892 -0.9392016 -0.1814479 0.2838242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 600 980 -0.751636 -0.879652 -0.016229 0.5659246 0.1072411 -0.0056866 0.8174327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 601 638 0.512578 -0.887912 -0.088089 -0.0914209 0.1059768 0.9166611 0.3743575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 601 981 0.617818 0.002760 0.846120 0.1854738 0.8306906 0.1818240 0.4924354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 602 637 -0.061128 -0.811776 0.574545 0.1097105 0.6641115 0.7387525 0.0341215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 603 983 0.678666 0.193014 0.434810 0.0233676 0.0471286 -0.1539915 0.9866709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 604 635 -0.807438 0.504116 -0.550155 -0.3308701 0.1934273 0.5399818 0.7493534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 604 984 -0.799994 -0.182441 0.742428 0.3329035 -0.7908617 -0.0725821 0.5083747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 605 634 0.067529 -0.324944 0.806087 -0.2555143 0.3917864 0.1832866 0.8646513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 605 985 0.728071 0.752454 0.091554 -0.7920882 -0.1717232 -0.0847094 0.5795962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 606 186 -0.024954 -0.569403 -1.038371 0.2441816 -0.3493773 0.4670077 0.7747352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 606 986 -0.146598 0.364805 0.937693 -0.2016535 0.0355631 -0.7837701 0.5863238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 607 592 -0.553453 -1.009899 0.458630 -0.4580252 -0.1516991 0.6172192 0.6214827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 607 632 0.550841 0.711982 -0.209183 -0.4578468 0.2547405 0.8465828 0.0937075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 607 987 -0.780305 0.613222 0.034961 -0.8702941 0.1985102 0.2488065 0.3758687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 608 631 -0.115964 0.659698 0.873615 0.6224977 -0.7564288 0.0187190 0.1999042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 608 988 -0.617648 -0.551054 0.434890 0.1087058 -0.7704190 0.5122646 0.3636244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 609 630 -0.406818 0.882833 -0.344025 -0.0060150 0.9079650 -0.0723049 0.4127170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 610 190 0.661363 -0.315251 -0.671001 -0.4209003 0.1356384 0.8957578 0.0454223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 610 629 -0.824866 -0.473739 -0.588758 -0.2262697 -0.1723936 -0.9009989 0.3275416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 610 990 -0.455440 0.446255 0.720624 0.0795270 0.2017386 -0.4437534 0.8695171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 611 991 -0.904621 -0.008567 0.477736 0.4116159 -0.7131865 -0.1836144 0.5368642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 612 627 -0.022502 -1.016035 -0.260850 0.3035447 -0.7202880 0.3198442 0.5354861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 613 626 0.375904 -0.079084 0.839551 0.5843138 -0.0756709 0.6753230 0.4436103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 613 993 -0.390741 -0.920298 0.200721 -0.0487809 -0.2171898 -0.5804407 0.7832864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 614 625 -0.736115 0.530454 0.335728 -0.5427581 -0.2014303 0.8007129 0.1539425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 614 994 -0.409736 -0.917003 0.239541 0.0082784 -0.6632784 0.6155763 0.4255104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 615 195 0.791612 -0.564575 -0.202871 0.7100689 -0.1697440 -0.6401724 0.2390992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 615 995 -0.916167 0.538914 0.488914 -0.0165837 0.5130485 0.6030911 0.6105631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 616 623 -0.850353 0.066413 0.329232 -0.0104428 -0.0258202 -0.0670818 0.9973587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 616 996 0.155505 0.706263 0.709221 -0.3166147 -0.5561168 -0.7654650 0.0674727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 617 197 0.281034 -0.909402 0.060846 0.1606382 0.6432406 0.4385574 0.6067160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 617 622 0.388945 0.190180 -0.818802 -0.4060374 0.4423447 0.0898604 0.7946004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 617 997 -0.181425 0.835109 0.374049 -0.0412271 -0.4571653 -0.8197475 0.3425119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 618 198 0.748921 0.098225 -0.564315 -0.2735616 -0.5190991 -0.6617839 0.4666286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 618 581 0.554968 0.563463 0.629895 -0.5050271 -0.0744931 0.8277357 0.2329205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 618 621 -0.418028 -0.578093 -0.524730 0.3050792 -0.2754235 -0.7904105 0.4542244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 618 998 -0.757949 0.053962 0.679398 -0.2173952 0.0707404 -0.9221771 0.3119689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 619 999 -0.892460 0.479762 0.135627 0.1375957 -0.8713775 -0.3306355 0.3353338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 620 659 -0.780845 0.151388 -0.264852 0.3783381 -0.3027144 -0.1465114 0.8624145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 620 960 -0.282599 0.344571 1.101547 -0.3548865 0.5367110 0.5994540 0.4760796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 621 658 0.853668 -0.378732 -0.164897 -0.4846488 -0.0069575 -0.7155401 0.5030600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 621 961 0.194576 0.000497 0.986013 0.5376317 -0.3500816 -0.5651056 0.5187010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 622 657 0.746622 0.491659 0.238086 0.3020989 0.1932309 -0.9053590 0.2274272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 622 962 -0.500857 0.414345 0.814783 -0.5322239 0.3834880 0.6339976 0.4095384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 623 656 -0.862968 -0.223954 0.163179 0.0200537 0.3310432 0.7027545 0.6294000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 623 963 0.112939 0.810726 0.626083 -0.0322682 0.8437038 0.4520692 0.2876737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 624 615 0.516860 0.476461 0.802949 0.4248322 0.1917524 0.8476249 0.2535364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 624 655 -0.689942 -0.265169 -0.787979 -0.6252012 0.7747213 -0.0589498 0.0738596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 624 964 0.608571 -0.934877 0.089900 -0.0405703 -0.7122977 0.6200565 0.3263680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 625 654 0.394211 -0.928513 0.605687 0.2487814 0.3608910 0.5784671 0.6879254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 626 653 0.884313 0.082427 0.488476 0.1428159 0.6197258 0.6024555 0.4822768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 626 966 -0.251658 0.991311 0.386218 0.2290414 0.9175421 0.2778995 0.1686074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 627 652 -0.354658 -0.606544 1.026086 0.3274033 0.5691695 -0.2795117 0.7005186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 627 967 0.737202 0.445422 0.590048 0.1533367 0.8368593 0.5006153 0.1598083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 628 611 -0.922251 -0.007461 0.018950 -0.4176658 0.5237371 -0.1264179 0.7316237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 628 651 1.150744 -0.112173 -0.077600 0.1466879 0.2220916 -0.8662417 0.4228277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 628 968 0.045505 0.918074 0.564433 -0.1781803 0.0426088 -0.9742595 0.1313571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 629 650 0.652484 -0.204625 -0.713494 0.6940010 0.5564272 0.2707279 0.3680459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 630 649 0.212201 0.951370 -0.364224 0.0825292 -0.2350145 -0.5253207 0.8136309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 630 970 -0.830556 0.483308 0.516688 -0.0369182 -0.4644460 0.2619087 0.8451809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 631 648 -0.286077 0.550396 -0.870427 0.0175338 0.9235520 -0.2316367 0.3051045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 631 971 0.897231 0.768473 0.007369 -0.6161209 0.5178102 -0.0063307 0.5934876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 632 647 -0.055831 -0.852403 -0.053897 0.1798485 -0.3554481 -0.4866901 0.7774599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 632 972 0.206354 -0.284696 0.974173 -0.3269597 -0.5130420 0.7858596 0.1109506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 633 646 0.794490 -0.437554 0.090656 -0.2807635 -0.1094600 0.0153721 0.9533908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 633 973 -0.231210 -0.017611 0.768549 0.7779703 0.0507068 -0.2429813 0.5771924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 634 645 -0.532257 -0.475605 0.563993 -0.2363024 -0.3001210 0.8484285 0.3664119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 634 974 0.422453 0.230155 0.974320 0.1807860 -0.4200456 -0.8435039 0.2817433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 636 603 -0.600151 0.229314 -0.752586 0.2129152 0.1691480 -0.9434241 0.1897551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 636 643 0.632543 -0.205480 0.714188 0.2181580 0.3338730 -0.9025275 0.1624194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 636 976 -0.629837 -0.841815 0.165752 -0.0461360 -0.4997197 0.1848970 0.8449643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 637 642 0.040591 0.772670 -0.687057 0.4563977 0.4733557 -0.2041800 0.7252214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 637 977 0.532372 0.352403 0.669775 -0.3631527 0.7212093 0.2469572 0.5357140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 638 641 -0.855530 0.166251 -0.407404 0.1587777 -0.5602721 0.7693562 0.2626326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 638 978 -0.464295 -0.260597 0.762299 -0.4282785 -0.4044686 -0.2505549 0.7682479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 639 979 0.621219 -0.704320 0.322319 0.6512945 0.5712484 -0.1847127 0.4640819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 640 679 -0.341706 -0.542305 -0.678651 0.1147878 -0.4360307 0.2520858 0.8562440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 640 940 0.701065 -0.906985 0.298848 0.0237162 -0.0131510 0.6038623 0.7966272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 641 678 0.627230 0.910720 -0.238505 0.2543780 0.3284745 -0.6003384 0.6833668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 641 941 0.441148 -0.101149 0.808373 0.2656569 0.7200538 0.3375154 0.5450067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 642 677 0.676456 0.015483 -0.768123 -0.7451027 0.1312515 0.3206865 0.5698729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 642 942 -0.239717 0.900798 0.041591 -0.0613678 -0.2651287 -0.5046027 0.8193393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 643 676 -0.435597 -0.051375 0.449257 -0.4456040 -0.3076307 -0.7421981 0.3948955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 643 943 0.566015 -0.083073 0.758155 -0.4606841 -0.4834285 -0.6471459 0.3677895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 644 635 -0.641245 -0.276210 0.744159 0.4261161 0.5640180 -0.5606645 0.4312355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 644 675 0.802715 0.107536 -0.950471 0.2713991 -0.0874227 -0.6780159 0.6774912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 644 944 0.754418 -0.455155 0.749515 0.6195729 0.5709326 0.4550770 0.2882193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 645 674 0.136012 0.400918 0.783152 0.1122635 0.6200258 -0.7673826 0.1186964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 645 945 -0.261002 -1.032464 0.336155 -0.3804898 -0.4558837 0.7943618 0.1280113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 646 673 1.043103 -0.440975 -0.278146 0.9098007 0.1000769 0.1808746 0.3599052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 646 946 -0.037928 -0.701959 0.589898 -0.2722800 0.0491120 -0.0094334 0.9609176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 647 147 -0.530664 -0.751522 -0.553549 -0.4634737 -0.1468619 -0.2933675 0.8231398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 647 672 0.618251 -0.729574 0.008382 -0.0282221 0.6668219 0.7402951 0.0807174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 647 947 0.561054 0.663053 0.490884 0.0185921 0.5203742 0.8512856 0.0646366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 648 671 0.739657 0.773228 0.194251 -0.5727916 -0.7617167 -0.2685263 0.1399680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 648 948 -0.666465 0.792299 -0.085288 -0.2384852 -0.0587338 0.2492333 0.9367806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 649 670 -0.752167 0.460949 -0.314201 0.4850336 0.5104126 -0.6369240 0.3139253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 650 669 -0.060712 -0.069321 0.900615 -0.5435438 0.7860558 0.2936673 0.0208805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 650 950 -0.538826 0.952754 0.232618 -0.4814452 -0.3120147 0.7674250 0.2862102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 651 668 -0.671544 0.732425 -0.132624 0.2757740 -0.1842444 -0.8471398 0.4151588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 651 951 -0.738295 -0.413211 -0.033722 0.4049056 0.7794147 -0.4000924 0.2617064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 652 667 -0.807434 -0.583283 0.280646 0.5361599 -0.2952435 -0.7412975 0.2753938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 652 952 -0.645253 0.872407 -0.052037 -0.5212086 0.2170648 0.6887793 0.4547609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 653 666 -0.482657 0.198702 0.874469 -0.3150071 -0.2887291 -0.5970093 0.6789595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 653 953 0.784571 0.582980 0.402819 0.0983383 -0.1333152 0.8131724 0.5579492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 654 665 -0.823317 0.145794 0.444151 0.0856507 0.4518822 0.6102676 0.6450116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 654 954 0.366654 0.869882 0.161453 -0.7273707 -0.4249557 -0.5385760 0.0167457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 655 155 -0.617992 0.752938 -0.027441 -0.5614124 0.7470337 -0.3129891 0.1696897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 655 664 0.298689 0.715531 0.651773 0.2034978 -0.8750766 0.4145886 0.1447266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 655 955 0.655880 -0.841279 0.204443 0.7080517 0.0921339 -0.3716844 0.5933168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 656 156 -0.393889 -0.260388 -0.949774 -0.6285050 0.2953032 0.5682245 0.4414731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 656 663 0.066277 0.908571 -0.257237 0.4587621 0.2934676 -0.6340673 0.5489742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 656 956 0.630923 0.214740 0.791053 -0.0992948 -0.2937037 0.6765469 0.6679544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 660 699 0.632825 0.168428 -0.441905 0.1257338 0.8372507 0.3264542 0.4202736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 660 920 0.590554 0.034067 0.689645 -0.3357155 0.0671772 0.3134143 0.8857504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 661 658 0.502339 0.187120 0.801560 -0.3011468 -0.5404271 0.6942272 0.3678285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 661 698 -0.713084 -0.215249 -1.026381 0.4057399 -0.7464991 0.0740041 0.5221471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 661 921 -0.846333 0.313180 0.600626 0.0575062 -0.3397909 0.7278069 0.5929016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 662 697 0.887427 -0.545008 -0.240942 0.9483650 0.0130920 -0.0133744 0.3166283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 662 922 -0.719610 -0.938409 0.072951 -0.6397129 -0.5717219 0.3167985 0.4044010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 663 696 -0.200224 -0.384529 -0.942668 -0.4122972 -0.2476074 0.4044424 0.7778997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 663 923 -0.883787 0.434511 0.025135 0.0818479 0.0422245 -0.7371929 0.6693763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 664 695 -0.299136 -0.091626 -0.807289 0.0987024 0.8570164 -0.3803898 0.3332932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 664 924 -0.266992 -0.812602 0.571339 0.9096652 0.1429828 -0.2754401 0.2760395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 665 694 -0.202641 0.849437 -0.135797 -0.6521131 -0.5596367 -0.4895026 0.1481299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 665 925 0.614057 0.270793 0.758249 0.4563507 0.0186581 0.6496296 0.6077642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 666 693 0.443105 -0.532230 0.717989 -0.8166171 -0.2182282 0.1631136 0.5088290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 667 692 0.560331 0.684043 0.686494 0.1853437 0.3253503 -0.9238054 0.0798651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 667 927 -0.459043 -0.421601 0.790396 0.8244537 -0.3985066 -0.2680522 0.2993603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 668 691 -0.440985 -0.841076 0.290124 0.4787345 0.3847977 0.5716256 0.5440479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 668 928 0.928985 -0.177442 0.505949 0.1060307 -0.1481448 -0.3299576 0.9262497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 669 690 -0.007886 0.374473 -0.831138 -0.0958001 -0.8669352 -0.2828391 0.3990586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 669 929 -0.653408 0.689219 0.292252 0.1311778 -0.0509538 -0.1597270 0.9770790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 670 689 0.671258 -0.702300 -0.375780 0.6217571 -0.4295268 0.3807435 0.5328783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 670 930 -0.652785 -0.333736 0.374623 -0.3594496 -0.1038242 0.7313030 0.5702740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 671 931 0.836030 -0.577176 0.322442 -0.0488883 0.0912739 -0.3900506 0.9149533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 672 687 -0.852514 -0.243347 -0.459750 0.1554820 -0.3280628 -0.8190952 0.4441657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 672 932 -0.429099 0.369008 0.738502 0.2836765 -0.2819719 0.6912720 0.6017994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 673 686 0.738172 0.196577 0.913368 -0.8476892 -0.5153912 -0.0249839 0.1231693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 673 933 -0.281282 0.979202 0.244602 -0.5735362 -0.2266614 -0.1864294 0.7648039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 674 685 -0.163473 -0.977216 -0.147835 0.4452274 -0.0363432 -0.7741212 0.4485399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 674 934 0.252611 -0.114102 1.101062 0.0277819 -0.5183229 -0.7559729 0.3988413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 675 684 0.178834 0.189991 -0.989753 -0.7627597 -0.3883859 -0.2326406 0.4617709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 676 683 0.755392 -0.590281 0.001329 -0.4485567 -0.3170982 0.5427302 0.6353657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 676 936 0.364061 0.521450 0.522693 -0.0395196 -0.6495717 -0.2857402 0.7034539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 677 682 1.001635 0.324274 0.051052 -0.5010983 0.2314789 -0.0022094 0.8338544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 677 937 -0.029794 -0.299140 1.043750 -0.1558606 -0.3613394 0.0622619 0.9172049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 678 681 -0.165334 0.836794 -0.782695 -0.5392367 0.0825560 -0.6030916 0.5819697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 678 938 -0.538567 0.596369 0.719488 -0.6383418 -0.4101971 0.4260621 0.4926755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 679 939 0.531719 -1.062696 -0.003731 0.2137814 -0.3831909 0.0460228 0.8974097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 680 100 0.209399 0.638297 -0.555705 -0.3869147 -0.5589603 0.6480820 0.3432930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 680 719 -0.898394 0.456863 0.161597 0.6891173 -0.2790894 0.1719129 0.6462758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 680 900 -0.225543 -0.796120 0.489459 -0.0191192 -0.1209740 -0.6068368 0.7853336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 681 101 0.216433 1.112509 -0.088324 -0.3893289 0.2954535 -0.8662713 0.1034618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 681 718 -1.024844 0.103279 -0.129933 -0.1446049 -0.6336280 0.5917539 0.4768987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 681 901 -0.065100 -0.968625 0.258068 -0.2059658 -0.6278447 0.5516280 0.5090144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 682 902 -0.525852 -0.775659 0.151227 -0.3625443 0.0289214 0.9170819 0.1633588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 683 716 -0.371901 -0.312925 -0.967261 0.4667179 0.0257732 0.2025479 0.8605141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 683 903 0.614704 -0.609573 0.033797 0.4436130 -0.6256799 0.6147857 0.1837683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 684 715 -0.577519 0.606889 0.756753 0.3584707 -0.0179852 0.0461102 0.9322281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 684 904 0.749518 0.001333 0.775902 0.2873630 0.3188596 0.4202468 0.7994646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 685 714 0.913718 0.203265 0.429333 -0.2354545 -0.5843253 -0.4820722 0.6088773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 686 713 0.676947 0.492658 -0.728458 0.2409336 0.6926591 -0.6250029 0.2674804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 686 906 0.780893 -0.647726 0.090969 0.3026435 0.6441246 0.5529980 0.4332477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 687 712 0.614517 -0.665037 0.281405 0.4149368 -0.2422857 0.0687895 0.8742958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 688 671 1.034531 0.444654 0.019342 0.2850868 -0.3407707 0.8067361 0.3895867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 688 711 -0.927978 -0.508630 0.085235 -0.3825345 0.0412895 0.7384104 0.5538164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 688 908 -0.015347 0.376042 0.889601 -0.4813066 -0.3335558 0.7429375 0.3242350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 689 710 0.320450 -0.480504 0.768489 -0.1584619 -0.5625575 -0.7458147 0.3196551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 689 909 0.204223 0.901709 0.576042 0.0934227 -0.6091773 -0.7857883 0.0520761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 690 709 -0.468177 -0.239856 0.883560 0.6105990 0.5400654 0.5787013 0.0245576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 690 910 0.774222 0.401589 0.640730 0.0805046 0.6490891 -0.5249979 0.5445912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 691 708 -0.935334 0.466805 0.053501 0.2039447 0.6688718 0.7099303 0.0837618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 691 911 0.022922 0.282470 0.958333 -0.6355339 -0.2323042 -0.5810787 0.4521935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 692 112 -0.278587 -0.099259 -1.008899 0.1445210 0.2379829 0.9512532 0.1326470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 692 707 -0.626274 -0.814023 0.265707 0.0704624 0.5256958 0.5817359 0.6166541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 692 912 0.139828 -0.028493 0.911404 0.1745984 -0.3225978 -0.8514436 0.3748198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 693 706 0.044017 -0.423330 -0.955442 0.6626763 0.0962162 -0.2033060 0.7143314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 693 913 0.594424 -0.831217 0.361163 0.5945658 -0.3453514 0.7078789 0.1616519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 694 705 0.436612 -0.426736 0.832814 0.3602538 0.3605408 0.8585849 0.0553123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 694 914 0.830323 0.714361 0.248009 -0.1370364 -0.0858932 -0.4115735 0.8969117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 695 704 0.885167 0.178323 0.495047 0.6508679 -0.4566222 -0.0823904 0.6008985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 695 915 0.181341 -1.124858 0.339037 0.1874083 0.6785317 -0.1892149 0.6845951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 696 703 -0.387078 0.619010 -0.495124 -0.4787840 0.2895017 -0.7163910 0.4168196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 696 916 0.016775 0.542686 0.936413 -0.5932458 0.0090347 0.7519807 0.2872330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 697 702 0.826273 0.340817 0.399016 0.7181044 0.2548351 -0.6434770 0.0729555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 697 917 -0.635601 0.585015 0.381219 -0.5948194 -0.4408832 0.0348431 0.6712659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 698 701 -0.405594 0.137935 0.890899 -0.4989911 0.6272396 0.1493971 0.5790155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 699 919 -0.801256 0.632943 -0.043579 -0.6318428 -0.5290516 0.2542089 0.5062183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 700 739 0.292527 0.873274 -0.368658 -0.4007061 0.0957263 0.9077735 0.0788568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 700 880 0.141616 0.105044 0.912673 0.2888533 -0.1470110 -0.8561534 0.4024337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 701 738 -0.889716 0.114296 -0.405628 0.1833058 0.4390721 0.5085046 0.7176613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 701 881 -0.442439 -0.103590 0.941217 0.7353053 -0.3372167 -0.5783548 0.1054358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 702 737 -0.263343 -0.230825 -0.852410 -0.3302891 -0.0887780 0.9172950 0.2039544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 702 882 -0.339500 -0.779986 0.283527 0.2170835 0.0569255 0.1562025 0.9618914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 703 883 0.077998 -0.868186 0.357148 0.2060433 0.2750542 -0.2120891 0.9148276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 704 884 0.913705 -0.023688 0.602435 -0.4316108 -0.3104157 -0.8071094 0.2567657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 705 734 -0.010044 0.865186 0.417726 -0.1085187 -0.4436556 -0.0485642 0.8882764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 705 885 -0.244950 -0.300771 0.963300 0.0154105 -0.4448053 -0.4698558 0.7623295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 706 733 0.465421 -0.880301 0.255798 -0.1271370 -0.0847403 0.4371961 0.8862928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 706 886 0.294245 0.457286 0.876837 -0.2489532 0.4224294 0.8710793 0.0282221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 708 731 0.959852 -0.358434 0.134867 0.0276450 -0.0904881 -0.9487290 0.3015974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 708 888 0.241379 0.709148 0.294341 0.4597342 0.5686795 0.4052897 0.5486240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 710 729 0.602841 0.726928 0.005787 -0.4787122 0.3042474 -0.5471294 0.6155628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 711 728 -0.331761 0.825617 0.280496 -0.2210896 -0.5508805 0.0485129 0.8033035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 711 891 -0.251725 -0.422973 0.936907 0.2454374 0.4000911 -0.8204051 0.3265319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 712 92 -0.567976 -0.658498 -0.469534 0.1724670 -0.4360202 -0.7489655 0.4681797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 712 727 0.466335 -0.643827 0.586535 -0.0188027 -0.2350276 -0.7431968 0.6261525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 712 892 0.780868 0.752898 0.347614 -0.7860265 0.0370678 -0.6066872 0.1127786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 713 93 0.522518 -0.431958 -0.712876 -0.3816481 0.5116959 0.7574107 0.1372626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 713 726 0.370758 1.178744 -0.442794 0.3368282 -0.1294333 -0.1894036 0.9131922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 714 725 0.099390 0.791181 0.110494 0.4680739 -0.3526823 -0.0530125 0.8085244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 714 894 0.406177 0.045944 0.895594 0.1306175 -0.0121614 0.0790686 0.9882000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 715 895 0.715811 0.174979 0.601825 -0.6122042 -0.3659829 -0.6398797 0.2860358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 716 723 -0.574025 -0.711606 -0.428502 0.3394464 0.2953720 -0.8753600 0.1768513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 716 896 0.309953 -0.659231 0.564133 0.4372500 -0.6569609 0.5352025 0.3012858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 717 722 -0.810096 -0.718451 -0.053673 -0.0709261 0.0428890 0.1501165 0.9851878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 717 897 -0.036448 -0.028630 1.036747 0.0151773 0.2625501 -0.9504314 0.1658831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 718 721 0.448454 0.567972 0.529934 -0.5593420 -0.0228860 -0.0631544 0.8262108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 718 898 -0.504328 -0.342530 0.708001 0.3393378 -0.1416873 0.9184155 0.1459025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 719 99 -0.245706 -0.563669 -0.709447 0.5319009 0.3289258 0.3410531 0.7018347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 719 899 0.148266 0.695431 0.746563 -0.0414232 0.4571956 0.5149311 0.7239490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 720 759 -0.704949 0.312699 0.652332 0.4667281 -0.1664715 0.8104524 0.3124405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 720 860 0.330442 -0.652277 0.905057 0.3990154 -0.6987431 0.3927229 0.4453241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 721 758 0.994249 -0.329872 0.764126 0.5462424 -0.7800683 0.1401175 0.2710714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 721 861 -0.355708 -0.775184 0.048392 0.2563289 0.6934000 -0.2589873 0.6216248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 722 757 -0.939377 -0.598460 -0.292738 0.1096203 0.6338027 0.5085504 0.5724107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 722 862 -0.146266 -0.039295 0.898238 0.4826440 -0.0041783 -0.8757276 0.0117686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 723 756 0.658424 0.575538 0.444996 -0.1930041 0.0731853 0.0435054 0.9774971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 723 863 -0.595237 0.352569 0.768870 -0.4634920 -0.1472085 0.8193051 0.3037170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 724 64 0.329690 -0.537583 -0.769196 0.2726249 -0.6634783 -0.5493980 0.4285254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 724 755 -0.559540 -0.818173 0.032980 -0.5401925 -0.1820449 -0.6475095 0.5057501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 724 864 -0.432058 0.542372 0.702278 0.2405574 0.3034947 0.7903182 0.4747843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 725 754 -0.343342 0.350730 -0.826497 0.7135400 0.4663908 0.3955386 0.3418911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 725 865 0.712184 0.469489 -0.073110 -0.2573203 0.1087234 0.8962671 0.3444861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 726 753 -0.349544 0.303855 -0.873768 0.6838023 -0.2134379 -0.6895159 0.1068946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 726 866 -0.739164 0.622459 0.469892 0.0595532 0.7864450 0.5721097 0.2250515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 727 752 1.000537 0.818539 0.117560 0.0312935 -0.1280532 0.6333256 0.7625758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 727 867 -0.554206 0.498612 0.505016 -0.2398160 0.2871669 0.0313622 0.9268440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 728 68 -0.423151 0.739670 -0.502437 0.0238526 0.7317518 0.2388055 0.6379203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 728 751 0.291769 0.509741 0.623737 0.2010720 0.7629365 0.1876848 0.5850405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 729 750 -0.714206 0.283647 0.603789 0.4638258 0.5000073 -0.1234834 0.7208399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 729 869 0.073471 -0.945435 0.378355 0.7434713 0.3155543 0.1353766 0.5738894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 730 709 0.222163 -0.845259 -0.495340 0.6116344 -0.2511580 0.5072901 0.5527023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 731 748 -0.588481 0.899802 -0.178366 -0.0210625 0.3534913 -0.7841385 0.5096343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 731 871 -0.721729 -0.795640 0.385681 0.0066204 -0.7590692 0.6162783 0.2096928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 732 707 -0.051008 -0.936653 -0.490940 0.6233221 0.1802903 -0.3730252 0.6631871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 733 746 -0.366252 -0.919364 -0.049961 -0.0527611 -0.0423061 0.1449852 0.9871199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 734 874 0.526594 -0.554724 0.571775 0.0618396 0.0122247 -0.2341823 0.9701469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 735 704 -0.553988 -0.496792 -0.805893 0.1569561 -0.7477705 0.2405106 0.5986307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 735 875 -0.624320 -0.495796 0.459467 0.1096742 -0.6991656 0.6882884 0.1593676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 736 703 0.491860 0.850770 0.151488 -0.6492263 -0.4209883 -0.0189414 0.6331786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 736 743 -0.392819 -0.957493 -0.462927 0.4710692 -0.1770985 -0.8446845 0.1823130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 736 876 -0.729001 0.213473 0.607925 -0.2158397 0.3684493 -0.8894232 0.1630485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 737 742 0.561407 0.653339 -0.570635 -0.0649572 -0.3803281 -0.8707108 0.3049488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 737 877 -0.404015 0.998898 0.228160 -0.1339877 -0.6758594 -0.4218160 0.5893494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 738 78 0.644141 -0.901154 -0.132446 -0.4548135 0.4287383 0.6706090 0.3995143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 738 741 0.259648 0.237633 -1.040954 -0.9154233 0.0635948 -0.1278153 0.3763233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 738 878 -0.361638 0.764874 0.137006 0.2644959 -0.8894381 -0.2525056 0.2741948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 740 779 -0.222438 -0.805699 0.635035 0.0277502 0.4093982 -0.0951288 0.9069584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 740 840 0.521472 0.424297 0.629539 -0.2309818 0.0321988 -0.3208763 0.9179592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 741 778 -0.031609 0.510507 0.848830 -0.0932956 0.6004986 -0.7870914 0.1057563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 741 841 -0.429678 -0.538010 0.448291 0.2645444 -0.1277196 0.3149026 0.9025189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 742 42 -0.255778 0.537001 -0.908089 -0.3238015 0.2052777 -0.4782996 0.7900906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 743 43 0.265807 -0.157680 -0.774416 0.0069910 -0.2961865 -0.9550229 0.0124915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 743 776 0.838755 0.588724 0.125993 -0.1834921 0.5122919 -0.8372387 0.0540276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 743 843 -0.079366 0.057961 0.984864 0.5212739 -0.0826167 -0.7957272 0.2970962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 744 735 0.314115 0.218076 -0.825190 -0.0434142 -0.3246974 -0.9189847 0.2194398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 744 775 -0.292038 0.074623 1.033996 -0.6300416 -0.0908128 -0.5645740 0.5254111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 744 844 0.387193 0.959601 0.295445 -0.5602822 0.2982098 -0.6148501 0.4680964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 745 734 -0.093397 0.733639 0.644876 -0.0734189 0.6388354 -0.7010406 0.3082873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 745 774 0.234245 -0.741545 -0.536298 0.8381352 -0.2896792 -0.3700736 0.2768769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 745 845 -0.237620 -0.951000 0.596042 0.3590789 -0.2989149 0.2132750 0.8580362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 746 773 -0.283551 -0.883871 -0.091844 0.2981351 -0.4620476 0.7345321 0.3976053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 747 732 0.421444 0.368104 0.994103 0.0310174 -0.6690626 0.7282271 0.1451845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 747 772 -0.360062 -0.313922 -1.050083 0.4218708 0.7684401 -0.3212986 0.3581788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 747 847 0.137288 -0.856654 0.366039 0.3572323 -0.7189187 0.1407201 0.5794298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 748 771 -0.221274 -0.592137 -0.712059 0.1303014 0.1555298 0.8349573 0.5115451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 748 848 0.699243 -0.874461 0.212974 0.7150583 -0.1573880 -0.3264458 0.5977907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 749 730 -0.772094 0.419188 -0.194606 -0.0341869 0.2291350 -0.8984042 0.3730930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 749 849 0.068531 0.273914 0.772286 0.3961905 -0.3072402 -0.2363427 0.8323333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 750 769 -0.692344 0.005675 -0.548416 0.1173553 0.1951647 0.9006800 0.3700189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 751 768 -0.348972 0.899566 0.191450 0.1547433 -0.6352199 0.6059552 0.4531760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 751 851 -1.005194 -0.472286 0.526472 0.1986633 -0.4576453 -0.6974398 0.5144623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 752 767 0.914713 -0.516643 -0.123436 -0.7920997 0.2608703 0.2155015 0.5080195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 753 53 0.702998 0.117861 -0.898190 0.5598605 -0.3110550 0.3759558 0.6696702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 753 766 0.730737 -0.626119 0.488214 -0.3694602 0.0106649 0.1009951 0.9236803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 753 853 -0.641726 -0.215513 0.609026 -0.0568936 -0.4038405 -0.8310378 0.3782224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 754 765 0.106253 -0.784847 0.225649 -0.0792655 0.0504519 -0.9032956 0.4186032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 754 854 0.880447 0.238578 0.540877 0.1541042 0.5239001 -0.7070156 0.4493434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 755 855 0.537923 -0.777344 0.550628 0.1913905 0.1475983 -0.5011827 0.8309033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 756 763 0.681965 0.021191 0.361278 -0.8030933 -0.2699218 0.2076759 0.4889316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 756 856 -0.800410 0.163555 0.516974 -0.4552797 -0.5400533 -0.3241883 0.6292573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 757 762 -0.136465 0.012771 -0.921579 -0.1535860 -0.4716516 -0.5691535 0.6557594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 758 58 -0.865735 0.004468 -0.724019 0.7716234 0.3148552 0.4629764 0.3018549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 758 858 0.875702 0.103106 0.501691 0.1606284 0.7832946 -0.3342610 0.4989164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 759 859 0.262590 0.324658 0.877176 0.0740406 -0.0271555 -0.9231378 0.3762939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 760 799 0.322411 0.417511 -0.771034 -0.8888835 -0.0189508 0.0459820 0.4554258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 760 820 -0.118248 0.766857 0.565408 0.1706063 -0.0949938 -0.5866121 0.7859745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 761 758 -0.856430 0.636921 -0.105682 -0.5105269 -0.0025416 0.2474457 0.8234843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 761 798 0.711657 -0.579677 -0.030549 -0.1997847 -0.5873595 -0.3807388 0.6856623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 761 821 0.466504 0.776515 0.063725 0.2031262 0.1563092 0.7835149 0.5660491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 762 22 0.391515 0.447979 -1.033812 0.3818211 -0.6047351 0.2720134 0.6438299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 762 797 -0.973118 -0.332778 -0.556814 0.8164051 -0.0346647 -0.4939312 0.2971752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 762 822 -0.364393 -0.429521 0.853438 0.4925825 0.1423128 -0.5697580 0.6422502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 763 796 0.670063 -0.532914 -0.827605 0.7251613 0.2967699 -0.2375281 0.5741508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 763 823 -0.468802 -0.683960 0.330730 0.2913879 -0.2625719 0.9197476 0.0146102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 764 24 -0.095628 -1.040989 -0.168620 -0.5778209 0.1874910 0.1783081 0.7740648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 764 755 0.771742 -0.279822 0.540235 0.3483285 0.1784484 0.8862438 0.2477810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 764 795 -0.776540 0.379475 -0.528072 -0.8908680 0.2412694 0.2447092 0.2970870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 764 824 0.208646 0.964543 0.114106 -0.5180039 0.0305825 0.4981491 0.6946827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 765 794 0.655550 0.548846 0.156176 -0.1894112 0.0418658 0.4149916 0.8889053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 765 825 -0.481808 0.453242 0.684222 0.6452227 -0.3001967 -0.3475248 0.6105703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 766 793 0.393661 -0.835045 -0.139698 0.3405851 -0.0014392 -0.8142197 0.4701552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 766 826 -0.681792 -0.854092 0.493522 0.7465851 -0.2068608 -0.2337075 0.5875373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 767 792 0.987907 -0.018989 -0.702618 0.0554794 -0.2984720 0.1820333 0.9352542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 768 791 0.798122 0.122368 -0.650333 -0.4902699 0.0824433 -0.8598010 0.1165366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 768 828 0.398392 0.323238 1.039583 0.0614221 -0.2679537 -0.9573077 0.0893876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 769 829 0.454239 0.785899 0.481358 -0.9365572 -0.2391779 -0.1959303 0.1651239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 770 789 -0.675426 0.760284 -0.063841 0.1110031 -0.0616617 -0.6296692 0.7664156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 771 788 -0.473277 0.065042 -0.636991 -0.1795588 -0.9197598 0.1261977 0.3253839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 772 787 0.664130 -0.237833 0.567060 -0.3305146 -0.3662809 0.6992858 0.5172985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 772 832 -0.693664 -0.400726 0.567257 0.8240383 -0.4194682 -0.0700468 0.3743005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 774 785 1.185337 -0.187782 0.215820 0.0181426 -0.3273665 -0.5927097 0.7356611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 774 834 0.045968 1.069690 -0.062082 -0.0543170 -0.1524165 -0.8787885 0.4489428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 775 835 0.123753 -0.006016 0.918731 0.1379685 0.4982897 0.3303938 0.7896278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 776 836 0.524319 -0.842001 0.109859 0.1001637 0.3215623 -0.6288905 0.7007579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 777 37 0.075863 0.745580 -0.591270 0.0038947 0.4552597 -0.6936054 0.5582427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 777 742 -0.792597 0.354003 0.582943 0.0903073 -0.6205139 0.6355763 0.4503885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 777 837 -0.203822 -0.868901 0.588483 -0.2622022 -0.4726107 0.8402492 0.0432479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 778 781 -0.305957 -0.837781 -0.221372 -0.0388716 -0.0697975 0.6830376 0.7260006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 778 838 0.615356 -0.372955 0.791008 -0.3581005 0.2784959 0.1964181 0.8692664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 779 839 -0.277200 0.669125 0.941713 0.5093391 -0.3710092 -0.4327084 0.6447397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 780 0 0.344083 0.368812 -0.960189 -0.0752671 -0.1927009 0.6904697 0.6931471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 780 800 -0.303317 -0.339501 1.022906 0.0169708 -0.1598638 0.7189177 0.6762492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 781 801 -0.213788 -0.600056 0.502639 -0.2831393 -0.2027127 0.2787328 0.8950127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 782 777 -0.457701 0.469991 -0.798685 -0.7969057 -0.0340821 -0.0704838 0.5990090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 782 802 0.074271 0.881805 0.670613 0.3247326 -0.1124079 -0.8840335 0.3168563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 783 3 -0.784697 0.456378 -0.546124 0.2942755 0.5956461 -0.0425256 0.7461898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 783 776 0.156558 -0.618702 -0.707380 -0.5623746 0.5884111 -0.1925172 0.5481280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 783 803 0.671130 -0.560193 0.487843 0.5377377 0.3905575 -0.5150853 0.5412856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 784 775 -0.287572 0.792016 0.611058 -0.0757283 0.4675399 -0.1049925 0.8744417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 784 804 0.810931 -0.190777 0.476388 0.1082785 0.0954977 -0.9388130 0.3127075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 785 805 -0.801527 0.432616 0.209370 -0.1796138 -0.4203781 -0.7676098 0.4492176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 786 773 -0.450820 0.501401 -0.469548 -0.0871689 0.0795730 -0.9188861 0.3764547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 788 808 0.779388 -0.452714 0.041721 -0.7400740 -0.3708303 -0.5231386 0.2027348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 790 769 -0.237257 -0.679053 -0.532874 0.4336224 -0.4796614 0.3622405 0.6713259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 791 811 0.121593 -0.253111 0.962057 0.3425611 0.0249928 -0.9215082 0.1812454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 792 12 -0.112182 0.803721 -0.351350 0.1787818 -0.6012384 0.2388450 0.7412844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 792 812 -0.022840 -0.828549 0.363667 0.1690060 -0.3081306 0.4976816 0.7929726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 793 813 0.271801 -0.159715 0.843130 0.1010011 0.2428454 0.4495764 0.8536427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 794 814 -0.269820 0.564213 0.904920 -0.0421574 -0.4306523 -0.9000363 0.0519231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 795 15 -0.083383 0.815448 -0.323490 0.8499046 0.4057317 -0.0689565 0.3290729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 795 815 -0.041962 -0.873709 0.281845 -0.1245729 -0.2995356 -0.0523389 0.9444684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 796 816 -0.818165 -0.154061 0.686679 -0.0173598 -0.1090034 -0.5076874 0.8544416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 797 817 -0.612976 0.644267 0.212666 -0.7358320 -0.1080519 0.1627390 0.6483765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 798 818 -0.038247 1.065328 0.044861 0.1172997 -0.7509684 -0.6458828 0.0715731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 800 839 -0.030446 1.050892 0.050866 0.6071234 -0.0201674 -0.5152845 0.6045464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 800 1580 -0.073342 -0.011144 0.918636 0.5134438 0.1749004 -0.3699472 0.7542707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 801 1581 -0.531514 -0.771822 0.197054 -0.3085029 -0.2707406 0.2134893 0.8865370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 802 837 0.282436 -0.787200 -0.233478 0.2743923 -0.1740004 -0.0580168 0.9439633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 803 836 0.991710 0.169885 0.546639 -0.2576666 -0.7298201 -0.6176742 0.1394600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 803 1583 -0.422365 0.856859 0.168868 -0.3244337 -0.4171529 -0.6073603 0.5931608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 804 1584 -0.730725 0.361741 0.276484 0.6504251 0.1428601 -0.5869092 0.4605169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 805 834 0.749759 0.198038 -0.365260 0.0283907 0.2627448 0.6748133 0.6890473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 805 1585 0.613847 -0.854199 0.514408 -0.0545254 -0.1046588 -0.9844904 0.1298157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 806 786 -0.661944 -0.618565 -0.501813 -0.2913681 0.2474261 -0.6300384 0.6759708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 806 833 -0.046196 0.722096 -0.666175 -0.2414456 0.3907158 -0.6811540 0.5701529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 807 787 0.391334 -0.378999 -0.709398 -0.3313683 -0.1610278 -0.1201585 0.9218606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 807 832 0.716544 0.842225 -0.126732 -0.2636909 0.8157100 0.5094641 0.0743682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 807 1587 -0.366674 0.422959 0.812522 0.0752130 -0.3539256 0.8747865 0.3222238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 808 831 -0.961187 -0.003261 0.214704 -0.0973666 0.7832194 0.1083811 0.6044342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 808 1588 0.101477 0.856973 -0.052422 -0.0904074 -0.6131155 -0.1686750 0.7664624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 809 789 -0.592865 -0.359670 -0.639420 0.6306924 -0.1314363 0.7620817 0.0646766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 809 830 -0.080283 -0.360395 0.727408 -0.5598675 0.3993514 0.6567383 0.3094538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 809 1589 0.822867 0.327117 0.567050 0.0903950 0.7475629 0.4173616 0.5087118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 810 790 -0.735007 -0.669468 -0.249844 -0.3117255 0.4835483 -0.6720373 0.4662340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 810 829 -0.655379 0.555788 0.522576 0.9453609 -0.0468036 0.3058603 0.1027214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 811 828 -0.652578 -0.104283 -0.787889 -0.6887023 0.3517884 0.5217350 0.3601757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 811 1591 -0.657987 0.449311 0.674869 0.0713974 -0.2145246 -0.9201795 0.3196112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 812 827 0.655746 0.489072 0.664670 -0.0224812 -0.5413025 -0.2541266 0.8011903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 812 1592 -0.272076 -0.471419 0.792904 0.4187631 0.0530502 0.6138802 0.6670639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 813 826 -0.905126 0.133203 -0.217194 0.2986018 0.0805273 0.0390018 0.9501743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 813 1593 -0.271419 0.043029 1.109303 -0.0496051 0.5947283 0.4290171 0.6780722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 814 825 0.806688 -0.593724 -0.076004 0.2676555 0.5964463 -0.0726854 0.7532126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 814 1594 0.260169 0.140979 1.101388 0.4093181 0.0901746 -0.1432475 0.8965530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 815 824 -0.417228 -0.351944 -1.076044 0.4570128 -0.1433709 -0.2179581 0.8503401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 815 1595 0.209278 -1.015944 0.053702 -0.0552397 0.6900261 -0.1585684 0.7040374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 816 823 -0.422313 -0.670666 -0.475291 0.2297891 -0.3547413 -0.7297508 0.5374192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 816 1596 0.037718 -0.607901 1.009458 0.8231078 0.2384833 -0.3476245 0.3804950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 817 822 0.060762 0.803666 0.303410 0.2853140 0.0392226 -0.1981805 0.9369002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 817 1597 -0.641519 -0.207436 0.860351 -0.0990764 0.1545420 0.5523742 0.8131318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 818 821 0.383696 1.067604 -0.020772 -0.3235375 -0.5121504 0.4645799 0.6459032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 818 1598 -0.164426 0.203468 1.114968 0.4615711 -0.1960581 0.2325747 0.8333201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 819 799 -0.664819 0.690620 -0.121058 0.0276242 0.2846942 0.2424220 0.9270478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 819 1599 0.584353 -0.579039 0.116992 -0.2045994 0.7007553 0.1188055 0.6730278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 820 859 0.158319 -0.021517 1.120296 -0.2916419 -0.2718135 -0.1416593 0.9060878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 820 1560 -0.817520 0.551875 0.267732 -0.3554153 -0.4883339 0.5394920 0.5866501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 822 857 -0.329815 0.720553 -0.357961 -0.3650046 0.3931517 0.6213791 0.5710441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 822 1562 -0.333877 0.289615 0.888488 0.2593533 0.1932006 -0.0497535 0.9449519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 823 856 0.663570 -0.650053 -0.135777 0.1680832 0.0174755 0.7933242 0.5848756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 823 1563 0.686916 0.700821 0.378581 0.3454943 0.3703437 0.5862042 0.6323321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 824 855 -0.224390 -0.721065 -0.312550 0.6095600 -0.0868645 0.3501375 0.7059001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 825 854 0.107323 -0.380969 1.038636 -0.8141934 0.5019825 0.2696335 0.1113571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 825 1565 -0.563801 0.485848 0.192166 -0.2887924 -0.4041934 0.8668658 0.0420756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 826 853 -0.850973 -0.188186 -0.495973 -0.3460812 -0.7123126 -0.4393389 0.4240517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 826 1566 -0.505153 0.625848 0.602176 -0.0310231 -0.3171408 -0.1783115 0.9309481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 827 767 -0.722729 0.190987 -0.429582 -0.5485065 0.7209752 -0.2647897 0.3304872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 827 852 0.506970 0.826046 -0.282027 -0.3751789 0.3509672 -0.7552468 0.4070197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 827 1567 0.799896 -0.356463 0.397089 0.7174460 -0.3546435 0.5889654 0.1123342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 828 851 0.731820 0.347245 0.462608 -0.1859202 -0.7263211 0.2038721 0.6295455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 828 1568 -0.769525 0.208775 0.342046 -0.7841073 0.0978045 0.5618698 0.2447699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 829 850 -0.249502 -0.327040 -0.918068 0.1354972 0.4244296 -0.8905713 0.0915578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 830 770 0.705470 0.626925 -0.174033 0.7558076 0.5744247 -0.2835958 0.1355157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 830 849 -0.624925 0.647386 -0.201812 0.8416431 -0.4224467 -0.1248904 0.3123748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 830 1570 -0.821192 -0.551814 0.192903 0.3854049 0.5539188 -0.7236405 0.1448497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 831 771 0.036008 -0.712257 -0.395814 -0.7597163 0.5260526 0.3156936 0.2154930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 831 848 0.145636 0.304307 -0.936485 -0.0284727 -0.4464992 0.3588394 0.8191838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 831 1571 -0.189727 0.975555 0.428810 -0.5557897 0.0783273 0.8264324 0.0444086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 832 847 -0.906911 -0.059030 0.533204 0.5241161 0.3951169 0.7494238 0.0868851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 833 773 0.792937 0.000640 -0.558504 0.1908534 0.1055194 -0.8542143 0.4719731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 833 846 -0.580488 0.529807 -0.577549 -0.0702546 0.0919810 -0.3148831 0.9420469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 834 845 0.169714 -1.106111 -0.056742 0.4960941 0.1225631 -0.8050012 0.3014000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 834 1574 -0.761427 -0.478650 0.294802 -0.2490045 0.0463649 0.8927958 0.3725088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 835 844 0.139072 0.982805 -0.560763 -0.2587688 -0.1444693 -0.2855324 0.9113937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 835 1575 -0.916260 0.513527 0.381042 -0.4331583 -0.7296874 0.5134799 0.1275487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 836 843 -0.259832 0.852207 0.064940 -0.1542339 0.4906421 0.8112926 0.2780045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 837 842 0.543469 -0.938286 0.186737 0.1891582 0.4458979 -0.6940579 0.5326142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 837 1577 -0.208457 -0.084489 0.877647 0.0119205 -0.0227654 0.8958879 0.4435365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 838 801 -0.050820 -0.526542 -1.141655 -0.2752940 -0.6536647 0.4480708 0.5442134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 838 841 0.145010 0.492799 0.826316 0.4210764 0.5285150 -0.7265313 0.1245745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 838 1578 0.004831 -0.937994 0.419453 0.3607778 -0.1149431 -0.5048427 0.7757328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 839 1579 -0.466395 0.807011 0.355757 0.1151986 -0.1114787 -0.2852687 0.9449463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 840 879 -0.369445 0.937948 -0.090588 -0.5192167 -0.2082228 0.0854611 0.8244718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 840 1540 0.156582 0.280501 0.886943 0.3630661 0.2218226 0.8479308 0.3162136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 841 1541 -0.572235 0.040263 0.814862 0.4360119 -0.4004120 -0.2866008 0.7532753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 842 742 0.585365 0.752775 -0.464850 0.0040835 -0.6193195 0.1933068 0.7609593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 842 877 0.068794 0.649666 0.761330 0.1469497 -0.4295804 0.7525684 0.4769773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 843 1543 -0.998451 0.257939 0.516447 0.0821231 -0.8008371 0.2443653 0.5405566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 845 874 0.557453 1.074520 0.164898 0.3712736 -0.2659697 0.8332705 0.3115707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 845 1545 0.051425 -0.035127 0.972012 0.0679018 -0.4505920 -0.3838998 0.8031047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 846 746 0.870736 0.553597 -0.487611 -0.0839163 -0.7157397 0.6640011 0.1994424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 846 873 -0.768353 0.411155 -0.767100 0.1163728 -0.0531450 0.3011503 0.9449558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 846 1546 -0.758858 -0.582091 0.654026 -0.1903861 -0.6537162 0.6113080 0.4033742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 847 872 0.748689 0.167072 -0.596528 0.0844163 -0.3030615 0.7199214 0.6186605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 847 1547 0.440875 -0.728796 0.318156 0.6376893 0.6410874 0.1931739 0.3808454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 848 871 -0.554906 0.339540 -0.633382 -0.9209537 -0.0695546 -0.3579835 0.1373111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 848 1548 0.983655 0.473290 -0.009812 -0.2977379 -0.0413262 -0.8463398 0.4397196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 849 870 -1.079894 -0.078786 0.235537 -0.6715779 0.4136290 0.0248048 0.6142304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 849 1549 -0.057806 0.829706 0.328860 -0.4451706 -0.2126704 -0.5754822 0.6522382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 850 750 0.448689 -0.594098 -0.447021 -0.7756273 0.0697811 0.2867751 0.5579362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 850 869 0.462797 0.704803 -0.530534 -0.5835411 0.4284616 0.3870235 0.5710632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 851 868 0.578834 0.127687 -0.782223 0.0833082 -0.2420258 0.7027455 0.6638012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 851 1551 0.872053 -0.079048 0.655604 0.8226542 0.1422823 0.5502823 0.0136123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 852 867 -0.931322 0.024743 0.215898 0.3158258 0.5355803 -0.1022321 0.7765026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 852 1552 0.206039 0.028363 1.015138 -0.5661022 0.2480064 -0.7152622 0.3262224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 853 866 0.195041 -1.042821 0.389591 0.8501852 0.4484664 0.2583124 0.0966314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 853 1553 0.713663 0.100673 0.533170 -0.6372937 -0.3043637 -0.6746539 0.2146197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 854 1554 -0.929519 0.474033 0.191892 -0.8766272 0.0450720 0.4113383 0.2455486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 855 864 -0.716585 0.046729 0.573593 -0.2375613 -0.4092786 -0.4582163 0.7523918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 855 1555 0.526884 0.017828 0.684417 0.2801357 -0.2676113 0.8743220 0.2923512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 856 863 -0.821511 -0.610179 0.235647 0.4252447 -0.4157229 0.7256433 0.3460972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 856 1556 0.589945 -0.728995 0.251431 0.3669257 0.4307791 -0.8242987 0.0180677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 857 757 0.938370 -0.544507 -0.402164 -0.0926318 0.3458988 0.1660384 0.9188061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 857 1557 -0.520826 0.386366 0.499094 0.1773045 -0.5038700 0.0942633 0.8401147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 859 1559 -0.778554 0.085014 0.907212 -0.7763079 -0.3052959 0.5157862 0.1952052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 860 899 -0.630393 -0.695331 0.398590 0.4967819 0.4332481 -0.1587260 0.7350578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 860 1520 0.679826 -0.519926 0.396391 -0.0788505 0.6541798 -0.5754492 0.4844477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 861 858 -0.830998 0.138961 0.563172 -0.2439379 -0.2511201 0.8091640 0.4718969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 861 898 0.654994 -0.229485 -0.666232 0.0095456 0.1050006 -0.7915314 0.6019650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 861 1521 -0.049509 -1.067356 0.432608 0.2976288 0.3193002 0.3307881 0.8366861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 862 857 0.628381 0.304702 0.761126 0.7513737 -0.3036645 -0.5854720 0.0211642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 862 1522 -0.668127 0.044473 0.523715 -0.1853080 -0.4776060 0.8003734 0.3113773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 863 896 0.341111 0.929731 0.233240 0.3807957 -0.5792574 0.6975291 0.1814074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 863 1523 0.083611 -0.276449 1.108641 -0.3597969 0.2176462 0.3201095 0.8489442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 864 895 0.118360 -0.740045 0.647414 0.6607618 0.5057607 0.5545831 0.0061246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 864 1524 0.644635 0.502761 0.639367 0.4648486 0.2870274 -0.0835008 0.8334019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 865 854 0.832925 -0.039686 -0.372770 0.7350791 0.3644998 0.3509493 0.4512575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 865 894 -0.991262 0.106138 0.304467 0.4068636 0.2641510 -0.6321707 0.6041908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 865 1525 0.000962 -0.948747 0.020119 0.4500160 0.5063340 0.1157507 0.7264387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 866 893 -0.642434 0.827536 -0.347490 -0.7216085 0.2829178 0.4043490 0.4855313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 866 1526 0.732447 0.684598 0.271715 -0.4687879 -0.0983098 -0.2296953 0.8472386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 867 892 -0.570851 -0.375663 -0.600182 -0.4424670 -0.5744451 -0.4802570 0.4935474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 867 1527 -0.895327 0.630340 0.355518 0.0167722 0.1417154 -0.9670103 0.2110131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 868 728 -0.119274 0.837550 -0.431113 0.0330113 -0.1705662 -0.2113813 0.9618396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 868 891 -0.320666 -0.496695 -0.852694 -0.0394735 -0.7223618 0.6892321 0.0399292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 868 1528 0.176589 -0.946391 0.291830 0.1219847 0.1234847 -0.2098930 0.9621934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 869 890 0.315097 -0.469481 0.869712 -0.3465962 0.8057666 0.4368799 0.1993669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 869 1529 -0.833622 0.244079 0.588202 0.7365732 -0.0374111 -0.6145626 0.2799520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 870 730 0.649290 0.167468 -0.598709 0.3510844 0.2990561 -0.6837456 0.5655061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 870 889 -0.764227 0.488766 -0.465720 -0.1995495 -0.7745228 0.5803139 0.1533959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 870 1530 -0.681126 -0.342227 0.706130 -0.5109512 -0.6640659 0.5232782 0.1553234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 871 888 -0.597342 -0.401804 0.566291 -0.7750738 -0.2020776 -0.5798166 0.1491241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 871 1531 0.634226 -0.120195 0.736852 -0.1553823 -0.1143379 -0.9459174 0.2608132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 872 732 0.585930 0.679519 -0.469827 0.3451486 -0.0708829 -0.1818586 0.9180281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 872 887 -0.317164 -0.314131 -0.808147 0.7839271 0.3469544 -0.4998586 0.1233786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 872 1532 -0.335399 -0.592539 0.597311 -0.1116698 -0.4633669 -0.1016261 0.8732085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 873 733 0.763819 -0.195460 -0.623580 -0.2169406 -0.5772993 0.6012349 0.5081130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 873 1533 -1.025285 0.040719 0.652046 0.3970910 -0.6136870 -0.6729769 0.1131773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 874 885 0.017636 -1.025405 -0.244916 -0.1388183 -0.0360149 -0.2505872 0.9574124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 875 844 -0.079999 -0.813214 -0.600343 0.0524654 0.7709314 0.0824148 0.6293806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 875 884 0.167732 0.739934 0.354978 0.6777979 0.3198915 0.6180318 0.2372683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 876 843 0.778360 0.662439 0.114525 0.1947338 0.6680219 -0.7181697 0.0075998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 876 883 -0.716601 -0.601660 -0.146009 0.5488915 -0.6141218 0.4812811 0.2999016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 876 1536 0.639226 -0.708706 0.035806 -0.5352878 0.3080979 -0.6028553 0.5050823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 877 882 0.751975 -0.723329 0.212811 -0.1975481 0.4393766 -0.6690461 0.5659507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 877 1537 0.326299 0.497666 0.934237 0.2992319 -0.4809735 -0.8215922 0.0641167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 878 841 -0.531215 -0.344420 0.809571 0.3791384 -0.4714659 -0.7278171 0.3228873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 878 881 0.649487 0.632963 -0.378078 0.3545687 -0.3479252 -0.4579791 0.7372138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 878 1538 -0.224018 0.927760 0.480678 -0.5226329 -0.5752993 -0.5889724 0.2213529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 879 739 -0.538400 0.804456 -0.267993 0.3844503 0.5386707 0.3259977 0.6750980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 879 1539 0.371033 -0.716740 0.325436 0.2985968 -0.2919332 0.8339367 0.3607833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 880 919 0.787267 0.530858 0.238913 -0.2943973 -0.4973991 -0.5116906 0.6356863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 880 1500 -0.494435 0.452849 0.577999 -0.3648204 -0.1238103 0.3543031 0.8520836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 881 918 -0.237379 -0.064148 -1.036175 -0.3359491 0.5336728 0.7597757 0.1583429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 881 1501 -0.737009 0.631806 0.098942 -0.2278268 -0.1561825 0.7510170 0.5997294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 882 1502 -0.594378 -0.691287 0.389155 0.0860728 -0.4979715 -0.3780284 0.7756999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 883 916 0.215279 0.721542 0.742086 0.1179874 0.7811557 -0.3520359 0.5019417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 884 915 1.048906 -0.216938 -0.093531 -0.6730087 0.1002145 0.5044869 0.5315160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 884 1504 -0.003145 0.861706 0.677318 -0.6493797 -0.1117025 0.7195663 0.2192100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 885 1505 0.901052 0.036010 0.750577 -0.5863478 0.6566641 -0.1639653 0.4450888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 886 873 -0.406942 0.445555 -0.493511 -0.7587743 0.1887450 0.6087656 0.1343184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 886 913 0.569565 -0.580344 0.611771 0.1070538 -0.6066965 -0.0307250 0.7870927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 886 1506 -0.775986 0.216771 0.614868 0.6873346 -0.4076911 -0.1085193 0.5912552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 887 707 0.898325 -0.109279 -0.397567 -0.0472276 0.0675852 0.3599556 0.9293190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 887 1507 -0.742011 -0.019079 0.554484 0.2553084 -0.8719157 -0.2316038 0.3477648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 888 911 0.253871 -0.007235 -0.776595 -0.7584982 -0.0159959 0.1894975 0.6233100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 888 1508 0.734766 0.698478 0.156142 -0.4610863 -0.5379112 -0.5202258 0.4768816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 889 709 -0.288532 0.638604 -0.598222 -0.3646569 0.0792174 -0.9082135 0.1894682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 890 710 0.031172 -0.954559 0.000023 -0.3125006 -0.6208071 -0.5333110 0.4822047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 890 909 -0.763458 0.098248 -0.715859 0.0539372 -0.6495363 -0.6609748 0.3718948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 890 1510 -0.118446 1.040149 0.072286 -0.3380292 0.1198851 0.3078569 0.8812423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 891 908 0.363069 0.774839 0.450911 -0.2620252 -0.7035678 0.6474313 0.1310261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 891 1511 -0.424721 -0.475576 0.895656 0.1575684 0.5962139 -0.1696020 0.7687238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 892 907 -0.723384 -0.682968 -0.174221 0.5086857 -0.3343372 0.3320245 0.7205673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 892 1512 0.401408 -0.504645 0.635357 0.1881051 -0.1417050 -0.8838762 0.4041027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 893 713 -0.144092 0.823250 -0.286056 -0.2343113 -0.2692060 0.9185926 0.1697470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 893 906 0.152379 0.368072 1.117151 0.5430222 0.6192388 -0.1556992 0.5453695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 893 1513 0.243230 -0.712530 0.536368 0.0962669 0.1674612 0.4682478 0.8622259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 894 905 -0.325194 -0.714620 0.520795 -0.5118058 -0.5376761 -0.6662413 0.0712862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 895 1515 0.356593 0.297550 0.658581 -0.8331876 0.3839646 -0.1675220 0.3609791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 896 1516 0.650630 -0.724496 0.268231 0.8256397 -0.1002855 0.1807874 0.5249552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 897 862 0.842804 0.380622 0.307727 0.1796183 0.3615589 0.1878637 0.8953880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 897 1517 -0.147293 -0.528679 0.895101 0.4254583 0.1029647 0.8986338 0.0289956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 898 1518 0.836671 0.343598 0.419715 -0.5042783 -0.3675218 -0.3640358 0.6914543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 899 1519 0.019744 0.289052 0.983659 -0.6001778 -0.0086481 0.7396875 0.3042601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 900 939 0.626225 0.651377 -0.200922 0.0454782 -0.3374697 0.3002590 0.8910053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 900 1480 0.609726 -0.722817 0.552650 0.2254352 0.5311542 0.5841040 0.5708561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 901 898 0.550062 0.413497 0.683407 0.2552068 -0.2275562 0.9275184 0.1509878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 901 938 -0.496458 -0.503709 -0.777979 -0.2410749 -0.3655223 -0.3137931 0.8425023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 901 1481 -0.488506 -0.364843 0.449689 -0.3574047 -0.2822798 0.7222419 0.5205253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 902 897 -1.001783 -0.023005 -0.169403 -0.3282260 0.3994145 0.8513982 0.0886388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 902 937 0.968680 0.486449 0.183298 0.1678445 0.3552955 0.9096128 0.1348997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 902 1482 -0.176364 1.089194 0.376702 -0.6815016 -0.0322090 -0.6956849 0.2248127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 903 896 -0.691809 1.014748 0.449178 -0.1843848 -0.4991518 -0.0114944 0.8465918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 903 936 0.377485 -0.656001 -0.194872 0.7711408 0.0245681 0.3904229 0.5023029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 903 1483 -0.100579 -0.307459 0.842904 -0.3973431 0.1642225 0.4213962 0.7984828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 904 895 0.145033 1.123627 0.064091 0.3212995 0.2623842 0.9061115 0.0829642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 904 935 -0.136819 -1.029900 0.114064 0.1095039 0.3855715 -0.9155893 0.0322458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 904 1484 -0.078546 -0.047325 1.143965 0.6878742 0.1551106 -0.0976808 0.7023021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 905 934 0.080193 0.523380 -0.932944 -0.4033074 -0.7428366 -0.2774896 0.4566579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 905 1485 0.493263 0.886264 0.263090 0.0521508 -0.6936382 -0.6734551 0.2502092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 906 933 -0.470019 0.338736 -0.834026 0.1774596 -0.3797282 -0.1362902 0.8976300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 906 1486 -0.747271 -0.079172 0.609884 -0.2567980 0.1255105 -0.2832470 0.9154633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 907 932 -0.526414 0.306731 0.557320 -0.4300958 -0.3261859 -0.5381573 0.6473076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 907 1487 0.648703 -0.197590 0.751500 0.7170284 0.0852208 0.2475739 0.6459991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 908 931 0.134794 -0.277102 -1.008863 0.5026846 -0.3176434 -0.5153357 0.6171224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 908 1488 -0.138790 -0.850953 0.247247 0.0386291 -0.2797664 0.1572938 0.9463071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 909 930 0.008988 -0.852345 0.392995 0.4163022 -0.1365644 -0.3928962 0.8085018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 909 1489 -0.438339 0.172868 0.703714 -0.0246918 0.0348730 0.9688012 0.2441279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 910 929 0.405568 1.054517 -0.042983 -0.5282163 0.3440013 0.2928975 0.7189309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 911 928 0.455089 0.833955 0.055061 0.3136551 -0.0551774 -0.4058579 0.8566536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 911 1491 0.901458 -0.287126 0.270685 0.2276478 0.0083165 0.9080747 0.3514365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 912 887 0.882876 -0.084977 0.311456 0.5573691 -0.4629634 -0.6841721 0.0831448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 912 1492 -0.143324 0.765485 0.668141 -0.6925328 -0.3017516 -0.0243248 0.6547920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 913 926 0.791970 -0.591296 -0.415080 -0.0197966 -0.0049074 0.2850415 0.9582982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 913 1493 0.492135 0.312627 0.772675 -0.2232839 -0.2799665 0.4991942 0.7890299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 914 885 0.810471 -0.064034 0.384733 0.3411729 0.5797372 0.6947990 0.2544804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 914 925 -0.925955 0.012388 -0.568089 -0.6497896 -0.3796581 0.1132561 0.6486959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 914 1494 -0.053400 1.140232 0.156863 0.0074933 -0.7550721 -0.1298199 0.6426172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 915 924 0.462175 -0.668982 -0.535808 -0.2886124 0.1273053 0.8784465 0.3589262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 915 1495 -0.264130 -0.721627 0.491279 0.0947515 -0.1042268 -0.9784190 0.1511795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 916 923 -0.803491 0.375496 -0.618892 -0.4764718 -0.4426174 0.1053773 0.7523031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 916 1496 -0.591539 -0.784016 0.147573 0.0675114 -0.6449070 -0.3193835 0.6910365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 917 922 -1.029643 0.079436 0.422796 -0.4345592 -0.4743400 0.7559390 0.1213101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 917 1497 0.224537 -0.434422 0.897833 -0.3834548 -0.5225016 0.7566655 0.0860917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 918 921 0.754757 -0.628679 -0.068935 0.3518273 -0.0164148 0.2803975 0.8929308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 918 1498 0.357214 0.275257 0.733854 0.1045825 0.4679749 0.2203371 0.8494195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 920 959 -0.797350 -0.210317 0.583388 0.4817773 0.5584571 -0.3341429 0.5868260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 920 1460 0.473138 -0.761124 0.480558 0.5106567 -0.1317096 0.3557195 0.7715867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 921 958 0.492015 -0.939452 0.482740 0.0139300 0.6263474 0.4258913 0.6527722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 921 1461 0.707144 0.469068 0.421313 -0.8744426 -0.1033106 -0.2441476 0.4062868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 922 957 0.433717 -0.562170 0.770967 -0.3111901 -0.7650061 -0.2186057 0.5197480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 922 1462 -1.033336 -0.354679 0.284017 -0.2895912 -0.1124158 0.8089185 0.4991498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 923 956 -0.479605 0.135355 0.800970 0.1874751 0.1986890 -0.4617962 0.8438720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 923 1463 -0.503425 -0.790564 -0.075366 -0.0580520 -0.6036073 -0.2793268 0.7444896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 924 955 -0.291052 0.189054 -0.768327 0.0670468 -0.8751871 -0.4787499 0.0187282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 924 1464 -0.759643 0.693359 0.348653 0.2790641 -0.1274926 -0.6603859 0.6853899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 926 953 0.538038 -0.960776 -0.247898 -0.2841517 -0.3674124 0.4840600 0.7415873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 926 1466 0.390560 0.059797 0.921563 -0.4800846 0.3914853 0.5036224 0.6021815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 927 912 -0.298795 0.121597 -0.911886 -0.1473581 0.8162506 0.2546320 0.4971751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 927 952 0.463309 -0.122040 0.924914 -0.6193761 -0.1095645 0.1040908 0.7704115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 927 1467 0.071274 0.940700 0.150703 0.5812478 -0.1975891 -0.7845370 0.0872425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 928 951 -0.445016 0.868017 -0.502089 -0.8901808 0.3114266 -0.0358867 0.3306111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 928 1468 0.848502 0.525175 0.278341 -0.5496963 -0.0415426 -0.3414878 0.7612452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 929 950 0.368649 -0.077432 1.033381 -0.5279042 -0.6515815 -0.4335321 0.3298617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 929 1469 -0.803224 0.618363 0.337435 0.0582159 -0.1229854 -0.3610136 0.9225804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 930 949 0.587677 0.056165 0.807577 -0.8526422 -0.2552505 0.4534961 0.0467949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 931 948 0.421170 -0.768423 -0.561488 0.3867838 0.6973958 0.5991157 0.0713991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 931 1471 0.862735 0.186557 0.456338 0.0776889 0.6087098 0.6377324 0.4655471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 933 946 -0.810312 0.329210 -0.070096 -0.7061766 -0.0061973 -0.0156831 0.7078349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 933 1473 -0.197507 0.205899 1.073720 -0.4454751 0.0296272 0.8232536 0.3506104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 934 945 -0.669432 0.205209 0.359370 -0.2272510 0.7715958 0.5332991 0.2618951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 934 1474 0.426522 0.928025 0.320547 0.0645672 0.5503194 -0.0767926 0.8289044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 935 675 0.101808 0.770691 -0.483150 -0.0117053 -0.2550250 -0.9613663 0.1029569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 935 944 -0.074307 0.640253 0.776928 0.8414775 0.0811045 0.0163257 0.5339205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 935 1475 -0.308320 -0.867680 0.551331 0.6233929 -0.2262470 0.0208241 0.7481711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 936 943 -0.155952 0.074480 1.057238 0.1524323 0.6033972 0.1996293 0.7568516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 936 1476 0.209249 1.033872 -0.080527 -0.1164838 -0.2601562 -0.6641605 0.6911158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 937 1477 0.638225 -0.560749 0.745486 -0.1435481 -0.2941423 0.3631927 0.8723333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 938 1478 0.149747 -0.801410 0.313719 0.8014735 0.2224939 0.3779471 0.4065620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 939 1479 0.499812 -0.867879 0.019304 0.2861008 -0.6552538 0.0934404 0.6928619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 940 979 0.573106 -0.037613 0.706193 0.6229179 0.1483819 -0.7553233 0.1394376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 940 1440 -0.474350 -0.750417 0.434649 -0.6712556 -0.5949223 0.4138385 0.1556315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 941 938 0.768737 0.188229 0.574489 -0.4847819 -0.3938866 -0.5628823 0.5412979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 941 1441 -0.806705 0.399647 0.508126 -0.1963431 0.3274429 0.7757276 0.5024711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 942 937 -0.301668 0.474265 -0.793629 -0.2424887 -0.3683217 0.8975133 0.0028677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 942 1442 -0.971319 0.045914 0.351795 0.6602148 -0.6318288 -0.2613085 0.3108482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 943 976 -1.019429 0.573352 0.033414 -0.6320763 0.5728804 0.1207246 0.5076546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 943 1443 0.538529 0.807263 0.239400 -0.8306737 0.2441760 0.0487303 0.4979806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 944 975 0.199123 0.260509 -0.982599 -0.2157071 -0.2748493 -0.7234920 0.5953887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 944 1444 -0.205501 0.934413 0.222721 -0.7485030 0.0091703 0.1264753 0.6508941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 945 974 0.222121 1.038305 -0.121400 0.5921923 -0.4038097 -0.5636279 0.4105724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 945 1445 -0.362896 0.235312 0.820816 0.2980589 -0.2963743 0.2644568 0.8679780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 946 973 -0.964811 0.040903 0.140568 0.9544543 0.2187282 -0.1736348 0.1050040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 946 1446 -0.173752 -0.915592 0.119151 0.5034133 0.2650802 -0.6369786 0.5201594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 947 972 0.895051 -0.071062 0.388051 -0.7574264 -0.0741573 0.3693896 0.5332516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 947 1447 -0.443000 0.321461 1.150121 0.0429630 -0.0192902 0.5516543 0.8327423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 948 971 -0.850344 -0.231198 -0.341719 -0.3029973 -0.2452974 -0.6618557 0.6402881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 949 970 -0.367989 0.037563 -1.180622 0.8262124 -0.2998992 -0.1484728 0.4531990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 949 1449 -0.221491 -1.041669 0.078339 0.1106348 0.1500835 0.0910833 0.9782324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 950 969 0.634276 0.582316 -0.490387 0.0490398 0.2485179 -0.2687292 0.9293108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 951 968 -0.792923 0.045172 0.662497 0.0917491 -0.8593839 0.4929096 0.1004068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 952 967 0.389453 -0.879299 0.035799 0.4226692 0.3472410 -0.0531189 0.8354357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 952 1452 0.153728 0.134750 0.930745 -0.2441564 -0.5417788 -0.7493699 0.2920757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 953 1453 0.252063 -0.976453 -0.130248 0.4776527 0.7229093 -0.3766236 0.3277267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 954 925 0.629440 -0.361971 -0.584586 -0.0265457 0.0587607 -0.1751559 0.9824271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 954 1454 0.634742 -0.292179 0.563579 0.4466494 0.1380477 0.8346479 0.2912217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 955 964 0.227455 -0.757855 0.666316 -0.5990379 0.6917724 0.0521367 0.3998578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 955 1455 0.528681 0.601981 0.351457 -0.7252340 -0.6092879 -0.3196752 0.0247305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 956 963 -0.790873 -0.070523 0.390907 0.6724298 0.2435645 -0.5726285 0.4007631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 957 657 -0.290877 0.835919 -0.249229 0.1579795 0.8003820 -0.0379786 0.5770518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 957 962 0.288410 0.085985 -0.947129 0.3389371 0.5569529 -0.7571200 0.0411621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 958 658 0.257454 -0.384099 -0.666827 -0.3922894 -0.3918849 -0.4228590 0.7167465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 959 659 0.701885 -0.397987 -0.660584 -0.2787589 0.7098097 0.6460473 0.0329630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 959 1459 -0.680318 0.164152 0.709103 0.3662008 -0.1383501 -0.6525690 0.6487757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 960 999 -0.625496 -0.677514 -0.205362 -0.2377628 0.5050867 0.7925741 0.2453214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 960 1420 -0.822008 0.462881 0.435370 -0.4974375 -0.7888011 0.0361681 0.3592222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 961 958 0.536437 0.218040 -0.768117 -0.5971823 0.2379934 0.1299639 0.7548787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 961 998 -0.441563 -0.198940 0.653569 -0.4814443 -0.3062005 0.7480484 0.3389341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 961 1421 -0.366325 1.009638 0.086958 -0.2190553 0.8434196 0.4905397 0.0053842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 962 1422 -0.775330 0.239949 0.755134 -0.1148892 -0.5746129 0.5544323 0.5909528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 963 996 -0.534992 -0.394799 0.518469 -0.3052712 0.1448458 0.5168421 0.7865770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 963 1423 -0.128032 0.891238 0.427413 0.2340804 -0.3320919 -0.2617816 0.8754380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 964 1424 -0.811686 -0.364749 0.511741 0.3388673 0.0169100 -0.3172275 0.8855787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 965 625 0.024647 -0.681355 -0.643299 -0.1027880 -0.2016342 -0.3220672 0.9192666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 965 994 0.379747 0.503170 -0.753748 -0.2515002 -0.3735275 -0.7634952 0.4629254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 965 1425 -0.085784 0.904859 0.235953 0.0468085 -0.6178705 -0.7255160 0.2994519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 966 953 -0.340264 0.946510 -0.138466 -0.3209230 0.1315085 0.7585456 0.5516543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 966 993 0.680813 -0.851631 0.009797 -0.4166118 0.0044530 0.5218162 0.7443941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 966 1426 0.753724 0.779899 0.061273 0.5704988 0.4238717 0.5609647 0.4244791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 967 1427 -0.349669 0.924283 0.409821 -0.2151296 -0.9091953 -0.2794935 0.2212839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 968 991 1.025210 -0.331657 -0.286059 0.5265302 -0.1589198 0.8073763 0.2136676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 968 1428 0.041415 -0.881732 0.637727 0.5557021 0.3291208 0.1564672 0.7472567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 969 629 -0.757419 0.302774 -0.486709 -0.6049778 0.3182846 -0.3442209 0.6435905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 969 990 0.389551 0.837891 -0.275009 -0.0222697 0.8704350 -0.1048282 0.4804769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 969 1429 0.799874 -0.046906 0.734456 0.5000580 0.7679594 0.2399942 0.3202862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 970 989 -0.286026 -0.537694 0.717310 -0.2924216 0.5635240 0.4688390 0.6141011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 970 1430 0.178449 0.607332 0.873937 -0.1431862 0.6653243 -0.0376934 0.7317243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 971 988 0.016150 -0.836451 -0.294306 0.2715092 -0.4634019 0.6364145 0.5536407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 972 987 0.285415 -0.628307 -0.631841 -0.5174710 -0.3679531 0.5051612 0.5845054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 972 1432 -0.679634 -0.742673 0.172527 0.0878497 -0.2416566 0.3124022 0.9144886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 973 986 -0.656360 -0.646432 -0.040588 0.2746470 -0.3316840 -0.8684988 0.2454883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 974 985 -0.836992 -0.430560 -0.218536 -0.3258294 -0.3254158 0.6499544 0.6045652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 974 1434 -0.368040 0.890606 0.591484 -0.7434146 0.4644808 0.4085638 0.2542989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 975 635 0.479109 0.542975 -0.474831 0.7001756 0.1025075 -0.1749449 0.6845734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 976 983 -0.616839 0.588963 -0.061299 0.2730719 -0.1932921 0.8922784 0.3031653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 976 1436 -0.239169 -0.537847 0.915724 -0.4684131 -0.1568527 0.8691346 0.0243218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 977 942 0.338815 0.495103 0.659511 0.7735274 -0.0276334 -0.3891430 0.4994593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 977 982 -0.342336 -0.377726 -0.728266 0.4875851 -0.0645079 -0.4298029 0.7572113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 978 941 -0.840705 -0.265421 0.600081 -0.0517769 -0.2713429 0.9420173 0.1905137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 978 981 0.923815 0.086923 -0.419043 0.6685502 0.6054248 -0.4076114 0.1426692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 980 1019 -0.359003 -0.792889 -0.608332 0.5419990 0.4129955 -0.7196844 0.1331393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 981 1018 0.479715 0.851307 -0.118827 -0.6317130 0.3894798 0.5731410 0.3474961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 981 1401 -0.969795 0.425714 0.463219 0.6918583 0.1736316 -0.6062496 0.3516328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 982 602 0.552477 0.116373 -0.839990 0.5132068 -0.2986494 -0.7997128 0.0888076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 982 1017 0.505014 -0.931182 -0.024415 0.3936730 -0.6661652 -0.4005012 0.4907589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 984 975 -0.560814 0.179992 0.718646 0.2068390 0.1873988 0.9598897 0.0266673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 984 1404 0.663197 0.544456 0.218456 -0.6973153 -0.3708506 -0.5402968 0.2903458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 985 1014 -0.364240 0.625813 0.671651 0.1082813 0.5705313 -0.6608908 0.4753867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 985 1405 0.910777 0.105228 0.586942 -0.5325734 0.6095339 -0.0340792 0.5862360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 986 1013 0.739151 0.102165 0.318300 0.2310591 0.5541098 -0.7959061 0.0781500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 986 1406 -0.007026 -0.440372 0.714686 0.6466671 0.4231953 0.0508900 0.6325643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 987 1012 -0.567408 0.692472 -0.697248 0.4218508 -0.7125120 0.1929906 0.5264249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 987 1407 -0.851408 0.013240 0.669998 -0.1113236 -0.9025336 0.1348374 0.3935214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 988 1011 -0.746546 0.373214 0.530586 -0.3387609 0.2360807 0.3048625 0.8582341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 988 1408 0.548911 -0.021831 0.631764 -0.7808709 0.3028805 -0.3761149 0.3962847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 989 1010 -0.719070 0.156879 -0.506124 -0.4643552 -0.3108208 0.0761300 0.8258140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 989 1409 -0.582629 0.275994 0.863660 -0.3385568 0.0510529 0.4460692 0.8269191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 990 1410 -0.778366 -0.339375 0.546502 0.6350971 -0.0460375 -0.4272245 0.6418812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 991 1411 0.502023 0.589495 0.688097 -0.7312744 0.1377401 -0.4886443 0.4555131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 992 967 0.402276 0.666162 0.699301 0.8473370 -0.0287184 -0.1620086 0.5049242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 992 1007 -0.339307 -0.613039 -0.773191 -0.2813812 -0.6477432 0.5066283 0.4945514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 992 1412 -0.474661 -0.889915 0.702601 0.2229988 0.3756149 0.5976189 0.6723367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 993 1006 -0.247749 -0.651513 -0.738391 0.6606749 0.2062482 -0.0740249 0.7179768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 993 1413 0.784946 -0.604086 0.167580 0.8171386 -0.3871843 0.3666631 0.2189317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 994 1005 -0.926453 0.160979 0.094542 -0.0290374 0.1676379 -0.2927905 0.9409188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 994 1414 -0.024934 -0.235726 0.832255 0.0784766 0.4874073 -0.6849405 0.5358471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 995 964 0.908605 -0.431260 -0.560163 -0.5998268 0.2564203 -0.6119275 0.4472148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 995 1004 -0.800494 0.051110 0.510240 -0.7327948 0.5040743 -0.2411252 0.3883034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 995 1415 0.416630 1.209732 0.033060 -0.0891334 -0.7591836 -0.4828354 0.4272768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 996 1003 -0.814701 0.203809 0.333510 -0.5028085 0.2126955 0.6428915 0.5372474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 996 1416 0.458485 0.228137 0.800002 -0.3252958 -0.2879290 0.1122084 0.8936939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 997 1002 0.555617 0.716428 0.382448 -0.0626543 0.4631132 -0.3968224 0.7900206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 997 1417 -0.283093 -0.401498 0.881062 0.7695737 -0.3580485 0.1269388 0.5132681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 998 1418 0.795449 -0.539066 -0.110051 -0.5170403 0.0486894 -0.8481221 0.1048215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 999 1419 0.219079 0.657532 0.582532 0.1239947 0.6174088 -0.0261881 0.7763671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1000 1039 0.528180 -0.488964 -0.578949 0.6246039 -0.3011304 0.0459413 0.7190826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1001 998 -0.791743 -0.327647 0.340287 0.5673718 0.2486974 0.7649961 0.1761244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1001 1381 -0.211406 0.781448 0.556791 -0.2279088 -0.3254057 -0.6407769 0.6569426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1002 1037 -0.617672 0.774892 0.636916 -0.2100801 -0.1678550 0.0032744 0.9631616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1003 583 0.617243 0.681783 -0.608475 0.4096103 0.7220862 -0.3411652 0.4409276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1003 1036 -0.060733 0.717339 0.850440 0.1871878 -0.3943608 0.1376778 0.8890923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1004 1035 -0.590266 -0.106659 -0.889197 -0.7356200 -0.5055707 0.4504103 0.0197983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1004 1384 -0.767121 -0.489316 0.454616 0.2774879 -0.4141606 0.7080698 0.5001087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1005 1034 -0.832961 -0.675261 -0.389976 0.3632639 0.0230286 -0.8637084 0.3485927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1005 1385 -0.293581 -0.370187 0.912830 -0.3711756 -0.2377140 0.5549109 0.7055456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1006 1033 -0.068703 -1.066294 0.416756 0.6386860 0.2409175 0.4512964 0.5747786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1006 1386 0.750041 0.294247 0.655117 -0.5135240 0.3475121 -0.5416749 0.5675533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1007 587 0.222659 0.808301 -0.497256 0.3686182 -0.4618990 -0.1093804 0.7992534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1007 1032 -0.583114 0.432682 0.541349 0.1769041 -0.6905995 0.0110240 0.7011817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1007 1387 -0.166051 -0.897992 0.484149 0.0232922 -0.0825987 0.7427319 0.6640664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1008 588 0.475114 0.815128 -0.015965 0.4138442 0.0175864 -0.7983109 0.4371767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1008 991 0.890441 -0.503432 -0.297268 0.7362378 -0.1922476 -0.5844387 0.2818266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1008 1388 -0.457899 -0.792695 0.168803 0.9611117 -0.0854860 0.2469043 0.0894132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1009 990 -0.279980 -0.465120 0.879282 -0.2548847 0.8025196 -0.3855595 0.3772798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1009 1030 0.204171 0.447239 -1.054435 -0.2821046 0.2982714 0.7573603 0.5077958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1009 1389 1.031076 0.280655 0.462598 -0.4928635 0.5525500 -0.5806140 0.3386170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1010 1390 0.186750 -0.638677 0.692489 -0.4354967 -0.2968113 0.5961620 0.6056703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1011 1028 -0.876013 0.394461 0.808054 0.5854963 -0.1704755 -0.7497372 0.2569559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1012 1027 -0.929250 0.711364 -0.016006 -0.4659716 -0.2499085 -0.2545515 0.8097035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1012 1392 0.640601 0.750718 0.447117 -0.4146250 -0.3602414 -0.6286970 0.5505020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1013 593 0.277682 0.510797 -0.894126 0.6380604 -0.3448962 0.5427602 0.4234818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1013 1026 -0.985131 -0.015124 -0.478055 -0.5326521 -0.1698781 0.2731627 0.7828188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1013 1393 -0.334025 -0.612302 0.856727 0.3781974 -0.4822364 0.4302234 0.6628141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1014 1394 -0.824823 0.178553 0.546255 0.3373165 -0.5168565 -0.7436882 0.2569140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1015 595 0.181737 0.929444 -0.460717 0.4096206 0.3803012 0.1429796 0.8167856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1015 1024 -0.102317 0.288479 0.982637 0.8802463 0.3543032 -0.0165717 0.3152158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1015 1395 0.062743 -0.809001 0.469371 0.3971368 -0.2493794 -0.6050439 0.6434393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1016 1023 0.576680 0.378915 -0.665623 0.1910218 -0.6885627 0.6937689 0.0898709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1016 1396 0.555320 0.086873 0.667708 -0.6940040 0.0913625 -0.0436037 0.7128184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1017 1022 0.806780 -0.205870 -0.619858 -0.4760960 -0.7693163 -0.4238444 0.0429057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1017 1397 0.434759 0.836455 0.379182 -0.2005858 0.0143542 0.5709124 0.7960015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1018 1021 0.166022 -0.847167 0.644645 -0.1918661 -0.5528859 0.3856684 0.7132773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1019 599 0.272695 0.576635 -0.441452 0.6153693 0.2073342 -0.5830185 0.4882854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1020 1059 -0.365922 -0.215912 0.687257 0.2115516 0.0730922 0.6977226 0.6805047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1021 1058 -0.216204 -0.993316 0.202548 -0.2218232 0.8857478 -0.4017743 0.0694467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1022 1057 -1.012556 0.230625 0.516076 -0.7811873 0.0557774 0.1023947 0.6133111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1022 1362 0.476678 0.612622 0.367793 0.1845736 -0.1872498 -0.5625391 0.7838493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1023 1056 -0.934417 0.215136 -0.413917 0.5528626 0.1977341 -0.5584827 0.5859533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1023 1363 -0.449892 -0.890857 0.112769 0.7223107 -0.5188654 0.0412691 0.4553492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1024 564 0.888880 -0.629371 -0.113456 -0.6674637 -0.4543967 0.5705120 0.1501064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1024 1055 -0.057536 0.307123 -1.006357 -0.3072225 0.9214232 0.2136554 0.1046182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1025 1014 -1.058885 -0.065154 0.110014 0.4800391 -0.6421275 -0.5763104 0.1584333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1025 1054 1.025730 0.091368 -0.350951 -0.5869018 -0.1687615 -0.1973310 0.7668939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1025 1365 0.084804 0.762673 0.172683 0.1386285 -0.8907087 -0.3779997 0.2110366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1026 1366 -0.706398 -0.868259 0.094554 -0.0692209 0.0394774 0.9769732 0.1979228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1027 1367 0.622398 0.542618 0.699937 0.2872234 -0.0142264 0.9563940 0.0510957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1028 1051 -0.512426 -0.131500 0.633434 0.2945265 -0.6690133 -0.6790333 0.0677428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1028 1368 0.164518 1.072335 0.329818 -0.7333475 0.0968230 0.3373791 0.5822388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1029 569 0.570588 0.861607 -0.323450 -0.2372086 -0.2498079 0.5799961 0.7381956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1029 1010 0.764032 -0.758807 0.234936 0.1638858 -0.3444588 -0.2097746 0.9002690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1029 1050 -0.729904 0.715194 -0.066818 0.1670721 0.3579351 -0.7611421 0.5144240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1029 1369 -0.671361 -0.594189 0.166324 0.0447273 -0.3845688 0.6936072 0.6074663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1030 1370 -0.366719 -0.824230 0.433203 -0.0907458 -0.7205846 0.6583270 0.1978092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1031 1008 0.776181 0.564611 -0.356286 0.0279654 0.1044148 0.5391416 0.8352496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1031 1371 0.411626 -0.651287 0.013157 -0.4181040 0.4390629 -0.7105817 0.3570526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1032 1047 0.478301 0.627651 0.490550 0.2908732 0.1745838 -0.0855862 0.9367968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1033 1046 -0.582976 0.773543 0.248756 -0.1209993 0.1607931 0.9601190 0.1941038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1033 1373 0.751978 0.246419 0.557761 -0.7399962 0.3218693 -0.0947278 0.5829515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1034 1045 0.888893 -0.177555 0.334623 0.4166059 -0.0595596 0.4573026 0.7834325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1035 575 0.513522 0.619122 -0.341764 0.4273980 -0.2107696 -0.4769748 0.7385135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1035 1044 0.294425 0.434832 0.871219 0.0656419 -0.2035594 0.2027402 0.9555894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1035 1375 -0.727745 -0.815606 0.344399 -0.1966906 -0.1583714 -0.4359638 0.8638095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1036 1376 0.043116 -0.422323 0.811044 0.4651989 -0.2360431 0.3396789 0.7826186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1037 1042 -0.272597 0.087688 0.832115 -0.5872448 -0.6395804 0.4451778 0.2188543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1037 1377 -0.477709 -0.886420 0.220324 0.9103410 0.2616308 -0.2561497 0.1929145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1038 1001 -0.683847 -0.530750 -0.693781 0.7169434 -0.1322309 0.1275782 0.6724812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1038 1041 0.668745 0.320351 0.696837 0.0064971 -0.8348719 -0.0611695 0.5469963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1038 1378 -0.486353 -0.556916 0.834709 -0.0784595 -0.1852374 0.9244808 0.3238310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1039 579 -0.823955 -0.747195 -0.385089 0.2333813 0.6415595 0.6005098 0.4163204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1039 1379 0.902639 0.357019 0.347994 0.2152352 0.3159147 0.3690734 0.8471461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1040 1079 -0.270868 -0.120891 0.721029 -0.3020416 0.3453867 0.8757713 0.1500120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1040 1340 0.648513 0.758292 0.266848 -0.2046811 0.7646444 -0.0340188 0.6101371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1041 1078 0.439635 0.548222 -0.847586 -0.4405492 0.8069520 0.1056094 0.3789347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1041 1341 0.939628 -0.583212 0.212701 0.4938898 0.5731525 -0.5473298 0.3577697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1042 1077 0.180688 -0.871263 -0.347736 -0.7386938 -0.3682253 0.4778331 0.3006944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1042 1342 -0.744959 -0.345603 0.662437 0.4130195 -0.3672995 0.5719374 0.6061300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1043 1036 0.278246 0.875133 -0.238270 0.4172459 -0.1920278 -0.8629199 0.2107138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1043 1076 -0.322396 -0.952798 0.414152 -0.1232951 -0.1013334 -0.2558902 0.9534412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1044 1075 0.858789 -0.072743 0.627843 -0.2863831 -0.3852319 0.8583735 0.1810414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1044 1344 -0.729992 -0.307136 0.498981 -0.6088501 -0.1504202 0.1788746 0.7580760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1045 1345 0.318089 0.794060 0.579790 -0.5239354 0.5177489 0.6420286 0.2126666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1046 1073 0.643776 -0.429041 0.750771 0.3399165 -0.4916369 0.3255141 0.7326599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1046 1346 -0.658709 -0.675706 0.400644 0.9372788 -0.1420380 -0.2914306 0.1280695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1047 1072 0.182505 0.843824 0.179216 -0.0528125 -0.0291678 -0.6767107 0.7337729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1047 1347 0.716196 -0.246054 0.843673 0.0413503 0.3050870 -0.9474521 0.0868708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1048 548 0.452514 0.515344 -0.455162 0.7427785 0.1109109 -0.5315268 0.3917373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1048 1031 -0.805996 0.424505 -0.606302 -0.0288749 0.8644406 -0.4867045 0.1225866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1048 1071 0.721150 -0.422877 0.085054 0.6218493 -0.0666295 -0.6442421 0.4402455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1048 1348 -0.464359 -0.539150 0.401479 0.0772970 0.1146715 0.6795130 0.7205121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1049 1030 0.585468 0.155237 -0.812121 0.1957764 -0.8683707 0.4519308 0.0579869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1049 1070 -0.799107 -0.154312 0.860071 0.1497234 -0.1311401 0.5284852 0.8252809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1049 1349 0.644125 -0.752549 0.341450 -0.1936307 0.1207600 -0.6825565 0.6942916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1050 550 -0.767030 0.293911 -0.508286 0.7433949 0.2534206 0.1573406 0.5986534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1050 1350 0.466619 -0.397575 0.654271 0.3450046 0.1574170 0.7117611 0.5912595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1051 1068 0.214928 1.074259 0.296776 0.8268460 -0.2194034 -0.2438781 0.4568494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1051 1351 -0.727427 -0.150765 0.745899 0.7324872 0.4466873 -0.5126810 0.0330326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1052 1027 -1.014898 0.286157 0.210766 0.4376661 -0.4623198 0.7545985 0.1590282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1053 1026 0.403436 -0.855060 0.030773 -0.6401974 0.7090873 -0.0143535 0.2951889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1053 1066 -0.575992 0.985016 -0.203413 0.2062924 0.7406671 0.6341690 0.0817643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1053 1353 0.813604 0.500781 0.458367 0.0877687 -0.3694045 -0.9043223 0.1950338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1054 1065 0.741302 0.718918 -0.154710 0.0913206 0.3709971 0.3458051 0.8569951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1054 1354 0.151641 0.044554 0.904517 -0.1184182 -0.6852358 -0.4626955 0.5498563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1055 1064 -0.010601 -0.025898 0.909854 -0.5333281 0.7570841 0.3257511 0.1904494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1055 1355 0.123833 0.919933 0.282733 -0.2533600 0.3939292 -0.0702072 0.8807380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1056 1063 -0.008075 -0.993487 -0.308110 0.0565955 -0.0186790 -0.3105561 0.9486848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1056 1356 0.151721 -0.004402 0.982344 -0.0380468 0.2536078 0.7479880 0.6121679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1057 1357 0.318462 -0.793049 0.371691 -0.3212054 0.0012237 -0.2632568 0.9096821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1058 1061 0.846656 -0.439472 0.366309 -0.3778183 -0.6687669 0.4432485 0.4620984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1058 1358 -0.528843 -0.584759 0.099939 0.6681051 -0.5918486 0.4133835 0.1801800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1059 1359 0.665258 -0.187236 0.630027 0.6292554 0.1715268 -0.1040086 0.7508651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1061 1098 -0.665421 -0.409563 -0.687238 -0.2775259 -0.0157982 0.8702830 0.4066169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1062 1057 -0.087514 0.903301 -0.226012 -0.3194737 -0.6771931 0.5818411 0.3175013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1062 1097 0.429926 -1.022475 0.104111 -0.0518135 -0.7712858 0.3981879 0.4938421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1063 1096 0.483432 -1.001136 0.055291 0.2372557 -0.0667064 0.9498685 0.1923794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1063 1323 0.287234 0.047271 0.941858 0.4142007 -0.0444313 0.1352701 0.8989803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1064 524 0.991945 0.016847 -0.582273 0.2051712 -0.1727172 0.8337487 0.4826351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1064 1095 -0.559505 0.190864 -0.847782 -0.2265263 0.0452509 0.9727717 0.0187971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1064 1324 -0.891793 0.007255 0.454015 -0.5705279 -0.2189492 0.5901129 0.5275660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1065 525 0.520142 -0.355056 -0.709062 -0.1723457 0.2599734 -0.9453844 0.0946530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1065 1094 0.837090 0.346650 0.625602 -0.3565898 0.4841221 0.6409850 0.4770826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1065 1325 -0.575932 0.367116 0.615934 -0.5888660 0.0360479 0.6885854 0.4216486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1066 1326 -0.460036 0.699387 0.501235 0.1938141 -0.3109069 -0.8465505 0.3861673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1067 1052 0.817336 -0.166752 0.356706 0.1658016 0.4536362 -0.8502611 0.2092367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1067 1327 -0.286306 0.399645 0.801754 0.1861404 0.2701806 0.8845499 0.3315505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1068 1091 -0.545202 -0.302603 -0.835650 -0.9255947 0.0227232 0.1298082 0.3548351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1068 1328 -0.563576 0.626740 -0.025049 -0.7210530 -0.4535212 -0.3980174 0.3405631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1069 1050 0.823435 0.248112 -0.184048 -0.3247256 0.2422280 -0.4842242 0.7755036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1069 1090 -0.746171 -0.642113 0.076116 0.1465452 -0.1840323 0.8651324 0.4429476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1071 1088 0.037272 0.923151 -0.676445 0.2798611 -0.1330992 0.0556821 0.9491374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1072 532 -0.401941 -0.492258 -0.919805 -0.1151841 -0.4135369 -0.0917305 0.8985018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1072 1332 0.313764 0.399397 0.900412 0.2508424 0.6233325 0.1389569 0.7274790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1073 1086 0.827338 -0.599169 -0.204424 0.0864647 -0.1858840 -0.5026896 0.8398060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1073 1333 0.085575 0.257697 0.983945 0.1946671 -0.0711246 0.6750370 0.7080756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1074 534 0.236847 -0.833670 -0.522418 -0.3853377 -0.6030773 -0.0833020 0.6934504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1074 1045 -0.857165 -0.345857 0.128726 0.0694505 0.3829512 0.5151474 0.7636414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1074 1085 1.003241 0.405857 -0.052825 -0.1554064 0.1929789 -0.9579404 0.1447692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1074 1334 -0.304246 0.982050 0.671847 0.2806304 0.3368785 0.8664237 0.2388920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1075 1084 -0.719402 -0.550700 -0.091773 0.1867694 -0.3576045 0.7426939 0.5344548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1075 1335 0.174760 -0.266500 0.840608 -0.1416365 -0.0668265 0.0398972 0.9868544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1076 1083 0.111344 -1.024752 0.182933 -0.5750843 -0.4520622 -0.3527854 0.5834897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1077 1082 -0.478578 0.868064 0.078369 -0.0383396 0.3430091 -0.8534204 0.3905744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1077 1337 -0.750235 -0.455145 0.365768 0.7076702 -0.2269249 -0.1980039 0.6391419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1079 1339 -0.493180 -0.783457 0.459749 0.5466539 0.2117998 -0.2455073 0.7720340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1080 1119 -0.714213 0.603202 -0.768879 0.6368411 0.3012033 -0.0048879 0.7097085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1080 1300 -0.602717 -0.867175 0.111928 0.4098160 0.0728099 0.0957204 0.9042052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1081 1078 -0.830347 -0.279380 0.580089 -0.8542063 -0.2030894 -0.4424115 0.1826427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1081 1118 0.780424 0.466150 -0.471663 0.4972198 -0.1248730 -0.7711215 0.3775591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1081 1301 -0.403304 0.929953 -0.168074 -0.5449427 -0.7384447 0.0585955 0.3928148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1083 1116 0.032219 -0.145013 -1.069299 0.6153964 0.4325766 0.6011579 0.2697664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1083 1303 0.339369 -0.887010 0.107066 0.6670560 -0.3872548 0.2822201 0.5704575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1084 1115 -0.127478 0.768253 0.097658 0.2407224 0.5253495 -0.7740228 0.2587456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1084 1304 0.310237 -0.375591 0.730170 -0.1794455 -0.3318122 0.0242725 0.9258028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1085 1114 -1.036462 -0.122037 0.068551 0.2314978 0.9117348 -0.1401411 0.3090452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1086 1306 0.119885 0.571630 0.991208 -0.1280116 0.2562047 -0.9185539 0.2724533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1087 1072 -0.342327 -0.910924 0.620637 -0.4488343 -0.0097983 -0.7109781 0.5412596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1087 1112 0.495159 0.755038 -0.481717 -0.2772684 -0.0506586 -0.9322113 0.2270198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1087 1307 0.707256 0.170492 0.505497 0.1418196 -0.4498888 0.8079589 0.3531143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1088 1111 -0.149582 0.754652 -0.780246 0.0242716 -0.3829340 -0.0555134 0.9217867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1088 1308 0.206208 0.774120 0.609157 -0.0323136 0.4961974 0.7685055 0.4026702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1089 1110 -0.234048 0.902881 -0.246524 -0.2140929 -0.8532204 0.1090738 0.4629062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1089 1309 -0.791606 -0.138801 0.341807 0.3984058 -0.3019815 -0.0897759 0.8614060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1090 510 0.160180 0.245960 -1.024016 -0.0808498 -0.4878197 0.4487844 0.7443707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1090 1109 0.264861 0.917754 0.365736 0.5685336 -0.3983626 -0.6626607 0.2809939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1091 511 0.459125 0.401993 -0.690495 0.1016841 0.1255503 0.3281521 0.9307060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1091 1108 -0.315970 0.970272 0.440736 0.4454487 -0.4951975 0.2454406 0.7043534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1091 1311 -0.675123 -0.501603 0.656015 -0.1612706 -0.6211738 0.2794461 0.7141742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1092 1067 -0.301138 -1.001582 0.170101 -0.1150015 0.3299960 -0.7440844 0.5693994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1092 1107 0.396281 0.902947 -0.201681 -0.4947114 0.4756995 -0.7002772 0.1964241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1092 1312 0.751453 -0.181614 0.379312 0.0386642 0.7280095 -0.0080751 0.6844283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1093 1066 0.378157 0.730041 0.065181 0.2775928 0.4039476 -0.7369641 0.4654594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1093 1106 -0.230917 -0.758973 -0.361565 -0.2264770 -0.3254922 -0.8830090 0.2511136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1093 1313 0.616762 -0.482074 0.246793 0.1482472 -0.6660347 0.6693132 0.2940074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1094 1105 -0.617138 -0.722281 0.434211 0.2869762 -0.0015823 0.1641496 0.9437675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1094 1314 -0.476908 0.659266 0.707577 0.1096710 -0.0493349 -0.6870803 0.7165606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1095 1315 0.551899 0.236653 0.817199 -0.1493672 -0.3118401 -0.8565515 0.3830987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1096 516 -0.329190 0.342613 -0.884047 0.6055000 -0.2498664 0.1108144 0.7474334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1096 1103 -0.601647 0.501244 0.630320 0.4688607 0.0828121 -0.5233209 0.7067157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1096 1316 0.208740 -0.477152 1.004567 0.3659556 0.6198679 0.3685386 0.5882343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1097 1102 -0.377901 -0.842243 0.182392 -0.8501590 0.0785038 -0.5099921 0.1047607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1097 1317 0.763294 -0.385905 0.582740 -0.1807721 0.2541769 0.6873742 0.6559209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1098 1101 0.121654 0.816503 -0.410330 0.2709258 0.0176288 0.4946912 0.8255720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1099 1060 -0.461236 0.765410 -0.305864 0.0036525 0.1748425 -0.3878315 0.9049881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1099 1319 0.862795 0.608418 0.410424 -0.1775135 0.0357713 0.9256701 0.3321811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1100 1139 0.444874 0.263861 -0.776791 -0.4257770 -0.1819607 -0.8442966 0.2697545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1101 1138 0.761217 0.012092 -0.712641 0.0700413 0.8972351 0.3387571 0.2744213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1101 1281 0.336660 1.026359 0.408165 -0.2124285 -0.1111920 0.8517168 0.4659281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1102 1137 0.436212 0.590326 -0.516265 0.0724518 0.7255544 0.4872613 0.4805184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1102 1282 0.889046 -0.056213 0.489994 0.6295674 -0.0301048 0.5663265 0.5310488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1103 1136 -0.929797 -0.368841 -0.189234 0.0190708 -0.0601786 0.9954238 0.0717382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1103 1283 -0.283843 0.748739 0.836831 -0.0812629 0.0756523 -0.9793604 0.1688975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1104 1135 0.334300 -0.915001 0.495719 -0.1704655 0.3374198 -0.6498682 0.6593638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1104 1284 -0.420203 -0.052516 0.767426 -0.1122582 -0.0463331 -0.8422921 0.5251622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1105 485 -0.070246 -1.019505 -0.111471 -0.5545252 -0.0002852 -0.5111582 0.6566727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1105 1134 -0.637262 -0.188912 0.653206 -0.8287293 -0.3035820 0.2491914 0.3986846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1105 1285 -0.142072 1.120678 0.280027 -0.5910930 -0.0474563 0.3516159 0.7243778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1106 486 0.200702 -0.976059 -0.265709 -0.3598914 0.4589156 0.7876994 0.1985051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1106 1133 0.429288 0.347483 -0.830934 -0.3292747 -0.5060508 -0.7797575 0.1657376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1106 1286 -0.412331 0.971966 0.311337 -0.6932762 0.0762610 0.7129736 0.0722567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1107 1132 -1.095587 -0.295399 -0.149581 -0.4748772 0.3483273 -0.7926604 0.1576364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1107 1287 -0.142777 -0.530824 0.882716 0.2457937 -0.0852766 -0.6038513 0.7534434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1108 1131 0.164958 0.746451 -0.651909 0.3034632 0.6207937 0.2752339 0.6684097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1108 1288 0.530958 0.258157 0.831656 0.4903638 0.2864854 -0.1664818 0.8060728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1109 1289 -0.397036 1.125737 0.236868 -0.8664514 0.1313376 0.4178549 0.2396030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1110 1129 0.392888 0.713943 0.408562 0.1352376 0.2670209 0.9278099 0.2226642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1110 1290 0.722478 -0.431842 0.275738 -0.0012308 0.8411222 -0.2447567 0.4822926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1112 1127 -0.912958 -0.568111 -0.164642 0.1424340 -0.1277320 0.9535676 0.2326067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1112 1292 -0.566282 0.489746 0.902973 0.2804154 0.0933353 -0.8080934 0.5095496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1113 1086 0.456671 -0.512599 0.790419 -0.2327051 -0.0612600 0.7318071 0.6376158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1113 1126 -0.317656 0.703135 -0.748259 -0.3987070 0.1581217 0.4177509 0.8009459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1113 1293 -0.787177 0.033474 0.299359 -0.7232877 0.0585478 0.3727581 0.5783412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1114 1125 0.639173 -0.592639 -0.593973 -0.2296394 0.1484344 0.9615621 0.0251245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1114 1294 -0.278258 -0.869534 0.316832 0.7949783 -0.4872109 -0.2305140 0.2783853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1115 1124 -0.390504 -0.628621 -0.692384 -0.7195890 -0.4864625 0.3055170 0.3901349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1116 1123 -0.489216 -0.842747 0.288747 -0.2747058 -0.5132289 0.3512110 0.7333374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1116 1296 -0.818613 0.601631 0.198107 -0.5905738 0.3141548 0.2952918 0.6821525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1117 1082 -0.483545 1.065926 -0.003024 -0.0798225 -0.7738874 -0.1129257 0.6180408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1117 1122 0.513852 -0.905415 -0.141562 -0.0484140 0.4320200 -0.8936660 0.1112472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1117 1297 -0.595429 -0.325214 0.856355 -0.1484814 0.2609711 -0.8996904 0.3168669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1118 498 0.532977 0.754009 -0.358554 0.0246057 -0.5149935 0.5676941 0.6417942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1118 1121 -0.209652 -0.204692 -0.991995 0.0090100 -0.4618519 0.3748288 0.8038128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1119 1299 -0.886339 -0.208845 0.419216 0.9113902 -0.0415711 -0.3258127 0.2479635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1120 1260 -0.219997 0.910922 0.344971 -0.2613821 -0.3352126 0.3299503 0.8428789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1121 1158 -0.866743 0.189250 -0.402787 -0.2025759 -0.3667184 0.1129206 0.9009604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1121 1261 -0.482738 -0.437505 0.860282 -0.0491493 0.2390328 -0.3675543 0.8974138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1122 1157 -0.230577 0.684445 0.772740 0.7471324 -0.1349729 -0.1752507 0.6267876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1122 1262 0.691763 -0.533385 0.383317 -0.2802714 0.3902784 0.5587778 0.6759424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1123 1156 -0.566461 -0.869867 0.386078 -0.5264459 -0.0370742 0.4873435 0.6956842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1123 1263 0.345857 0.370094 0.892797 -0.6875847 -0.0144602 -0.6576460 0.3074409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1124 1155 -0.595423 0.502436 0.684239 0.5353481 -0.4313273 -0.3990857 0.6067041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1124 1264 -0.392713 -0.917344 0.196494 0.8113785 -0.2217669 0.4366534 0.3190897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1125 1154 -0.344042 0.578755 -0.925629 0.0349073 -0.4228951 -0.5297547 0.7343712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1125 1265 0.377248 0.885576 0.182438 -0.5079687 -0.2192971 -0.7479935 0.3665818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1126 1153 0.730456 0.681099 0.183210 0.0358659 -0.7849784 -0.5568173 0.2692158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1126 1266 -0.626983 0.332738 0.629375 -0.0649710 0.1235422 -0.5712146 0.8088449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1127 1152 0.470256 0.838526 -0.256547 0.4918272 0.4910654 0.7061777 0.1351806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1128 1111 -0.812613 -0.017918 -0.558557 0.4825940 -0.3032253 -0.7944094 0.2099314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1128 1268 -0.477900 -0.838398 0.382457 0.6933075 0.3055892 -0.6457957 0.0942758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1129 1150 0.093269 -0.561246 0.978994 -0.3380433 -0.7337484 -0.3392976 0.4818892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1129 1269 -0.933836 0.315412 0.283627 -0.8667236 -0.2462692 0.1691774 0.3994003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1130 1109 0.045861 0.250346 -0.782898 0.6153590 0.5324834 -0.5022226 0.2925186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1130 1270 0.765882 -0.442753 0.047925 0.6421072 0.5721967 -0.2998605 0.4127625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1131 1148 1.111855 0.108369 0.113082 -0.7676757 0.4396441 0.4033608 0.2338530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1131 1271 -0.244764 0.723193 0.540721 -0.4884505 -0.0983475 0.7512485 0.4328620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1132 1147 0.819883 0.436204 -0.764490 0.5955231 -0.1907627 0.4911777 0.6063879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1132 1272 0.729740 0.086473 0.521935 0.6065395 -0.4495005 0.6138798 0.2306743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1133 1146 -1.014713 -0.483789 0.263879 -0.7150541 -0.2248620 -0.6618945 0.0055152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1133 1273 0.424151 -0.311754 0.740483 0.2168575 0.4247379 0.7744172 0.4157505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1134 1145 -0.738682 -0.641565 0.133802 0.3713098 -0.2232282 0.9006955 0.0323379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1134 1274 0.580809 -0.544292 0.433938 0.9495017 -0.0246030 0.1312306 0.2839363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1135 1144 0.695313 -0.070828 0.418746 -0.0382583 -0.9798876 0.1442744 0.1324444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1135 1275 -0.254679 -0.952173 0.248721 -0.1880851 -0.7600717 0.3817420 0.4911090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1136 1143 0.929568 0.465393 0.098389 -0.3163681 0.3818576 -0.8625392 0.1006088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1136 1276 0.384492 -0.628358 0.716030 0.1500622 -0.8942527 0.4209928 0.0236341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1137 1142 0.576779 -0.290935 0.762170 -0.2485301 -0.1023239 -0.6221149 0.7353473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1137 1277 -0.767339 0.184846 0.596842 0.3969183 0.5146892 -0.6355824 0.4166365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1138 1141 -0.552631 -0.508161 0.857428 0.0040269 -0.0230024 -0.4264754 0.9041976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1138 1278 -0.358227 0.772512 0.330527 -0.4756235 -0.2485106 0.7240730 0.4332933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1140 440 -0.192667 1.123043 -0.396282 -0.0166854 -0.1380764 0.3907955 0.9099095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1140 1179 -1.007201 -0.059179 0.339826 -0.3941169 0.6071619 -0.6162711 0.3102195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1140 1240 0.059147 -0.897798 0.266170 0.6805218 -0.4328563 -0.0411604 0.5897722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1141 1241 -0.850255 0.388713 0.558574 -0.8126451 -0.1385540 0.5400693 0.1695164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1142 442 0.209008 0.835652 -0.575336 0.0623250 -0.0848732 0.7650214 0.6353380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1142 1177 0.911901 0.323909 0.693178 -0.1486865 -0.3619241 0.9108331 0.1314777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1142 1242 0.058934 -0.817591 0.465898 0.8557174 -0.1093419 0.0094679 0.5056703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1143 1176 -0.921556 -0.131668 0.263058 0.2559354 -0.2205647 0.8365406 0.4313329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1143 1243 0.032002 0.098573 1.025897 -0.6657804 0.0488773 0.1786926 0.7227838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1144 1175 -0.393199 -0.265877 -0.577965 0.6942289 0.5306217 -0.1944753 0.4457198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1145 1174 0.581295 0.777865 -0.076882 0.1752669 0.0451907 -0.9539838 0.2390696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1145 1245 0.258492 0.229253 1.013271 0.4934175 0.0530282 0.2084011 0.8427907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1146 446 -0.552323 -0.681223 -0.124579 -0.7104474 0.6189701 0.2098779 0.2609441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1146 1173 -0.010731 0.184933 -0.984192 -0.2866460 -0.5718452 -0.6430603 0.4210708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1146 1246 0.627541 0.706923 0.276363 -0.0023040 0.2159807 0.3676108 0.9045493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1147 447 -0.686161 0.340341 -0.710078 0.1367556 -0.1845207 -0.9598276 0.1611861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1147 1172 -0.078411 -0.948594 -0.261800 -0.4067668 -0.0805644 -0.5348208 0.7362179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1149 1130 -0.446838 -0.365196 -0.883500 -0.3023407 0.0494272 -0.8579240 0.4124480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1149 1170 0.353554 0.390156 0.804163 0.7574779 0.3406146 -0.5315181 0.1664256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1150 1250 0.814772 -0.458611 0.581574 -0.1170059 0.7406236 -0.6594254 0.0542636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1151 1128 0.439884 -0.989740 0.117777 -0.6036196 -0.5648714 0.2891958 0.4826277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1151 1168 -0.507546 0.971770 -0.073813 -0.4121101 -0.0420090 0.7656434 0.4921287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1151 1251 -0.844204 -0.550086 0.505011 0.1086961 -0.0795952 0.9420199 0.3073245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1152 1167 0.087124 -0.533123 0.709538 -0.0595230 -0.7015655 -0.7072550 0.0636654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1152 1252 -0.134201 0.881013 0.438589 -0.0085015 -0.1046827 0.5359020 0.8377221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1153 453 -0.639507 -0.606200 -0.583151 -0.0852989 -0.6740915 -0.7308657 0.0644985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1153 1166 -0.680232 0.643560 0.326539 0.4358622 -0.0614844 0.8915768 0.1064641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1153 1253 0.699141 0.551195 0.465586 0.1859662 0.0771007 0.9790238 0.0313756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1154 454 0.399189 -0.868186 -0.322247 -0.4384090 -0.0663459 0.0308623 0.8957920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1154 1165 -0.845877 -0.434220 -0.137584 -0.7173392 -0.4103888 -0.4969082 0.2647410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1154 1254 -0.483374 0.786262 0.087003 -0.2935850 -0.6248517 -0.6999852 0.1827263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1155 1255 0.674569 0.136101 0.777273 0.6511935 0.4523089 0.3066601 0.5266149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1156 1163 -1.005604 -0.095050 0.014622 0.2382753 0.8586451 -0.2372415 0.3868720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1156 1256 -0.066754 -1.150877 0.316002 0.4127430 -0.6879278 0.3217243 0.5028836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1157 1162 -0.433321 0.717403 -0.564159 0.6525449 0.7240364 0.1847413 0.1258058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1157 1257 0.730250 0.683957 0.233190 0.5143200 0.5880050 0.5116989 0.3576162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1158 458 -0.345983 0.575706 -0.619449 -0.3923291 0.4221315 -0.2883440 0.7646834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1158 1161 -0.846744 0.311216 0.411793 0.1993423 0.0400071 -0.6408910 0.7402167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1159 1120 -0.363979 0.199753 1.030395 0.4320103 -0.1565348 0.8546616 0.2416973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1160 1220 -0.801530 -0.063759 0.729191 0.5411705 -0.5078341 -0.6131276 0.2707647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1161 1198 -0.694632 -0.592162 0.429234 0.0330151 0.1474775 -0.7277513 0.6689831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1162 1197 0.627769 -0.520308 0.507763 -0.4639101 -0.5911045 -0.3805513 0.5390394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1163 1223 -0.706214 -0.626401 0.305552 0.1621114 -0.1262289 -0.7661441 0.6089412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1164 1155 -0.091729 -0.642571 0.699372 -0.1322175 -0.7534416 -0.1283752 0.6311609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1164 1195 0.131162 0.636315 -0.653861 0.1798302 -0.5617519 -0.0404376 0.8065115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1165 1194 -0.551250 -0.408359 -0.702089 0.3029836 -0.8358109 0.3842188 0.2489918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1165 1225 0.392343 -0.741075 0.307772 -0.0552596 -0.1060400 -0.8636561 0.4896938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1166 1193 0.491968 -0.449758 -0.735559 0.0630795 -0.0036667 0.9940033 0.0892464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1166 1226 0.139507 -0.714142 0.705424 0.0230921 0.3991898 -0.2474560 0.8825417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1167 1192 -0.366231 0.871438 -0.587116 0.0088194 0.6882592 0.6735716 0.2693006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1168 1191 0.989206 0.181161 0.502963 -0.7880706 0.1150710 0.5836001 0.1584749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1168 1228 -0.426532 0.532036 0.523636 -0.7017315 -0.2718110 0.6521570 0.0915587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1169 1150 0.282477 -0.269170 -0.696658 0.4685180 -0.7598693 0.3629830 0.2670822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1169 1190 -0.399223 0.501779 0.843055 -0.1229150 0.0313874 0.0971490 0.9871519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1170 1189 -0.420209 -0.318164 -0.800351 0.1624007 -0.1836625 -0.5555579 0.7945121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1170 1230 -0.609039 -0.442344 0.550771 0.4713466 -0.6592461 -0.5778770 0.0963596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1171 1188 0.727075 0.269411 0.534497 -0.8379500 -0.1395956 0.2819663 0.4459237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1171 1231 -0.685513 0.900914 -0.024172 -0.8050548 0.3760937 0.2394765 0.3912689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1172 1187 0.309960 0.061214 -0.723202 -0.4905493 0.5347193 -0.2444208 0.6431914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1172 1232 0.576714 0.293106 0.592841 0.8043070 0.2694241 0.3778707 0.3710993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1173 1186 -0.869231 -0.380551 0.227005 -0.5279740 -0.2947479 0.7792611 0.1646795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1173 1233 -0.270200 0.936405 0.919163 0.1512337 0.0768153 0.7832148 0.5981658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1174 1185 -0.832784 -0.353599 -0.485543 0.4905743 -0.5571914 -0.4997958 0.4461823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1174 1234 -0.489126 -0.215709 0.751330 0.2126336 0.1127224 0.8175531 0.5231515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1175 1184 0.033339 -0.969534 0.401364 0.4204924 -0.3699621 -0.1526939 0.8142473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1175 1235 -0.610344 0.399116 0.918803 -0.1458783 -0.4983862 0.2791794 0.8077064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1176 1183 0.586352 0.974325 -0.033341 -0.3756696 0.3336121 0.2915944 0.8139705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1176 1236 0.686017 -0.480685 0.704774 0.3311457 0.6021535 -0.3348668 0.6446843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1177 1182 -0.499314 -0.891055 -0.306627 -0.3727254 -0.4090824 0.3942508 0.7336850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1177 1237 -0.514308 0.179331 0.874605 -0.0349674 0.0401321 0.8612328 0.5054155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1178 438 0.742757 -0.038529 -0.751928 -0.4871703 -0.3747181 0.7518337 0.2387415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1178 1141 0.841812 -0.052668 0.573225 0.8218267 -0.1053595 -0.4690465 0.3057706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1178 1181 -0.926955 0.432074 -0.620189 -0.0320720 -0.1667708 0.8542815 0.4912861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1178 1238 -0.592263 -0.256458 0.736267 -0.1028646 -0.1320734 0.3165351 0.9336922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1179 1239 0.818445 -0.130758 0.701593 0.0553430 0.0159622 0.0103842 0.9982858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1180 1200 0.401773 0.843679 0.313706 -0.5658607 0.0309672 -0.3126011 0.7623144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1181 1201 0.362770 0.626026 1.026159 -0.0660661 0.0805234 0.4757550 0.8733891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1182 1202 0.424016 -0.384425 0.985996 0.0322712 0.0773787 -0.9454044 0.3149313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1183 1203 -0.171155 -0.945271 0.175803 0.8279904 -0.2141410 -0.2160500 0.4710604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1184 1204 -0.323350 0.966371 0.510667 0.0816860 -0.1624415 0.9416444 0.2832773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1185 1205 0.281764 0.980752 0.430681 0.1811098 0.4560870 0.8503720 0.1898718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1188 1208 0.090616 -0.403214 0.807735 0.6411655 0.4053311 0.5171891 0.3963949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1189 1209 0.370470 -0.791808 0.926960 0.2294982 -0.4601345 -0.7237040 0.4602818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1190 410 0.056843 0.938437 -0.355950 -0.5494457 0.5359831 -0.6329118 0.1012626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1190 1210 0.149738 -0.976922 0.141939 0.5259636 0.0435110 -0.8170025 0.2323275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1191 1211 -0.774623 -0.456942 0.568651 -0.3816157 -0.4229910 -0.3072205 0.7622753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1192 1212 -0.348479 0.747360 0.757392 -0.2069005 -0.2732540 0.7929888 0.5036796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1193 1213 -0.271507 0.662445 0.738894 -0.0660189 0.3965629 0.0314744 0.9150894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1194 1214 0.384429 -1.028215 0.379192 0.5877603 0.0040393 -0.3613087 0.7238629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1196 1216 -0.670891 0.656958 0.422782 -0.0275596 -0.3974031 -0.7983852 0.4515443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1197 1217 0.360721 0.814533 0.521636 0.2308714 -0.8215722 -0.5163399 0.0714884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1198 418 0.752704 -0.281661 -0.770895 0.5681560 -0.3289152 0.1903010 0.7299308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1198 1218 -0.762802 0.069644 0.868656 -0.1652957 0.0310542 0.0608335 0.9838761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1199 1160 -0.586100 -0.002095 0.685354 0.4332045 0.6972530 -0.0911697 0.5637909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1199 1219 0.462735 -0.713230 0.268411 -0.6509275 -0.0443876 -0.6544361 0.3821472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1200 1239 0.031854 -1.135777 0.076297 0.2296049 -0.2921802 0.7361019 0.5657441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1200 1980 0.028115 0.054720 1.124614 -0.0212472 0.3257159 -0.8624495 0.3868315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1201 1238 -1.005087 -0.177123 0.368669 0.0807643 0.0361067 -0.9118443 0.4008907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1202 1237 -0.780928 0.523022 -0.049058 -0.1824540 -0.3548197 -0.8957379 0.1961302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1202 1982 0.016823 0.409274 0.882023 -0.1797079 -0.5072928 0.3780408 0.7532889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1203 1236 0.003777 -0.647082 1.067548 -0.1429635 0.3164213 -0.4244489 0.8362309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1203 1983 0.375227 0.875406 0.570936 0.1826394 -0.2758521 0.8787965 0.3438969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1204 1235 0.499347 0.515769 -0.747349 -0.0605686 0.4266699 -0.4903504 0.7575227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1204 1984 0.620150 -0.808647 0.139131 -0.4567694 0.5020161 -0.6219214 0.3905834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1205 1234 0.308206 -0.870842 -0.306866 0.5359912 0.0950994 0.1566954 0.8240850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1205 1985 0.368654 -0.084860 0.906387 -0.1046718 0.2134766 0.1732000 0.9557580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1206 1186 1.013166 0.141151 -0.551635 0.0121817 0.2699626 -0.7436572 0.6115111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1207 1187 0.505194 -0.710918 -0.140904 0.3719246 -0.2504122 -0.8490716 0.2793621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1208 1231 0.606859 0.210831 -0.777475 -0.5320355 0.0047749 -0.4328846 0.7276856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1208 1988 -0.062785 1.012402 -0.030942 -0.7884451 -0.2344818 -0.1545781 0.5472460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1209 1989 0.540503 0.797414 0.120213 -0.6798083 0.2988653 -0.5929303 0.3114063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1210 1229 0.851652 0.057789 -0.541779 -0.2275395 0.0626594 0.9703370 0.0524000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1210 1990 0.210152 0.752384 0.450075 -0.1522091 -0.8286095 -0.4247284 0.3314280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1211 1228 1.013464 -0.115214 0.212975 0.0812941 0.2587553 0.1722747 0.9469733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1211 1991 -0.026620 -0.965455 0.108485 0.5706267 -0.5152932 0.1971499 0.6082680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1212 1227 0.576709 0.680024 -0.021206 -0.0755752 0.9308218 -0.0600958 0.3524879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1213 1226 -0.013266 -0.621057 0.858944 -0.6837616 -0.1180837 0.6847059 0.2229444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1213 1993 -0.610131 0.533650 0.579616 -0.5245015 -0.6682299 0.3216576 0.4182145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1214 1225 0.671974 -0.844486 0.068248 0.6074120 0.4455102 0.4452389 0.4840802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1215 1195 0.867941 -0.536627 -0.231428 -0.3639810 -0.0434577 0.5234694 0.7691613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1215 1224 0.403201 0.832293 0.103616 -0.3787441 0.4466191 0.3719012 0.7202595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1215 1995 -1.010695 0.557404 0.066605 0.1972749 0.0621665 -0.7393242 0.6407945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1216 1223 -0.614305 0.774551 0.269428 -0.2419966 -0.1617101 -0.4941565 0.8192050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1216 1996 0.083676 -0.361724 0.938530 -0.0425436 0.0225149 0.4890872 0.8709057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1217 1222 0.189169 0.567726 -0.704191 -0.2536543 -0.5509525 -0.7737487 0.1828215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1217 1997 -0.653751 0.816761 0.270526 0.0928923 -0.1561209 0.5644432 0.8052336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1218 1998 -0.525158 -0.091320 0.908599 0.4907796 0.2274990 -0.7458084 0.3887795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1220 1259 0.411848 -0.588488 0.591956 -0.3571288 0.4248980 -0.6183303 0.5564067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1220 1960 -0.236360 0.725968 0.611080 0.3811998 0.0466319 0.9130058 0.1375957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1221 1161 -0.305280 -0.262366 -0.795896 0.4211665 0.1234050 0.6117899 0.6581057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1221 1218 0.703491 -0.753415 -0.428829 -0.0534641 0.4663544 0.1250667 0.8740786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1221 1258 -0.636840 0.593320 0.216184 -0.7442275 0.1402595 -0.4286047 0.4926974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1222 1257 -0.746260 -0.535026 0.564921 0.7214289 0.0739365 0.3088409 0.6153788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1222 1962 0.758113 -0.385906 0.566800 0.9515787 -0.0051063 0.3038157 0.0465612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1223 1256 -0.489997 -0.195703 0.665795 -0.5057658 0.2984273 -0.3074352 0.7487494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1224 1164 0.281794 -0.786185 -0.282624 -0.2422913 0.1747226 -0.2956405 0.9073939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1224 1255 0.051241 -0.261556 1.078017 -0.0888360 0.0437280 0.3361760 0.9365798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1225 1254 -0.713731 0.190299 0.836168 -0.2130813 0.2542074 0.5687483 0.7526622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1225 1965 0.453416 0.785060 0.114351 -0.9349106 -0.1267257 -0.2793691 0.1784258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1226 1253 -0.909246 0.029621 -0.149483 -0.0331075 -0.0434949 0.3437484 0.9374695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1227 1167 0.650761 0.401375 -0.082835 -0.3775706 -0.1183594 0.9110212 0.1160688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1227 1252 -0.573791 0.527487 0.292917 0.4371870 -0.7553362 0.2935387 0.3900894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1227 1967 -0.646848 -0.562751 0.341211 0.5171817 0.6365029 -0.5650450 0.0900629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1228 1251 0.514409 -0.088134 0.887094 0.3175478 -0.0786436 -0.8845529 0.3324828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1228 1968 -0.354910 -0.923010 0.254691 0.8743967 -0.0134198 0.2635755 0.4071589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1229 1169 0.381718 0.822315 -0.436915 0.0629438 0.2421522 -0.3576748 0.8997050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1229 1969 -0.620875 -0.700839 0.413442 0.8945643 0.1872387 -0.1731826 0.3670207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1230 1209 0.599026 -0.333998 0.435428 -0.2394196 -0.4353873 -0.0402708 0.8668878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1230 1249 -0.759207 0.428844 -0.513596 0.1804350 0.2979987 0.8103344 0.4711668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1230 1970 0.556026 1.069934 0.240438 -0.7303834 -0.4515827 -0.5010934 0.1073244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1231 1248 -0.095163 0.872127 0.243272 -0.1628305 0.4916990 -0.8535752 0.0559255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1232 1247 -0.012795 0.631627 -0.905067 0.5660064 0.4701421 0.5069641 0.4489884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1232 1972 0.956597 0.368089 0.405320 -0.1436531 0.2134982 0.6115157 0.7482184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1233 1206 -0.335844 0.973327 -0.283985 -0.0349685 0.5057303 0.8153532 0.2796661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1233 1246 0.155002 -1.013298 0.188599 0.5810403 0.1384879 0.4010281 0.6945428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1233 1973 0.721372 0.294931 0.451842 -0.7779059 -0.4520104 -0.3670192 0.2363174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1234 1245 0.203060 -0.629071 0.903516 0.2355915 0.5026172 0.3058029 0.7735355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1234 1974 -0.025360 1.083477 0.725249 -0.3932714 -0.2844256 0.5434839 0.6848831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1235 1244 0.100613 0.785318 -0.307215 -0.4452934 -0.3033104 -0.8220864 0.1840940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1235 1975 0.685666 0.127029 0.954496 0.5144493 -0.3595492 0.7157108 0.3063074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1236 1243 0.217852 -0.871972 0.459016 -0.3575722 0.0794314 -0.6960558 0.6175266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1236 1976 -0.734611 0.633346 0.798546 -0.0555625 -0.7623783 -0.6369068 0.1002094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1237 1242 0.432012 -0.963126 0.026637 0.4543833 0.4286426 0.4044294 0.6680106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1237 1977 0.376827 0.389298 0.823174 -0.6485862 0.0475247 0.0340798 0.7588913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1238 1978 -0.526640 0.077131 0.961755 -0.3168630 0.2775156 0.8971530 0.1330391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1239 1979 0.603937 0.033135 0.815570 -0.7750456 -0.2947253 -0.5321941 0.1709118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1240 1279 0.395247 -0.898068 -0.475099 -0.4316058 0.7599521 0.1522940 0.4615146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1240 1940 1.009577 0.084169 0.501987 0.3213035 0.1561247 0.8780049 0.3185853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1241 1238 -0.971446 0.218111 -0.284974 0.2743763 -0.1147537 0.3095497 0.9031767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1241 1278 0.834200 -0.237363 0.330821 -0.0734655 -0.5305946 -0.2138072 0.8169203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1242 1942 0.347492 0.732688 0.585305 0.4003787 0.1176316 0.3921150 0.8198204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1243 1276 0.848516 -0.135939 0.375032 0.0215129 0.0098901 0.1235122 0.9920605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1243 1943 -0.137224 -1.116524 0.251787 0.5714183 0.6181956 -0.4881293 0.2303153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1244 1144 -0.286900 -0.431162 -0.724475 0.3553040 -0.4257931 0.8145341 0.1702750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1244 1275 -0.094881 -0.804364 0.742546 -0.1319701 -0.1268803 0.9809876 0.0644096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1244 1944 0.410724 0.520995 0.738038 0.3954556 0.8003667 0.4279438 0.1410395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1245 1274 -0.811825 0.163666 0.445448 -0.4583908 -0.8482948 -0.1564992 0.2139670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1245 1945 0.158461 0.925109 0.505817 -0.2946782 -0.1963002 -0.8276624 0.4354377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1246 1946 0.758415 0.351615 0.476092 -0.0782394 0.5057380 0.8350861 0.2018389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1247 1147 -0.423334 -0.390325 -0.811983 -0.6617252 -0.0604009 -0.7415825 0.0923413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1247 1272 0.551379 -0.942830 -0.017172 -0.7115323 0.1145123 -0.4485257 0.5286147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1247 1947 0.608855 0.253116 0.754137 -0.6088217 0.2754493 0.6341773 0.3889510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1248 1148 -0.528109 0.459353 -0.151060 -0.0460755 -0.6481367 0.7334217 0.1997209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1248 1271 -0.368388 -0.510388 -0.719924 -0.6215758 0.7075621 -0.3327504 0.0477137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1248 1948 0.745068 -0.641253 0.158643 0.5432177 0.3277105 0.3044281 0.7105237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1249 1270 0.817754 -0.135286 -0.826161 0.7248944 0.3117038 -0.2127855 0.5762735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1249 1949 0.608775 -0.754182 0.670611 0.4625387 -0.2287021 0.8221609 0.2404263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1250 1229 -0.652409 0.809308 0.191343 -0.4432855 -0.5411346 0.2661457 0.6632027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1250 1269 0.496986 -0.721493 -0.221068 0.4342810 0.5306585 -0.4197988 0.5946179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1250 1950 -0.641887 -0.647392 0.374784 -0.0624930 -0.8484173 0.4553948 0.2624846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1251 1268 -0.728716 0.380065 0.135347 -0.0127884 -0.4522747 -0.8661766 0.2121844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1251 1951 0.615244 0.404627 0.635320 -0.5997755 -0.6658972 -0.2618706 0.3581538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1252 1267 0.161505 0.513038 -0.555582 -0.2848052 0.6300386 -0.5057118 0.5159388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1252 1952 0.933685 0.582598 0.597430 -0.4143574 -0.2679066 -0.3172381 0.8098728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1253 1266 -0.867543 0.542815 -0.030751 0.5127624 0.5437302 -0.6200115 0.2387844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1253 1953 -0.395739 -0.436878 0.684637 -0.0604375 0.2840450 -0.9343353 0.2065994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1254 1954 0.606719 -0.327644 0.751039 0.4228230 0.0777954 -0.7195364 0.5453768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1255 1955 0.172839 0.863103 0.396535 -0.1909950 0.1390692 -0.8586256 0.4549096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1256 1263 -0.382724 -0.877411 -0.450088 0.5040450 -0.3948259 0.3647612 0.6760181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1256 1956 0.735482 -0.549175 0.514808 -0.2401670 0.6151758 0.0257915 0.7504754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1257 1957 0.529591 0.396744 0.805064 0.1537292 0.0765505 0.9815683 0.0838512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1258 1158 -0.807864 0.597993 -0.101865 -0.2718606 0.7737813 -0.3080677 0.4821292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1258 1261 -0.649296 -0.567200 -0.203503 0.1974350 -0.7932051 0.5471238 0.1802793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1258 1958 0.571865 -0.785404 0.168364 -0.6016918 0.0247372 -0.5632443 0.5657835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1259 1159 0.665409 0.648269 -0.194779 0.2156319 0.4904806 -0.3305411 0.7769648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1259 1959 -0.716490 -0.637744 0.085408 0.1335435 0.4804776 -0.6959870 0.5166329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1260 1299 0.597114 -0.385400 -0.540444 0.0897301 -0.5425152 -0.8298376 0.0948435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1260 1920 0.814162 0.265601 0.583438 0.4438548 0.0567541 0.8845984 0.1313684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1261 1298 0.822850 0.379624 0.818620 0.4489753 0.1073216 -0.8689952 0.1781868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1261 1921 -0.523497 -0.569732 0.541428 0.7117008 0.2850004 0.2201675 0.6031443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1262 1297 0.448321 -0.421792 -0.753993 0.2156082 -0.5992065 -0.4399835 0.6331502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1263 1296 -0.533854 0.011310 0.895846 0.0306855 0.0149656 -0.9903106 0.1346079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1263 1923 0.852292 -0.521390 0.424467 -0.6382363 -0.2753872 -0.6570875 0.2916373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1264 1255 0.183177 0.341807 -1.111266 -0.0574901 0.0069994 0.1462897 0.9875451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1264 1295 -0.103021 -0.214892 1.049246 0.6072581 0.3848738 0.6932534 0.0500957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1264 1924 0.421125 0.963103 0.346016 0.4021921 -0.6344407 -0.4266331 0.5036970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1265 1294 0.831326 0.462481 0.321748 0.1197167 -0.5662018 -0.7377456 0.3475844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1265 1925 -0.009257 -0.452718 0.981844 0.1764633 -0.4587395 0.6079135 0.6235864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1266 1926 -0.729291 -0.540552 0.307961 0.4227930 -0.2891347 0.1844542 0.8388229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1267 1127 0.956484 0.358394 -0.618312 0.0528147 -0.1029539 -0.9390882 0.3236115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1267 1292 -0.254243 1.118183 -0.095780 0.3116553 -0.0386826 -0.2921097 0.9033530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1267 1927 -0.766824 -0.206414 0.405253 -0.4556174 -0.4726983 0.6822286 0.3217657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1268 1291 0.598105 -0.150748 0.813732 0.7417404 0.2461183 -0.5938454 0.1912969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1268 1928 -0.658305 0.392981 0.688344 -0.5658025 -0.0960776 -0.2776180 0.7704316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1269 1929 -0.503300 -0.817877 0.564947 0.1920669 0.6587585 -0.7171094 0.1220724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1270 1289 1.084923 -0.018662 0.207424 -0.8282894 0.1102394 0.3353925 0.4350814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1270 1930 -0.001933 0.860576 0.353997 -0.2233558 -0.5819913 0.2152682 0.7517033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1271 1288 0.322992 0.638901 0.671603 0.0943486 -0.1773532 -0.9628849 0.1802688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1271 1931 0.360874 -0.728536 0.659309 -0.2318653 0.6252704 -0.5432538 0.5100498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1272 1932 0.488839 -0.767579 0.672769 -0.0560677 0.5763059 -0.5318648 0.6179383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1273 1246 -0.038111 0.747932 -0.749709 -0.0155552 -0.1478129 0.8441163 0.5151476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1273 1933 -0.638569 0.380156 0.613315 -0.3035037 -0.0579460 0.8916466 0.3308990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1274 1285 0.627548 -0.654070 -0.244400 -0.7495801 0.0601628 -0.2173888 0.6222959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1274 1934 0.765037 0.630675 0.142512 -0.8581988 0.1375312 0.1103250 0.4820876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1275 1935 -0.401284 -0.916776 0.582748 -0.0329249 -0.7290479 0.5585481 0.3942451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1276 1283 0.906743 -0.310689 0.249380 0.0759535 0.9204289 -0.3557934 0.1430131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1276 1936 -0.371313 -1.054693 0.241055 0.7713403 -0.2293146 0.3053117 0.5091499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1277 1282 0.859695 -0.475833 -0.366783 0.1029761 0.4780777 -0.7207525 0.4912774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1277 1937 -0.327030 -0.887839 -0.085372 -0.0614824 -0.2917738 0.9443495 0.1388956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1278 1938 0.510930 -0.541031 0.438830 0.4157493 0.1070846 0.7835665 0.4491202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1279 1139 0.735320 0.754263 -0.333159 0.6960271 -0.4169365 -0.1888193 0.5532246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1279 1939 -0.740702 -0.662354 0.075626 -0.7145463 -0.2878681 0.6330705 0.0760085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1280 1100 -0.200168 -0.633262 -0.746901 0.1776756 0.0526144 0.6485994 0.7382289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1280 1319 0.299931 -0.809063 0.524465 -0.7281960 0.4611093 -0.2899782 0.4159584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1280 1900 0.208378 0.486100 0.715065 -0.5138842 -0.0567125 -0.1825358 0.8362939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1281 1278 -0.180310 -0.425997 -0.801123 0.5194308 -0.6607877 0.2419148 0.4847973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1281 1318 0.400551 0.442258 0.888995 -0.1760891 0.8265469 -0.2924111 0.4475584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1281 1901 0.250199 -0.826862 0.267174 0.6210488 -0.3432386 0.0762297 0.7004818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1282 1317 -0.151936 0.881893 0.542551 -0.2452283 -0.2590065 0.7474252 0.5604769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1282 1902 0.698747 -0.261604 0.672473 0.4311536 0.4578983 0.3215081 0.7078618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1283 1316 -0.992395 0.111473 0.243232 0.7293834 0.3286491 -0.5640758 0.2044706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1284 1275 0.659531 0.535907 0.426248 -0.1433391 -0.5903594 0.6934648 0.3873451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1284 1315 -0.676145 -0.561832 -0.083117 0.3936711 0.0645078 -0.7173554 0.5711944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1285 1314 0.800094 0.305717 -0.233848 0.1295160 0.3214796 -0.8876453 0.3032529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1285 1905 0.262976 -0.152194 0.883516 0.4199042 -0.1867082 -0.8778643 0.1348140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1286 1313 -0.578433 0.493469 0.453132 0.2046896 0.8220798 -0.2874285 0.4468464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1287 1272 -0.051339 -0.834677 0.241779 -0.2010844 -0.2332411 0.5734912 0.7591255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1287 1907 0.334835 0.398493 0.975865 -0.0738613 -0.4936459 -0.4969847 0.7098341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1288 1311 -0.642779 -0.024995 0.728980 -0.8424565 -0.1736493 0.2391260 0.4504794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1288 1908 0.002674 1.183694 0.014574 0.2690467 -0.2124686 -0.9331136 0.1084893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1290 1269 -0.549526 0.547238 -0.276764 0.2914111 0.4544977 -0.4636866 0.7024999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1290 1309 0.734615 -0.756875 0.220536 0.4529608 -0.1349098 0.1517888 0.8680933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1291 1308 -0.891067 0.447657 -0.455611 0.3924635 -0.5611562 0.1507906 0.7129785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1291 1911 -0.517350 -0.654233 0.372920 0.5550583 0.0112869 0.1892928 0.8099081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1292 1912 -0.515926 -0.283046 0.629943 -0.1768074 -0.0163330 -0.0227820 0.9838462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1293 1266 0.609433 0.417264 0.926256 0.2993156 0.2170657 -0.4107929 0.8333918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1293 1306 -0.512418 -0.633106 -0.787142 0.3440741 0.3162270 -0.7281127 0.5014632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1294 1305 -0.709203 0.502270 -0.173866 -0.9128382 0.3851458 0.0288560 0.1325012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1294 1914 0.557716 0.786683 0.184718 -0.6248483 0.4710252 0.2513124 0.5696859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1295 1115 -0.789471 0.346329 -0.532327 0.1328650 0.7855800 0.1238953 0.5914904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1295 1304 0.827429 0.823317 -0.305409 0.6476733 -0.4846763 0.3114216 0.4986229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1296 1303 0.363911 -0.058574 0.753480 -0.3144133 -0.5578756 -0.4339221 0.6337435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1296 1916 -0.527888 0.738824 0.591483 -0.6730923 0.2825870 -0.2842379 0.6215306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1297 1302 -0.254146 -0.826615 -0.423437 0.6298070 0.5221464 0.4488592 0.3594882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1297 1917 0.609427 -0.550031 0.438616 -0.0061324 0.7743989 -0.0843898 0.6270144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1298 1118 0.199577 -0.255716 -1.030563 -0.6651373 -0.1525539 0.7004040 0.2091745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1298 1301 -1.088464 -0.024060 -0.247464 -0.3699296 -0.4480951 -0.6069572 0.5421861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1298 1918 -0.098116 0.434725 0.899378 -0.2002630 -0.5809160 -0.4787719 0.6270636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1300 1339 0.460987 0.049021 0.790180 -0.1553278 -0.2610155 0.1664686 0.9381004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1300 1880 -0.747222 -0.253985 0.584258 0.7566262 -0.1586933 -0.2714147 0.5732951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1301 1338 -0.112641 -1.203064 -0.025759 0.4498279 0.5649778 0.5601882 0.4057637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1301 1881 0.801853 -0.048060 0.890985 -0.2591252 0.4277962 0.1126316 0.8585795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1302 1882 -0.220333 0.748189 0.581569 0.1304501 0.3037315 0.9028432 0.2749622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1303 1336 0.863969 0.522988 -0.123097 -0.1413071 0.3428643 -0.7864700 0.4939040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1303 1883 0.418927 -0.227613 1.050298 0.1663986 -0.2455970 0.5125333 0.8057935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1304 1335 -0.262543 -0.616353 -0.507187 -0.4418176 0.6629541 -0.4236330 0.4310733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1304 1884 0.729829 -0.523878 0.147360 0.1149825 0.0770621 0.8843725 0.4457867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1305 1085 0.166661 0.862214 -0.245866 -0.0299671 -0.9878853 0.1152879 0.0994652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1305 1334 -0.872384 0.192533 0.423374 0.3863777 -0.8154051 0.4263452 0.0636909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1305 1885 -0.098247 -0.982721 0.146237 -0.0933678 -0.5989585 0.3174003 0.7292381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1306 1333 1.081282 -0.287003 0.125789 0.1802807 -0.0891232 -0.5860355 0.7849320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1307 1292 -0.167002 -0.278623 -1.000508 0.5419613 0.5505928 -0.3470336 0.5316889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1307 1332 0.211223 0.355981 1.090852 0.1135922 -0.0741057 0.8665893 0.4802376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1307 1887 -0.219210 -0.764787 0.213679 0.5846134 0.7358875 -0.3413330 0.0137338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1308 1331 -0.688704 0.545500 -0.110240 0.0265278 -0.0924528 -0.8747333 0.4749636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1308 1888 0.048843 0.160349 1.066916 0.2222683 -0.3504625 0.7148555 0.5628094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1309 1330 0.646290 -0.382620 0.360273 0.0683658 0.4249766 0.5310191 0.7298902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1309 1889 -0.322786 0.421863 0.717478 -0.2986540 0.3484071 0.6718016 0.5814644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1310 1289 0.700459 -0.380062 0.505364 0.3967292 0.4188986 -0.5663619 0.5885270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1310 1329 -0.559299 0.347269 -0.527095 0.3468785 -0.7227965 0.2617416 0.5373377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1310 1890 -0.612928 -0.503899 0.506755 -0.5561572 0.1528668 0.7881955 0.2146363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1311 1328 -0.894580 -0.487325 -0.234093 -0.1680199 0.7321946 -0.6275943 0.2044154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1311 1891 0.200802 -0.878811 0.854215 -0.1271145 0.6405886 0.0370786 0.7563817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1312 1287 0.057977 0.855542 0.226003 0.0114725 0.0198441 0.9855770 0.1676678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1312 1327 -0.188019 -0.983293 -0.280708 0.3124593 -0.3583661 0.5596913 0.6787404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1312 1892 -0.376898 -0.134556 0.925646 -0.4369580 0.3208378 -0.1286829 0.8304045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1313 1326 0.218816 -0.365651 -0.691067 0.5622965 0.1086856 -0.1849737 0.7986206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1313 1893 -0.609907 -0.803304 0.056723 0.1795472 -0.0740804 0.6711066 0.7154655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1314 1325 -0.597573 0.569574 -0.376836 -0.3074365 -0.3094049 0.5778171 0.6898397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1314 1894 -0.639957 -0.273976 0.846811 -0.0490197 0.0117491 -0.8202894 0.5697231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1315 1324 0.639125 -0.677520 0.600212 -0.4808202 0.2882174 0.3981786 0.7260829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1315 1895 -0.129892 0.726486 0.538698 -0.8490284 0.1999728 0.4827451 0.0782228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1316 1323 -0.290054 -0.562679 0.791834 -0.1049026 0.7123373 0.6325069 0.2854927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1316 1896 -0.494154 0.600704 0.375815 0.3094772 -0.7381867 -0.0425863 0.5979052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1317 1322 0.759020 -0.376184 0.442484 -0.3513409 -0.3970963 0.8444823 0.0756557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1317 1897 -0.449060 -0.705075 0.378742 0.0012614 0.8752117 -0.3852327 0.2925725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1318 1098 -0.150436 0.849792 -0.400376 0.6487191 0.3418537 -0.3708986 0.5698542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1318 1321 -0.984008 -0.091325 -0.107024 -0.0890564 0.2161669 -0.6592102 0.7146906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1318 1898 -0.060230 -0.901838 0.515769 0.1907892 0.6614014 -0.1054111 0.7176602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1320 1060 0.198068 0.864517 -0.141916 0.5146479 0.1153119 -0.8466845 0.0704703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1320 1359 1.001796 -0.266648 0.465471 0.6823579 -0.3842976 0.6129058 0.1051166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1321 1358 0.147933 -0.580107 -0.609621 -0.7524306 -0.2868482 -0.5559298 0.2061756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1321 1861 0.571830 -0.020918 0.525383 -0.2011924 0.3247470 0.7358287 0.5591217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1322 1062 -0.059113 -0.358587 -1.093026 -0.3630960 0.3198876 0.3508156 0.8017242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1322 1357 -1.068767 0.363399 -0.091551 0.0325646 -0.5914037 0.6840170 0.4257957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1322 1862 -0.083652 0.407563 0.915864 -0.2973310 -0.1246495 0.4143061 0.8511212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1323 1356 -0.287091 0.613181 -0.659538 -0.1922516 0.7139483 0.5493074 0.3893309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1323 1863 0.322785 0.761851 0.491143 -0.4157494 -0.1714678 -0.8224168 0.3483988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1324 1355 -0.348170 -0.980540 -0.314248 -0.3047721 0.3080613 0.8972136 0.0849703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1324 1864 -0.342188 0.060358 0.965940 0.4203805 -0.1107549 0.8225871 0.3665570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1325 1354 0.422412 0.959629 0.246193 0.6221759 -0.0545555 0.7345731 0.2651850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1325 1865 -0.514480 -0.384046 0.957874 0.7487716 -0.2499134 -0.5461255 0.2804129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1326 1353 0.353234 -0.846365 0.122006 -0.6979312 0.0933198 0.7032619 0.0980106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1326 1866 -0.491766 -0.286608 0.751136 -0.0169125 0.0593859 -0.8302532 0.5539556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1327 1352 -0.745856 -0.212073 0.775521 -0.0261537 0.6093249 -0.0643646 0.7898711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1328 1351 0.959259 -0.001655 -0.031919 0.1827527 0.8769784 -0.0796469 0.4372261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1329 1069 -0.594506 -0.248454 -0.584561 0.2599618 0.0125775 0.7747588 0.5762035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1329 1869 0.649210 0.470647 0.777705 0.1194637 0.3194383 -0.3206452 0.8836709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1330 1070 -0.057423 -0.908274 -0.387656 -0.7806154 0.0263518 -0.3912701 0.4866753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1330 1349 -0.648016 -0.197248 0.884288 0.2007986 0.5166827 0.6172089 0.5583656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1330 1870 -0.114260 1.242183 0.408073 -0.1439103 0.2136987 -0.1252977 0.9580831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1331 1071 0.184576 -0.131585 -1.093617 0.1251774 0.0369074 -0.0212352 0.9912202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1331 1348 -0.216221 -1.106563 0.070407 0.3920672 -0.5062166 -0.7681319 0.0012258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1332 1347 0.380373 -0.206502 0.901075 0.0773899 -0.3189224 -0.7334832 0.5952324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1332 1872 -0.348525 1.110056 0.354859 0.4279597 -0.6463956 -0.5223969 0.3551405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1333 1346 0.369308 0.777678 -0.394459 0.1734093 0.6701427 0.7158796 0.0914022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1333 1873 0.703197 -0.022207 0.890231 0.2838771 0.1090105 -0.8468850 0.4362526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1334 1345 0.460924 0.639261 -0.575791 -0.1656068 0.7189080 0.3015715 0.6039870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1334 1874 0.925861 -0.100387 0.512921 0.0176667 -0.7141572 0.6833948 0.1504620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1335 1875 0.255023 -0.488526 0.802387 -0.1087149 -0.0852606 0.6384452 0.7571654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1336 1343 -0.828213 0.634285 0.233456 0.5442498 0.1962725 0.8036862 0.1391322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1336 1876 -0.061396 -0.431512 0.989120 0.7943632 0.1657310 -0.1232139 0.5712606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1337 1302 -0.992902 -0.088189 -0.247916 -0.2318137 0.6866489 0.6710811 0.1562876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1337 1342 0.964240 0.156657 0.181862 0.1576359 -0.4669366 -0.0732465 0.8670387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1337 1877 -0.173337 0.563924 0.874649 -0.3417728 -0.3369909 -0.4488691 0.7537540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1338 1078 0.072234 -0.611924 -0.896565 -0.5370214 0.2849376 -0.6893138 0.3940369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1338 1341 -0.859695 0.079783 -0.071098 0.2983038 -0.2376422 -0.3218983 0.8665579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1338 1878 -0.326049 0.781446 0.675870 -0.4732240 -0.3537483 0.6099360 0.5281092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1339 1879 -0.613282 -0.131908 0.883651 0.1151308 0.3255130 0.7249460 0.5960197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1340 1379 0.870774 0.360521 0.722364 -0.1599078 -0.6506306 0.0005836 0.7423671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1342 1377 0.753445 0.133510 -0.703349 -0.1762501 0.6902151 -0.0324108 0.7010624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1343 1376 0.499414 -0.424288 -0.481867 0.5914705 0.6304970 0.4564231 0.2105092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1343 1843 0.551612 0.884322 0.035690 -0.3712696 0.2095347 0.4066245 0.8080289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1344 1335 0.757948 -0.694121 -0.155335 -0.0770065 -0.8711234 0.3622598 0.3224622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1344 1375 -0.844860 0.458347 0.253629 0.1620172 0.5050644 -0.4151552 0.7391255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1344 1844 -0.496302 -0.902573 -0.060738 0.1262032 -0.9500499 -0.1311720 0.2535190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1345 1374 0.401747 -0.198683 0.787662 0.1481825 -0.2176764 -0.0348540 0.9640768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1345 1845 -0.826854 -0.440821 0.383273 0.2103495 0.2735349 -0.3562820 0.8683288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1346 1373 -0.050453 -0.298688 0.787414 -0.4587741 -0.3730662 -0.6897045 0.4179182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1347 1372 0.406467 0.767371 0.321365 0.2225988 0.6264587 -0.5715660 0.4809487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1347 1847 -0.374963 -0.152604 1.003463 -0.1274507 -0.3584581 0.5683302 0.7295648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1348 1848 -0.508308 0.744165 0.151761 -0.3576193 0.5897820 0.1392478 0.7105461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1349 1370 -0.107790 0.838289 -0.424432 0.0893340 0.2823617 0.7659496 0.5706247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1349 1849 0.726941 0.323482 0.451077 -0.0839159 0.4735769 -0.6188585 0.6210452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1350 1329 -0.885506 -0.347473 0.017745 -0.1430122 -0.4312071 -0.7990320 0.3938984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1350 1850 -0.303210 0.096312 1.070017 -0.7240323 -0.0395149 0.0383012 0.6875673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1351 1368 -0.533617 0.388496 0.665283 0.0088087 -0.8177063 0.2144693 0.5341177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1352 1052 0.444473 -0.211344 -0.857383 -0.7974401 -0.1840450 0.0755256 0.5696601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1352 1367 -0.752181 -0.355613 -0.359543 -0.3668961 -0.2429558 -0.2120247 0.8725854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1352 1852 -0.653565 0.408983 0.603339 0.1940063 -0.0779988 -0.8737092 0.4392151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1353 1366 0.116038 0.673943 -0.416673 0.4148103 -0.7023220 0.2474688 0.5229106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1353 1853 -0.688575 0.456651 0.448291 0.7599003 0.3280848 -0.5566485 0.0710940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1354 1365 0.556064 -0.793145 -0.035265 -0.1114231 0.2896100 -0.6170460 0.7231633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1354 1854 0.901955 0.397113 0.176018 -0.2168705 -0.2551191 -0.9255799 0.1765877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1355 1855 -0.114332 0.656953 0.576685 -0.1445992 -0.8955939 -0.2269231 0.3542719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1356 1363 0.940072 -0.226593 0.420436 0.0540404 -0.5145709 0.2182557 0.8274424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1356 1856 -0.675376 0.088312 0.951849 -0.4295742 -0.6257273 0.1597590 0.6311960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1357 1362 0.789174 0.713633 0.029493 0.6838314 0.5947781 -0.3743766 0.1961018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1358 1858 0.621090 0.602264 0.477898 -0.6807021 0.2942195 -0.0568438 0.6684671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1359 1859 0.529226 0.742376 0.382887 -0.6695175 -0.0615666 -0.6981028 0.2461876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1360 1020 -0.763376 -0.889780 -0.078557 0.3896560 0.7012906 0.2910134 0.5212206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1360 1399 -0.777271 0.563284 0.247120 0.0830942 -0.0018179 -0.7003736 0.7089209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1360 1820 0.416364 0.716410 0.352821 -0.5173177 0.0356383 0.1430056 0.8430075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1361 1021 0.467727 0.762315 -0.354797 0.1963059 -0.5107662 -0.4885516 0.6796317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1361 1358 -0.756310 -0.022310 -0.918925 0.3969998 -0.4633696 -0.7136491 0.3440709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1361 1398 0.634086 0.039117 0.870953 0.2810386 -0.5220969 0.7782955 0.2066113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1361 1821 -0.687507 -0.689384 0.260574 0.7303645 0.1912734 -0.6188615 0.2167780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1362 1822 -0.638344 0.953951 0.344030 -0.3763903 0.7091353 0.2703923 0.5313619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1363 1823 0.503910 0.317491 0.787464 0.4417493 0.6618403 -0.0559084 0.6030748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1364 1024 0.308553 -0.816409 -0.017499 -0.4757201 0.6347085 -0.0886315 0.6024782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1364 1824 -0.520949 0.855157 0.029405 -0.8722597 -0.4270298 0.1939569 0.1385251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1365 1394 0.901329 0.270659 0.422207 0.0282451 -0.6938303 -0.7182498 0.0438055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1366 1393 -0.940313 0.489271 -0.478909 0.4653046 0.6694897 0.5608969 0.1437699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1366 1826 0.440746 0.973934 -0.116728 -0.4190508 0.3420256 0.7065447 0.4562998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1367 1827 -0.205781 -0.465634 0.727586 0.3949612 -0.1492180 0.2445518 0.8728884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1368 1391 0.830980 0.157327 0.090122 0.7018530 0.2359221 -0.6390354 0.2082709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1369 1350 0.566059 0.567890 -0.183363 0.2664587 -0.2918077 -0.8739980 0.2827993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1369 1390 -0.608854 -0.906267 0.040484 -0.6505427 0.2502777 -0.0848873 0.7120038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1369 1829 -0.484309 0.393170 0.734225 0.1995395 -0.3388276 -0.4010346 0.8273760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1370 1389 0.863050 -0.152341 -0.072096 -0.0822774 0.0813021 0.3526529 0.9285776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1370 1830 0.023133 -0.428095 0.745350 0.1296877 0.3759453 -0.0295824 0.9170448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1371 1348 0.863232 -0.299876 -0.215904 0.1702243 0.7746136 0.3735911 0.4810687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1371 1388 -0.896920 0.344248 0.455410 0.0343147 -0.7382615 -0.6102830 0.2852140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1371 1831 0.374850 0.250707 0.680769 0.6327203 0.1828235 0.3563600 0.6627580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1372 1032 0.444696 0.850285 -0.150772 0.0650570 0.0163975 -0.5811093 0.8110553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1372 1387 -0.811281 0.325588 -0.732876 0.6965955 0.1404816 0.2675190 0.6507328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1372 1832 -0.319953 -0.884334 0.060034 0.2991248 -0.1884234 0.5508901 0.7560034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1373 1386 0.996629 0.168572 0.080848 -0.0387772 0.6587305 -0.7001318 0.2727380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1373 1833 0.335409 -0.789275 0.477758 0.4301575 0.4562730 -0.4181079 0.6572407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1374 1034 0.529261 0.422909 -0.792996 0.4253552 0.1139025 -0.8896298 0.1210698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1374 1385 0.946495 0.231569 0.458895 -0.3082646 -0.2717246 0.3282679 0.8505168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1374 1834 -0.341950 -0.278812 0.752991 0.6732257 0.1794148 -0.2136245 0.6847935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1375 1384 -0.335016 -0.345006 -0.885679 0.6157009 0.0905369 -0.5664256 0.5402569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1375 1835 0.386485 -0.957845 0.097536 0.6345174 0.1899545 -0.7194044 0.2091945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1376 1383 -0.772961 -0.121323 0.749447 -0.4759744 -0.3276972 -0.4105956 0.7053186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1376 1836 0.633946 0.423111 0.566699 -0.4384147 0.4303712 -0.6938272 0.3757352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1377 1382 0.683250 0.251996 0.531660 0.1514559 0.0823085 0.8775094 0.4475082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1377 1837 -0.632340 0.410347 0.604866 0.3047616 -0.0571874 -0.5141378 0.7996951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1378 1341 -0.413878 -0.822089 0.543287 0.3144254 -0.5799874 -0.7062264 0.2568960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1378 1381 0.248482 0.925188 -0.479012 -0.2593890 0.1996174 0.8814512 0.3404615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1379 1839 0.425981 0.243526 0.816116 0.0095596 -0.0363477 -0.4103982 0.9111316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1380 1000 -0.897855 -0.110400 -0.346942 -0.6441420 0.3257078 -0.4010647 0.5640414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1380 1419 0.341873 0.383294 -0.788041 -0.0591860 -0.4506211 -0.8208847 0.3458120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1381 1418 0.448799 -0.998431 0.017974 0.0119298 0.2601742 0.7670848 0.5863003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1381 1801 -0.133752 0.066166 1.072063 0.3022224 -0.3826994 0.8550100 0.1765242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1382 1002 -1.051973 -0.550855 -0.087845 -0.6619229 0.6707405 -0.2825605 0.1792340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1382 1417 -0.012974 -0.321012 0.736292 0.3557536 0.2417394 -0.2782376 0.8588279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1383 1003 -0.877597 -0.384561 -0.641714 -0.4954757 0.6219125 0.2490623 0.5528983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1383 1803 0.819138 0.320829 0.459918 0.6507624 -0.1424584 0.7382023 0.1061661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1384 1415 0.492505 -0.919665 0.241754 0.0895881 0.8128499 0.5223400 0.2416816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1385 1414 0.863825 -0.522882 -0.100881 0.4522392 0.5645976 -0.6640980 0.1888997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1385 1805 -0.480607 -0.697606 0.548811 -0.6631886 0.1632331 0.7266567 0.0742010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1386 1413 -0.817306 0.441428 0.346490 -0.2815331 0.3660199 -0.8402057 0.2842938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1386 1806 0.037224 -0.463619 0.803131 0.0377126 -0.3160916 0.9233875 0.2145211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1387 1412 -0.383148 -0.494833 -0.663546 0.8537914 -0.4219001 -0.2981933 0.0641971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1387 1807 -0.997509 0.070556 0.752311 -0.1388572 -0.2174298 0.9625082 0.0837911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1388 1411 0.791103 0.142425 0.664367 -0.2471814 -0.3505272 -0.8849146 0.1815438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1388 1808 -0.279684 1.170784 -0.062339 0.4343001 -0.8438277 -0.1805732 0.2583246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1389 1410 0.817533 -0.703368 -0.010715 0.5157130 0.1590165 -0.1651575 0.8255161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1389 1809 -0.454900 -0.429396 0.780499 -0.0526968 0.0612013 0.9414986 0.3271970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1390 1409 -0.217885 0.100607 -0.988703 0.7529695 -0.0535388 -0.2473333 0.6074511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1390 1810 -0.930711 -0.655266 0.281140 0.5901685 -0.3986143 -0.6790119 0.1781868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1391 1011 0.867650 -0.427601 -0.050119 0.5383200 0.0987618 -0.8128176 0.1994626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1391 1408 -0.008220 0.303603 -0.979830 -0.6195054 -0.7292742 0.2446981 0.1565089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1392 1407 0.172788 0.851399 -0.507745 0.4220817 -0.0144545 0.8623522 0.2792613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1392 1812 -0.243661 0.536750 0.838463 -0.7237717 -0.0793759 0.3225330 0.6048359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1394 1405 -0.779791 0.480126 0.086356 -0.0983378 -0.3179630 0.9295064 0.1588932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1395 1364 -0.689994 0.760823 0.403431 0.3315851 0.0907540 -0.6523735 0.6754435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1395 1815 0.761952 0.465953 0.275528 0.7324359 0.3813518 0.2981179 0.4787840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1396 1363 0.371986 0.834272 0.609491 0.0734261 0.2939152 -0.6465354 0.7001532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1396 1403 -0.334985 -0.695793 -0.540825 0.9620073 -0.1386611 0.0009638 0.2351896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1397 1362 0.066156 -0.540785 -0.682779 0.6423446 0.6515905 0.1507225 0.3743074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1397 1402 -0.197327 0.512045 0.709152 -0.0214189 0.1595533 0.8769673 0.4527829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1397 1817 0.639820 -0.390363 0.434233 0.6918983 -0.2549735 0.3953024 0.5477238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1398 1018 -0.611399 -0.147841 -0.598665 -0.1324149 -0.4830550 -0.8654078 0.0139080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1398 1401 0.158312 -0.959436 0.318412 0.0890573 -0.3916035 0.9135311 0.0646257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1398 1818 0.502027 0.377617 0.563956 -0.3365496 -0.0110214 -0.5274585 0.7800003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1399 1019 0.640035 -0.616275 -0.091919 -0.6578329 -0.3792159 -0.1743911 0.6269281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1399 1819 -0.811651 0.394856 0.206541 -0.3215054 -0.8515810 0.1650521 0.3797393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1400 980 0.165241 1.025243 -0.135646 0.6565721 0.6637002 -0.2896275 0.2110236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1400 1780 -0.220165 -0.813962 0.130914 0.0897190 0.0310343 -0.9773229 0.1892809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1401 1438 -0.118971 0.281958 0.987585 0.1123221 -0.0191660 -0.5460882 0.8299422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1402 982 0.796703 0.346348 -0.500170 0.6172733 0.0366499 -0.4818759 0.6208270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1402 1437 0.532618 0.103585 0.830294 0.2098595 -0.5151157 0.1836728 0.8104808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1402 1782 -0.798245 -0.241427 0.279345 -0.2219135 0.1660261 0.6257917 0.7290915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1403 983 -0.764376 -0.679457 -0.054441 -0.0590465 0.3547292 0.0472498 0.9319057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1403 1783 0.818455 0.702270 0.179283 0.6502422 0.0785392 0.6585434 0.3705904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1404 1395 -0.728681 0.551053 0.365532 0.1146864 -0.2037165 0.0670432 0.9699752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1404 1435 0.638118 -0.704977 -0.394336 -0.4688805 0.3586150 0.7386889 0.3253999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1406 1393 0.678214 0.498442 0.194096 -0.0203584 -0.8231170 -0.4889214 0.2881318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1406 1433 -0.642944 -0.723158 -0.281939 -0.7033010 0.3250119 0.6110858 0.1622011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1406 1786 -0.782434 0.326962 0.313213 -0.4297464 0.1599233 0.8786776 0.1329221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1407 1432 -0.051088 -0.623346 -0.580996 -0.0584925 0.6310397 -0.7389112 0.2288619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1407 1787 1.070751 -0.433479 0.487911 0.6073069 -0.4654254 0.5188447 0.3812579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1408 1788 0.684754 -0.763947 0.341628 0.5469476 0.5730153 -0.6078270 0.0552099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1409 1430 0.230440 -1.030160 0.345825 0.7483603 -0.1342674 -0.4876895 0.4290549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1409 1789 -0.462930 -0.175901 0.886027 -0.4722283 0.1164725 0.6885414 0.5379083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1410 1429 0.732994 -0.085097 0.686513 -0.5468581 0.5228478 0.5933627 0.2747674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1410 1790 -0.560386 0.043036 0.701352 0.4191102 0.2440484 -0.7911519 0.3726469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1411 1428 -0.261268 0.648353 0.716107 0.5974846 0.4967082 -0.2011657 0.5965110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1411 1791 0.008884 -0.582410 0.561307 -0.1175310 0.3674338 0.0454717 0.9214723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1412 1427 0.510748 0.645107 0.760241 -0.1202574 0.4448414 0.7454544 0.4816140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1412 1792 -0.961087 0.587660 -0.022371 -0.6622379 -0.3437442 -0.1080155 0.6569730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1413 1426 0.428001 -0.620548 -0.623105 -0.1168157 0.0560273 -0.2425143 0.9614582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1413 1793 0.571009 -0.297639 0.726660 -0.1838405 -0.2231372 -0.5695816 0.7694083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1414 1425 -0.533487 0.767502 0.248882 0.1343495 -0.2017707 0.6725001 0.6992727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1414 1794 -0.578618 -0.588004 0.508129 -0.2160337 -0.0704501 -0.1286286 0.9653087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1415 1424 -1.035382 0.011385 -0.397606 -0.7045299 0.1498045 0.0720032 0.6899361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1415 1795 -0.340068 0.694196 0.529289 -0.5226209 0.0823431 0.5535391 0.6431808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1416 1383 -0.412360 0.016901 0.950355 0.7381758 0.0394191 0.1268384 0.6614036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1416 1423 0.475419 -0.134365 -0.727609 0.1796752 -0.0488736 -0.9174119 0.3516868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1416 1796 0.873290 -0.456696 0.478759 -0.7471603 0.5179205 -0.2456751 0.3363831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1417 1422 -0.763323 0.185389 0.856887 -0.5762384 -0.0030725 0.3195705 0.7522065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1417 1797 0.339278 0.985384 -0.277422 -0.3673533 -0.1440978 0.2513100 0.8838160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1418 1421 -0.951068 -0.221265 -0.218698 0.0066505 -0.3057920 -0.3849323 0.8707894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1418 1798 -0.189619 0.608345 0.656356 -0.0951325 -0.3160969 -0.3820078 0.8631933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1419 1799 -0.363561 0.983873 0.354550 -0.1856134 -0.3145577 -0.9008008 0.2348598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1420 1459 0.597323 0.720527 -0.297071 -0.0139437 0.7889462 -0.5884552 0.1763236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1420 1760 0.656752 -0.650882 0.218705 0.5541142 -0.2458794 0.2895269 0.7407260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1421 1458 -0.442361 -0.873429 0.466494 0.1244683 0.0610807 0.7098001 0.6906233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1421 1761 -0.087726 0.352725 0.940340 -0.0769952 0.5924918 0.0164141 0.8017205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1422 1457 -0.712651 -0.414710 0.603154 0.2910411 0.5858633 0.6652090 0.3599393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1422 1762 0.721188 0.009044 0.671592 -0.0573442 -0.2698349 -0.9450984 0.1751851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1423 1456 -0.101146 0.007396 -0.973960 0.1256727 0.1638143 0.9731915 0.1013389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1423 1763 -0.465615 0.839400 0.286354 0.1257629 0.7178668 0.5163751 0.4496751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1424 1764 -0.396831 -0.426615 0.718841 0.4670778 -0.5683384 0.1528138 0.6599074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1425 1765 -0.093872 0.312677 0.991028 -0.4148580 -0.4787550 -0.7406994 0.2237207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1426 1453 0.625125 -0.284129 -0.564036 -0.0250459 0.1445079 -0.9772489 0.1532149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1427 1452 -0.382495 -0.182412 1.061767 -0.1684317 -0.2104921 -0.2115304 0.9394566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1428 1451 -0.498875 0.288118 -0.850860 -0.5036611 -0.5007467 0.0479117 0.7023409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1429 1450 -0.761569 -0.629570 -0.471662 0.0547026 -0.3128326 -0.7600297 0.5670081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1429 1769 -0.723266 0.707440 0.158305 -0.4183499 -0.0732463 0.7233433 0.5444197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1430 1449 0.581147 0.759055 0.303185 -0.5036620 0.0011458 -0.3953659 0.7681205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1430 1770 -0.636440 0.357454 0.365990 -0.5535985 0.1560184 0.7919700 0.2048669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1431 971 0.737709 -0.676828 -0.037737 0.1116066 -0.4312512 -0.7472091 0.4931987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1431 1408 -0.281746 -0.120101 -0.949255 -0.3078157 -0.3268164 -0.8922273 0.0486941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1431 1448 0.124380 0.013108 0.800947 -0.5130153 -0.3163469 -0.0739322 0.7945275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1432 1447 0.653091 0.661754 0.464098 0.4303087 -0.3866483 -0.4613110 0.6727033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1432 1772 -0.612449 -0.028772 0.744768 -0.0184462 -0.6024686 -0.7801306 0.1675938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1433 973 0.732645 -0.092468 -0.857006 0.3252100 0.3247969 0.2117238 0.8625071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1433 1446 0.351609 0.944428 -0.097566 0.0566558 -0.3253414 -0.0045792 0.9438867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1433 1773 -0.509903 0.081194 0.694350 -0.0946770 0.1512891 0.8388923 0.5142058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1434 1405 0.203595 1.126155 0.241569 0.0279872 0.1745661 -0.6541146 0.7354437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1434 1445 -0.301100 -0.939001 -0.178719 0.3849804 -0.4801600 0.3633708 0.6994270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1435 975 0.895249 0.379145 -0.176040 0.7085727 0.3420020 -0.4961309 0.3671696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1435 1775 -0.772405 -0.670383 0.227376 0.5893845 0.4125676 -0.5425534 0.4336470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1436 1403 0.423032 -0.861225 0.502047 0.0719163 -0.8632824 -0.2917676 0.4055160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1436 1443 -0.435091 0.556750 -0.367764 -0.3344874 -0.3660562 0.8354926 0.2367975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1437 977 -0.019418 -0.332964 -1.060013 -0.0141991 0.4188710 -0.3746665 0.8270251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1437 1442 0.937006 -0.122085 0.092998 0.2128238 0.6565527 0.4990864 0.5239821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1437 1777 -0.070715 0.484951 0.996983 0.3956797 0.2570002 0.7851823 0.4010951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1438 978 -0.361233 0.788603 -0.574844 -0.3501841 0.2782297 -0.0282615 0.8939578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1438 1441 -0.535996 0.338479 0.999748 0.2356897 0.0277205 -0.7849562 0.5722986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1438 1778 0.545005 -0.716682 0.559680 0.0197664 0.7276158 0.3200633 0.6064190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1439 979 0.529516 0.043993 -0.798223 0.3569032 -0.2406140 -0.0868285 0.8984352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1439 1400 -0.473286 0.687590 -0.578778 -0.7277394 -0.1683793 -0.1478203 0.6482229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1439 1779 -0.464097 -0.005651 0.698252 -0.5751911 0.0431700 0.4349062 0.6914826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1440 1740 -1.037291 -0.325941 0.376649 -0.2591587 -0.0038103 0.9252298 0.2770777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1441 1478 -0.679759 -0.400129 0.686917 -0.0924082 -0.7205001 -0.5524969 0.4087634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1441 1741 0.495716 0.699560 0.464128 -0.5520281 -0.5007473 -0.6522012 0.1383858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1442 1477 -0.476428 -0.239378 0.787307 -0.8958139 -0.1639708 -0.3864541 0.1458916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1443 1743 -0.054767 -0.619068 0.801234 -0.2059840 0.0136339 -0.4326462 0.8776115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1444 1435 0.303880 0.806552 0.542715 -0.3036007 0.4122997 0.1903993 0.8376059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1444 1475 -0.152537 -1.009612 -0.598539 0.4864264 -0.2039873 -0.1428250 0.8374841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1444 1744 -0.186729 -0.376261 0.906826 -0.2723401 0.2275189 -0.3152199 0.8801718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1445 1474 -0.375013 -0.380849 0.687028 0.1205925 -0.4680446 -0.4749316 0.7354126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1445 1745 0.582462 0.747144 0.369679 -0.7346462 0.3399125 0.5574972 0.1842589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1446 1473 0.272599 0.971627 -0.187941 0.1814964 0.1903509 -0.9228508 0.2813751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1446 1746 0.244375 0.149382 0.921349 -0.1455806 0.6300964 -0.5066578 0.5701603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1447 1472 -0.328659 0.849220 -0.379012 -0.0980194 0.6508408 0.1880011 0.7290089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1447 1747 -0.056218 0.349456 0.991620 0.2134710 0.2065903 -0.0715236 0.9521738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1448 1471 0.901013 -0.681230 0.227688 0.3288891 0.1473967 -0.6547996 0.6643371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1448 1748 -0.502303 -0.033328 0.947330 -0.0491339 -0.5035083 0.1082236 0.8557762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1449 1470 0.244729 0.049954 1.055110 0.6398326 -0.7008595 0.1147066 0.2936881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1449 1749 -0.739236 -0.720039 0.201681 0.0363376 0.3540219 -0.5590441 0.7488777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1450 950 0.520447 0.621927 -0.596268 -0.0421622 -0.8878200 0.3525158 0.2927978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1450 1469 0.457953 -0.851946 -0.150964 -0.3557834 -0.1022226 0.5938148 0.7143897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1451 951 -0.277201 0.746095 -0.676210 0.1903943 -0.7890450 0.5651171 0.1476502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1451 1468 -0.785350 0.590170 0.726236 0.4276234 -0.0942714 0.8869113 0.1471038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1451 1751 0.308573 -0.780011 0.707355 -0.1955354 0.3156838 -0.6406854 0.6720356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1452 1467 0.113597 -0.490673 0.906752 -0.6728340 0.4477536 -0.5561226 0.1937494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1453 1466 -0.901797 0.649600 -0.557701 -0.7767777 -0.0660499 0.2089873 0.5904051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1453 1753 -0.754233 0.083123 0.892064 0.7493051 -0.0016070 -0.6473112 0.1397412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1454 1425 0.865545 0.221114 -0.107933 -0.1259938 0.3055327 0.9270658 0.1769871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1454 1754 0.096975 0.333417 0.845114 -0.3019705 0.4292069 -0.4389546 0.7293244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1455 1424 0.022585 0.409107 -0.774332 -0.0534722 0.4565622 0.8317604 0.3112334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1455 1464 0.296893 -0.660295 0.768044 -0.0784325 -0.0128141 -0.9952420 0.0563691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1455 1755 0.878835 0.340673 0.051525 -0.5900912 0.3875662 0.6246179 0.3338223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1456 956 -0.430220 0.664233 -0.416697 -0.3327264 0.5085074 -0.0762913 0.7905017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1456 1756 0.645836 -0.610614 0.243951 -0.5610454 0.5305575 -0.4863554 0.4088951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1457 957 0.617992 -0.464389 -0.532473 -0.7431232 -0.3289730 -0.3800018 0.4417503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1458 958 -0.488110 -0.245726 -0.589703 0.1564843 0.4551502 0.7498047 0.4540307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1458 1758 0.645913 0.245442 0.687411 -0.5711100 -0.2441304 -0.6812724 0.3874294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1460 1499 0.127759 -0.897072 -0.033544 0.4596728 -0.2703574 -0.1870846 0.8249892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1461 1458 0.649575 0.462299 -0.801127 0.6593569 0.1663071 0.1160406 0.7239648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1461 1721 0.864036 -0.569676 0.195941 0.5931210 -0.3695968 0.5151193 0.4962437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1462 1457 -0.859690 -0.403630 0.266061 0.1983467 -0.2172621 -0.4699247 0.8322419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1462 1497 0.844009 0.639453 -0.231897 0.2448918 0.0911710 -0.8173612 0.5134555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1462 1722 -0.343490 0.631562 0.835198 -0.7472241 0.3174875 -0.2490250 0.5280571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1463 1456 0.667066 0.042631 0.734266 0.0414370 0.2525263 -0.2716586 0.9277473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1463 1496 -0.676118 -0.143811 -0.797019 -0.2636700 0.5734554 -0.3830156 0.6744821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1464 1495 0.008024 0.712096 0.761504 -0.1218250 0.1553543 0.9479924 0.2496681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1464 1724 -0.860110 -0.385637 0.371678 -0.1305869 -0.3389183 0.9210212 0.1407174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1465 925 0.807301 -0.632343 -0.159003 -0.3697722 -0.8213763 -0.0459346 0.4318558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1465 1454 -0.119706 0.111942 -1.030026 -0.5445614 0.2530724 0.6630325 0.4469845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1465 1494 0.021100 -0.186875 0.880703 0.3329374 -0.9159975 -0.0745647 0.2110480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1465 1725 -0.902557 0.555584 0.384309 -0.7151026 0.3235179 0.2937701 0.5455855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1466 1493 -0.164356 0.166650 0.891040 0.0614003 -0.4749633 -0.5743561 0.6638938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1466 1726 -0.731652 -0.685652 0.074374 0.0056029 -0.9894375 -0.0041053 0.1447939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1467 1492 0.817931 -0.416158 -0.025792 0.2760540 -0.2437339 -0.4297974 0.8244162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1467 1727 -0.470765 -0.890900 0.142037 0.9238552 0.2545004 -0.1671196 0.2319312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1468 1491 0.946982 -0.120481 -0.273979 -0.0418688 0.1551876 -0.8811985 0.4445819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1469 1490 -0.507499 -0.557068 -0.845161 0.1286321 0.2518050 -0.9413395 0.1841954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1470 930 -0.626531 -0.548366 -0.422523 -0.0841691 -0.3198969 -0.8193180 0.4682943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1470 1489 0.436331 0.269015 -1.009504 0.1769029 0.4255216 0.5509706 0.6957501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1470 1730 0.646367 0.471683 0.442483 0.1645826 -0.7162532 -0.6231809 0.2674686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1471 1488 0.249365 0.791609 0.310503 -0.4777739 -0.0672262 -0.1800284 0.8572062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1471 1731 -0.613790 -0.111312 0.796592 0.6372607 -0.2601725 -0.4851299 0.5393126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1472 932 0.928788 -0.539212 -0.196735 0.0288727 -0.9694337 0.0476857 0.2389368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1472 1487 0.533939 0.956650 0.068995 -0.1836537 0.2674797 0.8209833 0.4698003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1472 1732 -0.865974 0.471739 0.120218 0.6532129 0.1953010 -0.7013010 0.2082000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1473 1733 -0.645661 -0.017698 0.703091 -0.4985210 -0.2770308 0.4827812 0.6645698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1474 1485 0.719575 0.076425 0.579789 0.0742033 -0.3748515 -0.5056077 0.7735251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1475 1484 0.051465 -0.725917 0.467525 -0.0448694 0.8493956 0.5229603 0.0550125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1475 1735 0.245200 0.685483 0.813164 0.3072085 0.5444612 0.3481882 0.6985341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1476 1443 0.552573 -0.008531 0.713070 0.4275556 0.0691645 -0.8768796 0.2085535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1476 1483 -0.412591 -0.058980 -0.958870 -0.9270837 0.0101608 0.2434824 0.2848313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1476 1736 -0.790222 0.377884 0.546843 -0.3278588 0.5016351 0.6881236 0.4090925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1477 1737 -0.064687 -1.034262 -0.192263 0.7807797 -0.0808977 -0.2707000 0.5572793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1478 1481 1.063983 0.072401 0.033979 -0.5132371 0.4451390 0.4975384 0.5393463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1478 1738 0.009168 0.794809 0.573306 -0.2112053 -0.9093487 -0.2890404 0.2119737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1479 1739 0.283110 -0.862795 0.038037 0.8510648 0.3519673 0.2609546 0.2893276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1480 1519 -0.505226 0.221197 -0.697070 0.4775653 0.3212882 -0.6337447 0.5167910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1480 1700 -0.670016 -0.002164 0.696240 0.8792967 0.2941917 -0.3718136 0.0452021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1481 1518 0.158709 -1.108603 -0.089621 0.1408009 -0.7288979 -0.4801105 0.4673081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1481 1701 -0.440805 0.088221 1.064961 0.3605373 -0.0457826 0.0454702 0.9305102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1482 1477 0.275494 0.161100 1.003414 -0.0765524 0.1369712 -0.2122719 0.9645306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1482 1517 -0.191734 -0.365262 -0.948997 0.8398817 -0.4284282 0.0539497 0.3288425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1483 1516 -0.057273 0.635646 1.018109 0.4175885 -0.7962029 0.2204891 0.3782399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1483 1703 -0.750883 -0.486069 0.265617 0.6919848 -0.1459239 0.1533816 0.6901719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1484 1515 0.032320 -0.138868 -0.830652 0.4825036 0.0286499 -0.8494691 0.2115934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1484 1704 -0.272443 0.916754 0.001036 0.2708720 0.9342483 0.1999602 0.1175774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1485 1705 -0.603037 0.475772 0.403300 0.3501993 -0.1569240 -0.5493794 0.7422382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1486 1473 -0.579993 0.347529 -0.579630 -0.5029339 -0.5207443 0.5890098 0.3590965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1486 1513 0.769843 -0.492505 0.513692 -0.5569900 -0.5405940 0.3768422 0.5054802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1486 1706 -0.648047 -0.886007 0.198934 -0.4307703 -0.7301623 0.2824687 0.4489002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1487 1512 0.406334 -0.923688 0.777419 0.3668704 0.7557147 0.1624042 0.5176161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1487 1707 0.572793 0.634208 0.495567 0.3580776 0.7130541 0.5363974 0.2749764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1488 1511 0.480294 0.223714 0.991657 -0.4315023 -0.3971816 0.4839309 0.6495101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1488 1708 -0.091994 -0.855714 0.490195 0.6125858 0.4067575 -0.3490143 0.5809268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1489 1510 0.527241 -0.718780 -0.243639 0.3433910 0.0445732 0.2046780 0.9155342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1489 1709 0.365445 0.196411 0.973577 -0.2870245 0.7484673 -0.3659385 0.4727606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1490 910 -0.484085 0.624672 -0.587034 -0.0012874 0.2858375 0.9154367 0.2833212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1490 1509 0.842424 0.293854 -0.459373 -0.8311814 0.0298518 -0.5496361 0.0784004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1491 1711 -0.625425 -0.225753 0.678379 -0.4815090 -0.1359348 0.8555900 0.1328031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1492 1507 0.896945 0.385818 -0.308304 0.8180450 0.0022195 0.5617343 0.1234990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1492 1712 0.533726 -0.530567 0.552905 0.0305242 -0.2936232 0.7481648 0.5942248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1493 1506 0.233873 0.571061 0.880131 0.4799016 0.2169194 -0.8168579 0.2353370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1493 1713 0.519550 -0.800355 0.380450 -0.3117048 0.5316829 -0.4975919 0.6103734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1494 1505 0.383261 0.172822 -0.948364 -0.3044599 -0.0149499 -0.9522498 0.0173474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1495 1504 -0.085656 -0.453907 0.975505 -0.1213244 0.1749072 -0.9750710 0.0626447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1496 1503 0.797417 0.240479 -0.777427 0.7359022 -0.2758683 0.3732711 0.4929637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1496 1716 0.802350 -0.501584 0.459281 0.6400750 0.6434973 -0.2720089 0.3197285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1497 1502 -0.600949 0.602135 -0.938687 0.1233511 -0.2103218 -0.6831624 0.6883592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1497 1717 -0.856814 -0.625423 0.493138 0.7038582 -0.4389914 -0.4176346 0.3707446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1498 1501 -0.214183 0.754738 -0.745984 -0.2102373 -0.6867195 -0.6629627 0.2114169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1498 1718 -0.406962 0.440840 0.947756 0.1262970 -0.8247343 -0.3473318 0.4280455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1499 919 -0.704702 -0.811136 -0.299919 -0.4687553 0.2493639 0.3588328 0.7676752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1499 1719 0.532524 0.781198 0.329738 -0.4262918 0.2622460 -0.6478388 0.5742884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1501 1538 -0.230329 -0.503263 0.880003 -0.8082162 -0.1294439 -0.3744134 0.4357126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1501 1681 0.626966 0.464637 0.504395 0.6593777 0.4523715 0.2874215 0.5272286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1502 1537 -0.613129 -0.825812 -0.269694 0.4838679 0.4771606 -0.6089069 0.4091723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1503 883 -0.690018 0.299386 -0.487039 -0.2044542 0.4153145 0.1002726 0.8807144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1503 1536 -0.377960 -0.974211 0.075626 0.6204291 -0.0046703 0.1070993 0.7769013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1503 1683 0.850621 -0.254823 0.541827 0.0451868 0.8496668 0.0325255 0.5243726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1504 1535 -0.045539 0.106318 0.824808 -0.0623838 0.0065994 -0.9557290 0.2874836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1504 1684 -0.178200 -0.849880 0.202708 0.3473476 -0.0428432 0.8333533 0.4278275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1505 1534 -0.928047 -0.207688 -0.490341 -0.4873839 -0.5956873 0.6351854 0.0644443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1505 1685 -0.164208 -0.788504 0.205111 0.0253583 -0.5128194 0.6600191 0.5484050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1506 1533 -0.843755 -0.494547 0.044100 -0.2187516 0.4469698 0.4578277 0.7367222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1506 1686 -0.299264 0.930773 0.314809 -0.3847078 0.0260882 0.7929048 0.4718276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1507 1532 0.127725 -0.535045 0.893558 0.6301322 -0.1456750 0.7526061 0.1236782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1507 1687 0.621629 0.598199 0.410905 -0.2395027 -0.1316072 -0.2550862 0.9274961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1508 1531 0.996598 -0.224024 -0.110145 -0.0437377 0.7793266 0.6244569 0.0281186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1508 1688 0.127653 1.031399 0.489421 0.4406768 0.1942729 0.8758222 0.0315818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1509 889 -0.958001 -0.341736 -0.177901 -0.5594079 0.2810141 0.3739362 0.6842994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1509 1530 -0.213932 -0.362733 1.024442 -0.5206854 0.5093002 0.4632872 0.5048416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1509 1689 0.710420 0.632354 0.375293 -0.5705304 0.7111437 0.2651654 0.3137787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1511 1528 0.471228 -0.804580 0.145985 0.3704557 0.5263060 -0.7024351 0.3038906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1511 1691 -0.870825 -0.499534 0.054701 0.7400121 -0.6551675 -0.1263530 0.0846912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1512 1527 -1.070068 -0.065907 0.262310 -0.8591344 -0.1915248 0.3179175 0.3523277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1512 1692 0.176334 0.874920 0.252579 -0.3937515 -0.6818136 -0.2847848 0.5467975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1513 1526 -0.135484 -0.295188 -0.905878 0.4054499 -0.3244063 -0.8270049 0.2154850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1514 894 0.023876 -0.094715 -1.065030 -0.0107282 -0.2813055 -0.3219130 0.9039492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1514 1485 -1.094437 -0.334955 0.169202 0.3644357 0.2472661 -0.3377209 0.8318598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1514 1525 0.960669 0.457700 0.045315 -0.3980275 0.3966222 0.1214526 0.8182385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1514 1694 0.035923 0.077604 1.012078 0.5715148 0.2719589 0.2347367 0.7377723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1515 1524 0.897041 -0.153184 -0.557499 0.4659680 -0.1825348 -0.8283127 0.2518986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1515 1695 -0.013658 -0.888756 0.052040 0.7289917 0.3722737 0.0391763 0.5731044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1516 1523 0.641733 0.240826 -0.674162 -0.0154382 -0.1440317 0.9858931 0.0838526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1517 1522 -0.305527 -0.258912 1.030494 -0.7166725 0.0962527 -0.0806925 0.6860063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1518 1521 0.551824 -0.411233 -0.769854 -0.2464329 0.1177899 -0.9352357 0.2252344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1518 1698 0.896124 0.409785 0.225789 -0.4620911 0.5356706 -0.4097421 0.5758822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1520 1559 -0.542613 0.579497 -0.040358 -0.5936362 -0.1852361 0.6436353 0.4461136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1520 1660 -0.057686 -0.320800 0.974953 0.0180561 0.0741845 0.2751961 0.9583516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1521 1661 -0.495456 -0.488339 0.481178 -0.1472679 -0.5257511 -0.0434054 0.8366683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1522 1557 -0.207366 -0.960505 -0.435503 0.6805392 0.3074336 0.3761186 0.5485306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1522 1662 0.386987 -0.607277 0.783508 0.2955674 -0.6568948 0.4289685 0.5450827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1523 1556 -0.522260 0.024273 -0.852017 0.1339078 0.0382142 0.5446612 0.8270143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1523 1663 -0.650143 -0.694161 0.405976 0.3445657 0.1230303 -0.1869271 0.9116997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1524 1555 0.125981 -0.159483 -0.903502 0.5485580 0.2159267 0.8039854 0.0778926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1524 1664 0.487829 0.872955 0.044519 -0.6593112 0.3868009 0.6015772 0.2319454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1525 1665 -0.682669 -0.510076 0.437545 0.2788795 -0.7462552 0.4315277 0.4232177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1526 1553 1.062609 -0.456359 -0.507028 0.3915033 0.4810248 0.5026926 0.6021963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1527 1667 0.356519 -0.736071 0.207147 0.4161904 -0.2052436 0.8393587 0.2830858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1528 1551 -0.241533 0.662960 0.608831 0.7854179 -0.3250756 0.3757722 0.3691067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1528 1668 0.367539 -0.655410 0.540040 0.2024056 -0.2437266 -0.6365628 0.7031480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1529 1510 -0.357448 0.874011 -0.199749 0.2888412 -0.5967824 0.4371956 0.6076853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1529 1550 0.476759 -0.919927 0.244837 0.5347660 0.1971012 -0.4637385 0.6783237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1529 1669 -0.700827 -0.271920 0.334843 -0.7294529 0.3139479 0.5738959 0.1999467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1530 1549 -0.901003 -0.055046 -0.481505 0.0674566 -0.4561646 0.6935837 0.5534484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1530 1670 -0.300188 -0.893302 0.469987 0.3984275 0.4776558 -0.4491560 0.6413730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1531 1548 -0.923791 0.151689 -0.222780 -0.5107182 0.5383703 0.6691308 0.0398530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1531 1671 -0.186189 0.574269 0.729246 -0.2356162 0.1205199 0.8878317 0.3764502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1532 1547 0.829749 0.298370 0.574635 0.6342890 0.2714517 -0.7223736 0.0465596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1532 1672 0.166739 -0.758244 0.373842 -0.2911910 -0.3430745 0.5372611 0.7133430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1533 1546 -0.504249 0.689533 -0.382129 -0.3948706 -0.2755003 -0.8664333 0.1321747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1533 1673 0.089850 0.850030 0.646461 -0.4887819 -0.1950880 -0.4930941 0.6927418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1534 874 0.834002 -0.087952 -0.655962 -0.0606609 -0.3992681 -0.8015657 0.4409056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1535 875 -1.031113 -0.546235 -0.231138 -0.9007013 0.0302072 -0.0184201 0.4329957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1535 1544 -0.059305 -0.031061 1.072430 -0.2479102 -0.2098530 -0.5924190 0.7372530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1536 1543 -0.450974 0.012256 0.762065 0.2406749 0.1252094 0.1929571 0.9429559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1536 1676 0.826869 0.215231 0.624786 -0.1100997 -0.0497019 0.4327474 0.8933854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1537 1542 0.304117 -0.255059 0.781730 0.2522264 0.1087018 0.0166730 0.9613989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1537 1677 -0.915645 0.427418 0.561898 0.0555721 0.1509038 0.8977204 0.4101681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1538 1541 0.548712 -0.267315 -0.875129 -0.0466152 0.0781048 -0.8155375 0.5715114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1538 1678 0.808187 -0.102167 0.500698 -0.0689458 -0.3275932 -0.9411875 0.0457734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1539 1500 0.832776 -0.688749 0.225280 0.0249593 -0.1520227 -0.0666587 0.9858107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1539 1679 -0.119122 -0.004044 0.749694 0.1988053 -0.1912006 0.1515881 0.9491785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1540 1579 -0.645990 0.774041 0.351977 -0.1178911 0.7783018 0.5607850 0.2566481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1540 1640 0.578127 0.316097 0.941443 -0.4672091 0.1965461 -0.7806780 0.3655506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1541 1578 -0.059265 0.769983 -0.531740 0.2289981 0.2924455 0.8578293 0.3551963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1541 1641 -0.231221 0.615190 0.726110 -0.0312523 0.1944514 0.0123567 0.9803363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1542 842 0.849648 -0.768359 -0.115471 -0.9566317 -0.0708896 0.1924453 0.2068700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1542 1642 -0.758547 0.826113 0.014463 -0.8047997 0.0857024 0.0778012 0.5821508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1543 1576 -0.573410 0.383372 0.881430 -0.2176809 0.0137140 0.7270867 0.6509776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1544 844 0.193208 -0.934875 -0.367948 -0.6960117 0.1591280 -0.0753179 0.6961130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1544 1575 0.576039 -0.215971 0.740017 -0.1634201 -0.2741510 0.8916648 0.3210437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1545 1534 -0.389734 0.864608 -0.083803 -0.2232757 0.4822956 -0.5984983 0.5994486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1545 1574 0.444728 -0.878476 0.035358 0.1017806 0.2901450 -0.2210427 0.9255251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1545 1645 0.915217 0.568284 0.382944 -0.1145221 0.8785074 0.3533222 0.3004543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1547 1572 -0.244692 -0.171693 -1.105930 -0.5749622 0.2033950 0.7399344 0.2838062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1547 1647 -0.868709 0.534599 0.181249 -0.7101476 0.0242949 -0.0036577 0.7036240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1548 1648 -0.894889 0.408943 0.799756 0.0169368 0.5577606 0.7631632 0.3258807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1549 1570 0.234692 0.957757 0.286459 -0.1611492 -0.0728497 -0.4627277 0.8686811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1549 1649 0.074564 -0.235812 1.025109 -0.2284994 -0.2848131 -0.1674938 0.9157594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1550 850 0.588711 0.329839 -0.629541 -0.5224785 0.1661494 0.7533621 0.3631202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1550 1569 0.337027 0.646183 0.657585 0.3025788 -0.2084564 0.5846531 0.7233068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1550 1650 -0.684740 -0.245998 0.672653 0.5238456 -0.2486659 0.5811105 0.5710181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1551 1568 0.200492 0.170375 -0.927229 -0.2227276 0.7334525 -0.3916065 0.5090031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1551 1651 0.846492 0.390370 0.737987 0.8472175 0.4431284 0.2927933 0.0114835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1552 1527 0.216651 -0.143639 -0.910590 -0.2595483 0.2855917 -0.0876610 0.9183614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1552 1567 -0.224947 0.201548 1.124046 0.5788972 -0.3244105 0.2216618 0.7144942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1553 1566 -0.351070 -0.652774 0.628190 -0.1386950 -0.4135948 -0.8279388 0.3524490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1553 1653 0.373517 0.500744 0.725523 -0.5759038 -0.5750779 -0.5808434 0.0155290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1554 1525 0.526162 0.495849 0.719210 0.6473468 0.3713513 -0.6241569 0.2312325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1554 1565 -0.609089 -0.470488 -0.626476 -0.2222607 0.4478543 -0.7800585 0.3762120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1554 1654 -0.670099 -0.130833 0.584840 -0.1441281 0.1810359 -0.3129927 0.9211344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1555 1564 -0.933664 -0.314189 -0.069143 -0.1821632 -0.2399526 0.9238902 0.2359370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1555 1655 0.153500 -0.524933 0.728026 0.0165216 0.7430907 -0.2635030 0.6149060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1556 1563 -0.347253 0.028160 -0.800571 -0.2569594 -0.1126246 0.8875769 0.3653694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1556 1656 -0.751814 0.486711 0.394764 -0.2860146 -0.1105286 0.4982107 0.8110272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1557 1562 -0.873756 -0.232038 0.311236 0.1667200 -0.1939867 -0.6998089 0.6669641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1557 1657 0.059329 0.814368 0.611958 0.1513450 0.1714408 -0.9725105 0.0438882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1558 858 -0.314072 0.127293 -1.074268 -0.2104701 0.4512500 0.6660017 0.5554435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1558 1521 0.053441 -0.964971 -0.065965 -0.0827568 0.5714769 -0.2048937 0.7903063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1558 1561 -0.070037 1.072772 0.006018 0.5320008 -0.2573819 -0.3821387 0.7104222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1558 1658 0.167792 0.093083 0.776389 -0.4374430 0.5022865 -0.5403009 0.5142245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1559 1659 -0.835450 -0.638000 0.158050 0.2048164 -0.3957212 -0.8936351 0.0535848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1560 1599 -0.141828 1.117577 0.126771 -0.5701035 0.3957497 -0.0720368 0.7163622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1560 1620 0.773013 0.075325 0.844345 -0.2284221 0.3079694 -0.5931678 0.7079055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1561 821 -0.143251 -1.125965 -0.344650 -0.9124801 -0.2755511 -0.0682735 0.2946019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1561 1621 0.010412 1.042919 0.278881 0.6582388 0.2300057 0.6883233 0.2000751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1562 1597 0.364866 -0.519125 0.677503 -0.6493357 0.2264446 0.4728667 0.5508929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1562 1622 -0.844425 0.350844 0.473324 0.6212716 -0.2448446 -0.2555225 0.6991288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1563 1596 0.620206 0.483901 -0.516709 0.3961624 0.1447417 -0.7295105 0.5384419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1564 824 0.887889 0.013368 -0.694126 -0.2493671 -0.6054873 -0.3672580 0.6605473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1564 1595 0.631841 0.869092 0.639239 0.0061871 0.2097531 -0.8752991 0.4356797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1564 1624 -0.678138 0.027263 0.470238 -0.0720499 0.3139944 -0.3815178 0.8664066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1565 1625 0.600456 -0.725917 0.172966 0.4767138 -0.6182472 0.2081621 0.5892222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1566 1593 0.973286 0.128329 -0.135264 -0.2354690 0.7774343 0.4148713 0.4099171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1567 1592 0.471914 0.990964 -0.198659 0.3012256 0.1127912 -0.7096521 0.6268454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1567 1627 0.678239 -0.284445 0.491369 0.3651191 0.6465848 0.1729584 0.6470715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1568 1591 0.135497 0.860429 0.520541 -0.0019413 -0.3457777 -0.5031882 0.7919821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1569 1590 0.822145 -0.084223 0.126853 -0.0844318 -0.7558074 -0.5274716 0.3786822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1569 1629 -0.185053 0.834233 0.845975 -0.6198442 0.4058397 0.1958497 0.6424408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1570 1589 -0.683170 0.453905 0.372859 -0.0759716 0.1244983 0.9890341 0.0232375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1570 1630 0.289100 -0.297703 0.952241 -0.4334211 0.4141206 -0.2482907 0.7609218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1571 1631 -0.352855 -0.887436 0.470340 0.0499758 -0.2426705 -0.2454318 0.9372175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1572 832 0.070861 -0.044689 -1.024603 0.6882470 -0.0527292 -0.0572986 0.7212853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1572 1632 -0.135946 0.193351 0.981695 0.2069085 0.4133782 -0.7592921 0.4580206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1573 1586 -0.330155 0.905325 -0.078449 -0.2266077 0.1761446 -0.7837257 0.5508140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1573 1633 0.842899 0.634525 0.403820 -0.4516142 -0.3860610 -0.6959383 0.4033254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1574 1585 0.711677 -0.495880 0.496082 0.1587443 -0.1025160 -0.1946481 0.9624982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1574 1634 0.100217 0.679974 0.631817 0.0531095 -0.5395774 -0.4369197 0.7177303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1575 1635 0.686549 -0.800019 0.084928 0.6888408 0.6564132 0.2053496 0.2290233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1576 836 -0.147197 1.014536 -0.293523 0.5085969 -0.5033745 0.6869032 0.1269150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1576 1583 0.164216 0.312305 0.745679 0.0735760 -0.6290621 0.7722859 0.0494162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1577 1542 -0.923629 0.198359 0.232910 0.2127026 0.7051655 -0.0057149 0.6763627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1577 1582 0.861224 -0.036877 -0.159721 0.4273254 0.2607139 -0.0790839 0.8620714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1577 1637 0.248090 0.385900 0.848414 -0.0211660 0.2776255 -0.6025844 0.7479092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1578 1581 0.633966 -0.750050 -0.155633 -0.0244046 0.6777561 -0.7169395 0.1613967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1578 1638 0.680798 0.142016 0.643169 -0.5931496 -0.1414821 -0.7068881 0.3584209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1579 1639 -0.835058 0.534992 0.216628 -0.6457868 0.3311555 0.3539307 0.5899394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1581 1601 -0.836725 -0.514242 0.017588 0.2958911 -0.3429035 0.5343591 0.7136708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1582 1602 -0.205295 0.962706 0.311201 -0.2270905 -0.3033814 -0.7118413 0.5913304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1583 1603 0.027774 -0.218127 0.834342 0.0654083 0.3544140 -0.3903570 0.8471918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1584 1575 0.015183 0.179030 0.859797 -0.1559715 -0.9023285 -0.2360424 0.3252079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1584 1604 -0.632562 -0.640089 0.226634 0.3264543 -0.7838864 -0.2819305 0.4466149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1585 1605 -0.152755 0.929342 0.366274 -0.5620045 0.5533754 0.0758875 0.6100555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1586 1606 -0.647192 0.450132 0.814743 0.2844367 0.1179715 -0.8001989 0.5146457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1587 1607 0.868455 -0.624136 0.211249 0.7571106 0.1643769 0.5336472 0.3390936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1588 1571 -0.088294 -0.409799 1.095989 -0.7449325 0.0617352 -0.4918448 0.4464896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1588 1608 -0.074783 0.909781 0.414037 -0.9082680 -0.0840790 0.3804966 0.1523227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1590 810 -0.183867 -0.706303 -0.523790 0.4353968 0.5639491 0.4454488 0.5421867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1590 1610 0.336702 0.693952 0.690129 -0.0819210 0.0547460 0.0901885 0.9910388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1591 1611 0.310561 -0.557546 0.818360 -0.4344194 -0.1538770 0.8870912 0.0259024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1592 1612 -0.013417 0.758808 0.584510 0.2797832 0.4623500 0.4125196 0.7333358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1593 1613 -0.590696 0.601466 0.087166 -0.5651323 -0.4016245 0.6538494 0.3029921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1594 1565 0.955297 -0.108888 0.529826 0.0382462 -0.1123417 0.9550895 0.2715155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1594 1614 0.002839 0.989529 0.346915 -0.2048064 0.1201519 0.5271087 0.8159499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1596 1616 -0.607728 0.534587 0.131705 0.1596217 -0.4990220 0.2490020 0.8145526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1598 1561 0.382630 -0.005610 -0.870698 0.2221351 0.6644148 0.1045774 0.7058842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1599 1619 0.173519 -0.867620 0.427016 0.6411252 -0.0764830 0.4040938 0.6479329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1600 1580 -0.070780 0.084066 -0.920362 0.4669235 0.1695073 -0.3169977 0.8079370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1600 1639 0.051186 1.174757 0.034584 0.3844334 0.3215375 -0.0860658 0.8610559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1601 1638 -1.045419 -0.147967 -0.088002 -0.3317329 -0.5817449 -0.4351674 0.6017936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1601 2381 -0.253647 0.459192 0.523984 -0.3064547 -0.0599244 0.2598010 0.9137823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1602 1637 -0.160769 -0.836140 -0.209878 -0.0120237 0.1561453 0.1979940 0.9676117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1602 2382 -0.425354 -0.186490 0.947684 -0.5338310 0.3210784 0.7677894 0.1497750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1603 1636 -0.729739 0.618019 -0.322430 -0.3967959 -0.0998059 0.6725703 0.6166368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1603 2383 -0.462760 -0.116555 0.738503 0.4869708 -0.6912746 0.1447168 0.5138636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1604 1635 0.364594 0.783946 -0.421808 0.2668182 0.8041837 0.3483917 0.4008989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1605 2385 -0.854213 0.300400 0.491719 -0.3657014 0.4128363 0.8117217 0.1921888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1606 1633 -0.846998 0.340225 -0.207295 0.3735646 -0.1578023 0.7056180 0.5810776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1606 2386 -0.494984 -0.743691 0.489150 -0.1010247 0.0147085 -0.1396763 0.9849204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1607 1632 -0.917909 0.195138 0.015855 0.1734871 0.2809785 -0.9100562 0.2505016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1607 2387 0.255425 0.270990 0.815506 0.4853465 0.2712792 0.7694314 0.3143591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1608 1631 -0.800232 -0.015878 -0.616217 -0.0025061 0.6797170 -0.3540493 0.6423610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1608 2388 -0.316664 -0.880262 -0.051657 0.5466091 0.7405051 -0.3820177 0.0832660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1609 1589 -0.589873 -0.183508 -0.544273 0.2065100 0.6397609 0.3982953 0.6240356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1609 1630 -0.750142 -0.413738 0.637997 0.3869809 -0.5088857 0.7688790 0.0103056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1609 2389 0.606729 -0.000354 0.685261 -0.1123115 -0.0958855 -0.9487744 0.2793193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1610 1629 0.334919 -0.716358 0.448432 0.2491907 -0.2154553 -0.9441103 0.0117756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1610 2390 0.188477 0.659807 0.660195 -0.2924021 0.0420637 0.4358507 0.8501564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1611 1628 -0.195119 0.892577 -0.497618 0.3698977 -0.1190984 0.5746497 0.7202562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1611 2391 -0.700627 0.160768 0.593260 -0.7332383 -0.1920817 0.1109826 0.6427668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1612 1627 -0.413503 -0.056473 0.967805 -0.3188927 0.6258035 -0.1686160 0.6915534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1612 2392 0.396531 0.750765 0.271922 -0.0691446 -0.4991362 -0.6339945 0.5866285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1613 1626 0.863447 0.468879 -0.476719 0.3954267 0.0979965 -0.8954239 0.1795841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1613 2393 0.666612 -0.315542 0.709431 -0.0368647 0.2070811 -0.9365471 0.2804247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1614 1625 0.174901 -0.953578 0.394945 0.6125419 -0.3948438 0.6834744 0.0418757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1614 2394 0.402696 0.412471 0.700641 -0.2668901 0.7057487 -0.4834889 0.4437646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1615 1595 -0.092401 -0.384358 -1.025063 -0.5696252 -0.2642467 0.1603831 0.7615629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1615 1624 0.817096 0.547361 -0.155902 -0.7563461 0.0806682 0.5659276 0.3180554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1615 2395 -0.210379 0.366628 1.057394 0.1900659 -0.4296237 0.7382500 0.4840304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1616 1623 0.945821 -0.120966 0.502447 -0.0730094 -0.0112352 0.8184002 0.5698812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1617 1597 1.053217 0.088969 -0.316569 -0.5722453 -0.0505150 0.6559963 0.4895430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1617 1622 -0.437569 0.752979 -0.556986 0.8051255 -0.0553018 -0.0912385 0.5834296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1618 1598 0.192350 -0.486061 -0.935642 0.3803624 0.2131453 0.5717551 0.6949745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1618 2398 -0.258282 0.357556 1.014591 0.3853556 0.1760920 0.2031241 0.8827419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1619 2399 0.140492 0.412263 0.872651 -0.1485632 0.2342958 -0.9220698 0.2698551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1620 1659 1.032730 0.006775 0.010955 0.6113458 -0.3859514 0.2732429 0.6345362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1620 2360 -0.117796 -0.088865 0.947202 -0.5735429 0.2903702 -0.3659837 0.6728964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1621 1618 -0.148003 -0.596328 -0.927450 0.4863056 0.6379137 -0.1546787 0.5767560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1621 1658 -0.046681 0.370200 0.947140 0.1500270 -0.3010852 0.5228869 0.7832170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1621 2361 0.806365 -0.328954 0.380995 -0.3921308 0.5330366 -0.7235006 0.1966020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1622 1657 -0.532599 -0.626969 -0.260750 -0.7734613 -0.1593749 -0.2706381 0.5505563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1622 2362 -0.733227 0.536730 0.381011 0.2531581 0.1441290 -0.7589826 0.5823085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1623 1563 -0.992034 0.382239 -0.199949 0.3163884 0.1933544 -0.0593276 0.9268186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1623 1656 -0.350884 -0.777816 0.365556 0.2374673 0.4990131 -0.5117839 0.6577784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1623 2363 0.746887 -0.301075 0.286762 0.3069147 0.5993030 -0.1290182 0.7280066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1624 1655 0.564617 -0.480325 -0.593727 0.6092210 0.7616691 -0.2165044 0.0428446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1624 2364 -0.679733 -0.577959 0.142798 -0.5818096 -0.4866687 0.3995624 0.5147825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1625 1654 0.585207 0.519699 0.574511 0.0054154 0.5109825 0.2981358 0.8062150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1625 2365 0.418677 -0.837229 0.200506 -0.0324853 -0.2242170 0.5995228 0.7676222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1626 1566 0.803084 -0.521572 -0.190751 0.0702244 -0.6503250 -0.1965994 0.7304072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1626 1653 -0.325210 0.123191 -0.908330 -0.0433235 -0.9752465 -0.1592437 0.1471689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1627 1652 -0.927557 -0.451125 -0.463381 0.3215090 0.3327588 0.7525945 0.4685137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1627 2367 -0.530312 0.500812 0.594569 0.1806082 -0.1517448 -0.8068244 0.5416536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1628 1568 -0.099263 -1.035289 -0.054746 0.2592702 -0.6137037 -0.7106900 0.2259788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1628 2368 0.344734 0.960199 0.095488 -0.1779629 -0.6397945 0.0365889 0.7467620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1629 1650 -0.461091 0.792682 -0.093051 0.6547382 -0.5720271 -0.1840338 0.4585133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1629 2369 -0.751032 -0.501087 0.873270 0.8439240 0.0594785 -0.5119778 0.1487726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1630 1649 0.953515 0.135137 0.304867 0.3104964 -0.6835664 0.3804571 0.5399827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1630 2370 -0.097541 -0.890392 0.562701 -0.4258660 0.6683497 -0.6082423 0.0445896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1631 1648 0.651892 0.016156 -0.593541 0.4665890 -0.1323699 -0.6274476 0.6091654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1631 2371 0.501199 -0.993551 0.410601 0.3989533 0.4951135 -0.6311725 0.4442073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1632 1647 0.525171 -0.692497 0.202062 -0.0195924 -0.0254682 0.1937344 0.9805277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1632 2372 -0.603248 -0.458874 0.421684 -0.5317392 0.1058693 0.8024947 0.2490930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1633 1646 0.329117 0.632649 -0.574059 0.0228648 0.3181564 0.2078405 0.9246924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1633 2373 0.054900 0.699350 0.575769 -0.1629133 -0.1504778 0.7855332 0.5777138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1634 1605 0.714234 0.589965 -0.315520 -0.5310129 0.6509126 0.4976444 0.2160742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1635 1644 0.614732 0.441837 0.544623 -0.3211310 -0.4003472 -0.5301785 0.6749132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1636 1576 0.618376 -0.001436 -0.979183 -0.3889915 -0.6755641 0.6058641 0.1588316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1636 2376 -0.535971 -0.019398 0.804248 0.4116430 -0.6351751 -0.6439435 0.1115318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1637 1642 -0.063839 -0.744017 -0.213722 -0.7555307 0.0267136 0.6423607 0.1258270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1637 2377 -0.692783 0.091867 0.526490 0.3333078 -0.1338756 0.7913199 0.4947687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1638 1641 -0.030190 -1.022505 0.129684 0.2069158 0.4688074 -0.1236125 0.8497796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1638 2378 0.589131 0.456629 0.737246 -0.6400879 -0.1905090 -0.0032665 0.7443004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1639 2379 -0.611204 0.674562 0.591769 -0.8713744 -0.0714509 0.4818956 0.0581206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1641 1678 -0.268654 -0.774601 0.526946 0.4037699 -0.2394818 -0.4809716 0.7404625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1641 2341 -0.369994 0.678726 0.541392 0.0831964 -0.1014538 -0.3511197 0.9270925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1642 1677 0.180502 1.100383 0.158573 0.2250618 -0.5443521 0.6774549 0.4405483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1642 2342 -0.883115 0.128304 0.514235 -0.1579954 -0.6647553 0.3366951 0.6478998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1643 1543 -0.367322 0.885309 -0.065438 -0.1272136 0.3055428 -0.6968824 0.6362510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1643 1636 0.745285 0.283776 0.363357 -0.0654790 -0.7275471 0.6708548 0.1278344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1643 1676 -0.877322 -0.526825 -0.451497 -0.3073026 0.5411348 -0.3444146 0.7029344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1643 2343 0.449651 -0.883094 -0.034297 0.4928201 0.6996210 -0.4631263 0.2305925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1644 1544 0.098220 0.625245 -0.805397 0.6476584 -0.0090092 -0.5702082 0.5052920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1644 2344 0.093780 -0.462094 0.774257 0.6982271 0.0165099 0.4224616 0.5776959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1645 1634 -0.474386 -0.730412 -0.358729 -0.4796419 0.5731387 0.6043676 0.2760353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1645 2345 -0.801272 0.452826 0.274256 -0.3138764 -0.1689853 0.6522382 0.6689626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1646 1546 0.195518 -0.692604 -0.823719 -0.5807364 -0.2214741 -0.2766032 0.7329291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1646 1673 0.856295 0.565335 -0.409926 -0.4158653 0.0428538 0.2682246 0.8679142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1647 1672 0.240400 -1.029537 0.086888 0.7627451 0.4998244 -0.3952126 0.1104648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1647 2347 -0.828141 -0.237282 0.589688 -0.5356198 0.4143338 0.6095350 0.4121966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1648 1671 0.438330 -0.214668 -0.888251 0.3210548 0.4307303 0.8051382 0.2512919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1648 2348 0.662049 0.671992 0.228136 -0.2712714 -0.2993210 0.0774598 0.9114926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1649 1670 0.058918 -0.841872 -0.657165 0.0662103 -0.5164156 0.8368463 0.1691724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1649 2349 0.396847 -0.308105 0.733429 -0.1678876 -0.0356338 -0.5306568 0.8300285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1650 2350 0.313825 0.878588 0.448886 0.5268315 0.6838047 0.4009968 0.3066941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1651 1668 0.230266 -0.061313 -0.914844 0.1875730 0.1850736 0.0225975 0.9643928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1651 2351 0.943896 0.484294 0.046175 -0.3371597 0.2472337 0.6007769 0.6813707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1652 1552 -0.794072 -0.745968 -0.082395 0.2250279 0.0641665 0.7973506 0.5563067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1652 1667 -0.257534 0.394292 -0.974471 -0.3673964 -0.4465285 -0.7592190 0.2986948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1652 2352 0.920210 0.802069 0.117373 0.0564834 0.1397271 -0.5106726 0.8464629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1653 1666 -0.024742 -0.267511 0.802454 0.7727492 0.0395319 0.6178732 0.1397448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1654 1665 -0.092073 0.374912 1.003902 0.4499736 -0.4372529 -0.5620961 0.5388707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1654 2354 -0.487078 -0.779451 0.404182 0.6402437 -0.5661051 -0.4042439 0.3258833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1655 1664 -0.620183 0.627890 0.672103 0.1302246 0.3545441 -0.2155229 0.9004943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1655 2355 -0.300531 -0.909215 0.495008 0.8821141 -0.0120073 0.3368967 0.3289849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1656 2356 0.053818 0.625654 0.797581 -0.5310839 -0.4346449 0.4104524 0.6004686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1657 1662 -0.781956 0.306521 -0.492650 -0.0837315 0.5224363 -0.5162036 0.6734859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1657 2357 -0.533055 -0.931096 0.282003 -0.0967230 -0.5479267 -0.0865683 0.8263939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1658 1661 1.155291 0.125828 0.313017 0.2125149 -0.5649426 0.3464596 0.7180829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1659 2359 0.826522 0.580604 0.137186 -0.3413766 0.4681110 -0.2389210 0.7792630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1660 2320 -0.513514 -0.164228 0.922406 0.7801808 -0.1739437 -0.3681854 0.4748695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1661 1698 0.224259 -0.654884 -0.527253 0.0616050 0.0024736 0.5747452 0.8160066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1662 2322 0.441951 -0.656431 0.189541 0.0492696 -0.0150394 -0.7306242 0.6808338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1663 1656 -0.216747 -0.833690 -0.649435 -0.2298553 -0.0238963 0.9459961 0.2273474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1663 1696 0.282092 0.797224 0.512530 -0.4266200 0.1801530 0.7703928 0.4382182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1664 2324 -0.148510 -0.950344 0.340021 -0.0841996 -0.1705922 -0.0447114 0.9807189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1665 2325 0.734921 0.284971 0.512414 -0.3171349 0.7291559 -0.5409555 0.2740882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1666 1526 -0.525298 0.727120 -0.572018 -0.3084501 0.1289343 -0.7668040 0.5479471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1666 1693 0.726720 0.647169 -0.164955 0.2636505 -0.3506226 0.8455772 0.3042228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1666 2326 0.586409 -0.840785 0.436423 0.1356650 0.0959666 -0.4872863 0.8572849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1668 1691 0.494130 -0.279924 -1.006410 -0.5237855 -0.7797958 -0.2649071 0.2176958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1668 2328 0.786871 0.593691 0.212174 -0.6153407 0.5169886 0.3414584 0.4873241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1669 1690 0.033989 -0.457640 0.868556 -0.4735803 -0.3604323 -0.8029154 0.0337209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1670 1689 -0.260649 0.727573 0.469558 -0.4704713 -0.2133017 0.4026190 0.7556832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1670 2330 -0.242746 -0.387168 0.884641 0.1006989 -0.5369166 0.5720820 0.6118027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1671 1688 -0.619762 -0.880020 -0.202062 -0.3933595 0.1699354 -0.5948815 0.6800781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1671 2331 0.135113 -0.193041 0.885783 0.7025815 0.0963956 0.7039913 0.0385146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1672 1687 -0.685086 0.657229 0.254747 0.6770293 -0.6433078 0.1137473 0.3388921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1672 2332 -0.733739 -0.778140 0.197428 0.8234280 -0.3791585 -0.0321737 0.4209156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1673 1686 1.066702 0.156482 0.033469 0.1240787 -0.3131747 0.5900148 0.7337633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1674 1645 -0.688228 0.595341 -0.464805 0.8044689 0.1692717 -0.0415008 0.5678509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1674 2334 -0.472274 -0.754381 0.412105 -0.1822397 0.6793038 -0.6318509 0.3257292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1675 1535 -0.767514 -0.683115 -0.096446 -0.7315572 -0.6330300 -0.1341541 0.2147085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1675 1644 -0.011373 0.178031 -1.001465 0.4709376 0.1871483 0.8470346 0.1603921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1675 1684 0.122647 -0.164512 0.986937 0.1977636 0.9570211 0.1070576 0.1831364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1675 2335 0.643531 0.824108 0.201136 -0.5255586 0.7450335 -0.0943543 0.3997629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1676 1683 0.493540 -0.081735 -0.913511 0.1021430 0.7731894 -0.6012853 0.1737844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1676 2336 0.736869 -0.602062 0.380070 0.2247974 0.3391737 -0.0862852 0.9093856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1677 1682 0.479230 -0.233054 -0.903219 -0.1399174 -0.1177250 0.5421253 0.8201611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1677 2337 0.647093 0.449703 0.283818 0.4360413 -0.5552027 0.6850701 0.1797134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1678 1681 0.662469 0.366745 0.670120 0.1148107 -0.3743644 0.5435045 0.7424774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1678 2338 -0.718515 0.554838 0.594434 0.0334102 -0.6658312 -0.6052214 0.4350397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1679 1640 -0.628502 0.592330 -0.199270 -0.2706632 -0.0051578 -0.8845830 0.3797733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1679 2339 0.282196 0.316358 0.798607 0.4364227 -0.2458410 0.0402145 0.8645694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1680 1500 -0.288360 -0.738136 -0.457559 -0.4205574 -0.1730579 -0.5798727 0.6759660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1680 1719 -0.225754 -0.655938 0.780761 -0.4300100 0.6016670 0.3162399 0.5942059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1681 1718 0.744101 -0.640111 0.124738 -0.1879621 -0.4116485 -0.2795149 0.8468100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1681 2301 0.693043 0.877644 0.186330 -0.3721933 0.3797132 -0.6831883 0.5005436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1682 1502 -0.724816 0.551952 0.003028 -0.5094041 0.5924452 -0.3549016 0.5133820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1682 1717 -0.115299 -0.061982 -0.900267 0.0018146 0.2733262 -0.8348161 0.4778824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1682 2302 0.603771 -0.574980 0.169928 0.3511117 0.8561844 -0.1584108 0.3443471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1683 1716 -0.080050 1.008578 0.318947 0.8581106 -0.3529247 -0.3059504 0.2132714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1684 2304 -0.444338 0.766503 0.272573 0.2262747 -0.6777964 -0.3336669 0.6148644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1685 1714 0.011594 -0.860794 -0.066414 -0.0233250 0.4408849 0.4772920 0.7597821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1686 1713 0.136884 -1.134005 -0.406046 -0.4419452 0.3139270 -0.5625548 0.6242327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1686 2306 0.613390 -0.126818 0.883458 -0.3617979 0.3553764 -0.8368775 0.2060240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1687 2307 0.357944 0.917508 0.459114 -0.2002102 -0.2766563 -0.0623240 0.9378128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1688 2308 0.517237 -0.490572 0.698940 -0.2769992 0.2542634 0.0828184 0.9229099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1689 1710 0.425663 0.054666 0.829427 0.6427801 -0.0549957 -0.4476684 0.6191948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1690 1510 -0.514815 0.502297 -0.315103 0.3735244 0.2433498 -0.4173942 0.7918601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1690 1709 0.590870 0.818928 0.030131 0.0521000 -0.9064096 0.4116516 0.0790585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1690 2310 0.591025 -0.638910 0.179160 -0.2020598 0.4238653 -0.7586283 0.4516560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1691 1708 -0.872653 0.403201 0.465846 -0.2936310 -0.3834466 -0.7748944 0.4077846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1691 2311 0.483596 0.980310 0.088816 -0.6436951 0.4296217 -0.0867511 0.6273404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1692 1667 0.164298 -0.880562 0.617308 -0.1292628 -0.2284518 -0.8445897 0.4666574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1692 1707 -0.342406 0.856724 -0.649380 0.3358129 0.6652704 0.5527765 0.3729384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1692 2312 0.474305 0.542105 0.613378 -0.2404111 -0.1198256 0.9627559 0.0307465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1693 1706 -0.429950 -0.639255 -0.460115 0.3992149 0.5090617 -0.7517379 0.1279600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1694 1665 1.046006 0.225647 0.167760 -0.3659892 -0.0946765 0.5081979 0.7738367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1695 1664 0.671203 0.077703 0.717333 -0.5912402 -0.2554825 -0.1670185 0.7465042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1695 1704 -0.491420 -0.065637 -0.813570 0.3436294 -0.1134360 0.8533664 0.3752557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1695 2315 -0.709747 0.068240 0.587686 0.4586041 0.0838900 -0.7283660 0.5021233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1696 2316 -0.623276 0.756364 0.361275 -0.0882296 -0.5999137 -0.1561662 0.7796994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1697 1517 -0.101006 1.046493 -0.159290 0.5445128 -0.0934998 -0.6327997 0.5425202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1697 1662 -1.104836 -0.109859 0.181419 0.1441445 -0.3868175 -0.2130660 0.8855492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1697 1702 1.000033 0.224857 -0.169843 0.2598806 -0.1307783 0.1761954 0.9403799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1697 2317 0.136041 -1.082059 -0.058918 0.3265729 0.2601293 0.4392782 0.7954355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1698 1701 -0.420962 -0.762438 -0.467424 -0.1457024 0.1954737 0.8167306 0.5229837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1699 1519 -0.505757 0.491276 -0.606945 -0.1241012 0.3920694 0.3671509 0.8343145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1699 1660 0.460028 -0.473993 -0.945057 0.0083090 0.4281946 -0.8884619 0.1649719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1699 2319 0.388465 -0.380996 0.872489 0.0698933 0.0190874 -0.5914439 0.8030845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1700 2280 -0.954022 -0.658577 -0.180275 0.5986090 -0.5305795 -0.3698951 0.4725784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1701 1738 -0.008989 0.695184 -0.687015 0.2459739 0.6215100 0.5846638 0.4597721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1701 2281 -0.316284 0.725888 0.815399 -0.4427477 -0.5442845 -0.0008705 0.7125504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1702 1482 0.061144 0.819055 -0.724442 0.0106818 0.7567683 -0.4085460 0.5101742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1702 1737 0.987352 -0.393383 -0.257974 -0.1338963 0.0020946 -0.9644506 0.2278210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1702 2282 -0.110222 -0.810015 0.549023 -0.4605173 -0.7434371 0.4829035 0.0450466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1703 1696 0.229611 0.966713 -0.587238 0.2342646 -0.0757855 0.0214111 0.9689779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1703 1736 -0.323546 -0.790210 0.537563 -0.0910344 0.0953910 0.5267655 0.8397210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1703 2283 -0.685494 0.415998 0.346193 -0.2546309 0.3225000 0.1806769 0.8935954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1704 1735 -0.150879 0.418469 -0.992614 0.2839674 0.7434925 -0.1229715 0.5928401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1704 2284 0.557264 0.511177 0.017252 0.7852337 -0.1291644 0.6054905 0.0102878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1705 1694 -0.628294 0.166421 -0.735958 -0.3484936 0.5203877 0.7255033 0.2852958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1705 1734 0.477685 -0.214424 0.778273 0.3491898 0.4702177 -0.4820390 0.6516135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1705 2285 -0.755933 0.026022 0.606337 -0.1414638 0.3043152 0.9360235 0.1060205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1706 1733 0.384488 0.339998 0.982196 -0.2966485 -0.5434475 0.5279877 0.5812860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1706 2286 -0.337208 -0.827160 0.314517 0.1775725 -0.1323226 0.9575564 0.1845113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1707 2287 0.106434 0.725085 0.686804 -0.1893907 -0.3341276 0.6849631 0.6191248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1708 1731 0.677004 -0.789381 0.274762 0.4598635 -0.0953076 -0.0255963 0.8824890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1708 2288 -0.490058 -0.093342 0.779417 -0.2371414 -0.1257836 -0.9099792 0.3160385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1709 1730 -0.654701 0.466970 -0.821363 -0.4681996 0.1000701 0.6230143 0.6185695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1709 2289 -0.808119 -0.718112 0.203105 0.2416206 0.5261016 -0.6950901 0.4262468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1710 1490 0.043179 -0.222720 -1.145030 -0.4440259 -0.0569673 -0.6943728 0.5634200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1710 2290 -0.119090 0.041704 0.917143 0.4283615 -0.1306724 0.4133277 0.7928375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1711 1688 0.678333 -0.673992 0.025515 0.1656543 -0.4846293 0.8543526 0.0881745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1711 1728 -0.539461 0.676473 0.106526 0.5097800 -0.0483000 0.1056315 0.8524280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1711 2291 -0.326321 -0.290386 0.919601 0.5920585 -0.1432125 0.0763178 0.7893874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1712 1687 -0.063501 -0.796222 -0.573565 0.6270836 -0.3882556 -0.2826526 0.6132954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1712 1727 0.176043 0.660437 0.703167 -0.7275751 -0.1111651 0.6646809 0.1283594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1712 2292 -0.392860 -0.744569 0.508045 0.7298572 0.1663372 -0.0063556 0.6630233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1713 1726 0.864275 0.604714 -0.204845 -0.7138754 0.4840731 -0.4669141 0.1950547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1713 2293 0.437319 -0.361779 0.978756 -0.2737511 -0.4693157 -0.6515263 0.5294493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1714 1494 0.903624 -0.522452 -0.062031 0.2756406 -0.7355251 0.2697856 0.5569927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1714 1725 -0.442113 -0.700125 -0.639192 -0.8402602 0.4423251 0.3125727 0.0246894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1714 2294 -0.824845 0.552989 -0.099189 -0.3722026 -0.8409988 -0.1460193 0.3645061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1715 1495 -0.937820 0.385624 -0.092314 0.8220021 0.3330281 -0.1540219 0.4355250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1716 2296 -0.531675 0.864970 0.109184 0.4495393 -0.7001821 -0.0498525 0.5524257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1718 1721 0.630039 -0.244475 -0.670552 0.2174010 0.3071065 0.8708669 0.3162488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1718 2298 0.263213 0.882350 0.084242 -0.3649591 0.3322126 0.3461022 0.7979053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1719 2299 -0.683274 -0.215241 0.763133 0.3198682 0.5075280 -0.5078020 0.6182529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1720 1460 0.163452 0.183081 -1.000727 0.2002343 -0.2428769 0.4898950 0.8129699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1720 1759 -0.995703 0.113720 0.083083 -0.1807321 0.5096690 -0.2265346 0.8100960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1720 2260 -0.205557 -0.148462 1.097921 -0.2245113 -0.4119053 0.2880359 0.8348437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1721 2261 0.404818 -0.531634 0.674956 0.2063649 0.2223955 -0.9436002 0.1325606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1722 1717 0.163307 -0.130669 0.867014 -0.2184290 -0.2827174 0.9173733 0.1754588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1722 1757 -0.099620 0.005006 -1.056392 0.0895080 0.0891370 -0.3708275 0.9200706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1722 2262 -0.644545 -0.816629 -0.011496 0.7892070 -0.0048181 0.2820907 0.5454850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1723 1463 0.096357 -0.971967 -0.426004 -0.0624634 -0.1410703 0.9808940 0.1185093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1723 1716 0.867260 0.254474 -0.657973 -0.0569167 0.4397300 -0.1423981 0.8849411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1723 1756 -0.851883 -0.261902 0.548017 -0.7284021 -0.4319056 -0.0086967 0.5318011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1723 2263 0.093535 0.905429 0.420203 -0.0953991 -0.1876702 -0.4480669 0.8688585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1724 1715 -0.067239 -0.889165 0.055875 -0.5668747 -0.3258032 0.0461359 0.7552330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1724 1755 -0.155508 0.811184 -0.139147 -0.5669117 0.0483879 0.5747321 0.5881775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1724 2264 0.529611 0.046839 0.840107 -0.1164628 0.0229148 0.2768923 0.9535418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1725 1754 0.581765 0.690980 0.575462 -0.3184872 0.0910625 -0.3385856 0.8807005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1725 2265 -0.669752 0.382477 0.545977 0.2849359 -0.0585878 0.1978405 0.9360759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1726 1753 -0.422786 -0.594754 0.857445 0.3710972 0.5715801 0.5607069 0.4703093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1726 2266 0.640087 -0.593406 0.231847 0.4537494 0.8005481 -0.0584089 0.3870693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1727 1752 -0.485847 -0.751637 -0.059985 0.6323849 -0.4437861 -0.1474554 0.6175759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1728 1468 -0.026817 -0.816621 -0.796503 -0.2342101 -0.3879290 -0.1943417 0.8699931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1728 1751 -0.758681 0.422477 -0.452123 -0.3159743 -0.1530290 0.6219384 0.6999536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1728 2268 -0.018279 0.779457 0.430548 0.0740111 0.2435196 -0.9398507 0.2278185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1729 1469 -0.697171 -0.622519 -0.534050 -0.2130893 0.2820715 -0.8391337 0.4133803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1729 1710 -0.291879 0.893188 -0.343627 -0.4497104 -0.3687485 -0.8127533 0.0348878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1730 2270 -0.696485 0.465824 0.103119 -0.6042516 0.7627757 0.1888440 0.1318755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1731 1748 0.660036 -0.148624 0.817899 -0.1749967 -0.3501478 -0.9156085 0.0918353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1731 2271 -0.280142 0.704875 0.691838 -0.7399774 0.0110259 0.6304697 0.2341364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1732 1707 0.031568 -0.551454 -0.820297 0.3902204 -0.1448344 0.8602413 0.2945098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1732 1747 -0.258147 0.560680 0.641254 -0.1445574 -0.0344955 0.9555459 0.2546473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1733 2273 -0.573255 -0.355644 0.695754 -0.0277937 -0.1681903 0.6043726 0.7782501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1734 1474 0.594820 0.957906 0.119537 0.9487542 -0.2641358 -0.1440014 0.0967538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1734 1745 -0.548350 0.544013 0.650048 -0.5930319 -0.6422917 0.0823910 0.4785251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1734 2274 -0.646092 -0.812486 0.107040 -0.6124652 -0.5340007 0.4928379 0.3111919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1735 1744 0.833895 0.099380 -0.097244 -0.5342365 0.0517923 -0.7937076 0.2862468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1735 2275 0.015580 0.857911 0.266449 -0.2836565 -0.0490758 0.7497618 0.5958085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1736 1743 -0.978549 -0.235227 0.254713 -0.7788534 -0.3877967 -0.0924981 0.4841953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1736 2276 0.099470 0.831120 0.633858 -0.8130232 0.0678098 -0.5450891 0.1930621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1737 1742 -0.590699 0.715519 -0.132336 0.1411176 -0.0884631 -0.8464755 0.5057068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1737 2277 0.583221 0.393985 0.320974 -0.4863241 0.0328823 0.6513444 0.5815137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1738 1741 0.952223 -0.463880 0.229176 0.3534437 0.4881773 0.5239747 0.6018397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1738 2278 0.598752 0.861716 0.354481 0.4242275 0.4633748 0.3581666 0.6906747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1739 1700 0.638949 0.564095 0.160481 -0.8278344 0.2204900 -0.0164866 0.5155604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1739 2279 -0.618512 0.492110 0.657214 -0.0006214 -0.8043403 -0.3694866 0.4653128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1740 1779 0.576755 0.457593 -0.432257 -0.4990498 0.4407047 -0.1659506 0.7274538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1740 2240 0.168139 0.695109 0.543638 -0.1161623 -0.4782023 -0.0738660 0.8673942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1741 1778 -0.641783 -0.060578 0.681758 0.0090612 0.5136160 -0.8499619 0.1169673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1741 2241 0.836773 0.076394 0.691648 -0.1389314 -0.3501946 -0.5529616 0.7431657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1742 1442 0.673721 -0.216880 -0.371893 -0.5399982 0.6665411 0.4530713 0.2425929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1743 1776 -0.734010 -0.803201 0.092025 -0.0944561 0.1275760 -0.8748391 0.4576668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1743 2243 0.695618 -0.539986 0.391146 0.5440370 -0.5294866 0.5107593 0.4034757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1744 1775 -0.308648 0.316864 0.775312 0.2724494 0.4958546 -0.2901982 0.7718060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1744 2244 -0.258155 -0.934273 0.483229 -0.3667030 -0.3025573 0.7884094 0.3903827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1745 1774 0.881993 -0.717491 0.219631 0.2949406 0.7737848 -0.5449695 0.1314360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1745 2245 -0.713006 -0.845087 0.082291 -0.1036961 -0.6977766 0.7034980 0.0862875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1746 1773 0.523919 -0.807019 0.204929 0.5127391 0.1351065 -0.8448551 0.0711675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1746 2246 -0.693706 -0.663239 0.161825 0.4360894 -0.5940983 -0.3141476 0.5984852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1747 2247 -0.413419 0.840381 0.430519 -0.5306487 0.6597367 0.2345687 0.4776369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1748 1771 -0.256178 0.813684 0.423393 0.0876770 -0.1014106 -0.2868131 0.9485604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1748 2248 0.716160 -0.300452 0.672830 -0.5259123 0.3579533 -0.5060792 0.5823826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1749 1730 -0.499846 -0.166992 0.712281 -0.7402236 -0.5457004 0.3919964 0.0248776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1749 1770 0.683217 0.214731 -0.657808 0.2942343 0.6650152 -0.5347613 0.4303619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1749 2249 0.375149 -0.912422 0.227684 -0.3990020 0.5706686 -0.2115810 0.6858339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1750 1450 -0.145935 0.222465 -0.930836 -0.2375449 0.0222830 0.5124176 0.8249267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1750 1729 0.863778 0.003071 -0.074597 -0.0605269 -0.4771130 -0.6859295 0.5460772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1750 1769 -1.063210 -0.140633 0.007331 -0.1255350 -0.1156859 -0.6564059 0.7348394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1750 2250 0.106767 -0.334709 0.891801 0.0211137 0.0673081 0.1802366 0.9810905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1751 1768 0.461941 0.958808 0.155117 -0.1147331 0.4719465 -0.1879315 0.8536888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1751 2251 0.595791 -0.351763 0.715887 0.7501578 0.2379774 0.2893250 0.5449046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1752 1452 0.777669 -0.529220 -0.225324 0.0960205 -0.9385013 -0.3127359 0.1104159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1752 1767 0.554226 0.016615 0.887118 -0.6386835 -0.1547101 0.4693909 0.5897630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1752 2252 -0.635307 0.701929 0.159817 0.4051518 -0.6436671 -0.0626862 0.6462315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1753 1766 -0.433489 0.656727 -0.473554 -0.0061342 -0.0269994 -0.9588240 0.2826479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1754 1765 0.099450 0.559264 0.872817 0.3694730 -0.7633908 0.4073198 0.3388432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1754 2254 -0.770093 -0.604136 0.458434 -0.1380987 -0.2711775 0.3586830 0.8824613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1755 1764 0.665284 0.013713 0.808009 0.5844045 -0.5944136 0.5376788 0.1266702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1755 2255 -0.311245 -0.969007 0.000068 0.8966726 -0.4309910 -0.0739973 0.0689154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1756 2256 0.798848 -0.278829 0.644288 -0.4091701 0.3248205 -0.5685967 0.6354284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1757 1762 0.005014 0.045847 -1.055994 0.5230805 0.0512002 0.7015310 0.4812687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1757 2257 0.043869 -1.075041 0.357063 0.2551431 0.7777959 -0.4043965 0.4079203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1758 1721 0.192404 -0.962722 -0.050875 -0.6118464 0.1683432 -0.7451716 0.2049971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1758 2258 0.665227 0.313845 0.718649 0.3600370 0.7837848 0.3535538 0.3620145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1759 1459 0.485735 0.433868 -0.419601 0.7015036 0.3347537 -0.4722635 0.4156921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1759 2259 -0.663205 -0.536087 0.375679 -0.0436489 -0.3485823 0.5540817 0.7547043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1760 1799 -0.239532 0.461712 0.928765 -0.1542643 0.2411378 -0.0111583 0.9580869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1760 2220 0.548651 -0.585367 0.812911 -0.0350222 -0.8519138 0.4846169 0.1953527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1761 1758 -0.470625 -0.670888 -0.498393 -0.0238049 -0.8718660 -0.2691764 0.4084447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1761 1798 0.336801 0.935709 0.536475 0.0081829 -0.6473982 -0.0597308 0.7597637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1761 2221 -0.833900 0.632461 0.147545 -0.7743401 -0.4392427 0.1890213 0.4144083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1762 1797 -0.891656 -0.402760 -0.574264 0.0882721 0.4198545 0.8066932 0.4064188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1762 2222 -0.476603 0.581630 0.430921 -0.8714012 -0.1667421 -0.1726265 0.4278516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1763 1756 0.748491 -0.943020 0.112454 -0.9057095 -0.1151276 -0.3980528 0.0893866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1763 1796 -0.676151 0.866924 -0.171699 0.8000213 -0.0547722 0.5274375 0.2806698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1763 2223 0.871222 0.707997 0.233598 -0.1704493 0.9131529 -0.1440647 0.3410928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1764 1795 0.383889 -0.633265 -0.010187 -0.2544242 0.3940313 0.1863571 0.8632952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1765 1794 0.440251 -0.248115 -0.676681 -0.4404319 0.3232314 0.5725694 0.6113145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1765 2225 0.793925 0.433755 0.477630 -0.2443954 0.5538711 -0.0839584 0.7914851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1766 1426 -0.602934 0.395627 -0.514666 0.6977181 -0.1361353 0.5573107 0.4290239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1766 1793 0.063055 -0.932432 -0.498083 0.7832588 -0.0283577 0.0757115 0.6164165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1766 2226 0.760447 -0.592420 0.617885 -0.5282604 0.2205125 -0.5242524 0.6304559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1767 1427 0.094532 0.252015 -1.058745 -0.2610051 -0.4584615 -0.8134878 0.2447999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1767 1792 -0.311067 -0.864273 -0.093761 -0.2891666 -0.1340426 0.5839429 0.7466096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1768 1428 0.336393 0.511373 -0.860704 -0.2667115 0.0688369 0.8144381 0.5107025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1768 1791 -0.363727 0.723320 0.474936 -0.4113912 -0.6691325 0.5516742 0.2804897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1768 2228 -0.196616 -0.544274 0.826049 0.0960582 0.3433912 0.0969121 0.9292273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1769 1790 0.139342 -1.000421 -0.066343 -0.3123342 0.5447881 -0.2703849 0.7297570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1769 2229 0.650838 -0.042739 0.822623 -0.0558532 0.5783232 0.5938529 0.5565622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1770 2230 -0.039027 -0.021417 1.087016 0.1591326 0.4192390 0.6817482 0.5780439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1771 1431 -0.638954 -0.316409 -0.738744 0.2467296 0.7909571 -0.2254868 0.5125105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1771 1788 -0.846595 0.690977 0.727496 0.0329901 -0.5968427 -0.7808453 0.1815793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1772 1747 -0.497974 0.589659 0.645089 0.1346487 0.8830147 0.0685865 0.4443542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1772 1787 0.597055 -0.647320 -0.751417 -0.3800489 0.2995677 0.4222164 0.7665216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1772 2232 0.846358 0.406295 0.150408 0.0493165 0.8846800 0.1521697 0.4378968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1773 1786 -0.846673 0.878476 -0.445189 -0.3983541 -0.1699435 -0.7716729 0.4657833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1773 2233 0.043632 0.445588 0.874004 0.4548301 -0.2216259 -0.5593133 0.6566431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1774 1785 -0.825960 -0.044547 0.511825 0.2623562 0.3132031 0.4296657 0.8052704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1774 2234 0.317782 -0.689509 0.938481 0.2000596 -0.0052909 -0.8890630 0.4117222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1775 1784 -0.937736 -0.073740 -0.338826 0.7128017 0.1153731 -0.2130441 0.6581907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1775 2235 -0.245660 -0.738511 0.463479 0.6821457 -0.4492586 0.0006022 0.5769260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1776 1436 -0.148533 -0.747057 -0.478175 -0.3280016 0.5130985 0.3275938 0.7223761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1776 1783 0.990612 0.047568 -0.054172 0.2773459 -0.0238741 0.9239757 0.2622558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1776 2236 0.201093 0.597019 0.679243 -0.3277232 0.5281679 0.5850161 0.5209533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1777 1742 -0.499915 -0.368346 0.913813 0.1283243 -0.6402659 -0.7563858 0.0383787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1777 2237 0.802873 0.640753 0.645198 0.0410783 0.4484420 0.7590014 0.4702437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1778 1781 0.362881 -0.602226 0.207409 0.1041917 -0.8597245 -0.1253251 0.4840573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1778 2238 -0.888738 -0.441949 0.146803 0.3418699 -0.3767249 -0.8264612 0.2411746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1779 2239 -0.944336 -0.395099 0.623573 0.0748674 0.3688815 0.7637941 0.5243471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1780 1819 0.572350 -0.500952 0.802678 0.7731738 0.4812372 0.3880953 0.1414038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1781 1818 0.327760 -0.549981 -0.817958 0.6326898 0.1249272 0.7401593 0.1904234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1781 2201 0.769695 -0.419059 0.604925 -0.0913573 0.6970880 -0.4619901 0.5406360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1782 1817 0.496393 0.635037 -0.659403 -0.3210875 -0.7051008 -0.6192157 0.1277012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1782 2202 -0.662798 0.925667 0.068857 -0.4364969 0.5058847 0.7238824 0.1718874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1783 1816 -0.738585 -0.435899 0.276266 -0.1977122 0.8369651 -0.3346952 0.3851992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1783 2203 0.636239 -0.534718 0.307931 0.0305828 0.1002681 -0.9369495 0.3333717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1784 1404 0.593372 -0.405625 -0.760852 -0.1043834 -0.1577456 0.7351476 0.6509827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1784 1815 -0.677779 -0.644205 0.136826 -0.2203905 -0.6512800 -0.7261280 0.0007097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1784 2204 -0.641778 0.287665 0.719480 0.5670887 -0.3584269 -0.4614672 0.5805071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1785 1405 0.750539 0.029441 -0.794403 -0.2534037 0.1450457 -0.4418339 0.8482518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1785 1814 -0.487142 0.839555 -0.444073 -0.5264869 -0.4442560 0.7224493 0.0592886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1786 1813 -0.930124 -0.722378 -0.051055 -0.1605532 0.0893757 0.7312862 0.6568525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1786 2206 0.346798 -0.259578 0.902628 0.7018439 0.1499214 -0.4676493 0.5159872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1787 2207 0.325601 -0.777160 0.578438 -0.5558927 0.5947614 -0.5158844 0.2666559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1788 2208 -0.823274 0.660462 0.203782 -0.3715970 0.7001491 0.2861892 0.5383331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1789 1770 -0.711207 0.018500 -0.492286 0.1706146 -0.2200609 -0.5719102 0.7716104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1789 1810 0.848882 -0.124328 0.631497 0.0432988 -0.5562357 -0.7902953 0.2532991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1789 2209 -0.541342 0.133033 0.839241 0.4344451 0.1739927 -0.0467834 0.8824938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1790 1809 0.701890 -0.779505 -0.113873 0.7304634 -0.1842658 -0.0841669 0.6522157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1790 2210 -0.273519 -0.335570 0.692397 0.7212607 -0.0525666 -0.6532978 0.2241019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1791 1808 0.611407 -0.524668 -0.422296 0.8112182 0.2422627 0.2035646 0.4917268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1791 2211 -0.461318 -0.988672 0.225039 0.5882370 0.3957182 -0.3681218 0.6015569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1792 1807 -1.063268 0.364135 -0.152791 -0.0693647 -0.2530799 -0.5674669 0.7804617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1792 2212 -0.392169 -0.357735 0.844011 0.8322453 0.2437808 -0.1128671 0.4849740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1794 1805 0.692766 -0.393133 -0.803224 0.7618824 0.1865666 0.3586509 0.5060609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1794 2214 -0.281843 -0.981595 0.318551 0.2686130 0.3208961 -0.0428429 0.9072140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1795 1804 -0.054524 -0.865522 0.046102 -0.1013534 0.4313855 0.4572523 0.7710736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1795 2215 -0.010977 -0.113458 1.010439 0.1941669 -0.3628171 -0.7899128 0.4546435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1796 2216 0.704395 -0.674415 0.099958 0.0765146 -0.2029150 0.2225957 0.9504852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1797 2217 0.636868 0.606813 0.347234 -0.1529319 0.0028876 0.9633878 0.2201987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1798 1801 0.264808 0.841314 -0.357509 0.1069098 -0.3229670 0.7248171 0.5990849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1800 1380 -0.439831 0.642515 -0.266016 -0.0253755 0.1335297 -0.5368746 0.8326414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1800 1839 -0.308888 0.062664 0.989772 -0.0611802 0.3261063 -0.8464666 0.4164204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1800 2180 0.435710 -0.729777 0.458813 -0.4193294 -0.1432834 -0.7801566 0.4415750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1801 2181 0.678972 -0.213942 0.340503 0.1776707 -0.1817120 0.3293086 0.9093788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1802 1382 0.076609 -0.806946 -0.811865 0.4363967 -0.0036168 0.5485947 0.7131541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1802 1797 0.787362 -0.632837 0.401108 0.3373786 0.1901175 0.6247867 0.6779916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1802 1837 -0.716028 0.565745 -0.251542 0.2015877 0.0859395 -0.8326353 0.5086210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1802 2182 0.213262 0.677627 0.700885 0.2458049 0.2443267 0.9365086 0.0532552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1803 1836 -0.008617 -0.722048 -0.536900 0.1054477 -0.5824710 0.7270233 0.3479159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1803 2183 0.550274 -0.597394 0.545605 0.8533085 0.2750608 -0.0323994 0.4417652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1804 1384 0.888107 -0.121568 -0.546588 0.0060794 -0.1122066 0.7725474 0.6249346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1804 1835 -0.435597 -0.888433 -0.681005 0.1754092 0.0189721 0.5597529 0.8096594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1804 2184 -0.830262 0.132010 0.370953 0.0256245 0.3785730 0.9022538 0.2048510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1805 1834 -0.191973 -0.362065 0.990899 -0.4162978 0.1931943 -0.0273410 0.8880454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1805 2185 -0.637321 0.869262 -0.039432 -0.0564228 -0.0487561 0.1169451 0.9903349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1806 1793 0.928804 0.072393 -0.030564 0.0949590 -0.5727757 -0.3296118 0.7444910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1806 2186 -0.018626 -0.028336 1.152086 0.3378327 0.0872710 0.8727801 0.3413323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1807 1832 -0.610107 -0.827936 0.160671 0.2024103 0.6254723 -0.6565304 0.3698410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1807 2187 0.667220 -0.453536 0.479514 -0.6357436 0.2671231 -0.6667545 0.2826902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1808 1831 0.315637 0.046995 0.856509 0.0011688 -0.1957083 0.7509667 0.6306709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1809 1830 0.858220 -0.222479 0.335901 -0.3150178 0.3064732 0.8974312 0.0381478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1809 2189 -0.129428 0.959452 0.282609 0.0012608 0.3716978 0.5491618 0.7485055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1810 2190 0.393699 0.516773 0.542745 0.0120769 0.9283230 0.3576728 0.1007006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1811 1391 -0.169505 -0.524344 -0.959097 0.3431142 0.3025465 -0.5636899 0.6877441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1811 1828 -0.201461 -0.798979 0.538776 -0.5434944 -0.3269180 -0.4543041 0.6255767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1811 2191 0.262292 0.702612 0.822807 0.2438694 0.1930772 0.5397200 0.7822731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1812 1787 0.600710 0.368213 0.732852 0.0248835 0.3494656 -0.4387459 0.8275002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1812 1827 -0.633529 -0.409544 -0.651665 0.1991418 0.3271264 -0.8187503 0.4277603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1812 2192 -0.047792 -0.864180 0.397356 -0.0015301 0.9005026 -0.4171952 0.1226409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1813 1826 -0.663151 0.734485 -0.345394 0.0307712 0.1345757 -0.6847478 0.7155858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1813 2193 -0.725562 -0.326543 0.653912 -0.0141722 -0.1335756 0.2765940 0.9515527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1814 1394 0.332524 0.695914 -0.479180 0.6405916 -0.3191163 -0.1438575 0.6834561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1814 1825 0.652581 -0.554852 -0.277528 -0.2426408 -0.9161094 0.3187870 0.0156161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1814 2194 -0.294489 -0.827604 0.710896 0.5121669 -0.4139107 -0.3407079 0.6710299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1815 2195 0.795640 0.468857 0.439535 0.0279055 -0.7543302 -0.6554128 0.0253236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1816 1396 0.184498 0.831087 -0.580620 -0.2029795 0.5691752 -0.5652445 0.5615493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1816 1823 0.590593 -0.605387 -0.658897 -0.2320391 0.1519317 0.9339433 0.2254430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1817 1822 -0.474202 -0.185277 0.724074 0.5607896 0.6966761 0.1750419 0.4117252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1817 2197 0.974551 -0.215445 0.544554 0.1055194 0.6643055 0.5640011 0.4790268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1818 1821 -1.056458 0.319213 -0.099395 0.1669835 -0.3309874 -0.9169748 0.1473806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1820 1859 0.731264 -0.174050 -0.779939 0.2754968 -0.1224160 0.8218332 0.4834315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1820 2160 0.688010 -0.018481 0.661331 -0.1178245 0.4705222 -0.8637860 0.1363821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1821 1858 0.612548 -0.312593 0.696003 -0.4447987 -0.4051010 0.1485440 0.7848452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1822 1857 -0.554553 0.085737 -0.799501 -0.4826574 -0.1246371 -0.8641122 0.0694082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1822 2162 -0.441862 0.915730 0.363639 0.1626629 -0.5878804 -0.6871551 0.3946585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1823 1856 -0.195131 0.054605 -1.056467 -0.8091893 -0.5115247 0.0059348 0.2889981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1823 2163 -0.377767 0.837869 0.004983 -0.7098622 0.0950514 0.0949877 0.6914031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1824 1815 0.817477 0.370857 -0.259785 -0.6783195 0.2117617 -0.6502288 0.2687792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1824 1855 -0.937228 -0.286047 0.393994 -0.3652941 0.0375832 -0.7666103 0.5267413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1824 2164 0.492111 -1.063091 0.150150 0.6957458 -0.0029234 0.7169046 0.0444636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1825 1365 0.081481 0.814865 0.043953 0.9414117 0.2242585 -0.0124534 0.2515889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1825 1854 -1.193018 0.004350 0.111090 -0.5635700 -0.6921183 0.4390996 0.1027257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1826 1853 -0.752728 -0.648249 -0.388933 -0.2446085 -0.2682371 0.5215286 0.7721550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1826 2166 0.438551 -0.803090 0.771901 0.8232784 0.2724786 -0.2665140 0.4206404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1827 2167 0.347485 0.209864 0.851608 -0.4049033 -0.4082027 -0.7517430 0.3229648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1828 1368 -0.739791 -0.119482 -0.647836 0.3063311 -0.0556412 0.8436136 0.4374716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1828 2168 0.679216 -0.165294 0.799003 0.5747039 0.2519852 -0.0268840 0.7781363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1829 1810 0.281369 -0.662051 0.596928 0.0102291 -0.4569801 0.0368952 0.8886525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1829 1850 -0.453814 0.631276 -0.440383 -0.5530144 0.2945345 -0.5562959 0.5458566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1829 2169 -0.231684 0.398744 1.056787 -0.2675712 -0.2204912 0.3412965 0.8736738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1830 2170 -0.569799 -0.514936 0.804572 -0.2415391 -0.0043725 -0.3137721 0.9182520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1831 1848 0.220992 -0.562220 0.875724 0.1514568 0.9648100 0.0363471 0.2118525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1831 2171 0.716641 0.668154 0.218074 -0.7509018 0.0054360 0.0732862 0.6563125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1832 1847 0.330452 -0.508748 0.696693 -0.4237202 -0.0879991 0.8708086 0.2332588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1832 2172 -0.694291 0.270659 0.780901 -0.0823556 0.3508872 -0.9123475 0.1942105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1833 1806 0.362899 0.685966 0.056031 -0.2066655 -0.1530437 0.5822820 0.7712423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1833 1846 -0.505152 -1.043641 -0.020796 0.2331122 -0.5931961 -0.7671965 0.0720182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1833 2173 -0.420457 -0.009516 0.984563 0.3870518 0.0802417 -0.7393915 0.5450251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1834 1845 -0.361680 -0.839740 0.276864 -0.6095413 -0.0937249 -0.3112285 0.7230573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1834 2174 -0.817327 0.540894 0.362473 -0.0098893 -0.3542754 0.0808751 0.9315849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1835 1844 -0.748831 0.077843 -0.520401 0.8065014 0.3465745 0.4787408 0.0157763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1836 1843 -0.417610 0.734501 0.473274 0.2041013 -0.3505285 -0.3487771 0.8448828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1836 2176 -0.293196 -0.564632 0.540442 0.6940561 -0.0043582 -0.6373108 0.3348165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1837 1842 -0.029974 -0.981371 -0.164024 -0.1730926 -0.2632218 0.5593846 0.7667086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1837 2177 -0.748078 -0.076977 0.545233 -0.3534324 -0.4637651 -0.2752390 0.7643631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1838 1378 0.769165 -0.338871 -0.485715 0.3750421 -0.6647360 -0.4930567 0.4175698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1838 1801 0.126027 -0.133649 1.035154 -0.0327230 0.0699985 0.9966365 0.0272955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1838 1841 -0.176086 0.283894 -0.924119 -0.3080265 -0.2235429 0.8911048 0.2471445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1838 2178 -0.718688 0.408704 0.361014 -0.0216366 0.0928362 0.8093525 0.5795359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1840 1879 0.457733 0.535276 -0.283259 0.5343773 0.1125688 -0.2015378 0.8131123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1841 1341 -0.749484 0.289536 -0.471454 0.5027814 0.4990439 -0.3307690 0.6235045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1841 1878 0.727185 0.486444 -0.639966 0.2521706 -0.3464293 0.5992704 0.6762187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1841 2141 0.880445 -0.170763 0.706021 -0.2855425 0.2712634 0.6038295 0.6930163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1842 1342 0.279271 -0.350456 -0.945686 0.2295088 -0.4531285 -0.1668055 0.8450895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1842 1877 -1.054376 -0.038782 -0.286121 -0.1750040 -0.2573913 -0.4710860 0.8253492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1842 2142 -0.176599 0.197216 1.030268 -0.6356231 -0.1921941 0.1226462 0.7375653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1843 1876 -0.482675 0.459733 0.579345 -0.1937266 -0.6151897 -0.7631821 0.0395561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1843 2143 0.674218 -0.254736 0.776526 0.5751731 0.4022573 0.1673613 0.6923548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1844 2144 0.966122 -0.665365 0.252568 0.1616459 -0.1159192 0.7717620 0.6040006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1845 2145 -0.605607 -0.733273 0.326250 0.7412809 -0.0685502 -0.4504938 0.4928071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1846 1873 0.721173 0.342975 -0.749351 -0.2790692 0.6716192 0.0142016 0.6861825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1846 2146 -0.090848 0.905738 0.311887 -0.0981940 0.3234654 0.9410482 0.0125021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1847 1872 -1.108237 0.172852 0.010870 0.4147955 0.0062279 -0.7794956 0.4693532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1847 2147 0.114809 -0.064229 0.916228 -0.6257493 0.1308808 -0.6546690 0.4033815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1848 1871 -0.447802 -0.670982 -0.843606 -0.8046144 -0.3563915 0.2482943 0.4048835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1849 1830 -0.150474 0.368205 -0.636745 -0.7064203 -0.0005981 0.6946964 0.1355245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1849 1870 0.423880 -0.219411 0.806630 0.5764178 -0.4254027 -0.2022787 0.6677262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1849 2149 -0.648110 0.565149 0.553954 -0.6927191 -0.4560800 -0.3497118 0.4356981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1850 1869 -0.945722 0.360558 -0.083889 -0.3221029 -0.2847136 0.8829577 0.1886093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1850 2150 -0.218821 -1.001342 0.110696 0.1840475 -0.7496273 0.6280210 0.0988686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1851 1828 -0.209418 -0.728341 -0.480225 0.1814574 -0.5279127 0.6827157 0.4714665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1851 2151 -0.348486 -0.235620 0.692741 0.4010057 0.2721365 0.3107760 0.8176518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1852 1827 0.646740 -0.894816 -0.278994 0.0646467 -0.1537703 0.9497787 0.2647562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1852 1867 -0.622612 0.703716 0.267058 -0.1540038 0.1559781 0.5084687 0.8327144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1852 2152 -0.217235 -0.552413 0.862163 -0.4421015 -0.1000633 0.8904069 0.0413411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1853 1866 -0.961305 0.679618 0.014297 0.3025092 0.2170390 -0.6638521 0.6486005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1853 2153 -0.465626 -0.879338 0.187589 0.6238044 -0.7007531 0.0456845 0.3431124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1854 1865 0.361308 -0.892217 0.226598 0.7552545 -0.2093684 -0.0412852 0.6197185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1854 2154 -0.677868 -0.097220 0.538804 0.4709649 0.6003361 -0.5137389 0.3922513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1855 1864 0.547297 -0.650288 -0.568887 0.0840604 0.1759864 0.1525259 0.9688645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1855 2155 0.814431 0.796296 0.432063 -0.5324731 -0.4152524 -0.1941745 0.7115716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1856 1863 -0.363880 0.190090 0.860958 0.4881419 -0.2302323 0.5910068 0.5995178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1856 2156 0.677357 -0.636740 0.320211 -0.1095310 0.4062459 -0.2169448 0.8808531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1857 1357 -0.469970 0.754420 -0.159410 0.2796944 -0.3999825 -0.0538262 0.8711417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1857 1862 -0.291802 -0.241295 -0.801538 0.3439411 0.4114479 0.0040705 0.8440371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1857 2157 0.583606 -0.836190 -0.034187 -0.2969749 0.8871514 -0.3340131 0.1149064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1858 2158 0.247470 -0.264269 0.701688 0.6172018 -0.4334797 -0.2215628 0.6181159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1860 1320 0.546738 0.734041 -0.617303 -0.0382717 0.3475693 -0.3366079 0.8743146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1860 2120 -0.553470 -0.600475 0.599235 -0.1627427 -0.1386392 0.8686571 0.4469103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1861 1858 -0.371964 -0.280608 -0.929295 -0.1677933 -0.7291430 0.3945059 0.5334425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1861 1898 0.406879 0.083738 1.029769 0.1688448 0.1743264 -0.1694445 0.9551912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1861 2121 -0.749407 -0.514031 0.447056 -0.2699624 -0.1783514 -0.3562069 0.8766001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1862 2122 0.159831 -0.435406 0.834629 -0.2236305 -0.0707102 0.9615933 0.1425755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1863 1896 0.671677 0.808414 0.000068 0.4075249 -0.4093527 -0.7144677 0.3948287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1864 1895 0.446770 -0.848546 0.020477 -0.3275375 0.7002769 -0.6012188 0.2021569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1864 2124 0.864039 0.368710 0.435131 -0.6350841 -0.0513063 -0.7334563 0.2368076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1865 1894 0.578321 0.312838 0.391701 -0.4216975 -0.5872602 -0.6165787 0.3116526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1866 1893 -0.584192 -0.926325 -0.007755 0.4494701 0.1698839 -0.8334001 0.2730574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1866 2126 0.496398 -0.396167 0.846676 0.1352555 -0.5801721 0.8031813 0.0024537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1867 1327 0.743134 0.056933 -0.736617 0.1356189 -0.4982558 0.5629224 0.6453426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1867 2127 -0.802148 -0.116956 0.630252 -0.5113209 -0.7200522 -0.0378396 0.4675938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1868 1328 0.717102 -0.783046 -0.609539 -0.5076374 -0.2462577 0.8175962 0.1148823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1868 1851 -0.369568 0.249259 -0.892744 0.1479942 -0.1516851 -0.6942647 0.6878123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1868 1891 0.625591 -0.202712 0.948439 0.0016200 0.2313314 -0.6705821 0.7048424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1868 2128 -0.675489 0.392096 0.458438 -0.7814567 -0.1444288 -0.4005931 0.4560602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1869 1890 0.972576 0.063520 0.493003 0.3507287 -0.7630217 -0.5387265 0.0675347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1870 1889 0.641563 0.664315 -0.296228 -0.3317547 -0.0127002 0.1523603 0.9308941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1870 2130 -0.335436 0.927427 0.376387 -0.4559279 0.1364143 0.1359308 0.8689325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1871 1331 -0.296037 0.590201 -0.842007 0.3865941 0.0635617 0.3401683 0.8548628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1871 1888 -0.377724 0.586524 0.723604 -0.2297398 0.0724814 -0.5698402 0.7856515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1872 1887 -0.118132 -0.681162 0.609638 0.3107610 0.1185015 -0.7209415 0.6079707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1872 2132 -0.762281 0.650640 0.519696 0.2482123 0.0592367 -0.8107408 0.5268595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1873 1886 0.553726 0.048784 0.596945 -0.4545518 -0.1773147 0.4469248 0.7498002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1873 2133 -0.727930 0.439669 0.516713 -0.0044674 -0.1928881 0.4976437 0.8456507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1874 1845 -0.756337 0.573816 -0.619329 -0.4952783 -0.6546033 0.0785838 0.5657018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1874 1885 0.684403 -0.534526 0.595530 -0.4781892 -0.7646237 0.1777787 0.3938025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1874 2134 -0.865332 -0.614311 0.195470 0.3317506 -0.6369080 0.1625047 0.6766697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1875 1884 -0.631881 0.914231 0.309821 -0.6149585 -0.3484412 0.5672661 0.4226392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1875 2135 -0.441106 -0.483042 0.943614 -0.0432846 -0.6309733 0.7459764 0.2086104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1876 1883 0.903357 0.259435 0.463519 -0.1305185 -0.5803431 -0.7954908 0.1155906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1876 2136 -0.447367 0.909706 0.073146 0.4060041 -0.3132759 -0.7154669 0.4744744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1877 1882 -0.546308 -0.900737 0.002606 0.1438974 -0.3321721 0.1623810 0.9179257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1877 2137 0.355773 -0.212190 0.893243 0.6160920 0.3013010 -0.4941220 0.5343144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1878 1881 0.025091 -0.691412 -0.738541 -0.2006227 0.6983954 -0.6849270 0.0535664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1880 2100 -0.712764 0.266592 0.714199 -0.0869571 -0.5078493 0.0297508 0.8565293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1881 1918 0.147441 1.008352 0.375795 0.4357768 -0.4135762 -0.0208008 0.7991374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1881 2101 -0.102567 -0.570699 0.793088 -0.0759787 0.0843534 0.9631275 0.2439204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1882 2102 0.758913 -0.087812 0.570000 -0.2475890 0.1712836 -0.8777165 0.3727941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1883 1916 -0.628021 0.571875 0.608811 -0.2425112 0.6739213 0.1997633 0.6686651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1884 1915 0.510981 -0.686738 0.582961 -0.4876001 -0.2053306 0.2328106 0.8160176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1885 1914 -0.227810 -0.391455 -0.828983 0.3089170 0.1305264 -0.3717205 0.8656541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1885 2105 -0.310855 -0.700720 0.498997 0.8008835 0.2374324 0.1916416 0.5152523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1886 1913 0.398461 -0.780726 0.203621 -0.3606496 -0.3831416 -0.0103364 0.8503102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1886 2106 -0.095130 0.119756 1.070735 0.1412742 0.4319979 0.7104766 0.5372546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1887 1912 0.440603 0.353195 0.902234 -0.3596621 -0.4914574 0.3116211 0.7293868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1887 2107 -0.766357 -0.399232 0.289907 -0.1344504 -0.5058683 -0.3521235 0.7759055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1888 1911 -0.624269 -0.679495 0.494719 0.1193875 0.3364254 -0.9196229 0.1638852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1888 2108 0.896961 -0.446746 0.506634 0.8969555 0.3080602 0.2698974 0.1665089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1889 2109 -0.490683 0.342816 0.875762 0.0510848 -0.1204026 0.9387417 0.3188378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1890 1909 -0.913996 -0.046074 -0.586556 0.3911282 0.6357545 0.5870436 0.3133923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1890 2110 -0.086179 0.705811 0.481820 0.4047243 -0.5234271 -0.2648311 0.7014890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1891 1908 -0.037547 0.256096 0.846293 0.4635387 0.8029955 -0.3702183 0.0571705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1891 2111 -0.770361 -0.811668 0.353359 -0.2308556 -0.2594814 0.0595745 0.9358558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1892 1867 0.542133 -0.460846 -0.820477 0.3950290 -0.1656488 0.2965257 0.8535720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1892 1907 -0.556160 0.228914 0.910436 0.4382487 -0.5653878 0.6739573 0.1845435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1892 2112 -0.675144 -0.784452 -0.094427 0.9585459 0.1429235 -0.2341834 0.0769459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1893 1906 0.756829 0.279209 0.838506 -0.1307705 0.0947775 0.9731542 0.1639733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1893 2113 -0.787181 0.392104 0.459366 0.2075425 -0.2465603 -0.8194876 0.4738925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1894 1905 0.338969 0.808171 0.565941 0.1989967 0.5065144 0.7259342 0.4205508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1894 2114 0.452819 -0.685208 0.548489 0.7729736 -0.0874645 0.4616172 0.4263466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1895 1904 0.117005 -0.115717 0.784731 0.3880861 -0.4386542 -0.4968263 0.6404181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1896 1903 -0.930840 0.294497 -0.213034 -0.4341665 0.2388729 0.7622829 0.4163700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1897 1902 0.584851 0.404149 -0.740585 0.5881987 -0.0962065 0.7377752 0.3169454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1897 2117 0.287580 -0.931636 0.081115 0.0272552 0.2172277 -0.7964819 0.5636363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1898 1901 -0.023736 0.514339 0.798340 0.0752803 0.1834284 -0.8996531 0.3889874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1898 2118 -0.686531 -0.795902 0.474262 0.2141697 -0.4317971 0.3451346 0.8053352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1899 1319 -0.391764 -0.461463 -0.960167 -0.1534959 0.4708547 -0.8672076 0.0518253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1899 1860 -0.820977 0.176625 0.318036 -0.1239293 0.3999853 -0.8192065 0.3918596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1899 2119 0.288729 0.531107 0.848337 -0.8225682 -0.1911304 -0.1029439 0.5255980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1900 1939 -0.651040 0.420905 0.653386 0.1483577 0.1691190 -0.9715816 0.0736065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1900 2080 0.098247 -0.362639 1.025262 0.1616556 0.1294153 -0.6239493 0.7535293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1902 2082 -0.251418 0.392337 0.791896 -0.5019888 0.2547441 0.8265043 0.0017947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1903 2083 0.249370 -0.477319 0.820893 0.4800817 -0.3397965 0.1947996 0.7849287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1904 1284 -0.421215 0.470092 -0.917319 -0.0164277 -0.0527793 0.2267932 0.9723730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1904 1935 0.479176 0.787914 0.069451 -0.3088220 0.2902348 -0.4264256 0.7990957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1904 2084 0.208276 -0.507415 0.891050 -0.3375900 -0.4956449 -0.7895531 0.1302881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1905 1934 0.437303 0.358406 0.991588 0.1919388 -0.0326799 -0.9696453 0.1479175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1905 2085 -0.835757 0.544607 0.420416 -0.0298639 -0.5094958 0.3412209 0.7893608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1906 1286 -0.711303 0.169083 -0.716229 -0.3820784 0.6135336 -0.6523400 0.2281339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1907 1932 0.802384 0.003243 -0.366208 -0.3145309 0.4126360 0.5414053 0.6615755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1908 1931 -0.214039 -0.652923 -0.768600 0.1218822 0.6190029 -0.6011113 0.4905562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1908 2088 -0.336797 -0.993463 0.361822 0.1789648 0.2072655 -0.3367470 0.9008963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1909 1289 -0.863259 -0.643585 -0.068640 -0.6589747 0.3254367 -0.6773655 0.0319261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1909 1930 0.231679 -0.436819 -0.686598 0.8414496 0.4647703 0.2237208 0.1609353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1909 2089 0.831839 0.559481 0.127802 0.0929160 0.5760483 -0.4994523 0.6403768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1910 1290 0.358582 -0.734586 -0.497953 0.6709602 -0.2362615 -0.6980921 0.0816108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1910 1889 -0.186042 0.303738 -0.895213 0.1285667 -0.5751054 -0.4645366 0.6610069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1910 2090 -0.673044 0.765795 0.285376 -0.6573621 -0.2311284 0.1165684 0.7077193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1911 1928 0.506319 -0.117010 0.751182 0.4957039 0.3512290 -0.7238327 0.3270813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1911 2091 -0.932386 0.186580 0.649151 0.3272389 -0.6168292 -0.5311649 0.4798962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1912 1927 0.777467 -0.577431 0.171686 -0.3177626 -0.5144487 0.7961685 0.0220283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1912 2092 -0.592012 -0.488293 0.565244 0.0611437 0.1059535 0.3562926 0.9263320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1913 1293 -0.868801 0.418406 -0.605097 0.2068823 0.7641829 -0.5326698 0.2991440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1913 1926 0.391039 -0.595475 -0.816299 -0.1539625 0.2180636 -0.9433444 0.1970918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1913 2093 0.719754 -0.465197 0.481333 0.0761373 -0.6079473 0.7587498 0.2211379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1914 2094 0.032824 -0.264194 0.745607 0.3204904 0.0236590 -0.9468683 0.0129098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1915 1924 0.211350 -0.928063 -0.262652 0.3095902 0.1666893 0.3611087 0.8636950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1915 2095 -0.915196 -0.380679 0.280043 0.2540212 -0.3850894 -0.7299874 0.5042795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1916 1923 -0.596604 0.764376 -0.224251 0.7558126 -0.6406589 -0.1246379 0.0526201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1917 1882 0.755449 -0.662417 -0.118053 0.1065858 -0.2762400 -0.7537125 0.5867268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1917 1922 -0.751321 0.772942 0.000712 0.6185876 0.2165031 0.2627870 0.7081093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1918 1921 0.031540 0.817470 -0.683337 0.2525786 -0.3168273 -0.7956834 0.4502358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1918 2098 0.753334 0.424149 0.400520 -0.2022438 -0.0039800 -0.7779836 0.5948303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1919 1299 -0.047947 -0.180452 -0.972027 -0.4513638 0.4116218 0.7843852 0.1076019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1919 1880 1.068180 -0.479950 0.127803 0.3625519 -0.1474373 -0.8023802 0.4505600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1919 2099 -0.044976 0.140011 1.117753 -0.2144320 -0.0492472 0.8917998 0.3953312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1920 2060 0.122615 -0.286457 0.984119 -0.2038613 0.1624164 0.8073951 0.5293152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1921 1958 -0.428899 -0.933441 0.006109 -0.0505847 -0.7106873 0.5463138 0.4403476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1921 2061 -0.831880 0.513742 -0.056391 -0.1047953 -0.3403620 -0.1864503 0.9156462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1922 1957 -0.050118 0.253878 -0.857176 -0.4638120 -0.4438025 -0.1638236 0.7490525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1922 2062 -0.760306 0.603712 0.234922 0.0149409 -0.0714054 -0.5733926 0.8160263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1923 1956 -0.858752 0.590808 0.447247 -0.6497524 0.4513489 0.5485872 0.2704774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1923 2063 0.543308 0.661617 0.366603 -0.1606276 0.0291805 -0.7095127 0.6855210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1924 1955 -0.657610 -0.770671 0.140857 -0.8208446 -0.0605990 -0.0594475 0.5648078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1925 1914 0.370895 -0.670504 -0.537646 -0.1655453 0.4323966 -0.8860804 0.0221243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1925 1954 -0.359276 0.696401 0.485373 0.5114415 0.5374509 0.5617767 0.3660342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1925 2065 0.545770 -0.289256 0.812340 0.3223684 0.1431072 -0.0004266 0.9357343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1926 1953 -0.104226 0.862973 -0.384716 -0.3336754 -0.4140043 -0.1697599 0.8297245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1926 2066 -0.339932 0.416970 0.992435 0.1243399 -0.2467860 0.6578017 0.7006663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1927 2067 0.016143 -0.531690 0.883218 0.6702858 0.1965682 0.0322386 0.7148696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1928 1951 -0.980295 0.312821 -0.075530 0.8020525 -0.5005755 0.2902946 0.1478682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1928 2068 -0.263351 -0.795588 0.297114 -0.2108748 0.6664225 -0.6554650 0.2859694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1929 1950 0.637640 0.874195 0.292754 0.0003483 -0.3707418 0.1851526 0.9100928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1929 2069 0.510158 -0.464356 0.764224 -0.2289794 0.4864192 -0.8138106 0.2206287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1930 1949 -0.333422 0.216950 0.976919 0.5156061 0.3127481 0.7834595 0.1501007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1930 2070 0.691686 0.343663 0.408833 -0.4804808 0.1664367 -0.7295111 0.4574391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1931 1948 0.887578 0.199452 0.158427 0.2724471 0.2192675 -0.3450098 0.8710124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1931 2071 0.151018 -0.690245 0.781542 0.2668790 -0.6049750 0.6834737 0.3092647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1932 1947 0.397995 -1.055099 -0.369509 0.1906480 0.7508745 -0.4683964 0.4247890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1932 2072 -0.165176 -0.487107 0.916492 -0.2373915 -0.4969906 -0.0233418 0.8343265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1933 1906 -0.937951 0.537084 0.563153 0.5152491 -0.1709189 0.8020840 0.2489304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1933 2073 0.328752 -0.069436 0.832558 -0.6743186 0.1402426 -0.6437233 0.3335368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1934 2074 0.386786 -0.568299 0.395469 0.3350923 0.1985479 -0.9009687 0.1911736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1935 2075 0.282967 -0.637710 0.689353 0.1295504 -0.7150913 0.1939277 0.6589789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1936 1903 0.869359 -0.597186 0.241520 -0.3317269 -0.0377312 0.7423455 0.5809103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1936 1943 -0.816110 0.387307 -0.369502 0.1539301 -0.2882497 -0.8716060 0.3654047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1936 2076 -0.081197 0.527353 0.802844 -0.4512203 0.1118592 -0.8853712 0.0023775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1937 1902 -0.863282 0.417266 -0.184752 -0.0912057 0.5419387 0.5765688 0.6046092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1937 1942 0.789362 -0.357673 0.148559 0.1426048 -0.3540286 0.2680761 0.8845693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1937 2077 0.293502 0.501067 0.527950 -0.1125793 -0.6432824 -0.6526284 0.3841742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1938 1901 -0.453522 -0.945425 0.075012 -0.2343826 -0.1247693 -0.9522845 0.1505049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1938 1941 0.394147 0.857115 0.019140 -0.4579946 -0.0708573 0.8720151 0.1575116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1938 2078 -0.677191 0.239255 0.853737 -0.1288195 0.3611659 0.2782674 0.8806429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1940 1979 0.898647 -0.110756 0.266318 -0.4523310 -0.3780365 -0.8070430 0.0341576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1940 2040 -0.327760 -0.154068 0.918305 -0.4233028 -0.2195807 0.3364757 0.8120241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1942 1977 0.553749 -0.894986 -0.185511 0.6466390 -0.1309737 0.6899643 0.2977470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1942 2042 0.704950 0.430594 0.187164 -0.6100706 0.5652006 -0.5551389 0.0135262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1943 1976 0.179598 -0.846498 0.150155 0.3550695 -0.4562643 0.5286627 0.6215016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1944 1935 -0.227992 -0.006603 -0.689355 -0.1360760 0.3827898 0.8530592 0.3274832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1944 1975 0.288583 -0.166760 0.987083 0.4000208 0.2647743 0.8286751 0.2884017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1944 2044 0.243197 0.786514 -0.001812 0.2479391 0.6479099 0.4196802 0.5853268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1945 1934 0.575066 -0.712788 -0.045723 -0.2559910 -0.2686446 -0.4029367 0.8366246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1945 1974 -0.593318 0.859244 0.157051 0.1154932 -0.7386901 0.4623881 0.4766502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1946 1933 0.253925 0.797775 0.330538 0.0974724 -0.4352616 -0.7157625 0.5373365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1946 1973 -0.634464 -0.995527 -0.184553 0.2563240 -0.8725056 0.0765300 0.4088707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1946 2046 -0.798799 0.262207 0.599163 -0.3810380 -0.3870630 0.1029992 0.8332967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1947 1972 0.173566 0.051580 1.056968 0.3582329 0.4155052 -0.5756740 0.6063202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1947 2047 -0.749197 -0.662078 0.309124 0.5862064 -0.5984811 -0.0894015 0.5386926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1948 2048 -0.015091 -0.135121 0.968941 0.1869221 0.3610218 0.0537034 0.9120523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1949 1970 0.935119 0.273460 -0.227449 -0.2283516 -0.2214265 -0.4206011 0.8496591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1949 2049 0.173822 -0.005386 0.992798 0.0065219 0.2050070 -0.8117784 0.5467590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1950 2050 0.652929 -0.848352 0.480352 0.9248386 -0.1654600 0.2903798 0.1815932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1951 1968 -0.329318 0.560306 -0.393669 -0.2139649 -0.2820999 -0.5882792 0.7270256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1951 2051 0.713547 0.724929 0.231949 -0.2402071 0.8545170 0.4041014 0.2209146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1952 1927 -0.424741 0.908386 0.283587 0.2392179 0.1499329 0.9262731 0.2496258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1952 1967 0.669457 -0.943005 -0.105400 -0.4914584 0.2321859 -0.8374733 0.0565405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1952 2052 0.568566 0.378439 0.454167 0.6566321 -0.0429990 0.6205522 0.4264978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1953 1966 -0.414511 0.652181 0.492210 -0.2264672 -0.2782042 0.7923161 0.4935080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1953 2053 0.502664 -0.201637 0.656994 -0.3132633 -0.2364131 0.4812126 0.7838427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1954 1965 0.965830 0.462099 -0.276750 -0.7264877 -0.4522428 -0.4567465 0.2430530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1954 2054 -0.229361 0.864813 0.264566 -0.4435515 -0.1618880 -0.8369419 0.2767357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1955 1964 -0.471417 0.282565 -1.116712 0.1374358 0.4790042 -0.7847444 0.3685682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1956 1963 -0.553913 0.454849 0.695415 0.6015010 -0.3504133 0.5372246 0.4762318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1956 2056 -0.265496 -0.754154 0.404213 0.3334360 -0.7221991 0.6041616 0.0473042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1957 1962 -0.919939 0.739366 -0.037606 -0.2734272 -0.5939346 -0.6502993 0.3867688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1957 2057 -0.039987 -0.341658 1.139671 0.5586685 -0.0229868 -0.8257628 0.0740060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1958 1961 -0.046149 0.038603 0.777010 -0.0196450 0.6748760 -0.3087194 0.6699617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1958 2058 0.701218 0.688884 0.076841 -0.4011562 0.3358588 -0.8421073 0.1308732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1959 1920 -0.401668 0.010807 0.974761 0.2414199 0.3854477 -0.1070740 0.8841276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1960 1999 -0.087034 -0.666428 -0.799311 -0.0977325 -0.1650590 0.6837545 0.7040481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1960 2020 0.751157 -0.458500 0.398503 0.0400523 0.7956022 -0.4583815 0.3940804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1961 1998 -0.859346 -0.337866 -0.067232 -0.7417763 0.1032846 0.6213473 0.2302773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1961 2021 -0.589276 0.646443 0.558989 -0.5665014 -0.4004179 -0.3753304 0.6147103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1962 1997 0.380401 -0.784064 0.813892 0.4161507 0.3904966 -0.2447591 0.7838520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1962 2022 0.825610 0.416706 -0.099876 -0.3470059 -0.5117150 -0.7792356 0.1025987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1963 1223 -0.312895 -0.642841 -0.832818 -0.2552716 -0.2567985 0.3632782 0.8584404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1963 2023 0.132548 0.489519 0.839076 -0.6283246 -0.4430112 -0.5981533 0.2261901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1964 2024 0.674440 -0.814552 0.259074 -0.1221515 0.1413764 -0.4579783 0.8691073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1965 2025 0.687134 -0.583824 0.308516 -0.2515566 0.4916352 0.3415344 0.7605054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1966 1226 0.494185 0.576414 -0.561384 0.2158732 -0.2033832 -0.1116997 0.9484499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1966 1993 0.684563 -0.244915 0.518500 0.0241579 -0.0080282 -0.6973322 0.7162959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1966 2026 -0.561263 -0.779771 0.412534 0.0371936 -0.4720017 0.7238544 0.5018625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1967 2027 -0.097596 -0.613929 0.823668 0.1634007 -0.1289665 -0.9332488 0.2927703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1968 1991 -0.785193 -0.395114 0.301501 -0.5052317 -0.1275933 0.5834709 0.6229146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1968 2028 -0.576967 0.961686 0.456694 -0.0568858 -0.6625501 -0.2997630 0.6840566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1969 1950 0.036337 -0.828395 0.571701 -0.4746157 -0.4774049 0.6912843 0.2625843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1969 2029 -0.637591 0.441013 0.447833 -0.2308670 -0.6430229 -0.3294772 0.6516646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1970 2030 0.522943 -0.044137 0.665734 0.3303854 0.1493648 -0.4467309 0.8179041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1971 1231 0.520749 -0.978382 -0.403019 0.4487277 -0.3541354 -0.6916875 0.4413616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1971 1988 -0.117474 0.386208 -0.972096 0.0834421 -0.3711167 -0.8601097 0.3398840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1971 2031 -0.664030 0.746278 0.388147 -0.0824167 0.1403615 -0.9760318 0.1444575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1972 1987 -0.746761 -0.103129 0.350194 -0.1830963 -0.1283289 -0.9470703 0.2303591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1972 2032 0.391143 -0.796675 0.646980 -0.2796063 -0.8255474 0.4580767 0.1745210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1973 1986 0.309774 -0.436813 0.882786 0.3704867 0.3491436 0.5057536 0.6964565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1974 1985 0.431776 0.729700 -0.364427 -0.0127726 0.7330699 -0.2555321 0.6301974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1974 2034 0.889455 -0.346395 0.300333 0.4459727 0.2505067 0.1828819 0.8395886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1975 1984 0.263141 0.570426 0.672090 0.7037471 -0.2972905 0.6127253 0.2023020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1975 2035 0.689599 -0.520225 0.321648 0.9470622 0.0875897 0.2255417 0.2110265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1976 1983 0.059164 -0.514178 0.833734 -0.9044188 0.1542648 0.0754013 0.3905684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1976 2036 0.810813 0.650790 0.442609 -0.2926285 0.7474801 0.2267838 0.5515534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1977 1982 -0.473954 0.135807 0.878564 -0.4925640 0.5230065 -0.5404347 0.4379216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1978 1941 -0.908379 0.352944 -0.438180 -0.4302398 0.0092997 0.4396600 0.7883567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1978 1981 0.677500 -0.434460 0.291597 -0.4134018 -0.5537842 -0.3485689 0.6331838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1978 2038 -0.043393 0.429258 0.874641 -0.6037066 -0.4001617 0.6292779 0.2818125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1979 2039 0.729716 0.420095 -0.113586 -0.6685415 -0.3313943 -0.4273203 0.5105168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1980 2000 -0.353041 -0.541812 0.769216 -0.0145219 -0.3275737 0.8686895 0.3712991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1981 1201 -0.965924 0.284840 -0.489606 0.2440205 0.3421508 0.0841672 0.9034947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1981 2001 0.914156 -0.068296 0.418785 -0.0529533 0.8184700 -0.5616872 0.1086748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1985 2005 -0.345885 -0.265029 0.858431 0.2281665 0.4781753 -0.6783842 0.5090023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1986 1206 -0.636793 0.081522 -0.766099 0.0094086 0.0360432 -0.9976889 0.0568263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1987 1207 -0.093665 -0.902469 -0.465783 -0.1770930 0.8818283 0.0998648 0.4254926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1987 2007 0.268423 0.922420 0.370562 0.1467384 -0.0827048 -0.5558275 0.8140538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1988 2008 0.215609 -0.361432 0.840137 -0.2543976 0.3606395 0.8923281 0.0947191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1989 1970 -0.084906 -0.514100 -0.766515 0.2738068 -0.6589289 -0.1967081 0.6724199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1989 2009 -0.779320 -0.651544 0.467819 0.4684842 -0.5283153 -0.6568064 0.2645957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1991 2011 0.318433 -0.199220 0.767854 0.5830142 -0.3387630 0.7206596 0.1611949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1992 1212 -0.672059 -0.121778 -0.755041 -0.0392776 -0.1061822 0.1809087 0.9769619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1992 1967 0.171964 0.875777 -0.172004 0.2582920 -0.2039440 0.8461835 0.4191247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1992 2012 0.656412 0.046985 0.724257 -0.2434186 0.4022580 -0.7432841 0.4758830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1993 2013 0.811853 -0.554916 0.427101 -0.3525999 0.2099295 -0.8497053 0.3310646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1994 1214 -0.197252 -0.487454 -0.893883 -0.2240060 -0.3503250 -0.7009747 0.5794206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1994 1965 -0.941576 0.013609 0.279713 -0.7223298 -0.0329510 -0.5179497 0.4570361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1994 2014 0.176910 0.384711 0.832635 0.1894057 0.1589502 -0.9015664 0.3550187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1995 1964 -0.835200 0.503305 -0.244178 0.1139530 -0.4398780 -0.3143343 0.8334962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1995 2015 -0.148466 -0.950639 0.036622 -0.2988478 -0.4688479 0.3792328 0.7396311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1996 1963 0.235498 0.842076 0.428823 0.1266954 -0.1970922 -0.9569410 0.1713674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1997 2017 0.364509 0.958498 0.095253 0.6375834 0.7290971 0.2177382 0.1203950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1998 2018 -0.619311 -0.472393 0.767959 0.0071577 -0.0954478 0.9194041 0.3814900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1999 1219 0.525560 0.730692 -0.090798 0.7347506 -0.5774041 0.3534818 0.0423873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1999 2019 -0.594269 -0.695894 0.157992 0.2359834 -0.8673258 -0.1890501 0.3953704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2000 2039 -0.154826 -0.870567 0.020789 0.2936597 0.2050438 0.9169311 0.1759498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2001 2038 0.513257 -0.819179 0.038506 0.1043992 0.2525913 -0.4689061 0.8398961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2002 1982 0.278675 -0.784570 -0.056389 0.2181891 0.3423706 0.8730481 0.2701163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2002 2037 -0.012180 -0.309162 1.104192 -0.2233411 0.2115696 -0.2183019 0.9261217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2002 2782 -0.335497 1.073140 0.175053 -0.3581170 -0.6378238 -0.5511458 0.4014615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2003 1983 -0.583058 0.044262 -0.946616 0.6090219 -0.5214526 0.5704502 0.1782307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2003 2036 0.425081 -0.785091 -0.114070 -0.0653594 0.4439476 -0.6671187 0.5946354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2003 2783 0.468492 0.131653 0.800844 0.0069235 0.6900468 -0.7071436 0.1540628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2004 1984 0.439809 0.281525 -0.946514 0.1421460 -0.4705463 0.7249178 0.4825712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2004 2035 -0.141124 -0.816027 -0.505031 0.6468213 -0.2567301 0.4889876 0.5259306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2004 2784 -0.595763 -0.228036 0.937483 -0.4112352 0.4348239 0.7532787 0.2727363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2005 2785 -0.548390 -0.637770 0.568597 -0.2626695 -0.4727123 0.5880763 0.6014267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2006 2033 -0.240880 0.120915 1.036333 -0.1563029 0.2355933 -0.1450678 0.9481670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2006 2786 0.468502 0.973472 -0.063142 -0.7762936 0.0129955 -0.4703190 0.4195228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2007 2032 -0.642610 -0.704647 0.254900 -0.9916885 0.0037590 0.0573276 0.1151227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2007 2787 -0.625232 0.704190 0.210251 -0.2244203 -0.2713877 0.7405695 0.5723120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2008 2031 -0.398947 -0.633353 0.609014 0.2296472 0.2139388 -0.9489401 0.0317037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2008 2788 -0.428515 0.943651 0.337116 -0.6504819 -0.3609424 0.2532529 0.6184310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2009 2030 0.885335 -0.538517 -0.082400 0.0725965 0.5544179 0.0148009 0.8289339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2009 2789 0.673984 0.723370 0.429097 -0.3117610 0.0051322 0.8370394 0.4496041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2010 1990 0.558434 0.775592 -0.168967 0.8021668 -0.3340009 -0.4586035 0.1861576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2010 2029 -0.362154 0.743101 0.713541 0.0739640 -0.7046560 0.5950228 0.3793905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2010 2790 -0.478963 -0.686092 0.348785 0.8401640 -0.0784868 -0.2601304 0.4693574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2011 2028 -0.460875 0.016887 0.836015 0.5937288 0.3833658 0.2387255 0.6659782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2011 2791 0.877994 -0.187544 0.424536 0.5874416 0.7289762 0.3159328 0.1539237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2012 2027 -1.025772 -0.032568 -0.253836 0.2763434 0.1323920 0.8062151 0.5060868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2012 2792 -0.145698 -0.128716 0.751928 0.2832940 -0.2130348 -0.8212834 0.4470506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2013 2026 0.705485 0.681690 -0.500608 -0.1092317 0.0352189 -0.1555956 0.9811310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2013 2793 0.049575 0.166808 0.943476 -0.5179365 -0.5287409 0.2121319 0.6381026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2014 2025 0.702230 -0.494736 0.685035 -0.5943990 -0.3142035 -0.0086302 0.7401970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2014 2794 -0.632771 -0.230441 0.700482 0.4746663 0.0632695 -0.8778221 0.0108246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2015 2024 -0.170814 0.490590 0.730285 0.0450347 0.2371580 -0.9653234 0.0993915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2015 2795 -0.701529 -0.534082 0.365178 -0.1490544 -0.5435277 -0.6483552 0.5118554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2016 1996 -0.772033 -0.473134 -0.821562 -0.0228594 0.2999510 0.8713688 0.3875863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2016 2023 -0.803621 -0.063776 0.776906 -0.7551916 -0.3044024 -0.5769268 0.0646555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2016 2796 0.502580 0.491065 0.751298 -0.4095086 -0.2304710 -0.2883466 0.8342914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2017 2022 -0.342279 -0.121777 1.038421 -0.2927005 0.3913482 -0.5542372 0.6737909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2017 2797 0.816494 0.517887 0.272309 -0.7487070 0.6134220 0.0396638 0.2481494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2018 2021 -0.708314 0.299093 -0.452214 -0.4263897 -0.0929370 0.6331588 0.6392687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2018 2798 -0.083701 0.686247 0.821419 -0.1682440 -0.3738119 -0.1002330 0.9065936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2019 2799 0.794851 -0.650133 0.236035 -0.2955859 0.6301432 0.2317473 0.6795893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2020 2059 -0.669527 -0.275465 -0.778753 -0.0752756 -0.7337835 0.3947480 0.5477859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2020 2760 -0.513810 -0.410193 0.723383 -0.2872355 -0.4941463 0.4147116 0.7080463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2021 2761 0.317573 -0.618120 0.667038 -0.2298340 0.1629907 0.1382674 0.9494696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2022 2762 -0.209315 0.376738 0.744406 -0.2144114 -0.0438033 0.5560424 0.8018266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2023 2056 0.401047 -0.098037 -0.722200 0.8249390 -0.1544331 0.5425086 0.0362013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2023 2763 0.745108 0.055978 0.527692 0.2990807 -0.2274024 0.9143708 0.1508806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2024 2055 -0.160684 -0.917797 0.428786 0.6995046 0.5259095 0.3214225 0.3616629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2024 2764 0.889934 -0.129715 0.477150 -0.7239870 0.0412474 -0.4970366 0.4765460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2025 2054 0.597218 -0.249970 -0.910224 0.2790674 0.0358565 -0.1953027 0.9395172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2025 2765 -0.117927 -0.914437 0.078288 0.4528308 0.3432837 -0.7854582 0.2452670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2026 2053 0.408402 0.958962 -0.335875 -0.0110186 0.5653102 -0.8227947 0.0575484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2026 2766 -0.097641 0.269362 0.762485 0.0179245 -0.2852195 -0.9206504 0.2659536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2027 2052 0.165263 0.387387 -0.823858 -0.0503663 -0.1932778 0.6704101 0.7146028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2027 2767 0.138216 0.781654 0.498609 -0.3773088 -0.5208529 -0.7459742 0.1728376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2028 2051 -0.484534 0.853532 -0.473241 0.0275419 0.0510122 -0.7783085 0.6252000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2028 2768 0.309344 0.649019 0.832533 0.0741496 0.8689159 0.4000902 0.2818063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2029 2050 0.901913 -0.265873 -0.511611 -0.4143268 -0.4666575 -0.5557057 0.5493225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2029 2769 0.443194 0.084827 0.972137 -0.4296326 -0.1955598 -0.8815733 0.0008561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2030 2049 0.329692 -0.431962 0.829686 -0.5575713 0.0672001 -0.1887620 0.8055851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2030 2770 -0.066446 0.745242 0.518140 -0.2932877 -0.4174367 -0.0460473 0.8588414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2031 2048 -0.032252 -0.029884 1.065935 0.3377407 0.6002478 -0.7121777 0.1357816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2031 2771 0.580640 -0.945073 0.261212 0.7541196 0.0387156 0.2434294 0.6087256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2032 2047 -0.874403 0.689590 -0.207784 0.6624379 -0.1405424 -0.6103641 0.4109497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2033 1973 0.056220 -0.867370 -0.243247 0.4419540 0.6190649 0.4561732 0.4618889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2033 2046 -0.408338 -0.326260 0.732647 -0.0377290 -0.3832760 -0.8891419 0.2471896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2033 2773 -0.095790 1.053699 0.472720 0.2434222 -0.9273877 -0.2731002 0.0781920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2034 2005 0.978362 0.283949 -0.357737 -0.2285093 -0.2263484 0.8919887 0.3176571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2034 2045 -0.822382 -0.240855 0.123108 0.4094329 0.2570120 0.5533847 0.6782882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2035 2044 -0.405172 0.388505 0.674891 -0.6821972 -0.6349323 -0.2413780 0.2705636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2035 2775 0.595961 0.797713 0.469734 -0.1460044 0.7812073 0.5763287 0.1903762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2036 2043 0.727780 0.525844 0.805638 0.0058961 -0.7253222 0.6492134 0.2288991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2036 2776 -0.443565 -0.038135 0.923805 0.8217141 -0.2221819 -0.4805133 0.2110169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2037 1977 0.777679 -0.611143 -0.304609 -0.5929310 -0.5215519 -0.4609143 0.4049376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2037 2042 -0.274962 -0.668115 0.495604 -0.9223711 -0.1805239 -0.0707600 0.3341194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2037 2777 -0.878150 0.531876 0.230065 -0.4008589 -0.2634424 0.8188276 0.3153279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2038 2041 0.715179 -0.142364 0.778308 0.5685622 -0.1209767 0.1663926 0.7965018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2038 2778 -0.135140 -1.099088 0.083276 0.7005833 0.0467581 -0.2815659 0.6540011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2039 2779 0.373731 0.339811 0.636152 0.3615265 0.1818922 -0.0830777 0.9106656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2040 2740 -0.305862 -0.738712 0.548266 0.1575541 0.6913755 -0.7031077 0.0530674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2041 1941 0.348575 0.078519 -0.801267 0.0806964 0.1674447 -0.4909997 0.8510991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2041 2078 0.871686 0.164714 0.251133 -0.5815960 0.1958907 0.7837048 0.0958111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2041 2741 -0.260959 -0.184238 1.114212 0.0140029 -0.2563378 -0.5470635 0.7967537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2042 2077 -0.141095 -0.020578 -0.759844 0.7647438 -0.2361832 -0.4745573 0.3663057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2042 2742 -0.569312 -1.109691 -0.022485 0.8183904 0.3756617 -0.3957381 0.1802964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2043 1943 -0.752809 0.375474 -0.330281 0.3047705 -0.2102469 0.9053033 0.2081757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2043 2076 -0.160736 -0.742234 -0.655996 0.6483020 -0.6109729 0.3183877 0.3241078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2043 2743 0.673764 -0.643345 0.283033 0.8725238 -0.2867859 0.3201195 0.2323349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2044 2075 0.728350 -0.634214 -0.264582 0.0137172 -0.1993603 0.6764175 0.7088912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2044 2744 0.714810 0.555316 0.314307 -0.4353650 0.7249183 -0.3224419 0.4254198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2045 1945 -0.195184 -0.539484 -0.640102 -0.1900688 0.1954213 0.9591852 0.0751539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2045 2074 -0.355152 0.678259 -0.428214 0.1476967 0.3585036 -0.2210581 0.8948710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2045 2745 0.194710 0.549167 0.964451 -0.2331322 0.3616397 0.8924926 0.1353625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2047 2072 -0.418176 -0.901140 0.434438 0.3469192 -0.4004776 0.6688104 0.5214954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2047 2747 0.510305 0.330667 0.731744 0.1078477 -0.7596939 -0.6379840 0.0648880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2048 2071 -0.606430 -0.828129 -0.123861 -0.1626590 -0.1400806 0.9759882 0.0369673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2048 2748 -0.581847 0.256018 0.918862 -0.5266371 -0.1733770 0.5506274 0.6240218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2049 2070 0.622178 -0.919783 0.040123 0.3152428 0.1551421 -0.9313603 0.0955038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2049 2749 -0.350199 -0.154303 0.855369 -0.5037467 0.1195692 0.8496812 0.0999214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2050 2069 -0.471563 0.617640 -0.472161 -0.1345947 0.4754990 0.5219927 0.6952040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2051 2068 -0.646191 -0.473583 -0.400596 -0.2654003 -0.7499984 0.2532090 0.5504092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2052 2067 0.305927 0.158755 -0.757256 0.5923691 0.6181394 -0.2465713 0.4540982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2052 2752 0.855492 -0.399666 0.461339 0.2984920 -0.0016236 0.8826622 0.3630528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2053 2066 -0.461646 -0.203621 -0.794037 0.6908560 -0.5096198 -0.0704234 0.5079825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2053 2753 -0.191301 -0.968509 0.128848 -0.4430167 0.3678741 -0.7727495 0.2669513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2054 2065 0.822215 -0.388519 -0.654876 0.5688373 -0.2017949 0.1463902 0.7837556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2054 2754 -0.093892 -0.883786 0.499237 0.4669637 0.4396682 -0.7160194 0.2755955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2055 1955 -0.027472 -0.976433 -0.562065 0.4869165 -0.3159792 -0.8102289 0.0812310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2055 2064 -0.833649 0.271394 -0.470211 -0.8189801 0.2295966 -0.2854723 0.4416588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2055 2755 0.064547 0.631905 0.372149 -0.6509180 -0.3051823 0.1850368 0.6700230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2056 2063 -0.563465 -0.024449 0.983718 0.2764051 0.6146615 0.6351103 0.3773941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2057 2022 0.284400 -0.586791 0.660171 0.6341188 -0.3112044 -0.6478494 0.2851951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2057 2062 -0.386259 0.844057 -0.728058 -0.8655528 -0.0664170 0.2615776 0.4218817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2057 2757 -0.961111 0.240271 0.501034 -0.3539983 -0.6967602 -0.4204729 0.4608828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2058 2021 0.685854 -0.621954 0.430106 -0.1517920 -0.7653808 0.4200552 0.4633628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2058 2061 -0.736417 0.484383 -0.355199 -0.0957761 -0.1210042 0.5209114 0.8395452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2059 1959 -0.635015 0.579067 -0.612253 -0.3082959 0.0890736 -0.0098052 0.9470604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2060 2099 0.492053 0.716055 0.320031 0.4246111 0.1128219 -0.8619051 0.2531724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2063 2096 0.325609 0.816966 -0.302241 0.0444908 -0.7664678 -0.6222329 0.1528850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2063 2723 -0.762460 0.241109 0.460077 -0.6639825 -0.6651028 -0.0635759 0.3357433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2064 1924 0.453000 0.856633 -0.500675 -0.1645208 0.1655856 0.7227274 0.6505224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2064 2095 -0.871514 0.714498 -0.318904 0.3367055 -0.5130599 -0.2169010 0.7591791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2065 2094 0.217425 -0.828051 0.282160 0.0755365 0.3844968 0.0251619 0.9196865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2066 2726 0.681697 0.107399 0.651551 -0.2444059 0.0381154 0.7432237 0.6216361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2067 2727 -0.556590 0.757804 0.321007 -0.1842539 -0.5806202 0.2424092 0.7550950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2068 2091 -0.586063 0.008503 0.888461 -0.0317184 0.2539004 -0.7538973 0.6051176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2068 2728 0.754001 -0.406735 0.507364 0.2698639 0.2285355 -0.9269696 0.1251895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2069 2090 0.796812 0.370993 0.002055 -0.1062413 0.3365673 -0.4466486 0.8221559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2069 2729 0.289572 -0.675341 0.834252 0.7132417 0.1017675 0.0091926 0.6934299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2070 2089 -0.424816 0.986451 -0.315569 0.7073979 -0.1345879 -0.3476432 0.6005153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2070 2730 -0.301426 -0.056612 0.915965 0.5203033 -0.1600538 0.0686940 0.8360313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2071 2731 0.317738 -0.564470 0.755195 -0.0314872 0.6417994 -0.7159862 0.2728844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2072 2087 0.350046 0.281394 0.555514 -0.0753553 0.1719084 0.4554880 0.8702297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2072 2732 0.888797 -0.587561 0.232281 -0.1705076 0.3337134 0.3201981 0.8700780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2073 2046 0.054342 0.841286 0.765616 -0.2703034 0.6374627 -0.5388331 0.4798294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2073 2086 0.042447 -0.889944 -0.583511 -0.4175849 -0.4824280 -0.7235506 0.2633641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2073 2733 0.772868 -0.360523 0.465827 0.0821810 0.3531006 -0.4073246 0.8382439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2074 2085 -0.314088 0.576998 -0.763683 0.1190662 -0.6022882 -0.0227687 0.7890207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2075 2084 -0.672887 -0.626585 -0.237508 -0.6306143 -0.1018743 -0.7181181 0.2761406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2075 2735 0.697142 -0.970430 0.070618 0.3859081 -0.1914874 0.1078186 0.8959814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2076 2083 -0.193478 0.357925 0.850889 -0.0174983 0.1081158 -0.5673836 0.8161376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2076 2736 0.512186 -1.115339 0.390900 0.1365144 0.0438531 -0.5784524 0.8030153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2077 2737 0.280425 0.699128 0.790395 -0.0464105 0.1779684 -0.7428150 0.6437384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2078 2081 -0.621324 -0.471519 -0.737560 -0.2486649 0.0681506 0.3866700 0.8854420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2078 2738 -0.818213 0.206456 0.426176 -0.5707766 -0.6518182 -0.2387132 0.4385922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2079 1939 -0.658461 0.635657 -0.090078 0.5109538 0.2340014 0.7004119 0.4399918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2080 2119 0.767061 0.561770 0.075791 0.3894214 -0.3764815 0.8182229 0.1926760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2080 2700 -0.165884 0.453644 0.927830 0.1306752 0.3104431 -0.2116450 0.9174723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2081 1901 0.641429 -0.523179 -0.515346 -0.1523720 -0.1939197 0.8364897 0.4893495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2081 2118 -0.407308 0.189983 -0.828431 -0.0543515 -0.4491228 -0.5163292 0.7271443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2081 2701 -0.338559 0.604051 0.377808 -0.3530962 0.5652017 0.7104004 0.2262774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2082 2077 0.140740 0.972776 0.154491 0.3874613 -0.5648153 -0.1423632 0.7145559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2082 2117 0.001576 -0.927935 -0.353579 0.3363245 -0.6599293 -0.1204067 0.6609700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2082 2702 -0.845175 0.011456 0.924125 -0.3765579 -0.5363382 0.7156131 0.2417507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2083 2116 -0.503952 -0.230264 0.999657 0.1847701 -0.4636085 0.8653568 0.0456601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2083 2703 0.802241 0.139770 0.379218 -0.4427406 0.1828520 -0.8625237 0.1630911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2084 2115 -0.039643 0.164700 -1.067357 -0.5027321 -0.3339525 0.1097237 0.7897448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2084 2704 0.080505 1.032712 0.347168 -0.7408125 -0.0813305 0.2348002 0.6240602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2085 2114 -0.854632 0.313062 -0.250912 -0.1751576 -0.2490469 0.0725431 0.9497541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2085 2705 0.104713 0.854175 0.610760 0.2493819 0.1799010 0.6052656 0.7342328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2086 1906 0.044810 -1.115506 -0.087648 -0.1607325 0.3344246 0.7885479 0.4904258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2086 2113 -0.485492 0.023227 -0.734696 0.0357848 -0.5265132 -0.8408947 0.1199974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2087 1907 0.011851 1.112074 -0.171625 0.3835003 -0.0208261 -0.8407107 0.3817057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2087 2112 0.337448 0.034369 0.919435 0.4679211 0.0847125 0.7037382 0.5278506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2088 2071 0.546003 -0.723606 -0.475675 0.1454147 -0.4590773 0.3289243 0.8123493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2088 2111 -0.378928 0.822594 0.458357 0.0731863 0.7841692 -0.2533003 0.5617485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2088 2708 0.059003 -0.730408 0.893733 -0.0728059 -0.1793123 -0.8527061 0.4852203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2089 2709 -0.650537 0.871226 0.172973 -0.6105946 0.7067723 0.2739585 0.2293337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2091 2108 -0.084176 -0.779164 0.559440 0.3474301 -0.3718415 -0.1370717 0.8498456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2091 2711 0.377751 0.372139 0.832105 -0.4312518 0.4610594 0.5643483 0.5319371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2092 2107 -0.236886 1.004051 -0.366276 -0.0681106 0.0539647 -0.8444463 0.5285444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2092 2712 -0.845570 0.117952 0.634291 -0.0481698 -0.7221984 0.6896392 0.0225146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2093 2066 -0.596687 0.829362 0.254501 0.3170314 -0.6038340 0.6683826 0.2968842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2093 2713 -0.457545 -0.740544 0.494283 -0.1901432 -0.3951893 0.5625736 0.7008437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2094 2105 0.004974 -0.970819 0.588118 0.7184721 -0.4465483 -0.5175477 0.1285958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2094 2714 -0.457909 0.479909 0.669309 0.3731093 -0.6426470 -0.6475744 0.1686466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2095 2104 -0.670073 -0.095898 0.807346 -0.4168146 0.6823074 -0.3578889 0.4823254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2095 2715 0.520961 -0.059020 0.591221 0.8631968 0.2459277 0.3488389 0.2696708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2096 2103 -0.528612 0.105684 0.795459 0.1887761 0.3260088 -0.4550635 0.8068451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2096 2716 0.926066 0.492115 0.330444 -0.1187011 0.4487827 -0.3528790 0.8123919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2097 1917 -0.436689 -0.794989 -0.065765 -0.6501605 0.5002074 -0.3240126 0.4712745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2097 2062 -0.462611 0.610545 -0.620890 -0.2832089 0.2881681 -0.8244003 0.3963787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2097 2102 0.681655 -0.541425 0.705549 -0.0838847 0.6904837 0.6156252 0.3704068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2097 2717 0.472026 0.790334 0.564758 -0.6060921 -0.2458329 0.1083034 0.7486581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2098 2061 -1.050608 -0.195714 -0.244108 0.2046133 -0.0387602 -0.4816174 0.8512789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2098 2101 0.865705 0.024773 0.314896 0.2553653 -0.4372793 -0.6272310 0.5917404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2098 2718 -0.335351 0.497368 0.843109 -0.2728828 -0.5871951 0.2993522 0.7008032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2099 2719 -0.246996 -0.384593 0.863566 0.3671665 -0.2502707 0.6281803 0.6387040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2100 2139 -0.234545 1.016013 -0.149878 -0.4017437 0.6473343 0.0411198 0.6464282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2101 2138 -0.191799 0.730066 -0.574772 -0.8127981 0.0775801 -0.0988229 0.5688362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2101 2681 -0.294271 0.548598 0.800320 -0.0715713 -0.7181608 -0.3842813 0.5757174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2102 2137 -0.959373 0.157347 -0.056615 0.1072020 0.6061498 0.1691184 0.7697331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2102 2682 -0.172657 0.160733 0.938665 0.5406498 -0.3517136 0.3173711 0.6951769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2103 1883 0.481860 -0.895673 -0.576224 -0.3577693 -0.5342416 -0.6023926 0.4729802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2103 2136 -0.596435 -0.534834 0.347233 0.0157515 -0.0540585 -0.7091082 0.7028479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2103 2683 -0.176061 0.614448 0.471315 -0.2661326 0.1737211 0.9358251 0.1524000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2104 1884 0.382204 0.924226 -0.282254 -0.2413405 -0.2348689 0.5271721 0.7801801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2104 2135 -0.086887 -0.494307 -0.835056 0.1943195 -0.7349533 0.4208900 0.4949093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2104 2684 -0.196437 -0.926679 0.652711 0.6462072 -0.5312309 0.4113954 0.3618891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2105 2685 -0.728525 0.631391 0.274594 -0.9223400 0.0226485 0.2688465 0.2765820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2106 2093 -0.879184 -0.043445 -0.009571 -0.7645014 0.2045693 0.3748725 0.4828661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2106 2133 0.955759 0.107481 0.057822 -0.0416984 -0.8190063 -0.4694774 0.3272322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2107 2132 -0.809448 -0.425823 -0.452462 0.1119347 0.4352513 0.2072104 0.8689596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2107 2687 0.382412 -0.649856 0.256436 0.9305656 0.1245105 0.0241035 0.3434586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2108 2688 0.560700 0.871811 -0.107467 -0.2143852 -0.0138912 -0.9764357 0.0204798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2109 2090 -0.534646 -0.966926 -0.128808 -0.0647463 0.3684947 -0.2054826 0.9043210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2109 2130 0.475242 0.695148 0.024006 0.1559387 0.2966722 -0.8705916 0.3601930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2109 2689 0.662063 -0.418054 0.571947 -0.6152383 0.4067958 -0.2733609 0.6174729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2110 2089 -0.532493 -0.386131 0.677385 0.3723504 -0.7176361 -0.1739322 0.5622288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2110 2129 0.378096 0.601583 -0.742445 0.2074332 -0.4291059 0.1686232 0.8627896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2110 2690 -0.499271 0.924181 0.127439 0.1777949 0.8389147 0.5031056 0.1072187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2111 2128 -0.766562 0.305613 -0.696578 -0.2771302 -0.5357543 -0.2013912 0.7717563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2111 2691 -0.561186 -0.782137 0.129179 0.0223569 0.7168429 -0.6492570 0.2531835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2112 2127 0.642181 0.465762 0.494793 0.2332305 0.3973055 -0.8840962 0.0782671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2112 2692 -0.782871 0.493536 0.406972 -0.3285368 -0.1600768 -0.9076539 0.2064059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2113 2693 -0.125269 -0.345898 0.965621 -0.0536412 -0.5490069 0.7216785 0.4182036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2114 2125 -0.706736 0.367348 0.345409 -0.0663323 -0.4792689 -0.1985757 0.8523315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2114 2694 0.598478 0.513648 0.720878 0.2517424 -0.1800216 -0.6814533 0.6632039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2115 2124 -0.328317 1.029617 -0.033768 -0.5140959 -0.0730931 -0.8383859 0.1657464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2115 2695 0.729737 0.241701 0.570382 -0.2761159 0.0181298 0.6855881 0.6733500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2116 1896 0.713837 0.685641 -0.431959 0.8123893 -0.3236369 0.2385937 0.4223219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2116 2696 -0.571658 -0.666694 0.490781 0.2742657 -0.5214168 -0.0536339 0.8062421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2117 2122 0.207510 -0.783116 0.453187 -0.1856885 0.5010558 -0.3323353 0.7771847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2117 2697 0.630463 0.727225 0.523354 -0.3492823 0.2569380 0.8997019 0.0502126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2118 2121 -0.894068 -0.690844 0.206267 -0.6748938 -0.0010142 -0.2114089 0.7069821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2119 2699 0.678566 -0.696398 -0.010126 -0.4013175 0.5589043 -0.3941736 0.6092597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2120 2660 -0.081928 0.561520 0.666878 0.1946591 0.3114108 0.8912240 0.2661783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2121 2158 -0.524054 -0.080007 -0.804595 -0.8724645 0.2727541 -0.3907975 0.1081120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2121 2661 0.175986 -1.130167 0.177228 0.6459198 -0.0331882 -0.5942684 0.4780494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2122 2157 0.302881 -0.643759 0.391610 -0.5603705 -0.4256375 0.3367889 0.6256124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2123 1863 0.737817 -0.525830 -0.561301 -0.4463133 0.0128280 0.8571177 0.2568835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2123 2116 -0.561299 -0.395579 -0.636119 -0.6744528 0.0356501 -0.0862412 0.7323968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2123 2156 0.750758 0.276296 0.759832 -0.4907912 -0.5532045 -0.1039182 0.6650487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2124 2155 -0.147443 -1.066133 -0.176175 0.5229526 -0.3575682 0.1217069 0.7641027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2125 1865 -0.437286 -0.703893 -0.158156 0.0139552 0.8423871 -0.2963705 0.4498374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2125 2154 -0.090498 0.105235 0.945713 0.7641964 -0.4791142 0.4311710 0.0233448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2125 2665 0.774906 0.861733 -0.047727 -0.0501949 -0.5551232 -0.7847847 0.2709829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2126 2113 0.551653 0.404581 0.636055 0.2461426 0.3706069 -0.4619645 0.7672374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2126 2153 -0.673263 -0.252591 -0.745946 0.2525976 -0.3200434 -0.6152634 0.6746982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2126 2666 -0.134457 -0.788798 0.710868 -0.1578140 -0.2354932 -0.8992344 0.3331895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2127 2152 -0.663282 -0.433110 -0.030925 0.4219655 0.0684288 0.7065883 0.5639109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2128 2151 -0.945878 -0.103840 0.216085 0.8749700 0.4532577 -0.1417302 0.0943263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2129 2150 -0.171468 -0.010636 -0.909152 -0.4736069 -0.6586781 -0.5299052 0.2470630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2129 2669 -0.173591 0.952347 0.055791 -0.5450041 -0.0482827 0.7696901 0.3289628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2130 2149 -0.734977 -0.205255 -0.630608 -0.7068056 -0.4984998 0.0671147 0.4974128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2130 2670 -0.694879 0.180342 0.740474 0.0103341 -0.7498259 -0.4345949 0.4987801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2131 1871 -0.691450 0.561627 -0.511753 0.1193129 0.0745433 0.3811116 0.9137624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2131 2148 0.799264 0.031547 -0.796551 -0.4695661 0.1000094 -0.6364808 0.6036538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2131 2671 0.809428 -0.320679 0.590553 0.0426144 -0.2500844 0.8372304 0.4844451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2132 2147 -0.421337 -0.562143 -0.817595 0.1743539 -0.8537482 0.4692116 0.1433712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2132 2672 -0.509776 -0.589971 0.710363 -0.4266637 -0.5994108 0.5509895 0.3937961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2133 2146 -0.641699 0.686533 -0.326016 -0.5059392 0.3319685 0.5976748 0.5259347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2134 2105 0.862553 -0.706059 -0.158774 0.0586016 0.6836162 0.3563362 0.6342391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2134 2145 -0.853816 0.621310 0.155254 0.1964698 0.1351147 -0.0505464 0.9698395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2134 2674 0.026954 -0.079059 1.034196 0.3678738 0.6221509 0.1390364 0.6769535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2135 2144 -1.074563 0.138316 0.553811 0.2648981 0.6057272 -0.7501147 0.0158594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2135 2675 0.233813 -0.468477 0.718347 0.1833938 0.6693666 -0.6843068 0.2236943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2136 2676 -0.775439 -0.337508 0.379049 0.2781994 -0.4078366 -0.2960925 0.8176819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2137 2142 -0.081999 0.159196 -1.048151 0.5767309 0.1288400 -0.7732364 0.2299720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2138 2678 -0.394730 -0.846714 0.294794 -0.7716886 0.0177105 0.6168041 0.1540641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2139 2679 -0.656244 -0.460163 0.481441 -0.3329781 -0.1041893 0.2077121 0.9138522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2140 1840 -0.193552 -0.880138 -0.636086 -0.4246438 -0.1310443 -0.0728656 0.8928581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2140 2640 0.042471 0.942373 0.442721 -0.4518345 -0.4284669 -0.0376450 0.7815655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2141 2138 0.608561 -0.735972 -0.058637 -0.2683902 -0.4471935 0.0110566 0.8531486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2141 2178 -0.712320 0.472326 0.004447 0.6384305 -0.4581309 -0.5881812 0.1912211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2141 2641 -0.583033 -0.726974 0.081247 0.2569539 -0.3362756 0.1461290 0.8941699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2142 2642 -0.068447 -0.813864 0.238346 -0.2009115 -0.0499240 -0.9475146 0.2436356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2143 2136 -0.105956 0.674552 -0.756203 -0.3452403 0.2671353 -0.5663772 0.6990456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2143 2643 -0.009782 0.582199 0.906713 -0.0603665 0.8580984 0.4693096 0.1994281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2144 2175 0.731650 -0.739162 0.156949 -0.6444401 -0.4362718 0.5722570 0.2586230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2144 2644 -0.682073 -0.439872 0.544102 0.2427659 0.2971866 -0.4514596 0.8055613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2145 2174 -0.803526 0.534527 -0.313372 -0.0494162 0.2645580 0.5668690 0.7786055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2145 2645 -0.418563 0.245883 0.991182 -0.4036629 0.0758873 -0.5430196 0.7324118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2146 2173 0.397052 0.329195 0.562810 0.4782418 0.3752984 -0.7199510 0.3348230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2147 2647 0.764229 -0.593210 0.162618 0.5423775 0.1223586 0.5466927 0.6260848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2148 1848 -0.761762 -0.054860 -0.617474 0.1760558 0.8278439 0.5278858 0.0708199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2148 2171 -0.265889 1.022337 0.114870 -0.3377000 -0.0216630 0.1583312 0.9275886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2148 2648 0.687631 0.216663 0.779496 0.0536237 0.3342646 -0.3659255 0.8668853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2149 2170 -0.980760 -0.289101 0.531731 0.1973489 -0.7669005 0.3403736 0.5070136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2149 2649 0.185692 -1.053189 0.061109 -0.4242763 -0.7266939 0.5315552 0.0967193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2150 2169 -0.713434 -0.539675 0.185983 -0.1501430 0.0718233 -0.2743934 0.9471044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2150 2650 0.570820 -0.121598 0.708352 -0.1801935 0.3925442 0.4370125 0.7889610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2151 2168 -0.699029 -0.706569 -0.093680 -0.1134208 0.1988886 0.6611125 0.7144993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2151 2651 -0.866412 0.603942 0.102136 -0.2979427 0.1503649 0.8592992 0.3875893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2152 2167 -0.471299 0.805795 -0.473450 0.0685043 0.2820506 0.9492562 0.1211085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2152 2652 -0.321935 0.174159 0.642134 -0.1184735 -0.6510780 -0.7495984 0.0128004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2153 2166 0.441276 -1.041374 0.093719 -0.0597986 -0.5184184 -0.7316654 0.4385570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2153 2653 1.015737 0.297630 0.425328 -0.7517266 -0.3757465 -0.5393340 0.0532968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2154 2165 0.488129 -0.368313 -1.023970 0.8830636 -0.2008381 0.3537769 0.2338903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2154 2654 -0.503525 -0.902914 -0.114502 0.4054021 0.6495646 -0.5635158 0.3101047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2155 2164 -0.160959 -0.424817 1.032240 0.0973053 0.3200859 -0.1092546 0.9360236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2155 2655 0.645866 0.641554 0.266641 0.4402485 0.5076406 0.6705481 0.3144002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2157 2162 -0.355813 -0.420079 -0.465981 0.0234474 -0.2700487 0.9374237 0.2185421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2158 2161 -0.802481 0.497397 -0.001586 -0.0182408 0.0508767 0.9928979 0.1059840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2158 2658 0.776831 0.668036 0.154914 -0.3019282 0.4286552 -0.3623037 0.7706037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2159 1859 0.660757 -0.134657 -0.361937 -0.2055713 -0.3978590 -0.4055769 0.7968413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2159 2120 -0.519715 -0.214073 -0.701697 0.5060605 -0.4177971 -0.7545266 0.0061677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2159 2659 -0.923959 0.153405 0.544896 0.0580804 0.2579162 -0.8274655 0.4953855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2160 2199 0.713710 -0.862478 0.022039 0.5756905 -0.0878187 -0.3116390 0.7508325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2161 1821 0.563015 0.773435 -0.172761 -0.6141840 -0.4118198 0.6354585 0.2222048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2161 2198 0.826166 -0.827772 0.366189 0.3528182 0.2270002 -0.9068113 0.0410307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2161 2621 -0.596347 -0.839502 0.143372 0.9590901 -0.1552216 -0.0059037 0.2366802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2162 2622 -0.246921 0.199869 1.006825 0.0471769 -0.3405198 0.8937344 0.2882004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2163 2156 0.071099 0.978953 -0.221302 -0.3071976 -0.0505060 -0.7397024 0.5965895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2163 2623 -0.541842 0.003155 0.950927 -0.0814861 0.1853550 -0.4939610 0.8455803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2164 2195 -0.597412 -0.369467 0.880790 0.3748221 -0.6338210 -0.6598020 0.1498025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2164 2624 0.225299 0.858281 0.486942 0.2356092 0.0926340 0.9634017 0.0881161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2165 1825 -0.031887 -0.944779 -0.314526 -0.7628621 0.1092099 -0.5991931 0.2169844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2165 2194 -0.256130 -0.296945 1.065400 -0.0643823 0.3156130 0.6113581 0.7228310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2165 2625 0.115223 0.924354 0.482676 0.0906718 -0.0902373 -0.8441215 0.5206676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2166 2193 0.385377 0.460767 -0.913849 0.5871915 -0.4630346 -0.6563072 0.1003297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2166 2626 -0.557478 1.124693 -0.041312 -0.1856946 -0.2764259 0.6118894 0.7174243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2167 2192 0.601379 -0.873654 0.028581 -0.2861988 0.0553035 0.7610510 0.5795112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2167 2627 0.520548 0.356675 0.424518 0.0212268 0.6540677 -0.3791825 0.6541907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2168 2191 -0.745910 0.630798 -0.598623 0.3674520 0.6075227 0.5812349 0.3975690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2168 2628 0.390161 0.907799 0.440957 0.4216535 0.5926240 0.5893232 0.3517149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2169 2190 -0.368384 -0.932372 -0.084366 0.3129128 0.7474941 0.3950614 0.4327408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2169 2629 0.364449 -0.078284 0.709729 -0.2318310 -0.2520159 0.6770189 0.6514505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2171 2188 -0.048235 0.825880 0.630771 0.8014698 -0.1339816 0.3059467 0.4960764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2172 2147 -0.207758 0.308048 1.014820 -0.6700157 0.6511925 -0.2467019 0.2572266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2172 2187 0.210253 -0.193392 -0.947552 0.7844294 -0.3869803 0.3143159 0.3689476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2172 2632 0.485193 -0.793299 0.263911 0.6263935 -0.1309343 -0.1196129 0.7590653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2173 2186 -0.901564 -0.089468 -0.693566 0.3048868 -0.5511372 -0.2852593 0.7224396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2173 2633 -0.799234 -0.013380 0.764791 0.6214531 0.4059228 -0.6533631 0.1487932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2174 2185 0.238035 0.917518 -0.429762 0.3249722 -0.0808924 -0.1709436 0.9266217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2174 2634 -0.353335 0.736352 0.908934 0.0354140 0.0208282 -0.9380542 0.3440442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2175 1835 0.637677 0.296988 -0.611240 -0.4029242 0.3653083 0.8280497 0.1361457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2175 2184 -0.800428 0.253253 -0.462906 0.3365710 -0.7152265 -0.4059542 0.4586635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2176 2183 0.959510 0.560080 0.036476 0.3208935 -0.4381509 -0.1073647 0.8327809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2176 2636 -0.117250 0.776819 0.559022 -0.1607015 -0.3030253 0.9319536 0.1175294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2177 2142 -0.055965 -0.422714 -0.992317 0.0538677 -0.7432202 0.3738792 0.5522104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2177 2182 0.025045 0.306835 0.942774 0.2889174 0.1566436 -0.4147591 0.8485072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2178 2181 -0.363207 -0.030579 0.890637 0.2037600 -0.0075906 0.7764298 0.5963062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2178 2638 0.720381 0.753778 0.438154 -0.3761763 -0.2896439 -0.2990680 0.8277416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2179 1839 0.934594 0.397634 -0.252424 0.1174127 -0.3874814 0.7541394 0.5170553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2179 2639 -0.687701 -0.341354 0.374265 0.6611162 -0.1340450 0.2264345 0.7026271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2180 2219 -0.828273 0.375422 -0.249483 -0.3897179 0.6071281 -0.2360070 0.6510117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2180 2600 0.347751 0.940345 0.048612 -0.8611003 0.0927537 -0.4343260 0.2475154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2181 2218 0.299551 0.670178 0.657500 0.1007160 -0.2332793 0.2678878 0.9293402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2181 2601 0.788096 -0.647228 0.207061 0.1162060 0.8190434 -0.0954423 0.5536739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2182 2217 -0.739628 0.495806 0.363597 -0.4800574 0.1205166 0.4695424 0.7311297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2182 2602 0.346194 -0.303471 0.917371 -0.3464249 -0.0901557 0.6823528 0.6373824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2183 2216 0.118775 0.241842 -0.968201 -0.9385471 -0.1581579 0.2036022 0.2294810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2184 2215 -0.144725 -0.144168 0.966552 0.1592340 0.4305270 -0.1705919 0.8718885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2184 2604 0.816400 0.595705 0.412766 -0.2273326 0.0660187 -0.7673799 0.5958939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2185 2214 -0.155993 0.431172 -0.968993 -0.4533101 -0.0179417 -0.5647404 0.6893883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2186 2213 -0.545028 -0.446414 0.651971 -0.5728099 0.2508855 -0.7279409 0.2811536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2186 2606 0.533339 0.448430 0.757346 -0.6700373 0.2438822 -0.7005940 0.0271956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2187 2212 -0.613929 -0.396330 0.681494 0.2179445 -0.3942670 -0.8889242 0.0828695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2187 2607 0.765074 -0.114433 0.640513 -0.3920868 0.1396478 0.6876420 0.5949074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2188 1808 -0.757840 -0.083182 -0.585704 0.1471817 -0.1092912 -0.9220017 0.3410364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2188 2608 0.813665 -0.057491 0.563482 0.1333327 0.6774895 0.6952515 0.1996390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2189 2170 0.064180 -0.623358 0.691431 -0.6719999 0.0990764 0.3677716 0.6350937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2189 2210 0.043666 0.819720 -0.566686 0.1151629 -0.6565968 -0.7406590 0.0839194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2189 2609 0.394554 0.732836 0.721515 -0.0715275 -0.5239783 -0.8471007 0.0524493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2190 2209 -0.693435 -0.507759 -0.542069 -0.1099717 0.0269154 -0.1155438 0.9868290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2190 2610 -0.712858 0.602781 0.069843 0.1077066 -0.3458297 -0.9277082 0.0903247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2191 2208 0.941752 -0.375131 -0.571470 0.4174449 0.0879432 -0.4225731 0.7996485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2191 2611 0.605418 0.379529 0.863412 -0.2024384 -0.1569181 0.4406101 0.8603826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2192 2612 0.010917 -0.905122 0.560485 0.5588600 -0.6103357 0.4166663 0.3762380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2193 2206 0.305708 -1.011744 0.073858 -0.4718516 0.5828732 0.6337793 0.1895752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2193 2613 -0.462862 -0.259824 0.851756 0.2194958 0.3564119 0.3028268 0.8562056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2194 2205 -0.503743 0.229069 0.592021 0.4740906 -0.0272992 0.7688888 0.4281389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2194 2614 0.533686 0.147549 0.738179 0.0329468 0.3647557 0.2360524 0.9000817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2195 2204 0.177613 0.838229 -0.133643 0.5766267 -0.4058711 -0.3201942 0.6326499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2196 1816 -0.071737 -0.812309 -0.372990 -0.8797466 0.2192472 -0.0653966 0.4167733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2196 2163 0.435836 -0.366191 0.552357 -0.1254763 -0.5291880 -0.8019934 0.2470270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2196 2616 0.257168 1.035318 0.349724 0.2716987 0.6200056 0.3296870 0.6580877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2197 2162 -0.398551 0.708779 -0.482471 0.5786337 -0.2310407 -0.7566357 0.1982567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2197 2202 0.471023 -0.681285 0.576398 0.4411858 -0.1830317 -0.8735082 0.0940098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2197 2617 -0.969317 0.032701 0.596838 -0.2899881 -0.6064310 -0.0456935 0.7389590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2198 2201 -0.805817 0.614177 0.038859 -0.3410367 0.3139675 -0.5719879 0.6767187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2198 2618 0.219421 0.458506 0.592171 0.2365755 -0.4637389 0.8441062 0.1283080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2200 1780 0.101606 -0.994539 -0.198426 0.1843821 0.2130275 0.3945472 0.8746171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2200 2239 -0.895783 0.027584 -0.258451 0.1455361 0.4919708 0.1402277 0.8468295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2201 2238 -0.931831 -0.551422 -0.348821 0.2012449 -0.6165469 -0.4107619 0.6408159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2202 2237 -0.099328 0.910415 -0.152409 -0.0819947 0.1334079 -0.0113428 0.9875984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2202 2582 -0.058956 0.061623 0.973803 -0.5504176 -0.2445898 -0.5638411 0.5650659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2203 2236 -1.070221 0.161886 -0.320956 -0.4647786 0.4263775 0.4073165 0.6605121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2203 2583 -0.094388 0.757915 0.533066 -0.3976125 0.1352214 0.7458811 0.5169921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2204 2235 -0.654531 -0.116981 -0.745076 -0.0810366 0.5475276 0.7577002 0.3457411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2204 2584 -0.649408 0.517474 0.460768 -0.3312758 -0.7517176 -0.3703473 0.4336126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2205 1785 -0.763774 0.121622 -0.796249 0.1234263 0.3205512 0.7655216 0.5440492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2205 2234 0.663512 0.728678 -0.398697 0.1840496 0.0525179 -0.6981911 0.6898527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2205 2585 0.653608 -0.065748 0.620812 0.1331899 -0.5706608 0.7225196 0.3668408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2206 2233 -0.193756 -0.054754 -0.960370 -0.3706518 0.5738268 -0.0306281 0.7296588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2206 2586 -0.526045 0.868082 -0.109827 0.4635872 0.7407566 0.4856331 0.0229595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2207 2192 0.112169 0.573346 0.885501 0.1451042 -0.1122123 0.4378982 0.8801127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2207 2232 -0.138462 -0.399221 -0.787884 0.1182951 -0.1030060 0.9849461 0.0726440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2207 2587 0.910290 -0.666158 0.291018 0.0240623 0.0368089 -0.9939909 0.1002406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2208 2231 0.902433 0.192224 -0.273510 -0.2470828 0.0781500 -0.3873382 0.8847665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2208 2588 -0.288778 1.028775 0.044199 -0.7700638 -0.4428510 -0.4209749 0.1834801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2209 2230 -0.476918 -0.488506 -0.562066 -0.2150616 -0.0405776 0.3822214 0.8977799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2209 2589 -0.780707 0.635845 0.149762 0.6090064 -0.5247545 -0.5921750 0.0554311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2210 2229 -0.238059 -0.687009 0.313225 0.4208970 -0.2378376 -0.6010569 0.6364036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2210 2590 -0.524882 0.658495 0.481261 0.5218166 -0.0963829 -0.6976563 0.4813455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2211 2188 0.835241 0.411054 0.504695 -0.2092315 -0.0818659 -0.9672435 0.1181530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2211 2228 -0.721068 -0.470607 -0.423408 0.2425190 0.3635791 -0.4291485 0.7904596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2211 2591 -0.600931 -0.189170 0.759917 -0.3425313 -0.0522668 -0.8002123 0.4894903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2212 2227 0.427162 0.422247 0.186060 -0.6555112 -0.0150641 0.5273937 0.5403092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2212 2592 -0.885431 0.415670 -0.122398 -0.6351317 -0.0036201 0.7100959 0.3039054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2213 2593 0.061705 -0.992132 0.469319 0.3170618 0.1752125 -0.3023378 0.8816826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2214 2225 -0.796369 0.609510 -0.099831 0.3607945 -0.1556386 -0.1582942 0.9058404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2214 2594 -0.631658 -0.526795 0.582589 -0.4170929 -0.1998738 0.2664629 0.8456249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2215 2224 -1.019486 -0.166078 0.500936 -0.6990995 0.2568129 -0.5442120 0.3861869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2216 2223 0.434180 0.254988 0.855578 -0.0335579 -0.1950577 0.8980289 0.3929001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2216 2596 0.057070 -0.949175 0.115021 0.9420395 0.3033712 0.0558009 0.1319610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2218 1798 -0.364695 0.801028 -0.276375 0.3345117 -0.3769892 0.8619682 0.0546988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2218 2221 0.688504 0.504242 0.295081 -0.0809607 0.8348261 -0.3674971 0.4018168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2219 1799 0.576961 -0.389012 -0.560264 -0.2829452 -0.3187617 0.9028213 0.0569799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2219 2599 -0.737988 0.387517 0.739954 0.2734911 -0.0845641 -0.4301904 0.8561470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2220 2259 -0.712163 0.488992 0.475071 -0.4138621 -0.5031265 0.7073225 0.2743660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2221 2258 -1.018922 0.135105 0.196510 0.8911163 0.1435848 -0.0966379 0.4194714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2221 2561 0.019180 -0.613352 0.695981 -0.3871952 0.5690967 -0.5432716 0.4806919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2222 2217 -1.038247 0.123576 -0.186469 0.1922858 0.7011439 -0.0066412 0.6865706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2222 2257 0.935042 -0.125374 0.223738 -0.0611324 -0.8279016 0.4999297 0.2468035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2223 2563 -0.945798 0.594279 0.251108 0.0203440 -0.1789637 0.6132239 0.7690998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2224 1764 0.195389 0.942442 -0.258659 -0.3468763 0.4060722 -0.8447557 0.0342042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2224 2255 0.062189 -0.169145 -0.968110 0.8765373 -0.2424386 0.4049689 0.0943723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2224 2564 -0.182056 -0.962622 0.128721 0.8002966 -0.1910230 -0.1479241 0.5487750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2225 2565 -0.117009 -0.037463 0.992510 -0.5395583 -0.5400006 0.2322332 0.6027801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2226 2213 0.593999 0.667174 -0.625807 -0.4744571 0.5440438 -0.6782549 0.1373941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2226 2566 0.907705 0.059520 0.649791 -0.4417655 0.4302219 0.5840334 0.5278801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2227 2252 0.374814 -0.964854 0.064946 0.3445092 0.5463384 0.4771328 0.5959631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2227 2567 0.048680 -0.032205 0.869540 0.2587479 -0.2587487 -0.0871119 0.9265582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2228 2568 -0.843292 -0.441629 0.505423 -0.3839658 -0.4461267 0.3880052 0.7092202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2229 2250 0.645575 0.416287 0.643346 -0.3151488 -0.3816509 0.1324858 0.8587615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2230 2249 -0.774319 0.289784 -0.773101 -0.6509845 -0.2741037 -0.7078743 0.0005856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2230 2570 -0.078849 0.905815 0.732798 -0.1658471 -0.0029591 -0.5241700 0.8353034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2231 1771 0.759269 -0.321309 -0.412525 -0.1217491 -0.3976827 0.7004550 0.5799900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2231 2248 0.490939 0.798776 0.179759 -0.4898922 -0.6865749 -0.0301043 0.5363901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2231 2571 -0.901571 0.178738 0.315426 -0.1665816 -0.8347398 -0.0638139 0.5209490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2232 2247 -0.101191 0.653011 -0.665214 -0.5386008 0.5594699 0.3454756 0.5268295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2233 2246 0.762192 0.643479 -0.000682 -0.1000706 -0.6993483 -0.7010840 0.0968452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2234 2245 -0.226386 0.706009 -0.641924 -0.0866543 0.0287218 0.7272072 0.6803203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2234 2574 0.153671 0.730671 0.699546 -0.4954560 -0.3929058 0.6946370 0.3429690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2235 2244 0.764300 -0.532346 -0.506862 0.0547810 -0.2205084 -0.8525507 0.4706723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2235 2575 0.641146 0.796295 0.534892 -0.1451168 -0.0030310 0.7948618 0.5891746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2236 2243 0.113067 0.996216 0.125997 0.0406252 0.3609497 -0.9312768 0.0280788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2236 2576 -0.431537 -0.049005 0.839261 0.2165038 0.2308680 0.7404685 0.5929017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2237 2242 -0.201328 0.774837 0.078414 -0.6151684 0.4220271 0.6633478 0.0585713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2238 2241 -0.009017 -0.880197 0.583996 0.6571931 0.6715496 0.3418419 0.0161987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2238 2578 0.880834 0.389939 0.383626 -0.2208803 0.1332151 -0.3422342 0.9035161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2239 2579 0.068421 0.925525 -0.227762 -0.7843699 0.0421672 0.5905503 0.1850299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2240 2279 0.133441 -0.576009 0.726660 0.4988479 0.6076653 0.5003272 0.3627207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2241 2278 -0.666760 0.379858 -0.612706 0.1876442 0.3369099 0.4335853 0.8144232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2241 2541 0.394357 0.902858 0.323679 -0.7882079 0.1698612 0.3084169 0.5047321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2242 1742 0.641164 -0.631548 0.057197 0.6886055 -0.5913903 -0.2619484 0.3278156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2242 2277 -0.362874 -0.369793 0.733561 -0.8897605 -0.4189799 0.0176114 0.1801999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2243 2276 -0.162303 -0.635552 -0.631565 0.2754580 -0.8941370 0.3458824 0.0707626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2243 2543 0.361611 -0.604190 0.547035 -0.3198338 0.0588160 -0.4441279 0.8348637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2244 2275 -0.163612 0.457272 -0.635021 -0.3048304 -0.8006916 0.2189869 0.4669220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2244 2544 -0.783764 0.304153 0.481184 0.0459194 0.2776122 -0.9588168 0.0386410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2245 2274 0.905476 0.252766 -0.585853 0.0518911 0.4765265 -0.7660434 0.4282607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2245 2545 0.627623 0.050912 0.733949 -0.3224306 0.2150995 -0.5301121 0.7541564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2246 2273 -0.764625 0.287461 0.571256 0.1947579 0.3282720 0.8396538 0.3863785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2246 2546 0.548862 0.003428 0.701910 -0.3625441 -0.6270961 -0.6009500 0.3378924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2248 2271 0.724024 0.526583 -0.081247 -0.0541205 0.3902952 0.2317357 0.8894039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2248 2548 0.580465 -0.711633 0.765773 -0.0024250 -0.0730863 -0.0355465 0.9966890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2249 2270 -0.340465 -0.533180 -0.650317 0.1120891 0.1370414 -0.9533863 0.2443569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2249 2549 0.744396 -0.432721 0.112707 -0.3779298 0.3281559 -0.2410500 0.8314912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2250 2269 1.042911 -0.228220 0.163431 0.0631394 0.2171478 -0.3425314 0.9118840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2250 2550 -0.199927 -0.326192 0.757423 -0.4982232 -0.1094765 0.7899657 0.3402100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2251 2228 0.864994 -0.109824 -0.339879 -0.2512779 0.1064608 -0.8071954 0.5234129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2252 2267 -0.889580 -0.540397 0.270136 -0.4445747 -0.0012418 -0.8833939 0.1482124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2252 2552 -0.349829 0.855438 0.283623 0.2074935 0.9226902 0.3233662 0.0319925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2253 2553 0.728751 -0.405203 0.576789 0.2218447 0.5517129 0.2588317 0.7611859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2254 2225 0.826113 -0.107551 0.546779 0.0765044 -0.3320890 -0.0096394 0.9400910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2254 2265 -0.714190 0.193554 -0.767232 0.7118272 -0.1684877 0.0248224 0.6813940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2254 2554 -0.602714 -0.181718 0.758383 -0.1371646 -0.6428139 0.6233634 0.4235495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2255 2264 -0.432766 0.291826 0.859955 -0.8212633 -0.0158115 -0.0655240 0.5665538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2255 2555 0.392815 0.792903 0.070678 0.1832314 0.9317088 0.3089419 0.0538494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2256 2223 0.871352 -0.042479 -0.502172 0.4449063 0.3056939 -0.7451500 0.3916134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2256 2263 -1.056052 0.123343 0.408076 0.2645900 0.4947774 0.5425149 0.6251920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2256 2556 0.394054 -0.276769 0.850943 0.3035438 -0.5865242 0.7505238 0.0237601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2257 2557 -0.171937 -0.697506 0.497726 0.2687701 0.4067192 0.0212559 0.8728633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2258 2261 -0.880275 -0.368590 -0.061179 -0.3104509 -0.0702365 -0.2055407 0.9254405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2259 2559 -0.604497 0.364085 0.738794 -0.0311135 -0.2290896 -0.0875258 0.9689629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2260 2299 0.191092 -0.383159 -0.967857 -0.1923774 -0.7857215 0.5279228 0.2587084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2260 2520 0.447471 -0.832955 0.590069 0.3530586 -0.6493690 0.6536575 0.1624850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2261 2298 -0.876226 -0.462117 -0.507134 -0.2114315 -0.3533112 0.4073462 0.8151914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2261 2521 -0.600277 0.594287 0.743924 -0.6322760 0.5271397 0.5675310 0.0161051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2262 2297 0.541350 0.821382 0.177285 -0.1313356 0.3756415 0.4051418 0.8231067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2263 2296 -0.208567 0.623773 -0.584588 0.4732938 -0.0349837 0.0325258 0.8796085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2263 2523 -0.433875 0.469597 0.568845 0.1153141 -0.5418664 0.4217715 0.7177690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2264 2524 0.417981 -0.362916 0.708085 0.2689086 0.2634046 0.5750186 0.7264020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2265 2294 -0.713584 -0.613177 0.159380 -0.0088323 0.2346213 0.9464797 0.2214747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2265 2525 -0.441535 0.984134 0.101933 -0.8190565 0.0763835 0.5684394 0.0137387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2266 2253 -0.638955 -0.495558 -0.500830 -0.1229276 -0.4723557 0.8446796 0.2197391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2266 2293 0.719108 0.495165 0.628959 0.4363429 -0.4633653 0.5737174 0.5155054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2267 1727 -0.087873 1.128040 0.005620 0.8060821 0.5101960 -0.2900951 0.0760033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2267 2292 0.822718 0.195710 -0.639986 0.7088175 0.1048346 0.5624371 0.4126161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2268 2251 0.529599 -0.442465 -0.654113 0.7808032 -0.2563074 -0.5598691 0.1058280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2268 2291 -0.547633 0.548805 0.783805 -0.0855978 -0.1093189 0.9797395 0.1443360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2268 2528 -0.648925 -0.736856 0.180122 0.9408235 -0.1594959 0.0950446 0.2835113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2269 1729 0.400190 0.334731 -0.841891 0.1772485 -0.6065654 -0.5800423 0.5140159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2269 2290 0.785070 0.259587 0.448630 0.1524648 0.0956377 0.9776883 0.1083212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2269 2529 -0.388899 -0.466108 0.830537 0.6249426 -0.1917645 0.3890455 0.6490891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2270 2289 0.968669 0.455626 0.011914 -0.2867902 -0.4453751 -0.8307493 0.1710205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2270 2530 -0.299177 0.746928 0.131598 0.0837734 0.2346267 0.6272384 0.7379054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2271 2288 0.647323 0.203027 0.834373 0.2553093 -0.6454845 0.7119848 0.1060398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2271 2531 -0.062199 -0.684374 0.527460 0.3856803 -0.4636183 0.6811534 0.4151371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2272 1732 0.650478 -0.480928 -0.499457 -0.7788849 -0.3367287 0.3313677 0.4124895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2272 2532 -0.661048 0.613011 0.470884 0.2421500 -0.6990772 -0.5545174 0.3810051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2273 2533 -0.338248 0.228203 0.906936 0.2988031 -0.5431595 0.0122194 0.7845669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2274 2285 -0.222663 0.942396 -0.198447 0.0638151 0.0182970 0.9185342 0.3897277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2274 2534 -0.838682 -0.178670 0.829861 -0.3756336 -0.1020944 0.7223382 0.5715799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2275 2284 0.020606 0.857707 0.438796 0.1862626 -0.1714564 0.5566814 0.7912110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2275 2535 0.972607 -0.497517 0.655851 0.8453615 0.0387383 0.0114768 0.5326645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2276 2283 0.276243 0.091931 1.073564 0.5935934 0.2643350 0.6267673 0.4300425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2276 2536 -0.073438 -1.019226 0.143653 0.1327052 -0.2312275 0.7063932 0.6556919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2277 2282 -0.511835 -0.368463 -0.838549 0.3274499 0.7788698 -0.0044098 0.5349008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2277 2537 -0.012094 -0.926927 0.321589 0.1089763 -0.5064572 0.0172594 0.8551768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2278 2281 0.350802 0.031736 -0.845548 0.3333046 0.1672832 0.5404438 0.7542181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2278 2538 0.691535 0.555208 0.541321 -0.5252336 0.0361350 -0.3215263 0.7870481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2279 2539 0.607490 0.441111 0.719033 -0.4971666 -0.5410298 -0.6726224 0.0876997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2280 2319 0.501914 0.806848 -0.669028 0.1839205 -0.0685372 0.1204490 0.9731228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2282 2317 0.523780 -0.794294 0.024624 -0.7471048 -0.4223511 0.4301301 0.2800749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2282 2502 -0.701168 -0.450633 0.195670 0.3484149 0.1665180 -0.6839009 0.6189979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2283 2503 -0.684787 0.687831 0.409771 -0.0300850 -0.9310019 -0.0512433 0.3601451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2284 2315 0.788723 0.288467 0.101596 0.2092040 0.6812341 -0.5571881 0.4262572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2284 2504 0.260878 -0.685887 0.716481 0.3609521 -0.4451179 0.5739229 0.5849753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2285 2314 0.842672 -0.217845 -0.271981 -0.0106940 -0.2829607 -0.7310127 0.6208376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2286 2273 0.068887 -0.664329 0.697964 -0.3098816 0.5470142 0.2105341 0.7486149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2286 2313 -0.056067 0.564534 -0.841576 -0.6363721 -0.3609665 -0.6398249 0.2352823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2287 2272 -0.644717 -0.847455 -0.283297 0.4517281 0.3927036 0.7576073 0.2603014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2287 2507 0.665313 -0.716118 0.389328 0.7211732 0.2239904 0.4453596 0.4810326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2288 2311 -0.143794 -1.254568 -0.129609 -0.1043992 0.6195990 -0.5876907 0.5097230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2288 2508 0.804041 -0.161982 0.646392 0.1049651 -0.0578160 -0.9742158 0.1911629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2289 2310 -0.945060 0.133278 0.629762 -0.3469894 0.1912474 -0.9179855 0.0180405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2289 2509 0.415092 -0.614078 0.333678 -0.1436570 0.6826286 0.2594238 0.6678923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2290 2309 -0.455162 -0.324753 1.042983 -0.0572406 0.8491590 0.3561378 0.3857698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2290 2510 0.603891 0.602887 0.688317 -0.1212048 0.7191466 0.1351716 0.6707206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2291 2308 0.856922 -0.512703 0.642428 -0.1353817 -0.0615647 0.9583834 0.2436859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2291 2511 0.143299 0.771401 0.352020 0.0847194 0.7417820 0.6631099 0.0535472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2292 2307 -0.197981 -0.727713 0.784828 0.0091323 -0.8185512 -0.0428549 0.5727600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2292 2512 -0.662153 0.676639 0.643125 -0.2693093 0.4235978 0.8568093 0.1179626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2293 2306 0.680003 -0.849393 -0.271067 -0.1760812 0.5858584 0.4996085 0.6133161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2293 2513 0.768353 0.609792 -0.101854 -0.0932314 0.8207775 -0.0728598 0.5588592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2294 2305 0.701925 0.965992 -0.218794 -0.3538186 0.2505580 -0.9000910 0.0432359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2294 2514 0.721899 -0.249380 0.722419 0.5858461 -0.4623204 0.6646472 0.0358927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2295 1715 -0.745401 -0.486792 0.021010 -0.1528244 -0.0632522 0.5193424 0.8384076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2295 2264 -0.528902 0.647627 0.605075 0.2102775 0.3303502 0.6270946 0.6733532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2295 2304 0.510595 -0.745236 -0.422669 -0.2170221 0.0520661 -0.6752801 0.7029846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2295 2515 0.718549 0.516720 0.137668 -0.0932705 -0.7908746 -0.5496913 0.2523041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2296 2303 -0.225054 -0.002515 -0.977037 -0.3281099 0.0659262 0.7643309 0.5511768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2296 2516 -0.302326 0.890996 0.104229 0.0777649 -0.8224968 -0.5372374 0.1697869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2297 2302 0.819460 0.201538 0.703478 0.6244821 -0.5963599 -0.4644562 0.1966148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2298 2301 -0.693071 0.267373 0.198480 -0.0167727 0.4998480 -0.2886074 0.8164413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2298 2518 0.513464 0.121360 0.933599 -0.3273425 -0.3545652 0.7781762 0.4019604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2300 1680 0.677919 -0.578921 -0.597575 0.0088281 0.2316176 0.6855764 0.6901162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2300 2339 -0.749175 -0.214192 -0.683699 0.3579272 -0.1685786 0.4203939 0.8165405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2300 2480 -0.423314 0.753020 0.497836 0.1672019 0.1915793 -0.9530773 0.1642701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2301 2338 -0.665750 -0.428997 -0.726219 0.2033270 -0.5356203 -0.5005313 0.6490280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2301 2481 -0.669048 -0.191994 0.566592 -0.5293488 -0.4277554 -0.3632717 0.6362773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2302 2337 -0.593577 -0.078184 -0.889096 0.3540130 0.5093555 -0.6291206 0.4684432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2302 2482 -0.727958 -0.214411 0.534530 -0.2899779 -0.0107770 -0.2939815 0.9106984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2303 1683 -0.726499 -0.083977 -0.801652 -0.1440805 0.3332684 0.8659560 0.3439379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2303 2336 0.582812 0.446327 -0.666519 -0.5216591 0.0282420 -0.8067178 0.2761892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2303 2483 0.736746 -0.108701 0.720152 0.5662036 0.4483728 0.6074898 0.3306531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2304 2335 0.479122 0.610838 -0.561250 -0.5838951 0.1441437 -0.1847109 0.7772844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2304 2484 -0.435796 0.469057 0.438081 -0.0409468 -0.3033001 -0.4607884 0.8330705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2305 1685 0.076218 0.247956 -1.106229 -0.2523903 -0.0759992 0.8715131 0.4135071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2305 2485 -0.066041 -0.079323 1.111873 0.3978144 -0.2500884 -0.0958154 0.8775072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2306 2333 -0.316361 -0.891630 -0.380061 0.3214969 -0.0987280 0.8883060 0.3127378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2307 2332 0.627194 -0.502093 -0.262692 0.0964484 0.3202429 -0.2266341 0.9147563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2307 2487 0.686877 0.558431 0.380793 -0.4304261 0.7465513 -0.4435866 0.2462226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2308 2331 -0.901806 0.155314 0.425387 0.0647740 -0.1113022 -0.8041948 0.5802472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2308 2488 0.299354 -1.072104 0.221742 0.7977700 -0.3587341 0.4389198 0.2054805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2309 1689 0.911426 -0.459471 -0.622057 -0.1577374 0.1227329 -0.6152751 0.7625563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2309 2330 -0.317330 0.352751 -0.657461 -0.3181237 -0.5095105 -0.5185431 0.6085305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2311 2328 0.766924 -0.187397 0.664748 0.3028549 0.5417210 -0.7612964 0.1877368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2311 2491 -0.301751 -0.169227 1.003062 -0.1023450 -0.6221856 0.4354715 0.6424758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2312 2287 0.656161 -0.677970 -0.713714 0.0288210 -0.8742086 -0.2301869 0.4265474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2312 2327 -0.315980 0.659550 0.498818 0.7329621 0.1440959 -0.4154501 0.5190415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2312 2492 -0.693799 -0.712050 0.087944 0.1668229 -0.2996625 0.4924305 0.7999279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2313 1693 -0.518351 0.445566 -0.789913 0.1355498 -0.0628277 0.9654736 0.2134002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2313 2493 0.566344 -0.137097 0.778206 -0.6453945 0.2163647 -0.4203984 0.5999312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2314 1694 0.466534 -0.554458 -0.617684 -0.0090136 0.5633159 0.5599369 0.6075068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2314 2325 -0.387801 0.729426 -0.489869 -0.8359118 0.0536510 0.2561526 0.4824509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2315 2495 -0.455744 -0.213449 0.790794 0.1359276 -0.6463769 0.3222595 0.6781367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2316 2283 0.897850 -0.610173 -0.155686 -0.1807366 0.7031566 0.5527146 0.4091597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2316 2323 -0.746532 0.328865 -0.193642 -0.2263502 -0.4402342 -0.8607096 0.1189050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2316 2496 0.186902 0.488776 0.915336 -0.4938994 0.3305998 0.7293970 0.3387436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2317 2322 -0.703770 0.704867 -0.593769 0.2380428 -0.7599134 -0.5961493 0.1023390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2317 2497 -0.780858 -0.313223 0.542369 0.4772932 -0.0345900 -0.8383747 0.2610031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2318 2281 -0.185659 -0.817433 -0.750237 -0.6630547 0.3377928 -0.6658392 0.0539687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2318 2321 -0.107282 0.910202 0.777280 -0.3244702 0.5084517 0.2079220 0.7700418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2318 2498 0.215503 -0.486072 0.593304 0.2429139 0.4897590 0.5784855 0.6053788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2319 2499 0.485233 0.351478 0.694869 0.0260617 -0.4116330 -0.8994869 0.1442300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2320 2359 -0.709701 -0.648071 -0.408203 -0.4531075 -0.1843891 0.2227294 0.8432590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2320 2460 -0.659488 0.956975 0.171019 0.2286853 -0.5122001 -0.2632307 0.7848972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2321 1661 0.463422 0.881842 -0.160475 0.3086146 -0.3043591 -0.1454744 0.8893592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2321 2358 -0.648291 0.529437 0.627258 0.2243064 0.4564152 -0.4006240 0.7621497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2321 2461 -0.415202 -0.834315 0.256526 0.3544589 -0.4360096 0.4463091 0.6964645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2322 2357 0.136938 -0.302541 0.947670 0.8688379 -0.2932258 0.3881511 0.0920770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2322 2462 0.801880 0.782704 0.007563 0.6458198 -0.0040802 0.7460888 0.1620237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2323 1663 -0.414202 -0.359912 -0.863739 -0.4788266 0.3204392 0.4764319 0.6641208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2323 2463 0.160669 0.472740 0.929287 -0.4325081 -0.1299393 0.8340950 0.3167617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2324 2315 -0.887827 0.148322 0.406368 0.2770521 0.7576303 -0.5875957 0.0630053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2324 2355 0.860682 -0.278456 -0.369377 0.7678197 0.2300008 0.5588501 0.2126949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2324 2464 -0.139944 -0.979375 0.462583 -0.0213586 0.5299844 -0.8083014 0.2555568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2325 2354 0.405396 -0.056112 1.026986 0.4536701 -0.4613949 0.7401549 0.1829451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2325 2465 -0.632697 -0.562067 0.261783 -0.1380966 -0.3703924 0.9155106 0.0746933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2326 2313 -0.028334 1.016427 -0.214636 0.1431476 0.1220065 0.4086386 0.8931056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2326 2353 0.073096 -0.838982 0.225898 -0.3120011 0.0673581 -0.3531226 0.8794445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2326 2466 0.842293 0.172841 0.568974 -0.5430012 -0.0133929 -0.6123104 0.5744966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2327 2352 -0.855422 -0.353400 -0.174973 0.6867357 -0.4310256 -0.4891476 0.3214743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2327 2467 -0.316702 -0.016656 0.958207 -0.1807070 -0.3343996 -0.8361450 0.3954534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2328 2351 -0.926264 0.157736 0.071173 -0.0189296 -0.3340349 -0.1209639 0.9345748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2328 2468 -0.199462 -0.884892 0.489682 -0.3241055 -0.3698077 0.6132575 0.6181531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2329 1669 0.605511 0.785684 -0.121655 0.9458445 0.0102082 -0.3019379 0.1187746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2329 2310 -0.567926 0.141716 -0.774113 0.6058776 -0.4145312 0.2822342 0.6175921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2329 2350 0.714059 -0.193503 0.702543 -0.0206126 0.0353386 -0.9819394 0.1847194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2329 2469 -0.492935 -0.907070 0.201130 0.2764010 -0.6104460 0.6269125 0.3974152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2330 2349 -0.947507 -0.418287 0.349972 0.4169595 -0.2854779 0.0573653 0.8610205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2330 2470 0.324066 -0.595731 0.730354 0.0242800 0.2717445 0.4143410 0.8682666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2331 2348 0.150986 -0.610906 0.664379 0.1831845 0.0794873 -0.0379477 0.9791247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2331 2471 0.915954 0.334388 0.137894 0.9085892 -0.0699850 0.3759837 0.1679406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2332 2347 0.942802 -0.362727 0.528680 0.1208210 0.4175506 -0.0094037 0.9005362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2332 2472 -0.097289 0.652575 0.810452 -0.4246663 -0.6916208 -0.4323778 0.3928979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2333 2346 -0.647327 0.869321 -0.011189 -0.0094699 0.0505239 -0.9065895 0.4188713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2333 2473 0.519297 0.281688 0.685166 -0.6579100 0.2886249 -0.4634494 0.5187145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2334 2305 -0.213245 -0.265078 0.933996 0.6500818 -0.1834101 0.6497996 0.3485899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2334 2474 0.709916 -0.562217 -0.120544 -0.4291992 0.7048686 -0.5283672 0.1994404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2335 2344 0.230512 0.598151 0.720511 0.5299926 -0.4272122 -0.7015488 0.2107769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2335 2475 -0.693077 -0.333086 0.519122 0.1779304 -0.3262720 0.9273838 0.0429731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2336 2343 -0.866941 0.417284 0.485106 0.0639809 0.5515448 0.2301493 0.7992097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2337 2342 0.977132 -0.283788 -0.440546 0.3286761 -0.8161267 0.4660354 0.0933824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2337 2477 -0.302893 -1.096763 -0.000241 -0.2461298 -0.0544934 0.9010748 0.3528665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2338 2341 0.102902 -1.135801 0.126375 -0.0508096 0.4062513 0.9013156 0.1414515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2338 2478 0.335593 0.111609 1.003149 0.1248400 0.1635256 -0.8629254 0.4615561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2339 2479 0.493195 0.904370 -0.120040 -0.5674658 0.1124942 -0.4640046 0.6708408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2340 1640 0.845751 0.262919 -0.524131 -0.2677208 -0.6258581 0.3796892 0.6264690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2340 2379 0.555462 -0.569682 0.574428 0.7235942 0.5790261 -0.3498727 0.1368552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2340 2440 -1.027528 -0.412457 0.591523 -0.5648751 -0.5256508 0.0509851 0.6340409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2341 2378 -0.352636 0.850528 -0.385760 -0.4706398 -0.7707868 -0.0204350 0.4289153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2341 2441 -0.535920 0.416852 0.665213 -0.1850883 -0.4996023 0.5611982 0.6334007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2342 2377 -0.788658 -0.517359 0.603314 -0.2361649 -0.3857285 -0.6779369 0.5795180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2343 2376 -0.736235 0.555317 -0.585160 -0.0911142 0.5293913 0.7256800 0.4299205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2343 2443 -0.702781 0.375003 0.591339 0.1022595 -0.0282374 -0.3246447 0.9398678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2344 2444 0.149100 0.854572 0.530180 0.1281288 -0.0405959 -0.9577035 0.2544387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2345 2334 0.542491 -0.540326 0.092463 0.3880901 -0.4367148 0.7472957 0.3165682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2345 2374 -0.751003 0.774028 -0.176578 -0.6555481 0.3174597 0.0306125 0.6844991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2345 2445 0.244833 0.553523 1.056716 0.4993609 0.3356601 0.3274097 0.7285423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2346 2373 -0.216900 -0.972940 -0.144927 -0.0820155 -0.5189148 0.5987036 0.6046114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2346 2446 -0.529172 0.079711 1.082441 -0.2954598 0.4103433 -0.7527893 0.4214619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2347 2372 0.029250 0.037811 1.011819 -0.0997902 -0.1613506 -0.0568109 0.9801941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2348 2371 0.161949 -0.401770 0.763049 -0.1669651 0.6487248 -0.2427177 0.7016887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2348 2448 0.841232 0.284005 0.181899 -0.8716475 0.2579914 -0.2534609 0.3308000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2349 2370 -0.577587 0.254956 0.719995 0.6500912 -0.1088348 0.6158817 0.4315393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2349 2449 0.718568 0.234570 0.657728 -0.4658832 0.5162044 0.3200898 0.6434504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2350 2369 -0.501198 0.314148 0.892838 -0.1005913 0.8465774 0.5035542 0.1400758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2350 2450 0.867461 0.490456 0.148144 -0.7096935 0.0738405 -0.5658665 0.4131317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2351 2451 0.352967 -1.021721 0.569862 0.7279220 -0.3760056 0.1898521 0.5410227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2352 2367 0.259541 0.029522 1.093296 -0.5942541 0.4747384 0.6492124 0.0029421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2353 1653 -0.585601 -0.178988 -0.721363 -0.2475816 -0.4960269 -0.4751386 0.6833037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2353 2366 0.656634 -0.762274 -0.382734 0.0620022 -0.3545048 -0.6798318 0.6389920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2353 2453 0.359755 0.292069 0.998620 0.4005964 0.4305936 -0.3468015 0.7306438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2354 2365 0.733548 -0.613024 0.294646 0.1465703 -0.2273727 -0.9625724 0.0165301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2354 2454 0.722063 0.511175 0.266805 -0.2876538 0.3787443 -0.5213450 0.7085249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2355 2364 -0.170997 -0.013802 0.889389 -0.4730240 -0.0689751 -0.4509443 0.7537506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2355 2455 -0.299076 0.815552 0.056271 0.7703357 -0.4444495 -0.4376558 0.1323066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2356 2323 -0.751526 -0.582274 -0.256801 0.7262916 -0.0752755 0.5218463 0.4410335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2356 2363 0.685043 0.686486 0.256044 0.5011724 0.4230903 -0.0506507 0.7531636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2356 2456 0.430031 -0.803262 0.419541 -0.2864646 0.2656351 -0.2776687 0.8776538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2357 2362 0.876502 0.075103 -0.454528 -0.1646101 -0.9279694 0.2544552 0.2168616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2357 2457 0.098982 -1.006458 0.289345 -0.0972936 -0.0058214 -0.2545244 0.9621421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2358 1658 -0.222678 0.868183 -0.558224 -0.0548008 0.0419366 0.0490922 0.9964076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2358 2361 -0.992814 -0.315726 -0.245369 0.3226128 -0.4408815 0.7007887 0.4587371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2359 2459 -0.093529 0.456365 0.930937 -0.3228431 0.6549802 0.5118352 0.4525461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2360 2399 -0.454733 0.035953 -0.789631 0.2265392 -0.1059690 0.0316035 0.9677044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2360 2420 0.085536 -0.850212 0.023798 0.3591240 0.8658277 -0.1129355 0.3295723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2361 2398 0.049356 0.995826 0.060256 -0.0236442 0.6268655 0.7709648 0.1099726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2361 2421 0.025431 -0.038126 0.998836 -0.2581852 0.4985167 0.8275222 0.0053431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2362 2422 -0.417838 -0.759309 0.082063 0.7060420 0.2827580 -0.1811916 0.6234760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2363 2396 0.546236 0.861136 -0.060802 -0.2493366 -0.0542764 -0.6134432 0.7473772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2363 2423 -0.296417 0.345870 0.791774 0.0888026 0.3126592 -0.0949658 0.9409250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2364 2424 -0.800516 -0.107445 0.595198 0.0125460 -0.0702118 0.2345933 0.9694735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2365 2394 -0.713079 0.687011 -0.311931 0.0201170 0.0718936 0.0256317 0.9968799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2365 2425 -0.774090 -0.454873 0.343368 0.3333256 0.5187882 -0.7402086 0.2680373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2366 1626 0.120380 -0.786370 -0.388609 -0.3074159 0.8800595 0.1550656 0.3270250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2366 2393 0.326901 0.298878 -0.740148 -0.2181291 0.6810704 0.3928282 0.5781426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2367 2392 -0.864056 0.470215 -0.215043 0.5949274 0.0925009 -0.1055706 0.7914290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2367 2427 -0.545309 -0.300279 0.925499 -0.3794754 -0.2594786 0.8174586 0.3470313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2368 2351 -0.919026 0.262093 -0.480731 0.0991722 0.2197085 0.9181423 0.3144959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2368 2428 0.482240 0.860480 0.060477 -0.5467191 -0.6351625 -0.5364004 0.0997072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2369 2429 -0.847046 0.248806 0.482727 0.5732097 -0.2756061 -0.7667324 0.0871402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2370 2389 0.723422 0.888695 -0.503475 -0.0779301 0.1091935 -0.9224792 0.3619887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2371 2388 -0.359703 -0.838144 0.336615 -0.5611379 0.2133356 0.4690249 0.6477869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2371 2431 -0.262986 0.284474 0.894236 0.1377565 0.2693870 0.8957999 0.3255708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2372 2387 0.603073 -0.230064 0.738612 0.0183597 0.1741892 0.7552413 0.6316103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2372 2432 -0.404034 0.841163 0.627945 -0.0771095 0.3648860 0.6520691 0.6600896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2373 2386 -0.598108 0.053656 0.646060 0.1526331 -0.6388206 0.7119343 0.2485173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2373 2433 0.514595 -0.431345 0.660387 -0.5580764 0.3881156 -0.6340664 0.3686147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2374 1634 0.406274 0.810707 -0.386175 0.4209672 -0.1674522 0.7542552 0.4752320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2374 2385 -0.771885 0.608921 0.493094 0.7340986 -0.3242882 0.2054025 0.5601306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2374 2434 -0.360404 -0.842467 0.241096 0.4759182 0.4094554 -0.5692456 0.5308555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2375 2344 0.571763 -0.422168 0.624128 0.4096277 -0.4566127 -0.0202790 0.7894927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2375 2384 -0.840669 0.169499 -0.596219 0.4580483 -0.3208541 0.5062549 0.6564682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2375 2435 -0.481832 0.239827 0.644320 -0.0209033 -0.3637982 -0.0399359 0.9303865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2376 2383 0.960018 -0.130050 0.136145 0.0378500 -0.0827795 0.3841827 0.9187593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2377 2382 0.827774 -0.627742 -0.272851 -0.0357076 0.9329849 0.0676744 0.3516877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2377 2437 0.737242 0.659146 0.241756 -0.0632278 0.2927699 0.4651970 0.8329944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2378 2381 0.354601 0.281149 0.890914 0.7503015 -0.0867577 0.6316378 0.1747983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2378 2438 0.820053 -0.522696 -0.096841 0.4368404 0.1012707 0.0989514 0.8883262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2379 2439 -0.546304 -0.592563 0.122604 -0.1880866 -0.7555742 0.5585499 0.2859249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2380 1600 -0.426019 0.470003 -0.510549 0.2437241 -0.3105457 0.9187252 0.0101958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2380 2400 0.500571 -0.712751 0.686414 0.2574828 -0.3107097 0.9140041 0.0419347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2381 2401 0.104561 0.391549 1.035437 0.0044037 -0.2246818 -0.2202690 0.9491998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2382 2402 -0.561643 0.514148 0.558533 0.6458306 0.0714878 -0.7381231 0.1815672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2383 2403 0.741039 0.569602 0.164705 -0.3786791 -0.2818614 -0.7205833 0.5078544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2384 1604 -0.759048 -0.828378 -0.193704 -0.8043702 -0.4371511 -0.4008349 0.0349142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2385 2405 0.205846 0.683509 0.688747 -0.1158905 0.8205177 0.3955406 0.3960653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2386 2406 -0.201213 -0.882943 0.365805 -0.0791999 0.1953215 -0.9513006 0.2249535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2387 2407 0.878821 0.445030 0.598937 -0.8217999 -0.1016522 -0.2718943 0.4902911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2388 2408 -0.713347 -0.267551 0.531016 -0.2396186 -0.1143050 0.9604431 0.0840613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2389 2409 -0.161051 0.735051 0.709189 -0.1499102 0.2135499 0.5206483 0.8129260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2390 2369 -0.405696 -0.866129 0.155034 0.2752343 0.6977376 -0.1649286 0.6404739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2390 2410 0.409094 -0.287473 0.815481 0.0096303 0.2564912 0.1082700 0.9604151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2391 2368 0.326765 0.272057 0.901531 0.6612585 -0.5401845 -0.5040052 0.1300641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2391 2411 -0.706028 -0.623780 0.731425 0.5249376 0.4971274 -0.6697159 0.1696626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2392 2412 -0.770904 0.662100 0.395255 0.1388367 -0.4218341 0.3598474 0.8205426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2393 2413 -0.281992 0.582248 0.935026 0.2812509 -0.3399148 -0.8862110 0.1413713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2394 2414 -0.695165 -0.565753 0.138252 -0.0829902 -0.1776747 0.2481098 0.9486758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2395 2364 -0.297361 -0.839520 -0.475573 0.1498281 0.0695830 0.9108883 0.3781431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2395 2415 0.906654 -0.346183 0.385158 0.1630735 0.0067348 -0.6936665 0.7015615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2396 1616 -0.167911 0.539919 -0.704974 0.8066675 -0.0861698 -0.1680474 0.5600200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2396 2416 0.110260 -0.546117 0.659495 0.5478853 -0.2399890 -0.7403970 0.3066583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2397 2362 -0.654878 0.624078 -0.232518 0.5115667 0.4727872 -0.7160929 0.0445283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2398 2418 -0.005753 0.985625 0.313011 -0.0795310 -0.3955041 -0.8508947 0.3364961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2399 2419 0.188545 -0.790233 0.606238 0.1746739 0.4835951 -0.6887458 0.5111302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2400 2439 0.117051 1.054338 -0.210881 -0.1953252 0.1384899 -0.8507012 0.4679489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2400 3180 0.214272 -0.094284 0.812972 -0.4513141 0.5503808 -0.6128116 0.3433052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2401 2438 -0.881238 -0.161681 0.415141 -0.6184328 0.0013326 -0.4259031 0.6604132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2401 3181 0.550727 0.287768 0.790209 -0.1321948 0.4904924 -0.6067300 0.6114086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2403 2436 -0.476446 -0.861468 0.558247 -0.5716862 0.5373173 0.6194629 0.0270312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2403 3183 -0.255111 0.553469 0.804553 0.4359603 -0.5194072 -0.4394249 0.5891184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2404 2384 0.786279 0.610213 -0.580886 0.5978470 -0.5083108 0.5183655 0.3398473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2404 3184 -0.648387 -0.578516 0.489394 0.5137546 -0.6232622 -0.0428043 0.5880206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2405 2434 -0.767644 -0.074144 -0.596705 -0.6002138 0.2328261 0.7122739 0.2796450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2405 3185 -0.612162 0.716728 0.388803 -0.4522048 -0.2925937 0.7640573 0.3551284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2406 2433 0.826182 -0.479503 -0.559125 -0.7393591 -0.0771347 -0.6624938 0.0921976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2406 3186 0.824687 0.585508 0.842922 -0.2200561 -0.6640239 -0.7053334 0.1146841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2407 2432 -0.066381 0.871084 0.658561 0.7599766 0.2788830 0.4605655 0.3640594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2407 3187 0.860451 -0.475111 0.351502 -0.0165712 0.5569618 -0.0316664 0.8297687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2408 2431 -0.998442 0.036348 0.104892 -0.2530358 -0.2861593 -0.6510176 0.6559435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2408 3188 0.380415 0.100733 0.852617 -0.5085292 -0.0341884 -0.8497975 0.1344372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2409 3189 -0.084878 0.391032 0.935454 0.4188734 0.1103456 -0.8943794 0.1115990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2410 2429 -0.545495 -0.676630 -0.410675 -0.0316777 -0.0188682 0.9974567 0.0609969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2411 2428 -0.797770 -0.528771 -0.266423 0.1110695 -0.2731807 -0.5858297 0.7548771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2412 2427 0.789650 -0.502692 -0.111007 -0.0335702 0.4822330 0.8709603 0.0880487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2413 2426 0.882026 -0.381032 0.447066 0.1773303 -0.0374294 0.9819012 0.0549815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2413 3193 -0.621456 0.376778 0.863815 -0.0844504 0.2082107 -0.9740657 0.0266927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2414 2425 0.153144 -0.980023 0.121901 -0.3447346 -0.5036173 0.7904423 0.0522356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2414 3194 -0.848893 -0.109922 0.385395 0.4358169 -0.3759803 -0.6282524 0.5234514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2415 2424 0.849211 -0.372558 -0.057052 -0.1227280 -0.2771222 -0.8285879 0.4707263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2415 3195 0.475255 0.783664 0.338008 -0.1279912 0.8076790 0.0846333 0.5693066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2416 2423 0.600511 0.092475 -0.701050 0.4307555 -0.6767774 -0.5400197 0.2545599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2416 3196 -0.056602 1.067574 0.215435 -0.6098747 0.3367383 0.2803705 0.6603427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2417 2397 -1.113374 0.456621 -0.573206 0.4322834 0.4730524 0.4623756 0.6128306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2417 2422 -0.631346 -0.537129 0.613257 0.2377839 -0.1135873 0.9398352 0.2174088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2417 3197 0.824514 -0.591290 0.498439 -0.2195966 0.3317980 -0.9091391 0.1230999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2418 2421 -0.409106 -0.777525 -0.600270 -0.2561935 0.2584241 0.8928629 0.2652880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2419 3199 -0.188545 -0.227075 1.014582 0.0033802 -0.0988956 0.1847141 0.9777980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2420 2459 -0.795028 0.538372 -0.538082 0.8935733 0.1466429 -0.0691392 0.4186197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2420 3160 -0.576084 -0.728481 0.383927 0.4528279 0.5385219 -0.1069938 0.7024908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2421 2458 0.512112 0.574384 -0.676071 0.0813054 -0.9471825 -0.3038030 0.0627571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2421 3161 -0.431395 0.886022 0.375480 -0.6156701 -0.4410211 -0.5925054 0.2745688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2422 2457 0.576780 1.092369 0.390973 -0.2724323 0.3434869 -0.8407411 0.3177293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2422 3162 -0.661425 -0.101628 0.875980 -0.3344207 -0.5817779 0.4117729 0.6165552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2423 3163 -0.696358 0.252429 0.701337 -0.3126435 0.5148877 0.6013448 0.5249086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2424 2455 -0.348389 0.821181 -0.573873 -0.8402923 -0.0454056 0.5175977 0.1547249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2424 3164 -0.761108 0.168662 0.683615 0.4883625 -0.0687327 0.1860271 0.8498069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2425 2454 -0.572229 0.585484 0.662820 0.4231760 0.4588019 -0.1913714 0.7574958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2426 2366 -0.577050 0.158406 -0.696835 0.0661083 -0.1602472 -0.7725962 0.6107746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2426 2453 -0.763504 0.226931 0.609521 0.5263766 0.5410791 -0.3375865 0.5623135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2426 3166 0.528005 -0.208843 0.767040 0.0320081 -0.1615069 0.9828453 0.0831033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2428 2451 0.215649 -0.938773 0.148553 0.0149381 -0.3288596 0.1124043 0.9375465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2428 3168 0.361717 0.139194 0.921716 -0.4653528 0.3771683 0.3356842 0.7269848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2429 3169 -0.071317 0.038370 1.164197 0.1418425 -0.5178714 -0.8418113 0.0551691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2430 2370 -0.747319 -0.407131 -0.615047 0.3544865 0.0826051 0.6465550 0.6704345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2430 2409 -0.729036 0.559860 0.450210 -0.0407839 0.6077295 0.1848460 0.7712545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2430 2449 0.763411 -0.623493 -0.361146 -0.6996028 0.5191848 0.0471615 0.4886501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2431 2448 -0.058098 -0.915570 0.084360 0.2034854 -0.1298402 0.8390240 0.4876208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2431 3171 0.531163 0.388798 0.629241 -0.4569583 -0.1168585 0.6009189 0.6453136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2432 2447 0.735068 0.308464 -0.597105 0.1224059 -0.2173670 -0.9057853 0.3425221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2432 3172 0.396517 0.714295 0.894723 -0.5805825 0.3953446 -0.2363104 0.6714045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2433 2446 -0.376320 0.767685 0.698074 -0.5970543 0.5135027 -0.1480569 0.5982644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2433 3173 0.535061 -0.448624 0.546357 -0.5733240 0.4840717 -0.6601043 0.0351645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2434 2445 0.729446 0.790722 0.371416 0.0693286 0.4613037 0.8804249 0.0851137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2435 2404 -0.903971 0.334675 0.101147 -0.4303662 0.4367867 0.0539482 0.7880938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2435 2444 0.981146 -0.253605 -0.042036 -0.2726552 -0.2256415 0.9350136 0.0222392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2435 3175 0.121703 0.273098 0.921246 -0.3229310 0.6093255 -0.0899575 0.7185720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2436 2376 0.664468 -0.461971 -0.627590 0.3569064 -0.7691389 -0.1601353 0.5053710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2436 2443 0.255870 1.150913 -0.198336 -0.6390163 0.1013288 0.3977539 0.6505248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2436 3176 -0.752869 0.507195 0.562465 0.0031803 -0.0915491 0.1262595 0.9877587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2437 2402 -0.090205 -1.010161 0.047501 0.0803601 -0.3892722 0.8716693 0.2867092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2437 2442 0.115413 0.991342 0.006935 0.6712641 0.5175117 0.4871862 0.2103228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2437 3177 0.671053 0.020632 0.734390 0.4248176 0.4664586 0.7351715 0.2479298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2438 2441 0.022469 -0.772112 -0.553230 0.2588870 -0.1144288 0.1197322 0.9516027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2438 3178 0.765244 -0.518149 0.744502 0.3853931 0.5632396 0.3559496 0.6383832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2440 2479 -0.105821 0.073738 0.896815 0.2728715 -0.4106035 0.5264689 0.6926590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2440 3140 -0.245936 -1.124030 0.265702 0.8291462 0.2114642 -0.5174035 0.0096530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2441 2478 -0.191858 -0.950143 0.133374 0.1180309 0.7051307 0.2080957 0.6674995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2441 3141 0.602285 -0.222779 0.752220 0.5270929 0.7258702 -0.0058352 0.4418727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2442 2342 -0.164247 -0.772261 -0.374751 -0.7842100 -0.2620225 -0.1952111 0.5274954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2442 2477 0.814268 -0.584888 0.144054 0.0613832 0.2478930 -0.4044771 0.8781682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2442 3142 0.308039 0.945561 0.390191 -0.8988468 -0.1188311 0.1983780 0.3722898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2443 2476 0.650366 -0.027274 0.591337 -0.7970373 -0.2962200 0.2500130 0.4631185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2443 3143 -0.795119 -0.029624 0.834017 -0.2502066 -0.8132624 0.2783234 0.4455749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2444 2475 -0.856288 0.401765 -0.451572 0.3647811 -0.7293727 0.4529728 0.3602304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2444 3144 -0.595130 -0.707275 0.424352 0.3128759 -0.5828430 -0.7092331 0.2437028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2445 3145 0.215974 1.101527 0.270657 -0.2315560 0.6858205 -0.0557064 0.6876982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2446 2473 -0.866130 -0.354766 -0.023693 0.2330482 -0.9379413 0.2492293 0.0619628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2446 3146 0.118172 -0.827371 0.182536 0.4578208 0.5848203 0.1611819 0.6499275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2447 2347 0.762666 -0.003388 -0.639491 0.2240455 0.2456375 0.4741062 0.8152847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2447 2472 -0.655755 -0.059616 -0.694609 0.0681176 -0.6856339 -0.5235432 0.5011674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2448 2471 -0.567989 0.294524 0.716581 -0.3876870 0.2195718 -0.4392790 0.7800776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2448 3148 0.166005 -0.685802 0.522702 0.7428308 -0.2914755 0.0016697 0.6026953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2450 2469 -0.359327 0.852736 0.155535 0.3266893 -0.0915979 0.0335584 0.9400839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2450 3150 0.264407 -0.517557 0.913921 0.3078479 -0.3867196 0.8390048 0.2274832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2451 2468 0.119507 -1.079629 0.109722 -0.1754402 0.6964393 0.4061774 0.5649893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2451 3151 0.850412 0.208226 0.536754 0.2221908 0.5787317 -0.3533351 0.7006105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2452 2352 0.878757 -0.521909 -0.056333 -0.6313048 0.7559160 0.1412209 0.1005085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2452 2427 -0.186556 0.132922 -0.811973 -0.7758490 0.0714598 0.6012398 0.1773767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2452 3152 -0.861581 0.649349 0.138818 -0.4902904 0.8550767 0.1431567 0.0892492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2453 2466 -0.503010 -0.270618 -0.743671 -0.3115376 -0.6919053 -0.1128574 0.6414629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2453 3153 -0.701031 0.849731 0.301919 -0.2368848 -0.5405549 -0.0525242 0.8055602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2454 2465 -0.701024 0.225356 -0.711889 -0.0650597 0.0212711 0.8462882 0.5283096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2455 2464 0.365519 -0.642114 0.616795 0.1863778 -0.6231199 0.0120001 0.7595004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2455 3155 -0.784303 -0.280976 0.466499 -0.2830587 -0.7543124 0.5027200 0.3133099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2456 2423 0.044087 0.494695 0.842583 0.4132199 0.5497337 0.5414333 0.4836239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2456 2463 0.011994 -0.475350 -0.888910 -0.1433555 0.9278413 -0.0766956 0.3356747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2456 3156 0.651953 -0.458996 0.208338 0.0226300 -0.0327429 -0.9859300 0.1623508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2457 2462 -0.634058 -0.614424 0.261822 0.0640946 0.5080874 0.1018075 0.8528624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2457 3157 0.597027 -0.650614 0.106606 0.3357917 -0.3100025 0.8029086 0.3827273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2458 2358 -0.274367 -0.926173 -0.231225 0.4516184 0.0938949 0.8872537 0.0023292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2458 2461 -0.256044 -0.036766 1.137650 -0.5695866 0.2347106 -0.0577243 0.7855889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2458 3158 0.180328 0.883706 0.184669 -0.3327575 -0.3234208 -0.8566500 0.2254380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2459 3159 -0.647946 0.577945 0.291155 -0.5484990 -0.5622948 -0.0591726 0.6160131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2460 2499 0.317250 0.972859 -0.439294 -0.4412769 0.2416201 0.1950870 0.8419237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2460 3120 -0.535515 0.491492 0.554474 -0.5568910 -0.3901873 0.1401854 0.7197044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2461 3121 -0.150513 -0.019915 1.081633 -0.4025465 0.3531338 0.8058703 0.2526380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2462 3122 0.096795 -0.650399 0.613555 -0.0429679 0.2072685 0.4117099 0.8863907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2463 2496 0.762005 -0.158039 0.711463 -0.5643232 -0.5054448 0.5289025 0.3825271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2463 3123 -0.529772 -0.918942 0.238195 -0.5095120 -0.6804347 0.3414250 0.4010425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2464 2495 0.657946 -0.748831 -0.341326 0.1684011 -0.2165776 0.4623994 0.8431619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2464 3124 0.214701 0.018001 0.970902 0.3941292 -0.5717292 0.7101933 0.1158163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2465 2494 0.627036 0.634053 -0.422966 0.0545511 0.5004419 -0.4439557 0.7412728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2465 3125 0.533207 0.279485 0.863994 -0.6111075 -0.0204354 -0.4785040 0.6302094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2466 2493 -0.894524 -0.261215 0.396329 0.0504436 -0.3679979 0.4966105 0.7844814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2466 3126 0.460354 0.155969 0.925043 -0.3071145 -0.3370509 0.7148096 0.5302118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2467 2452 0.543788 -1.005494 -0.294760 0.1008921 -0.4643116 -0.8711317 0.1239561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2467 2492 -0.224150 0.929442 0.427445 -0.0283619 0.3313443 -0.7905883 0.5141758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2467 3127 0.740085 0.098743 0.568294 -0.2638359 -0.1001736 -0.3269148 0.9019327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2468 2491 -0.355588 -0.555992 -0.695491 -0.0588806 -0.6929235 0.6598628 0.2845542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2468 3128 -0.635202 -0.245756 0.665594 -0.4839311 0.0306630 0.7452749 0.4576415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2469 2490 -0.077187 0.893466 -0.395930 0.3873738 -0.3757785 -0.8352093 0.1056288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2469 3129 0.193047 0.222667 0.981016 -0.1838173 -0.3674499 -0.0809847 0.9080932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2470 2449 -0.932656 0.200131 -0.181842 -0.3195690 0.0774162 -0.0691969 0.9418568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2470 2489 0.812080 -0.557693 0.353947 -0.2757561 -0.6239742 0.4470121 0.5786146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2471 2488 -0.707017 -0.848366 0.229748 0.4125398 0.0321454 -0.4076291 0.8140124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2472 2487 0.185286 -0.856218 0.536426 -0.4891767 0.5746237 0.5837532 0.2995763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2472 3132 0.678757 0.261237 0.627946 -0.4503696 -0.0373061 0.6448606 0.6163849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2473 2486 0.856429 0.297200 0.316785 0.6945735 0.3918364 -0.5949737 0.1001914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2473 3133 0.141859 -0.978656 0.386149 -0.0624069 -0.5190375 0.8043822 0.2822672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2474 2445 -0.597782 0.605575 0.614443 0.7071009 0.1359200 0.4991718 0.4820390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2474 3134 0.076595 -0.455257 0.840825 0.4039647 -0.3036106 0.6937488 0.5131721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2476 2336 0.517946 0.990554 0.001867 0.5759807 -0.1146793 -0.5997287 0.5435259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2476 2483 0.469267 -0.408147 -0.938182 -0.3323287 -0.2349951 0.9102483 0.0760461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2476 3136 -0.511393 -0.946535 -0.014936 0.3284442 -0.2961287 -0.5426188 0.7141408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2477 2482 0.637739 0.339093 0.749693 -0.6398229 -0.0120798 -0.5087036 0.5759353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2477 3137 -0.511137 0.759080 0.179903 -0.1739958 -0.5604826 -0.3560924 0.7271746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2478 3138 -0.756377 0.035384 0.687043 0.1397416 -0.8136340 0.1032141 0.5548142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2479 3139 -0.341852 0.201586 0.901611 -0.5711853 -0.0702935 0.5721805 0.5843078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2480 2519 -1.100715 0.180551 0.270894 0.5503127 0.5465116 -0.4678066 0.4238373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2481 2478 -0.633350 -0.421731 -0.166614 -0.0727432 -0.4829783 0.8455969 0.2154211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2481 2518 1.037204 0.400239 0.351921 0.0470986 -0.9416783 0.2659237 0.2007691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2481 3101 0.349320 -0.981776 0.186628 -0.1914851 -0.8924866 0.3917237 0.1155580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2482 2517 0.655451 -0.231626 0.710656 0.3138010 0.7913403 -0.4388850 0.2875577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2482 3102 -0.645834 -0.589767 0.140134 0.5633772 0.1494954 -0.7444635 0.3256246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2483 2516 0.081289 0.770545 -0.693389 -0.1985898 -0.0086387 0.0393499 0.9792543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2483 3103 0.131274 0.727203 0.775209 -0.2718910 0.2210159 -0.7025464 0.6193995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2484 2475 -0.316099 0.815969 -0.422494 -0.2539180 -0.4131408 -0.8486764 0.2111602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2484 2515 0.706681 -0.757560 0.425402 0.5693680 -0.0494695 -0.2094134 0.7934222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2484 3104 -0.345757 0.491911 0.917536 0.1228023 0.3253835 -0.9004624 0.2611754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2485 2474 -0.433233 -0.378610 0.589164 -0.3001159 0.1840319 0.7490598 0.5612238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2485 2514 0.711728 0.486201 -0.550368 -0.6738615 -0.0478291 0.1585057 0.7200687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2485 3105 0.196771 0.636043 0.684694 -0.3374775 0.6781107 0.3839805 0.5280472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2486 2306 0.778424 -0.618817 -0.395740 -0.6266733 -0.2836010 0.3200966 0.6514517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2486 3106 -0.755306 0.589584 0.180952 -0.1949907 -0.9012803 -0.2191548 0.3188160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2487 2512 -0.362210 0.426888 -0.898131 0.6735665 -0.2151654 -0.6197630 0.3404495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2487 3107 -0.763060 -0.612972 0.075875 0.1152536 -0.7523742 -0.1392999 0.6334392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2488 2511 0.170901 -0.599532 0.735521 -0.2968435 0.0749194 -0.5026845 0.8084425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2488 3108 0.935418 0.432500 0.281230 -0.4389961 -0.7671824 -0.4660906 0.0383800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2489 2309 0.065991 0.652564 -0.736513 0.6699556 0.3995057 -0.4614619 0.4226199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2489 2510 -0.348840 -0.624738 -0.571025 0.4971486 0.3098070 -0.7503615 0.3063014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2489 3109 -0.052900 -0.908497 0.589566 -0.2075038 0.4828036 -0.7887745 0.3188692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2490 2310 0.790648 -0.146029 -0.480629 -0.3596840 -0.0401689 0.7452834 0.5599702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2490 2509 -0.089977 -0.896863 0.494901 -0.0361795 0.2097300 -0.5472512 0.8094569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2491 2508 -0.111220 0.739916 0.633006 0.3149083 0.1372439 -0.9310611 0.1229717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2491 3111 0.646601 -0.396023 0.887819 -0.1153757 0.2087840 -0.9011153 0.3620621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2492 3112 -0.573538 0.180828 0.612643 -0.4275202 -0.3291047 0.8321092 0.1284946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2493 2506 -0.251830 0.357060 0.742974 0.7637895 0.0400666 0.6369492 0.0965197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2494 2314 0.837428 -0.023925 -0.327820 -0.6720536 0.2685826 0.6518093 0.2266097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2494 2505 0.061956 0.951509 -0.252352 0.2008481 -0.8216740 -0.0965996 0.5245764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2494 3114 -0.871838 0.306967 0.599003 0.0734179 -0.2494454 -0.8244060 0.5027341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2495 3115 0.838365 -0.100785 0.640920 -0.0270259 0.5583500 -0.7880414 0.2578868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2496 2503 -0.452822 -0.459593 -0.796800 0.3107365 -0.7762459 -0.4307490 0.3396181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2496 3116 -0.773087 -0.285383 0.626412 0.7672744 0.0354807 -0.6402957 0.0072495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2497 2462 0.295244 -0.901727 -0.040053 -0.2722819 0.3347096 -0.7586202 0.4881879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2497 2502 -0.471626 0.914485 0.063820 -0.3082828 0.2378314 -0.8406725 0.3763876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2497 3117 0.135369 0.010217 1.053281 0.3304119 -0.5808267 0.7399047 0.0775197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2498 2461 0.501727 0.675691 0.491859 -0.0171221 -0.3767775 -0.0679055 0.9236527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2498 3118 -0.855338 0.208551 0.593805 0.5037530 0.1985231 -0.8403427 0.0254113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2499 3119 -0.640799 0.154858 0.585905 0.4058472 0.3197628 -0.5916729 0.6188400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2500 2280 0.671967 -0.647246 -0.446179 -0.1763770 -0.5802890 0.1690557 0.7769016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2500 2539 -0.491497 -0.784966 0.094983 -0.2309986 0.2189394 0.7184268 0.6185209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2500 3080 -0.680246 0.652866 0.424232 0.0949288 0.2125434 0.8190646 0.5243540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2501 2281 -0.368047 -0.451750 -0.699429 0.0059747 -0.1781871 0.4160822 0.8916778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2501 2498 0.947767 -0.419083 -0.222730 0.1625467 0.3947590 -0.5692160 0.7026642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2501 3081 0.342815 0.281895 0.923069 -0.7392658 0.1579191 0.0291377 0.6539868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2502 3082 0.152334 -0.520159 0.710158 -0.3952266 -0.6187898 0.6422523 0.2200162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2503 3083 0.853351 0.491715 0.336538 0.2290931 -0.0063950 0.9600306 0.1606755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2504 2495 0.125409 -0.847776 -0.422467 -0.4722351 0.2687529 -0.7956227 0.2678627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2504 3084 0.357918 -0.383825 0.747208 -0.2490401 -0.6330139 0.5531417 0.4809435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2505 2285 -0.469695 -0.500925 -0.428499 -0.1447637 -0.1343624 -0.2606059 0.9450264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2505 3085 0.780226 0.501218 0.291626 -0.5806697 0.7372667 0.0246824 0.3444579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2506 2286 -0.527242 -0.362700 -0.622732 0.3715060 0.4931827 0.3869943 0.6848280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2506 2533 0.821995 -0.392894 -0.368365 0.5478092 0.5043253 0.4639738 0.4798847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2506 3086 0.370221 0.589995 0.763444 0.4609502 0.3436681 0.5684686 0.5884391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2507 2532 -0.929776 0.162393 0.124808 -0.0327132 -0.4124561 -0.6212624 0.6654644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2508 2531 -0.405472 -1.056009 0.187851 -0.2569065 0.1697913 0.7655056 0.5649523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2509 2530 0.486582 -0.489070 0.702850 0.3348397 -0.3641420 -0.8585189 0.1350119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2509 3089 -0.796908 -0.563563 0.122064 -0.1253322 -0.5461479 0.3793261 0.7362921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2510 2529 0.859954 0.178703 0.296141 -0.0686664 0.7655801 0.6150883 0.1756090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2510 3090 -0.423948 0.432341 0.663588 -0.0554570 0.7459389 0.6215626 0.2327223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2511 2528 0.561983 -0.468678 0.435336 0.3274918 0.1595216 0.0470152 0.9301030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2511 3091 0.025075 0.623062 0.942587 0.2272213 -0.0552720 0.7114858 0.6626487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2512 2527 0.460148 -1.202568 0.111197 0.2149099 0.4554546 0.2504955 0.8268173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2512 3092 0.316196 0.313583 0.856758 0.4744418 -0.0184827 -0.5300191 0.7025974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2513 2486 0.110899 -0.634266 0.890368 0.1720708 0.1768490 -0.1215239 0.9614302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2513 2526 -0.277333 0.675874 -0.621535 0.2694014 0.1475936 0.3455006 0.8867178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2513 3093 -0.332110 0.564258 0.681504 0.2402046 -0.0991958 -0.7700185 0.5826949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2515 2524 0.658814 0.469558 0.280101 -0.5007995 -0.2431089 -0.0078451 0.8306843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2515 3095 -0.558020 0.759027 0.127745 0.0663539 0.0587146 -0.9094449 0.4062754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2516 2523 -0.029181 0.886872 -0.455486 -0.5523611 -0.5108712 -0.6581154 0.0281420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2516 3096 0.037860 0.446132 1.003737 -0.4742164 -0.0308368 0.8360503 0.2742039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2517 2522 -0.886625 -0.054873 -0.078555 0.2844921 0.3714492 -0.6730553 0.5727882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2518 2521 -0.569778 0.148460 -0.853615 0.7790079 0.1234747 0.3945085 0.4714485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2518 3098 -0.036003 -1.080664 0.100264 0.7896644 -0.3527688 0.1956316 0.4622906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2519 2299 0.926430 -0.018146 -0.673048 -0.1300096 0.2457847 -0.3582310 0.8912676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2519 3099 -0.619077 0.078633 0.646523 0.1653446 0.1428867 0.8976999 0.3825956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2520 3060 0.198087 -0.625060 0.774060 0.0420719 0.3035299 -0.0135557 0.9517961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2521 2558 -0.793859 -0.723377 -0.435795 -0.3746460 -0.7909515 -0.1515561 0.4594201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2521 3061 -0.964075 0.507958 0.441281 0.3183829 -0.2412454 -0.5364146 0.7434328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2522 2557 0.244146 -1.017761 -0.281068 0.2728269 0.3896104 -0.8091822 0.3449542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2522 3062 0.234292 -0.037112 0.919062 -0.2162490 0.1024196 0.9030938 0.3566064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2523 2556 0.145574 -0.752295 0.674891 -0.0995983 0.1507493 0.7800485 0.5990652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2523 3063 0.916048 0.457949 0.444630 0.1990040 0.1924933 0.9519311 0.1310377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2524 2555 1.021613 0.122055 0.168801 0.0540423 0.4000585 0.7510873 0.5223988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2524 3064 -0.397843 -0.074591 0.967896 -0.2683237 0.6461288 0.7003886 0.1413354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2525 2514 -0.113333 0.650771 0.740431 0.1263723 0.4709950 -0.7100363 0.5079785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2525 3065 -0.541402 -0.668206 0.505966 0.6999177 -0.0694461 0.1730933 0.6894427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2526 2266 0.042296 -1.058797 -0.146442 0.0410010 -0.4815504 -0.7175465 0.5015528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2526 2553 0.499392 0.193790 -0.992907 -0.6110873 0.2902346 -0.1355966 0.7238437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2526 3066 0.093048 1.102755 0.183053 -0.4921475 0.0738114 -0.8352246 0.2339713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2527 2267 0.472234 -0.739567 -0.702148 -0.6520496 -0.4047329 0.6221351 0.1548243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2527 3067 -0.337053 0.584498 0.798926 0.2313796 -0.2889424 0.4614988 0.8062224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2528 2551 0.354233 -0.180693 0.726908 -0.3285545 -0.1794483 -0.7332522 0.5676192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2528 3068 -0.189848 0.992025 0.451143 0.6981190 -0.1858244 -0.6499598 0.2359055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2529 2550 -0.824784 0.252886 0.080096 0.3287767 -0.5652431 -0.7564098 0.0158252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2529 3069 0.265768 0.844072 0.321593 0.5272627 0.7083413 0.3220850 0.3413325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2530 2549 -0.495823 0.893027 -0.370667 -0.8262343 0.0061928 0.1037376 0.5536578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2530 3070 0.855411 0.550535 0.173284 -0.3928903 0.5573429 -0.6185809 0.3903380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2531 2548 -0.565417 0.785480 0.026023 -0.8033394 0.0992509 -0.4720144 0.3492815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2532 2547 -0.115257 -0.921999 0.651883 -0.1497842 0.3871090 0.2344931 0.8790474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2532 3072 0.170481 0.549563 0.739795 -0.3458558 0.5908736 0.4775013 0.5506765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2533 2546 -0.039359 -0.202016 0.695371 0.5205618 0.6064980 0.1198192 0.5889134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2533 3073 0.500345 0.654333 0.493861 0.1186712 -0.9143368 -0.3862411 0.0268918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2534 2545 -1.155031 -0.285292 -0.491830 -0.1161431 -0.1852288 -0.6958080 0.6841435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2534 3074 -0.264867 0.167938 0.887436 0.4950292 -0.2072711 0.0831848 0.8396815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2535 2504 0.344755 -0.128880 -0.802798 0.2225750 0.3984406 0.7369508 0.4986069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2535 3075 0.802613 0.721298 0.228901 -0.2750156 0.3069093 -0.3039221 0.8589555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2536 2543 -0.457024 0.413998 -0.749306 -0.1458311 -0.8258555 -0.0858572 0.5378890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2536 3076 -0.917763 -0.083970 0.733057 -0.2932223 0.2615026 0.7938129 0.4642177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2537 2502 -0.912253 -0.487370 0.054673 0.3584769 -0.6827942 0.4869857 0.4100382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2537 2542 0.760349 0.362472 -0.140391 0.4282296 0.2815819 -0.3113106 0.8002605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2538 2501 0.085040 0.963751 -0.283807 0.4576131 0.2024587 0.7134136 0.4905524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2538 2541 -0.121364 -0.874149 0.238054 -0.4996428 0.1217730 0.1283149 0.8479762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2538 3078 0.362853 0.045492 0.794633 -0.4216100 0.4422187 0.2656083 0.7457478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2539 3079 0.313445 0.505620 0.788071 0.2817423 0.4090049 0.4185925 0.7603398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2540 2240 -0.659286 -0.707889 -0.098222 0.1254343 0.3135168 0.0461280 0.9401307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2540 2579 -0.681942 0.659992 -0.126052 -0.8440270 0.2870836 -0.4319303 0.1365200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2540 3040 0.599516 0.728679 0.142804 -0.0627756 -0.4660960 -0.8785845 0.0830838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2541 2578 -0.113733 -0.527395 -1.006423 0.4453387 -0.2537887 0.8512532 0.1123953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2541 3041 -0.052644 -0.911013 0.661227 0.2601922 -0.3386132 0.3210775 0.8453108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2542 2242 -0.006752 0.079144 -0.965180 0.6254712 0.2179203 -0.4363443 0.6090158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2542 2577 0.682114 0.716141 -0.017912 0.0580172 0.6383273 0.4333864 0.6335207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2542 3042 0.139018 0.000809 1.117791 -0.3793370 -0.1243957 -0.8791936 0.2600920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2543 2576 -0.309304 0.121660 0.855643 0.6008948 0.3552061 -0.2838438 0.6574091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2543 3043 0.844603 -0.576083 0.214957 0.5714508 0.7533672 0.1786358 0.2719763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2545 3045 0.292462 -0.295704 1.038481 -0.5588307 -0.1433557 -0.7990855 0.1691736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2547 2247 0.267721 -0.293112 -0.707431 -0.0461155 0.5343790 0.2206995 0.8146190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2547 2572 -0.786035 -0.610571 -0.143566 -0.3294657 -0.3278348 -0.5191367 0.7172682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2547 3047 -0.524328 0.241660 0.740761 -0.2507359 0.2509235 -0.5022964 0.7885856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2548 2571 -0.896562 -0.815589 -0.170460 0.1817246 -0.0199637 -0.3491661 0.9190542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2548 3048 0.580344 -0.539695 0.449139 0.3309460 -0.5200884 0.4432901 0.6507509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2550 2569 0.857416 0.379681 0.691464 0.4957693 -0.0269519 -0.6919115 0.5241612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2550 3050 -0.756960 -0.271690 0.581108 -0.1466848 -0.7976737 0.5207773 0.2664418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2551 2251 0.419706 0.369662 -0.738380 0.6550757 -0.2355920 0.2968358 0.6536518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2551 2568 0.931309 0.423255 0.566050 0.0242351 0.0258489 0.0022356 0.9993695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2551 3051 -0.328515 -0.427179 0.871894 -0.0277724 0.6663052 -0.6689547 0.3282769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2552 2527 0.585459 -0.032672 -0.691698 -0.2247418 0.1001628 -0.5861431 0.7719422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2552 2567 -0.598895 0.227408 0.845561 0.0949169 0.4565124 0.2113707 0.8590167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2552 3052 0.442720 0.808561 0.276309 -0.6474560 0.4402390 -0.5230070 0.3368294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2553 2566 0.329563 0.762353 0.329911 -0.7511578 -0.1637282 0.3104006 0.5591122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2553 3053 -0.587157 -0.066022 0.690336 -0.3717535 -0.3230739 -0.6167901 0.6139972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2554 2525 0.396893 0.836835 0.190262 -0.2476091 0.5628755 0.1676234 0.7705604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2554 2565 -0.298924 -0.944616 -0.210566 -0.6558688 0.3509660 -0.0733439 0.6642888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2554 3054 0.641482 -0.271445 0.723492 0.4649069 0.6479382 -0.2317212 0.5570843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2555 2564 -0.805512 -0.411039 0.455374 -0.0578474 0.5410939 0.6942401 0.4710645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2555 3055 -0.302727 0.902236 0.650982 -0.8597575 0.2124366 -0.0691033 0.4592520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2556 2563 -0.903729 -0.048761 0.512961 0.5499683 -0.0281246 0.8286317 0.1005655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2556 3056 0.234365 -0.802897 0.387779 0.2229042 0.4351895 -0.1705635 0.8554717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2557 2562 0.315859 0.705801 0.550700 0.7532754 0.4023234 -0.5000655 0.1436892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2557 3057 -0.786918 -0.111766 0.600994 0.1186553 -0.4413470 -0.8799547 0.1296671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2558 2258 -0.685221 -0.057727 -0.420519 0.1681194 -0.1770432 -0.8439216 0.4776903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2558 2561 -0.287679 -0.827818 0.208007 0.4410340 -0.4699154 0.5164450 0.5638733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2558 3058 0.852276 -0.178015 0.495573 0.3248683 0.7345840 -0.1454642 0.5776566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2559 2520 0.790972 -0.541430 0.258491 0.0180095 -0.2452301 0.9692831 0.0053014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2559 3059 -0.119279 0.111139 0.918218 -0.0150277 -0.3065475 -0.9222705 0.2349892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2560 2220 -0.373012 0.645117 -0.450401 -0.2178384 -0.5371330 0.5832306 0.5691017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2560 2599 0.457080 0.787728 0.477652 0.2650296 0.3672916 0.6099596 0.6502350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2560 3020 0.456786 -0.617953 0.491546 0.0568081 -0.0122084 -0.5592343 0.8269709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2561 2598 -0.021752 0.311887 0.904629 -0.4309974 0.4274408 -0.3707339 0.7029168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2562 2222 0.840026 0.454423 -0.357673 -0.3687822 -0.4598090 -0.1701333 0.7897025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2562 2597 -0.266045 -0.205464 -0.806170 0.0813760 -0.1609363 -0.8056371 0.5642928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2562 3022 -0.766357 -0.497584 0.365112 -0.1318223 -0.3492378 0.2460012 0.8945050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2563 3023 0.305679 0.958147 0.502248 0.0081204 0.8258234 0.1120536 0.5526244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2564 3024 0.313411 0.551326 0.843724 -0.5496603 -0.1589778 -0.7738515 0.2715757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2565 3025 0.098186 -1.040616 -0.020240 0.4713712 0.2005247 0.4005098 0.7597308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2566 2593 0.687218 -0.665658 0.113747 -0.2674720 -0.7283349 0.6039805 0.1821937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2566 3026 -0.761324 -0.716555 0.191572 0.0974699 -0.5187442 0.7780647 0.3406162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2567 2592 -0.708535 0.674914 -0.097846 -0.3463903 0.2131180 0.3751525 0.8329796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2567 3027 0.239096 0.523092 0.538589 -0.5661306 0.6436750 -0.1324681 0.4976252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2568 3028 -0.386717 -0.338164 0.928795 0.3335046 0.1905437 -0.7315489 0.5632974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2569 2229 0.121111 -0.002595 -0.930622 0.3793760 0.3192237 -0.3476764 0.7957960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2569 2590 -0.560498 0.517679 -0.054051 0.3072561 0.4255927 -0.5250294 0.6699319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2570 2549 -0.842189 -0.361050 -0.751914 -0.2278871 -0.0451460 -0.9332744 0.2739128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2570 3030 -0.808918 -0.108769 0.573533 -0.1795188 -0.0660439 0.9410794 0.2788921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2571 2588 -0.164353 -1.069230 0.024116 -0.4894564 0.1053004 -0.0068786 0.8656194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2571 3031 0.719647 0.054754 0.753961 0.1492061 0.6264470 0.3107321 0.6991046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2572 2232 -0.642808 0.583131 -0.638564 0.5101064 0.5759971 -0.0234242 0.6383339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2572 3032 0.480978 -0.440594 0.670086 -0.4479474 0.5480304 -0.3701726 0.6016461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2573 2546 0.498032 0.464174 0.556426 0.7933196 0.0403411 0.5247915 0.3059584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2573 2586 -0.741602 -0.630874 -0.608978 -0.4201352 0.3145149 -0.8163204 0.2412214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2573 3033 0.067634 -0.556286 0.705807 -0.3214836 0.4878798 -0.2387943 0.7756281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2574 2545 0.732608 0.524222 0.154595 0.2104770 0.5258779 -0.4172207 0.7106889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2574 2585 -0.903217 -0.362095 0.066498 0.1718717 -0.8483732 0.2515703 0.4329382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2574 3034 0.302378 -0.929402 0.177105 0.6503968 0.4737818 0.4778588 0.3523717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2575 2544 -0.384536 -0.582096 -0.671221 -0.2372842 0.2113489 -0.2869992 0.9036920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2575 2584 0.478416 0.530568 0.785168 0.5309144 -0.3517374 -0.0013519 0.7709792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2575 3035 0.273653 -0.750191 0.589056 0.0361549 0.0270356 0.7059883 0.7067831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2576 2583 -1.157739 0.419348 0.046993 -0.6062064 -0.0907511 -0.5691532 0.5480353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2576 3036 0.206472 0.852562 0.394595 -0.1057530 0.4122907 0.8724439 0.2401549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2577 2237 0.864801 -0.583231 -0.306791 -0.5379046 -0.1999928 0.3537973 0.7385723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2577 3037 -0.756782 0.614136 0.350692 -0.8254570 -0.1782155 0.1461215 0.5152752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2578 2581 -0.603546 0.719517 -0.053998 -0.0850722 0.2334708 0.7834957 0.5695513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2578 3038 0.430782 0.424856 0.763443 0.1937361 0.0110648 -0.9785635 0.0689731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2579 3039 0.230500 -0.983489 0.387206 0.7892012 -0.4121670 0.3390320 0.3038702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2580 2200 0.660092 0.226575 -0.561077 0.2848539 -0.0274546 0.6676357 0.6872897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2580 2619 0.011308 0.817438 0.445360 0.2345302 -0.2709007 0.8455257 0.3958468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2581 2201 0.072276 0.197282 -0.789041 -0.0355786 0.2289390 -0.0331597 0.9722250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2581 2618 1.045066 0.469572 0.201156 -0.3033716 0.6758712 -0.5021256 0.4461318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2581 3001 -0.106912 -0.308609 0.808969 0.5531349 -0.0299587 0.7858524 0.2749185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2582 2617 0.541944 0.364168 -0.698751 -0.4921428 0.5081572 -0.4402328 0.5529618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2582 3002 0.859778 -0.408162 0.381371 0.2279709 0.3989494 0.7755667 0.4328567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2583 2616 -0.763023 -0.712629 -0.210333 0.7624605 -0.0711215 0.2677845 0.5847113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2583 3003 0.202439 -0.500348 1.124979 0.3964009 0.5409298 0.3783204 0.6380713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2584 3004 0.928291 -0.436040 0.274666 -0.3014364 0.2217623 0.2281238 0.8988421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2585 2614 0.707640 0.254861 0.866797 0.4037692 -0.4822222 0.5984722 0.4962492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2585 3005 -0.021207 -1.018323 0.401701 0.8767835 -0.0523125 -0.3336403 0.3423423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2586 2613 0.340309 0.834614 -0.588747 0.4255628 0.6670074 -0.4429751 0.4216284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2586 3006 0.806695 -0.230704 0.346665 -0.5275665 0.1994227 -0.3506272 0.7476395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2587 2572 0.348417 0.478927 -0.905118 -0.6393408 -0.6001189 -0.0660126 0.4761755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2587 3007 -0.551151 0.515668 0.316208 -0.4658807 0.5314229 0.6949329 0.1327144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2588 2611 -0.238505 -0.548206 -0.686008 0.6119806 -0.6089455 0.4639088 0.1986298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2588 3008 0.667998 -0.725579 0.466561 -0.1251953 0.7284637 -0.0925474 0.6671594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2589 2570 0.999176 0.082759 0.256413 -0.5553948 0.1731128 0.8084986 0.0888741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2589 2610 -0.911780 -0.188517 -0.313842 -0.4343655 -0.3625297 0.0827134 0.8204007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2590 2609 -0.232314 -0.516333 -0.897642 -0.4258934 -0.1472535 0.8045595 0.3868014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2591 2568 0.206662 -0.028310 -0.991159 0.2634300 -0.0910959 0.8502724 0.4464784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2591 3011 0.735787 -0.566890 0.426198 0.7237778 0.1371844 0.3543868 0.5759654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2592 2607 0.119268 0.970250 0.330789 -0.4087856 -0.4428661 0.7355909 0.3093058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2592 3012 0.102760 -0.284862 0.936159 0.0977770 -0.7473832 0.6108469 0.2423304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2593 2606 -1.028400 -0.251648 -0.036083 -0.4088040 -0.2929861 0.1025724 0.8582059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2593 3013 0.124786 -0.351850 0.846140 0.0739132 -0.0806780 0.2681522 0.9571428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2594 2565 -0.314784 0.718017 0.907829 -0.1234819 -0.1441769 -0.4854223 0.8534228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2594 2605 0.168758 -0.658683 -0.556467 0.2350419 -0.6891390 0.5875095 0.3530940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2594 3014 -0.780461 -0.453541 0.117664 -0.3732451 -0.5374490 0.2640702 0.7085927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2595 2215 0.627391 -0.595571 -0.435215 0.0796418 -0.5886840 0.0681317 0.8015400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2595 2564 -0.743585 -0.329905 -0.595204 0.1373169 -0.7547836 -0.5228141 0.3716331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2595 3015 -0.698933 0.733202 0.481913 0.1408962 0.1895705 -0.9059582 0.3513560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2596 2563 0.638973 0.263974 -0.602479 0.0274894 -0.9511268 -0.3075199 0.0058082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2596 3016 -0.300746 0.935441 0.182717 -0.3893440 -0.1309610 -0.2780986 0.8682866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2597 2217 -0.809259 0.290932 -0.650426 -0.3071711 0.2042581 0.5600238 0.7418206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2597 2602 0.398361 -0.406118 -0.869524 -0.1688836 -0.0389322 0.6543681 0.7360468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2598 2218 -0.920045 0.354731 -0.331110 -0.3144061 0.2161355 0.2041152 0.9015382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2598 2601 -0.443703 -0.754256 0.184681 -0.1536019 0.7629028 -0.5441977 0.3134240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2600 2980 -0.023242 -0.608445 0.809834 -0.1750899 0.2863184 -0.4030768 0.8514073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2601 2638 0.717828 -0.697473 0.074084 0.2733079 -0.2704648 -0.9088166 0.1618763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2601 2981 -0.545511 -0.451170 0.879442 -0.6995468 -0.4202158 0.4306166 0.3855157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2602 2982 -0.414460 -0.961304 0.245764 0.3712203 -0.3492297 -0.8522592 0.1178490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2603 2183 -0.648961 -0.605229 -0.528593 0.3218262 0.8532926 0.2318049 0.3385059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2603 2596 -0.594440 0.079953 0.713899 0.2734220 0.9225146 0.2717360 0.0191530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2603 2636 0.638458 -0.058353 -0.647557 -0.9365905 0.1267994 -0.1303360 0.2995541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2603 2983 0.661363 0.797016 0.522658 -0.4894148 0.4576611 -0.4809398 0.5654348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2604 2595 0.471567 -0.516065 0.478279 -0.4953526 0.5800905 0.5331345 0.3659076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2604 2635 -0.706992 0.553000 -0.673316 0.2535790 0.1193644 -0.1310125 0.9509393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2604 2984 -0.580406 0.578678 0.737183 0.0159860 -0.1072257 -0.1822560 0.9772563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2605 2185 -0.469082 -0.342402 -0.719091 0.1453880 -0.1284642 -0.7263566 0.6593673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2605 2634 -0.699240 0.033507 0.482904 0.0478412 0.0333568 0.9539000 0.2944032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2605 2985 0.720234 0.250572 0.636663 -0.0706640 0.7500650 0.6574571 0.0126223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2606 2633 -1.000261 -0.289261 0.621986 0.0934130 0.5003937 0.3155211 0.8008287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2606 2986 0.506243 -0.906900 0.120431 0.2595060 -0.8497279 0.4530766 0.0730794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2607 2632 0.651779 -0.641012 -0.134996 0.0931993 0.2713968 -0.9076497 0.3063165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2607 2987 -0.688298 -0.872914 0.195072 -0.7980936 0.3074987 0.5045137 0.1181400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2608 2591 -0.377132 -0.835330 0.405386 -0.4590291 -0.6256650 -0.5287522 0.3438846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2608 2631 0.333619 0.891616 -0.415095 0.6512571 -0.0793102 -0.7468799 0.1083719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2608 2988 -0.656511 0.373041 0.456728 -0.5053979 0.0755466 -0.2004554 0.8358728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2609 2630 0.335314 1.101970 -0.320844 -0.1556018 0.7135044 0.3405493 0.5922210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2609 2989 -0.063555 0.412463 0.852328 -0.5960431 -0.1275676 0.4329761 0.6640714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2610 2990 0.433595 -0.433679 0.871174 0.6183432 0.2783704 -0.6840610 0.2687417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2611 2628 -0.194005 0.463438 0.839078 0.2795382 0.1182523 -0.3796298 0.8739313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2611 2991 0.480644 -0.537436 0.381428 -0.0911213 0.4578996 -0.8103625 0.3540304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2612 2587 -0.373582 0.821909 0.457060 0.4962555 0.7185206 0.0104577 0.4871850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2613 2626 0.608089 0.817456 -0.628671 -0.0098154 0.7487353 0.6317145 0.2005889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2614 2625 0.724894 -0.779448 -0.141502 -0.5270846 0.1768907 0.7042627 0.4414812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2614 2994 0.241641 0.055605 0.989571 0.1632499 0.6712714 -0.7035806 0.1664886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2615 2195 -0.599109 0.526895 -0.649950 0.3276190 0.2009873 -0.9230871 0.0134214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2615 2584 0.040937 -0.697419 -0.693616 0.4580355 -0.4000156 0.2009546 0.7679898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2615 2624 0.105103 0.661103 0.795689 -0.3593984 0.6579206 -0.5603578 0.3520971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2615 2995 0.484291 -0.416762 0.613333 0.2964372 -0.4651070 0.6897032 0.4691587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2616 2996 0.512500 0.784980 0.463172 -0.1557005 -0.4817668 -0.0700450 0.8595067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2617 2997 0.222395 -0.424966 0.831338 0.6677684 0.5205705 0.3756492 0.3768016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2618 2621 -0.740991 0.039315 0.717657 0.8433201 0.2058301 -0.4733715 0.1495479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2618 2998 0.048475 -1.066407 0.082659 0.3253450 -0.2920529 -0.0981175 0.8939959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2619 2199 -0.517059 -0.641550 -0.520640 0.0985047 0.5896368 0.7820651 0.1760669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2619 2999 0.540824 0.716005 0.478843 0.2457861 0.3812806 0.6203564 0.6398220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2620 2160 -0.007948 -0.059983 -1.013729 -0.2445145 0.4082159 -0.1738260 0.8621815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2620 2659 -0.094079 0.975946 -0.041165 -0.1112109 -0.5698834 0.7971799 0.1654366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2620 2960 0.092243 0.183238 1.080026 0.3653854 -0.5608874 -0.7411726 0.0506160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2621 2658 -0.813879 -0.610201 0.042716 0.2552714 -0.7419026 -0.5613544 0.2632455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2621 2961 -0.316627 0.843408 0.170703 -0.3870970 -0.1909666 -0.7994635 0.4177868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2622 2617 0.625844 -0.421301 -0.742698 0.1786192 -0.0285321 0.1467450 0.9724952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2622 2962 0.551631 -0.527613 0.577306 0.5337707 0.1061499 0.4463869 0.7103237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2623 2616 0.790978 -0.466902 0.263294 0.6545187 -0.5295971 -0.1932415 0.5037757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2623 2656 -0.878355 0.498498 -0.179344 0.0069255 -0.2379881 -0.8527506 0.4648980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2623 2963 -0.451105 -0.374036 0.757630 -0.1434444 0.2999986 -0.4418613 0.8331765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2624 2655 -0.745786 -0.560781 -0.266382 0.2965114 0.0880540 -0.4443361 0.8407692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2624 2964 0.181739 -0.605135 0.427892 0.3149675 0.0654699 -0.9449722 0.0594697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2625 2654 -0.482886 -0.457087 -0.942051 0.2416998 -0.2955920 -0.3619210 0.8504233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2625 2965 -0.734055 -0.314668 0.356263 -0.0361720 -0.6322318 -0.0927460 0.7683572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2626 2653 -0.218508 -0.455648 0.664494 -0.4618976 -0.1544117 -0.2831828 0.8262053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2627 2612 0.353533 -0.325854 1.096906 0.1007814 -0.3245083 -0.9379695 0.0689246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2627 2967 -0.822566 0.453145 0.466700 -0.9351564 -0.0360092 0.2216155 0.2739933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2628 2651 -0.672575 0.509935 0.375485 -0.5065778 -0.2490714 -0.6374241 0.5244357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2628 2968 0.643967 0.337952 0.669738 -0.5892390 -0.5314517 -0.4211289 0.4393256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2629 2650 1.056795 -0.113948 -0.011844 0.3833837 0.2889881 0.0551005 0.8754809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2629 2969 -0.252387 -0.801509 0.222521 0.1498329 0.4847306 -0.8195433 0.2663363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2630 2649 0.440603 0.323650 0.961570 0.5114909 -0.3869116 -0.4155302 0.6449892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2630 2970 -0.799610 0.723813 0.014006 0.3478611 -0.3520914 -0.3084681 0.8123248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2631 2171 0.514345 0.657913 -0.722011 -0.0652380 -0.5177857 -0.3257831 0.7883573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2631 2648 0.062363 -0.896007 -0.532825 0.5884822 -0.1245871 -0.3881867 0.6981961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2631 2971 -0.462832 -0.332786 0.764975 0.0427590 -0.5540900 0.0010294 0.8313573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2632 2647 -0.220434 1.066936 -0.112906 -0.4463640 0.2676022 -0.7300854 0.4428584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2632 2972 0.818630 -0.034812 0.449982 0.2217722 0.0585825 -0.9123917 0.3390083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2633 2646 -0.802432 0.409686 -0.504387 -0.1247143 0.8305143 -0.5265144 0.1321930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2633 2973 -0.556020 -0.647224 0.177220 0.0463567 0.5182729 -0.4091055 0.7495845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2635 2175 0.728697 -0.577178 -0.328716 0.6849825 -0.0985392 -0.6912617 0.2079573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2635 2644 -0.749196 0.020451 -1.122070 -0.2805265 -0.1952694 -0.6241203 0.7026013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2636 2643 0.462014 0.470988 0.631588 0.5795277 0.1792607 0.7897364 0.0912669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2636 2976 0.612195 -0.671927 0.203105 0.1956666 0.1262346 -0.8005388 0.5521930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2637 2602 0.751309 -0.138085 0.600959 -0.0564751 0.2437461 -0.4962255 0.8313595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2637 2642 -0.766182 0.241025 -0.686932 -0.0908017 0.5602724 0.8194066 0.0801417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2637 2977 -0.646342 0.036083 0.760256 0.1233347 0.4196951 -0.3118347 0.8434475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2638 2641 -0.170037 0.738680 -0.623360 -0.0330854 0.2673107 0.9541855 0.1303088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2638 2978 0.389344 0.617105 0.554058 0.2693880 0.0720714 0.0708078 0.9577171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2639 2600 -0.853546 -0.379455 -0.086410 -0.7122992 -0.2205476 -0.2540777 0.6159814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2640 2679 0.117858 1.021211 -0.418439 0.1413747 0.2695541 -0.9510571 0.0533311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2641 2678 0.726322 -0.651088 -0.004826 0.7725960 -0.2718299 -0.4774905 0.3181302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2641 2941 -0.470603 -0.372552 0.825097 -0.0837392 0.1120780 -0.8971493 0.4189862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2642 2677 0.674069 -0.558030 0.117824 -0.3390733 0.3496232 0.5780706 0.6546963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2643 2676 0.565189 -0.215244 0.602737 -0.3717045 0.4228148 0.7553712 0.3353771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2643 2943 -0.167611 0.822054 0.374596 -0.5373701 -0.1962834 0.8196808 0.0288008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2644 2675 -0.508496 -0.318551 -0.570151 -0.3627868 -0.4413817 0.5661719 0.5941527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2644 2944 -0.256305 -0.631024 0.441652 -0.0778394 0.4506741 -0.4692278 0.7554199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2645 2674 0.724908 0.444087 0.542747 0.1308513 0.3794989 0.7780214 0.4832611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2645 2945 -0.034093 -0.409818 0.681465 0.1276249 -0.4914774 0.6173491 0.6008677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2646 2673 0.598372 0.774433 -0.222210 0.0181624 0.9233729 0.1529337 0.3516587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2646 2946 0.855127 -0.779591 0.257375 0.1211830 0.7197398 -0.3101834 0.6091597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2647 2672 -1.044471 -0.469900 -0.073703 -0.1807281 0.4381650 -0.4713178 0.7437797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2647 2947 0.027232 -0.030929 1.059956 0.2267952 -0.5353658 0.8019363 0.1372793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2648 2671 0.736822 -0.396026 0.608915 -0.1933682 0.2037750 -0.6350781 0.7195556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2648 2948 -0.241031 0.267942 0.872239 -0.1698643 0.6994707 0.4158252 0.5558563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2649 2670 -0.155765 0.927942 -0.278770 0.1439526 -0.6559831 0.4037042 0.6212784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2649 2949 -0.900951 0.152611 0.555311 0.5699751 -0.0463522 -0.0062562 0.8203296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2650 2669 0.759202 -0.313577 0.513232 -0.0034441 -0.7539829 0.6568374 0.0079052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2650 2950 -0.551348 -0.402881 0.822866 0.3342544 -0.2017225 0.0831931 0.9168756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2651 2668 0.205352 -0.949432 0.000328 -0.5103442 0.3964443 0.5138503 0.5642150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2651 2951 0.530758 0.315847 0.865836 0.6149075 -0.3492540 0.7001591 0.0984255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2652 2627 0.260724 -0.559430 0.672268 -0.1592465 0.4876812 -0.6385768 0.5736090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2652 2667 -0.445466 0.701013 -0.677370 -0.3620730 -0.3531564 -0.5178307 0.6899530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2652 2952 0.821849 0.731970 -0.081923 -0.0150771 0.0920382 -0.2866247 0.9534925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2653 2666 0.314462 -0.858919 0.181118 0.6557545 0.2600230 0.2861644 0.6484473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2653 2953 0.749349 0.480911 0.511249 -0.5057120 -0.1602545 -0.2736833 0.8022913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2654 2665 -0.257348 -0.938141 -0.251761 0.1747521 0.3976522 0.2610035 0.8620972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2654 2954 -0.068326 -0.313804 1.039555 -0.2765592 -0.5965916 0.0627459 0.7507705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2655 2664 0.301128 -1.035651 0.037839 0.2386630 0.4061994 -0.8765267 0.0987065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2655 2955 0.355328 0.352052 0.936671 0.3731723 0.5941132 0.2516512 0.6666660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2656 2156 -0.583035 -0.246766 -0.566397 0.0324202 0.0400792 0.5512499 0.8327462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2656 2663 -0.043675 -0.889921 0.272902 -0.6060262 -0.0480799 -0.5913107 0.5298794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2656 2956 0.645452 0.020929 0.529549 0.1259139 0.4592264 0.8577547 0.1936844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2659 2959 0.170201 -0.794254 0.421876 -0.2080114 0.0710947 0.8672889 0.4466393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2662 2122 0.521813 -0.564187 -0.641013 -0.2763115 0.1877354 0.0932290 0.9379316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2662 2657 0.572780 -0.395817 0.659214 -0.5097303 0.5594024 0.6410856 0.1274884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2662 2697 -0.651023 0.404633 -0.670531 0.6272585 -0.0074663 -0.7115653 0.3164899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2662 2922 -0.360843 0.539979 0.625833 -0.3714199 0.3298086 0.1419387 0.8562283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2663 2123 -0.775560 -0.088816 -0.695306 0.0381709 -0.1561195 -0.9551449 0.2487327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2663 2923 0.692277 0.010634 0.794997 -0.2967004 0.6733004 -0.1646651 0.6569025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2664 2124 0.827709 0.424362 -0.177432 0.3471419 -0.5162044 -0.0903894 0.7777244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2664 2695 -0.245633 0.701358 0.740428 0.3017079 0.5082409 -0.5761636 0.5645343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2664 2924 -0.859333 -0.658274 0.233330 0.2884102 -0.1125734 0.3110490 0.8985518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2665 2694 -0.475674 -0.862985 -0.558804 -0.4930787 0.5127705 0.4433545 0.5453225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2665 2925 -1.007545 0.054875 0.648454 -0.4742613 -0.2441638 0.6573892 0.5322591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2666 2693 -0.447900 0.298549 0.810819 0.6524641 0.0269677 0.7497230 0.1071392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2667 2127 -0.037056 -1.007258 -0.500679 0.1984846 -0.1573609 0.9369102 0.2409162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2667 2692 -0.952326 -0.174510 0.374104 -0.7914049 -0.1483745 -0.5856274 0.0932946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2667 2927 0.058686 0.689394 0.527115 -0.5085038 -0.1819256 0.8363259 0.0942651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2668 2691 -0.276431 -0.267164 -0.889182 0.2043910 -0.6925422 -0.1791436 0.6682195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2669 2690 -0.856288 -0.440567 0.179812 -0.6652341 0.2160128 -0.6525777 0.2914524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2669 2929 0.521443 -0.972531 0.453835 0.5956509 -0.2283060 0.4908201 0.5934408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2670 2689 -0.089790 0.813361 -0.530489 0.1142078 -0.1904225 0.7240715 0.6530056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2671 2688 0.545767 0.475950 0.841502 -0.5663455 -0.6667137 0.3913158 0.2856877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2671 2931 -0.549009 -0.525139 0.465147 0.7060548 0.1885126 -0.3835338 0.5646693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2672 2687 0.454375 -0.616132 -0.485885 0.5775321 -0.3590576 -0.7031460 0.2076537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2672 2932 -0.292950 -0.878733 0.538511 0.2841658 -0.0169296 -0.7998246 0.5284353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2673 2133 0.787722 0.364711 -0.026221 0.0018431 -0.2145613 0.8812360 0.4211687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2673 2686 -0.248198 0.466996 0.701273 0.3963517 0.3657840 -0.4462270 0.7141350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2673 2933 -0.591265 -0.386138 0.043181 -0.9764642 -0.0062952 0.2058281 0.0641312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2674 2685 -0.063351 -0.313976 0.962355 -0.8823205 0.2536123 0.3954953 0.0278348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2674 2934 -0.562816 0.807375 0.059916 0.6338149 -0.7084200 -0.1748258 0.2566237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2675 2935 -0.536900 -0.448396 0.426254 0.2039407 -0.2157700 -0.9548603 0.0096592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2676 2683 -0.933240 -0.195274 0.196082 -0.3344900 0.1182425 -0.5678681 0.7427389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2676 2936 0.084050 0.114625 1.052203 -0.5235641 -0.3353372 -0.1963578 0.7582039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2677 2137 -0.253514 0.540690 -0.903536 0.7391283 0.3812429 -0.3141920 0.4578500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2677 2682 -0.387505 -0.788416 -0.619153 0.2836277 -0.4795006 -0.4978574 0.6646597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2677 2937 0.539956 -0.554960 0.940514 0.4637774 -0.2859150 0.7676118 0.3375429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2678 2681 0.709404 0.535522 -0.236437 -0.2463024 -0.2173371 0.4816163 0.8124934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2678 2938 -0.613633 0.927103 0.333684 -0.7214503 -0.2263606 -0.5653294 0.3296559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2679 2939 -0.824363 -0.268374 0.523718 -0.8543391 0.0391977 0.5087836 0.0985266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2680 2100 0.732981 0.456525 -0.415486 0.3985500 -0.5767155 -0.3002860 0.6468273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2680 2719 -0.043866 -0.701081 -0.831488 0.5017462 -0.4641300 -0.5092277 0.5229925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2681 2718 0.855503 -0.132549 -0.435689 0.7472000 0.2298976 0.6234937 0.0097343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2681 2901 0.619189 0.566327 0.565931 0.1395458 0.7438394 0.6493609 0.0745681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2682 2717 0.759873 -0.652278 -0.098694 0.7969163 0.4092403 0.4059560 0.1806835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2682 2902 0.596393 0.717575 -0.039936 -0.3356266 0.1391713 -0.8613932 0.3549477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2683 2716 -0.187684 -0.671957 -0.497647 0.1807428 0.2097204 -0.9254803 0.2585260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2683 2903 0.226248 -0.548392 1.018174 -0.0115241 0.2419358 0.0596745 0.9683869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2684 2675 -0.827842 0.035904 0.699024 -0.2589705 0.4303696 -0.7950850 0.3399355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2684 2904 0.722955 0.388626 0.566484 -0.2460544 0.6744448 0.2800517 0.6373009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2685 2714 -0.681106 0.395109 -0.759723 0.7683593 -0.3194238 -0.4377792 0.3405024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2685 2905 -0.558551 -0.573250 0.556779 -0.2270998 -0.1771377 -0.0322426 0.9570832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2686 2106 0.356707 0.755499 -0.417925 0.8454094 -0.0373639 0.1260965 0.5176742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2686 2713 -0.898811 -0.014132 -0.282945 -0.1640307 -0.5982642 0.7217671 0.3069628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2686 2906 -0.342129 -0.750596 0.380030 0.7050198 -0.4217130 0.5454440 0.1661206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2687 2712 0.926144 0.038743 -0.493469 0.6791793 0.1807343 0.6544144 0.2789130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2688 2711 0.231794 -0.448841 -0.937697 0.6400026 0.5235510 -0.2893746 0.4822378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2688 2908 -0.454409 -0.882881 0.126783 0.4600224 -0.4037889 0.4935870 0.6178234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2689 2710 0.345035 0.213223 -0.966290 0.8012822 -0.3483920 0.4696476 0.1264955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2689 2909 0.722579 -0.559834 0.192244 0.3693675 0.3469886 -0.3011111 0.8077739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2690 2709 0.273472 0.326184 -0.872276 -0.0318837 -0.6159730 -0.7775460 0.1224049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2690 2910 0.774169 0.398479 0.656638 0.3963883 0.6161229 0.6280313 0.2623843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2691 2708 -0.610997 -0.614796 0.438360 -0.8039487 -0.0492978 -0.5926507 0.0011465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2691 2911 0.752938 -0.515079 0.554390 0.3521741 0.3095820 -0.7016968 0.5364270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2692 2707 -0.270255 -0.271220 -0.867424 -0.7235604 0.6700298 -0.1622257 0.0346886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2692 2912 0.562786 -0.729354 0.041884 0.8289148 0.2228471 -0.0106824 0.5129574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2693 2706 0.871210 -0.057385 -0.029740 0.0231380 0.7433027 -0.5380144 0.3968706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2693 2913 0.124332 -0.607227 0.653250 0.2794971 0.1136917 0.7168698 0.6285327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2694 2705 0.508626 0.470695 -0.951743 0.1665722 0.7789914 0.5814898 0.1652140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2695 2704 -0.905759 -0.449531 -0.266749 0.1082096 0.0922650 -0.4135711 0.8992979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2695 2915 0.050667 -0.972426 0.428649 0.1628064 0.2590566 -0.9166793 0.2570657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2696 2663 0.823808 -0.636216 -0.050965 0.4235902 -0.1005406 0.8284732 0.3522714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2696 2703 -1.040162 0.324065 0.147655 -0.1231129 0.1714003 -0.0513609 0.9761287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2696 2916 0.297517 -0.084723 0.998909 0.3844724 0.2066200 0.3916148 0.8100167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2697 2917 -0.768365 -0.541182 0.278112 -0.0216497 -0.9074561 0.3314956 0.2572264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2698 2118 -0.069691 0.412705 -0.867959 0.0636261 0.2446603 -0.6765473 0.6916479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2698 2661 -0.599608 0.706644 0.460426 -0.2785256 -0.3405318 -0.8771816 0.1923902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2698 2918 0.363673 -0.092173 0.842471 0.0917987 0.4886504 0.5649270 0.6585221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2699 2660 0.541281 -0.259971 -0.669841 0.0528331 -0.0088187 -0.3002078 0.9523687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2699 2919 0.594921 -0.179771 0.624286 -0.2190086 -0.4173267 0.8677986 0.1574778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2700 2739 -0.513822 -0.896183 -0.224025 -0.6233713 0.0026569 0.4637518 0.6295518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2700 2880 -0.649211 0.332367 0.398567 -0.0096300 -0.3633072 0.5284821 0.7672169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2701 2698 0.963351 -0.332648 0.369140 -0.0726412 -0.2065066 -0.9542571 0.2036460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2701 2738 -0.961922 0.089759 -0.518855 -0.0798917 -0.4073928 0.8730018 0.2559615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2701 2881 -0.118221 0.439091 0.860396 0.0438187 -0.8468194 -0.5124733 0.1354542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2702 2697 -0.531216 0.483125 0.801144 0.0962363 0.6433487 0.1480720 0.7449267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2702 2737 0.580973 -0.640659 -0.586662 -0.0773193 0.0330560 0.8165718 0.5710863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2703 2736 -0.886967 0.311435 -0.009612 0.4501375 -0.0656191 0.8873507 0.0753599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2703 2883 0.066998 -0.424679 0.936403 0.6005709 -0.1244398 -0.0381056 0.7889089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2704 2735 -0.308249 -0.978802 -0.234724 -0.5676489 0.4679249 -0.4212488 0.5304436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2704 2884 0.643669 -0.438367 0.728087 -0.4126564 0.5838800 -0.2799277 0.6406554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2705 2734 -0.191584 -0.668598 0.773921 -0.1190703 0.1309039 -0.8942056 0.4111968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2705 2885 0.767688 0.341337 0.525400 -0.4901470 0.0887066 0.2312803 0.8357012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2706 2886 -0.328548 -0.940362 0.609514 0.8655482 -0.3737717 0.1505797 0.2974001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2707 2087 -0.864057 0.500820 -0.149755 -0.4437513 0.8717341 -0.1089587 0.1768968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2707 2732 -0.112393 0.352553 0.989512 0.5072661 -0.8401167 0.1887323 0.0355693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2707 2887 0.580410 -0.742868 0.216842 -0.3998715 0.8899011 -0.1496895 0.1605363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2708 2731 0.102529 0.502268 -0.726267 -0.3686210 0.4863244 0.4113169 0.6770713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2709 2730 -0.552015 -0.815128 -0.064147 0.2965478 -0.7158110 -0.0782167 0.6273405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2709 2889 -0.881169 0.526144 0.546843 -0.2746213 -0.0055170 -0.6717511 0.6879703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2710 2890 0.675334 0.326137 0.684957 0.5064568 0.0246863 0.1032666 0.8557033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2711 2728 0.845620 -0.233729 0.625587 0.8386506 -0.0912712 -0.4776077 0.2454091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2711 2891 -0.707802 -0.287341 0.557576 -0.7640376 -0.1066717 0.5895970 0.2392553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2712 2727 -0.161018 -0.448061 0.664171 0.5647615 0.2177271 -0.2217697 0.7644983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2713 2726 0.759005 0.436807 0.387122 -0.4500744 -0.5428333 0.4441881 0.5526862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2713 2893 -0.419418 -0.164348 0.847952 0.0833927 -0.7234296 0.3997789 0.5566616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2714 2725 -0.383300 -0.567368 0.575184 -0.7180245 -0.1668212 -0.6255945 0.2554270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2714 2894 -0.298559 0.923501 0.528166 -0.1017348 -0.8348288 -0.1653011 0.5151567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2715 2895 0.791666 0.974088 -0.075961 -0.7956203 -0.5494790 -0.2533231 0.0298089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2716 2723 0.642404 0.803210 -0.072390 0.0622552 -0.4174734 0.9058454 0.0358394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2716 2896 -0.558718 0.371778 0.934555 -0.1780660 -0.1464988 0.0859631 0.9692476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2717 2722 -0.426681 0.772855 0.628922 0.3085515 0.8415958 0.1709030 0.4090289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2717 2897 0.973157 -0.093748 0.495338 -0.2146303 0.1675249 0.5615576 0.7813593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2718 2721 -0.651032 0.110512 0.696419 -0.3239456 0.1964553 -0.8768169 0.2960687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2718 2898 0.738456 -0.014293 0.490934 0.5321247 0.6629203 -0.3786776 0.3660373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2720 2860 -0.872957 -0.653586 0.211188 0.0021622 0.1546690 -0.3014273 0.9408583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2721 2061 0.114812 -0.249118 -1.035061 -0.1608401 0.3315638 0.3865643 0.8454371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2721 2758 0.624574 -0.845810 0.296965 -0.3953588 -0.0944323 -0.2312606 0.8839075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2721 2861 -0.109852 0.226149 1.074067 -0.1251974 0.1429975 0.9309317 0.3118390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2722 2062 0.736507 -0.731438 -0.278292 0.4131911 -0.0146931 -0.5785519 0.7030896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2722 2757 0.383641 0.562111 -0.583239 -0.3508547 -0.4723313 0.7871188 0.1850624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2722 2862 -0.670860 0.500624 0.357374 0.5490549 -0.7645712 -0.1993750 0.2724319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2723 2863 0.737270 -0.929295 0.233474 0.2770837 -0.6802234 0.1565814 0.6603053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2724 2064 -0.795305 -0.423241 -0.564505 -0.6521042 0.5490828 0.1407307 0.5034511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2724 2715 -1.061327 0.280854 0.445289 0.7058577 0.4642190 0.2402738 0.4780524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2724 2755 0.747416 -0.239701 -0.497471 -0.3253445 -0.0193716 0.2682593 0.9065388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2724 2864 0.594138 0.317182 0.531924 -0.4808099 -0.2594691 -0.8326069 0.0909035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2725 2065 -0.550298 0.723873 -0.161208 -0.0636470 0.4960803 -0.7530243 0.4275602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2725 2754 0.789965 0.492209 -0.617844 0.5024296 0.1462389 0.7224857 0.4518773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2725 2865 0.793149 -0.888289 0.003256 -0.7713371 -0.1507221 -0.5987365 0.1543906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2726 2866 -0.149136 -0.949653 0.289562 0.3464993 0.2135698 0.2670796 0.8734957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2728 2751 -0.231835 0.447134 -0.943070 0.4427888 -0.7446361 -0.4565567 0.2025119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2728 2868 -0.690880 0.473302 0.543934 -0.1618449 0.5860211 0.7460275 0.2717138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2729 2710 0.843373 -0.045779 -0.507762 -0.3450769 -0.2835815 0.2278968 0.8651974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2729 2750 -0.984006 -0.076750 0.419676 -0.3827185 0.6171753 0.6730242 0.1402128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2729 2869 0.140599 0.715175 0.523960 -0.2439074 0.2623085 -0.8083232 0.4672441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2730 2749 0.558585 -0.606326 0.837824 -0.2344853 0.2875395 -0.3020034 0.8781410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2730 2870 0.030465 0.851183 0.616631 -0.6514662 -0.2829861 -0.5378902 0.4540757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2731 2748 0.749387 -0.031649 0.403389 -0.0404029 -0.2898736 0.3600317 0.8858432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2731 2871 -0.346711 -0.563008 0.972026 -0.1492249 -0.2994254 0.7150467 0.6138278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2732 2747 0.257463 -0.351802 -0.970826 0.8030105 0.3377785 0.4501021 0.1961834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2733 2706 1.013121 -0.281240 -0.325843 -0.5054219 0.2057642 0.3928843 0.7401701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2733 2746 -0.951823 0.374291 0.349597 -0.3940682 -0.1828495 0.6799821 0.5906781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2733 2873 0.393203 0.144230 0.877246 -0.4081227 0.3025601 0.8032238 0.3110060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2734 2074 0.646448 0.076891 -0.823076 -0.0204495 0.2082529 0.3772633 0.9021557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2734 2745 0.746403 -0.136176 0.792750 0.5550756 -0.0322512 -0.7758015 0.2983002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2734 2874 -0.681336 0.034066 0.711868 -0.6779196 -0.0221676 0.4800033 0.5563545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2735 2744 0.813731 0.270903 -0.381333 -0.0950133 -0.5410549 0.7977524 0.2486425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2735 2875 0.395006 -0.604091 0.398865 -0.1235013 0.9564385 -0.2466038 0.0957047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2736 2743 0.606422 -0.271688 -0.826782 0.1072648 0.0621445 0.2038416 0.9711235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2737 2742 -0.676359 -0.352532 -0.565472 -0.1303009 -0.0072581 0.2225777 0.9661409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2737 2877 -0.890798 -0.222969 0.624710 0.3425681 -0.3996988 0.0949065 0.8449146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2738 2741 0.806447 0.685367 0.049500 0.6706419 -0.4259622 0.5396371 0.2785451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2739 2079 0.607621 0.004302 -0.643283 -0.0549523 -0.7118673 0.6625890 0.2262765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2739 2879 -0.645152 0.022620 0.574958 0.3655012 0.0402802 0.8380601 0.4030405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2740 2779 -0.619902 0.538540 0.534366 0.0248120 -0.2887812 -0.9563712 0.0366606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2740 2840 0.010454 -0.640685 0.875213 0.3540277 0.5884638 -0.6943953 0.2149183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2741 2778 -0.311636 -1.002173 0.148597 0.1693172 0.2184318 0.0888767 0.9569327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2742 2777 -0.516649 0.086151 -0.871327 0.0282952 0.0507004 -0.9945622 0.0864577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2742 2842 -0.633378 0.134913 0.672583 0.6441136 -0.5821311 -0.3198562 0.3793851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2743 2776 0.434829 -0.444265 -0.533592 0.4014969 0.7398736 -0.2464056 0.4802827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2743 2843 0.773735 -0.189732 0.643802 -0.3426458 0.0069149 -0.0090390 0.9393957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2744 2775 -0.524471 0.248479 -0.629815 0.6317029 -0.0742355 -0.3731352 0.6754337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2744 2844 -0.811665 -0.235368 0.606724 0.7291886 -0.5068455 0.2007894 0.4136125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2745 2774 -0.620524 0.629897 -0.429053 -0.5042208 0.0305814 0.8416434 0.1909516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2745 2845 -0.518354 -0.076564 0.868018 -0.3031209 -0.2618378 -0.6781461 0.6161790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2746 2046 -0.213626 0.854225 -0.251492 0.1975786 0.7152160 -0.6031163 0.2927105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2746 2846 0.152952 -0.926103 0.284300 -0.4284386 -0.3569356 0.8151691 0.1566416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2747 2772 -0.609543 -0.420721 0.604524 -0.1793128 0.6199177 0.6017555 0.4705734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2747 2847 -0.299925 1.121322 -0.086124 0.2951182 0.3036660 0.8841541 0.1973923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2748 2771 0.927552 -0.538174 -0.321510 0.2452935 -0.0802771 0.6493969 0.7153113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2748 2848 -0.288303 -0.297710 0.710698 0.7159357 0.0324922 0.0822880 0.6925381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2749 2849 -0.649183 0.221754 0.686520 -0.8206283 -0.3023461 0.2672917 0.4046125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2750 2769 0.448309 0.839759 0.229845 0.0127685 -0.2364259 0.6377764 0.7329264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2750 2850 -0.762281 0.292426 0.708098 -0.2638464 0.2673768 -0.3201504 0.8697117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2751 2051 0.083375 -0.848142 -0.597290 0.2644177 -0.3297963 -0.7692617 0.4791180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2751 2768 -0.342476 -0.564519 0.692462 0.0062011 0.6927820 0.1939969 0.6945357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2751 2851 -0.080633 0.820521 0.857177 -0.6517340 0.4084452 -0.2560053 0.5855566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2752 2727 -0.763132 -0.515464 -0.455895 -0.0460777 -0.3909109 -0.9000438 0.1870473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2752 2767 0.766035 0.515323 0.532257 0.2184138 -0.4577533 -0.0327120 0.8612127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2752 2852 -0.624599 -0.045097 0.846865 0.3291261 -0.3793100 -0.8615694 0.0741487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2753 2726 -0.154883 0.585051 -0.532507 -0.7396084 0.5150473 -0.1186019 0.4167005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2753 2766 0.076978 -0.703346 0.574362 -0.5430789 -0.2298593 -0.7378492 0.3283421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2753 2853 0.922391 0.521832 0.470090 0.0713077 0.8924290 -0.0767438 0.4388576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2754 2765 -0.210376 -0.956724 -0.010054 -0.0315131 -0.3306284 0.1425072 0.9324074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2754 2854 -0.290322 0.350943 0.744550 0.0273399 -0.7236667 -0.5333962 0.4370898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2755 2855 0.624435 -0.416609 0.468440 0.1986330 0.3251733 -0.8152115 0.4361621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2756 2856 0.094378 -0.121568 0.898260 -0.3843756 0.5158424 -0.5124307 0.5688381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2757 2857 0.739093 -0.456092 0.258031 0.5968662 -0.3134033 0.4670684 0.5721681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2758 2058 -0.105147 0.755184 -0.992488 -0.0335939 0.4394833 0.2252601 0.8688980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2758 2761 0.812714 -0.491739 -0.390108 -0.1667081 -0.4740830 0.5063824 0.7007357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2758 2858 0.199406 -0.402528 0.728426 0.1046366 0.5299165 -0.7570242 0.3676332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2759 2059 -0.262650 -0.816711 -0.107123 -0.8672815 -0.2371363 -0.1943784 0.3921813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2759 2720 0.056725 -0.047222 -0.985622 -0.7353065 0.6398359 0.2081864 0.0811959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2759 2859 0.257419 0.913983 -0.061089 -0.4110263 0.6357339 0.4191169 0.5012393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2760 2799 0.410085 -0.440019 -0.561478 -0.2277117 -0.6689796 0.5120619 0.4882685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2760 2820 -0.000291 -0.526240 0.828713 0.1565385 -0.3286929 -0.4320859 0.8250808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2761 2798 -0.371298 -0.361486 -0.860588 0.2965260 0.0587955 -0.8009595 0.5167971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2761 2821 -0.114342 -0.931845 0.353460 -0.0925706 0.1474987 0.9841061 0.0347847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2762 2757 -1.098755 -0.368121 -0.098979 -0.2809042 -0.6074462 0.1917893 0.7178571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2762 2822 -0.227991 0.127183 1.101748 0.2099208 0.3270714 -0.6771132 0.6248802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2763 2756 -0.893938 0.352756 -0.318753 0.0424104 0.2872042 -0.9564976 0.0287670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2763 2796 1.027727 -0.042729 0.194993 0.2295149 -0.2242359 -0.7005207 0.6374260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2763 2823 -0.297053 -0.703827 0.889750 0.4443019 -0.1974322 -0.7162050 0.5006664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2764 2755 0.362443 0.039204 -0.722968 -0.7924341 0.1728863 -0.5716575 0.1239603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2764 2795 -0.508599 -0.033460 0.730364 -0.8577238 0.1760658 -0.1953741 0.4417462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2765 2794 -0.528899 -1.015438 0.296313 -0.1003383 0.0316690 -0.6395929 0.7614790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2765 2825 0.062473 0.463431 0.914342 -0.3572285 0.4426523 -0.7207089 0.3962644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2766 2793 0.919765 0.463819 0.050667 0.5117385 -0.4024044 0.7468180 0.1358574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2766 2826 0.119388 0.400608 0.978532 0.2707039 0.3140512 -0.1330323 0.9002187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2767 2792 0.724297 0.401404 -0.452389 -0.0796855 -0.0988149 -0.6202020 0.7741029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2768 2791 -0.745326 -0.309328 -0.382877 0.2875420 -0.6533963 -0.1198415 0.6899499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2769 2829 0.331216 0.535798 0.725854 -0.5777393 0.1712280 -0.0439008 0.7968507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2770 2789 -0.679637 0.647577 0.197269 -0.3631197 -0.1643679 0.7186172 0.5698391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2770 2830 0.442491 0.503407 0.778547 0.3594918 0.4401228 0.6479324 0.5071895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2771 2788 -0.400137 -0.954086 0.407094 -0.2512389 -0.0003202 -0.9658986 0.0626005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2772 2032 -0.539167 -0.441104 -0.620942 -0.4569492 0.0602469 0.8658462 0.1946227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2772 2787 -0.402621 0.990000 -0.219859 0.5979448 0.1996151 0.5716020 0.5252495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2773 2746 0.578308 0.468088 -0.490393 0.3224907 0.0056493 -0.9444274 0.0634411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2773 2786 -0.701706 -0.497801 0.739389 -0.6841573 0.2600460 0.6616752 0.1627599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2773 2833 -0.489416 1.014469 0.132414 -0.4823099 0.1503047 0.4530852 0.7345063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2774 2034 0.544903 0.053046 -0.815910 -0.0282142 -0.4480735 -0.2747511 0.8502622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2774 2785 0.723423 -0.261608 0.642251 0.3618421 0.0270734 -0.8445280 0.3938398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2775 2784 -0.239882 -0.779556 -0.003488 0.5301531 0.1484882 0.0653000 0.8322409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2775 2835 -0.527879 0.081646 0.851286 -0.1010637 0.1015755 0.9879803 0.0579961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2776 2783 0.266986 -0.002673 1.022857 -0.9553679 0.0170346 0.1477228 0.2552645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2776 2836 -0.711167 0.519639 0.322877 -0.1496710 -0.7523052 -0.1334962 0.6275462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2777 2837 0.682773 -0.255209 0.616752 0.2799461 0.0614318 -0.3402838 0.8955798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2779 2839 0.053073 0.791907 0.354307 -0.6776784 -0.4274492 -0.3443675 0.4893365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2780 2000 0.038884 -0.876154 -0.460851 -0.1382311 0.5261671 0.8104123 0.2174218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2780 2800 0.042674 0.854407 0.478509 -0.1273726 0.5265781 0.8186263 0.1906377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2781 2001 0.497280 0.015949 -0.945875 0.5190760 0.3970187 -0.6179956 0.4370557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2781 2778 -0.869227 0.008822 -0.364448 -0.0484964 -0.0526258 0.8070716 0.5861008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2781 2801 -0.411320 -0.037134 0.746021 0.3637189 -0.1962473 0.3922657 0.8217805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2782 2777 0.921593 0.051863 -0.284204 -0.5370860 0.1638394 -0.7993300 0.2139316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2783 2803 -0.759913 -0.485208 0.174139 0.7249183 0.2173087 -0.3282863 0.5652419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2784 2804 -0.749439 0.828927 -0.021721 -0.9087272 -0.2004743 0.3657052 0.0168711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2785 2805 -0.352783 -0.395791 0.977901 -0.3222262 0.2602551 -0.3185788 0.8526108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2786 2806 -0.298007 -0.450108 0.601688 0.3560641 -0.3189726 -0.2594699 0.8391366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2789 2809 0.029384 -0.921876 0.171912 0.4684292 -0.6000066 0.0294101 0.6478435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2790 2769 -0.803909 0.257817 -0.652424 -0.0812805 -0.4484905 -0.0087838 0.8900408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2790 2810 -0.384999 0.492820 0.678161 -0.0939625 0.5565035 0.7594593 0.3235683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2791 2811 -0.128904 1.035737 0.099587 -0.0488859 -0.0081471 -0.3353580 0.9407863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2792 2812 -0.022122 0.308112 0.916616 0.4374346 0.0724918 -0.1312720 0.8866586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2794 2814 -0.157756 0.114032 0.827453 -0.1544342 0.0053424 0.4540246 0.8774869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2795 2815 0.698548 -0.731862 -0.049887 -0.1939497 0.8521859 -0.1706290 0.4550258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2796 2816 0.704535 0.183757 0.810494 0.0841336 0.8919804 0.2012605 0.3959631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2797 2817 -0.221557 -0.965480 0.222532 0.0174476 -0.0201098 0.4163997 0.9087918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2798 2818 0.287235 0.475330 0.740834 -0.1266387 0.0518115 -0.8354200 0.5323079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2800 2839 -0.035290 -1.109850 0.035467 0.0136104 -0.2691789 0.6961684 0.6653623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2800 3580 0.003283 -0.005369 1.141690 -0.0921178 0.2201330 0.1459438 0.9600813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2801 2838 -0.738926 0.534934 -0.252892 -0.5354023 0.4168677 0.3491366 0.6462734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2801 3581 0.134400 0.587272 0.627883 -0.3232049 0.5649275 -0.1723470 0.7393863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2802 2782 -0.311022 0.852111 -0.295093 0.0805789 0.5489085 -0.6013457 0.5749695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2802 3582 0.417360 -1.054911 0.444370 0.0290765 -0.0940209 0.0807136 0.9918669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2803 2836 -0.843502 0.310442 -0.579510 0.2798798 -0.4983351 -0.3110342 0.7593334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2803 3583 -0.704268 -0.399076 0.729458 0.6475334 0.1778373 -0.6435466 0.3673176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2804 2835 0.967493 -0.108779 0.335334 0.3948582 -0.5592050 0.6277625 0.3705280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2804 3584 0.094881 -0.894463 0.311985 -0.3521359 -0.3034774 0.8059989 0.3664253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2805 2834 0.793461 -0.067860 -0.040156 0.0446025 0.0285764 -0.2675490 0.9620871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2805 3585 -0.181728 -0.993114 0.255266 -0.3853211 0.3666638 -0.8315274 0.1601484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2806 2833 0.896985 -0.359910 -0.246856 -0.0023462 0.1239774 -0.1920881 0.9735123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2807 2787 0.127955 -0.503182 -0.892370 -0.3011492 -0.6274000 -0.1587156 0.7003483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2807 2832 -0.432986 0.703831 -0.731595 -0.2614046 0.5462300 0.3287566 0.7247203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2807 3587 -0.156902 0.613249 0.896510 -0.6932968 -0.2525382 -0.4998887 0.4535144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2808 2788 -0.650014 -0.148097 -0.627548 -0.4507093 0.1725534 -0.2621476 0.8356824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2808 2831 -0.636334 -0.189570 0.748219 -0.4414854 -0.0233405 -0.4802230 0.7575828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2808 3588 0.638576 0.238990 0.727048 -0.1505194 0.4664555 0.7080865 0.5083076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2809 2830 -0.699536 -0.187013 0.798487 0.3516510 0.2714304 -0.3729746 0.8145901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2809 3589 0.505524 -0.626490 0.541388 -0.2349139 0.3384554 -0.4022949 0.8175709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2810 2829 1.045909 -0.151960 -0.094174 0.0874300 -0.0161330 0.9934165 0.0722449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2811 3591 -1.034695 0.545566 0.128949 -0.2122535 -0.3635759 -0.2117323 0.8820037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2812 2827 0.655408 0.074398 0.886194 0.0824439 0.1320422 0.5559760 0.8164916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2812 3592 -0.556702 0.732537 0.265569 -0.7111648 -0.4527145 0.2353491 0.4836373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2813 2826 0.215943 0.843923 -0.835861 0.0760771 -0.3704340 -0.8374124 0.3946281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2813 3593 0.545730 0.347490 0.726613 -0.1119229 0.6493653 0.7368551 0.1511375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2814 3594 -0.322279 -0.379447 1.025161 -0.3076384 -0.4210501 -0.8462437 0.1093025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2815 2824 -0.858590 0.053969 -0.227431 -0.3746238 0.1320700 0.8350494 0.3806665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2815 3595 -0.238510 -0.511438 0.760514 -0.2281292 -0.7442869 0.5690688 0.2648675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2816 2823 -0.431606 -0.578719 -0.503833 0.1550870 -0.8401093 -0.1669747 0.4922234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2816 3596 -0.909141 0.449192 0.089548 0.3931556 -0.0802373 -0.9158732 0.0129215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2817 2822 -0.357944 0.301471 -0.812350 0.6950387 0.3129082 -0.3173970 0.5641531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2817 3597 -0.928764 -0.452822 0.213061 0.4298183 -0.5707208 0.1883492 0.6738386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2818 2821 0.155394 -0.848297 -0.013076 0.5193386 0.0383070 0.4057124 0.7511441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2818 3598 -0.509587 0.025417 0.881625 0.6058173 -0.3366908 -0.5766334 0.4325721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2819 2799 0.292916 0.353984 -0.903269 -0.1131817 0.5640123 -0.6123289 0.5423406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2820 2859 -0.518261 0.144330 0.914945 -0.3586107 -0.0007802 -0.9334695 0.0056938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2820 3560 0.841631 0.247114 0.551319 -0.2256944 0.6612045 0.4206539 0.5787235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2821 2858 -0.830828 -0.191892 0.758362 -0.6140625 -0.1607367 -0.4826072 0.6034743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2821 3561 0.028976 1.065249 0.343604 -0.4699810 -0.7900142 -0.3567927 0.1664164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2822 3562 -0.853409 -0.289095 0.599077 -0.2361064 -0.2948706 0.2635011 0.8876217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2823 2856 -0.050049 -0.680413 0.739649 0.0440444 0.2576881 -0.9651627 0.0108556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2823 3563 0.307163 0.741605 0.680899 0.1785495 -0.1436581 0.2627632 0.9372502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2824 3564 -0.755037 0.487823 0.477243 0.5122741 0.5330138 -0.6717026 0.0478231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2825 2854 -0.983804 0.091954 0.013433 0.7559614 -0.4152955 -0.1144711 0.4928979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2825 3565 -0.239025 -0.815551 0.493650 0.9227031 -0.2988105 0.0273349 0.2420416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2826 3566 -0.526143 0.438391 0.559646 -0.0171871 -0.3542664 0.9058176 0.2317205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2827 2767 -0.660995 -0.789574 -0.216394 -0.1386301 0.4389560 0.1060990 0.8813866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2827 2852 0.002125 -0.412521 1.060758 -0.4680796 -0.4551450 -0.5007557 0.5683206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2828 2768 -0.425840 0.859039 -0.329517 0.9338232 0.2830151 0.0443684 0.2142617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2828 2811 -0.718837 -0.014488 0.306597 -0.5727332 -0.3247622 0.7368527 0.1534741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2829 3569 0.177363 -0.548036 0.747971 0.1802439 0.4369157 -0.7879297 0.3946942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2830 2849 -0.971155 -0.419703 0.330724 -0.3029817 -0.2835614 0.8970739 0.1518333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2830 3570 0.302339 0.200993 0.971814 -0.4606082 -0.1467835 0.3009282 0.8220322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2831 2771 -0.535989 -0.264008 -0.827178 -0.2677713 -0.0615521 -0.9283417 0.2503828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2831 2848 0.148515 -1.123216 -0.122735 0.3782623 0.6491752 0.6505186 0.1109716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2832 2772 0.489203 -0.347428 -0.615301 -0.0348074 0.0102001 0.8614678 0.5065152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2832 2847 0.636591 0.625440 0.278059 0.2101852 -0.2417571 0.9462739 0.0440607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2833 2846 0.838822 -0.174081 -0.196490 0.3429895 0.1032589 -0.5815795 0.7303842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2833 3573 0.095893 0.316048 0.889998 -0.6449681 -0.1417500 -0.1458643 0.7366455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2834 2774 -0.517330 0.719464 -0.426627 0.1676862 0.6297084 -0.7502494 0.1116898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2834 2845 1.002509 0.468240 0.116101 0.0987146 0.0397267 -0.1952679 0.9749603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2834 3574 0.372562 -0.823755 0.270959 0.2169680 -0.4195969 0.7539575 0.4565210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2835 3575 0.503548 0.071599 0.858740 -0.3620593 -0.2312863 -0.2865837 0.8563233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2836 2843 -0.850263 -0.151949 0.518297 -0.1361415 -0.2931336 0.2474280 0.9134098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2837 2842 -0.845047 -0.056670 0.603109 0.2268711 0.8059652 0.3913956 0.3817840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2838 2778 0.299047 0.472021 -1.106675 0.3335431 -0.2788855 0.1304881 0.8910358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2838 2841 0.015290 0.901735 0.523016 -0.3338722 -0.0317531 -0.6428501 0.6886689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2838 3578 -0.421511 -0.417315 1.080049 -0.2087063 0.5464583 0.8110451 0.0055523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2839 3579 0.358023 -0.165838 0.763293 -0.3551521 0.0453480 -0.9321751 0.0534798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2840 2879 -0.087489 0.922330 0.661971 0.1494095 -0.5312388 -0.8006693 0.2332184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2840 3540 -0.786197 -0.418738 0.492275 0.0346997 -0.0902559 0.6596650 0.7453133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2842 2877 0.167238 0.239249 -0.892864 -0.2917429 0.3280065 0.2435676 0.8648541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2842 3542 -0.155430 0.870411 0.211573 -0.2244478 0.6642277 0.4951463 0.5130837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2844 2835 -0.826982 0.119346 0.405781 -0.1310363 0.5859702 0.5391095 0.5906178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2844 2875 1.074018 -0.126671 -0.444084 -0.8520618 0.3174703 0.4068134 0.0877847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2844 3544 0.324568 1.094332 -0.031665 0.0207850 0.0312664 0.2309576 0.9722392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2845 2874 0.593362 0.683567 -0.374155 0.1720855 0.7965041 -0.0821680 0.5737736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2846 2873 0.491392 1.004681 0.071156 0.7436979 -0.1295369 -0.5292886 0.3872819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2846 3546 -0.713702 0.382628 0.631577 -0.5788310 0.0019776 0.0453902 0.8141809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2847 2872 -0.316531 -1.022693 0.368310 0.9687922 0.0344939 -0.0403726 0.2421198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2847 3547 0.809608 -0.493234 0.124929 0.8367763 -0.4835521 0.0793238 0.2443165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2848 2871 -0.876604 0.354534 -0.494749 -0.6284234 0.3197578 0.2810747 0.6510269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2849 2870 0.219554 0.186801 0.989958 0.1304146 0.5639885 -0.6926940 0.4302138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2849 3549 -0.377398 -0.971993 0.500895 0.2454463 0.1838313 0.7363509 0.6031165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2850 2869 0.307210 -0.663530 -0.750893 -0.6995709 -0.6311744 0.1699947 0.2886543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2851 2828 0.139991 -0.755273 -0.866700 -0.3344905 -0.8822370 0.1451103 0.2978540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2851 2868 -0.151935 0.712917 0.775739 0.6981295 -0.5465950 -0.2839255 0.3650143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2851 3551 -0.888057 -0.528200 0.221001 -0.7376904 -0.3708313 0.5602892 0.0661290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2852 2867 1.064424 0.077672 -0.117038 -0.4460776 -0.3263283 -0.7960234 0.2467211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2852 3552 0.021506 0.675637 0.638273 -0.3204900 -0.2571871 0.2245518 0.8835822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2853 2866 0.755026 0.704211 0.127232 -0.0453788 -0.2309686 -0.4989014 0.8340813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2854 2865 -0.741057 0.572582 0.562950 0.5277605 0.7225857 0.2931527 0.3367496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2854 3554 0.855139 0.599645 0.449116 0.5960105 0.4741023 0.6477220 0.0213262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2855 2824 0.417813 0.835255 -0.380813 0.6445323 -0.3869830 -0.4968838 0.4335075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2855 3555 -0.564220 0.542943 0.720406 0.4032465 0.0050952 -0.7433414 0.5336758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2856 2863 -0.003724 0.404272 0.888981 -0.0583735 -0.9643993 0.0890710 0.2420597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2856 3556 -0.215390 -0.936301 0.216775 -0.1469329 -0.8417514 0.1693955 0.4910911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2857 2822 -0.653022 -0.877843 -0.286900 -0.1290934 -0.0903984 0.8461738 0.5090706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2857 2862 0.432436 0.819731 0.211101 0.7142915 0.4538440 0.1510414 0.5108813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2857 3557 0.517396 -0.474805 0.652562 -0.3452778 0.3802372 0.1751872 0.8399478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2858 2861 0.323407 -0.661960 -0.092243 0.3281951 -0.0580221 -0.4294972 0.8393173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2858 3558 -0.404304 -0.499001 1.019375 0.6112886 0.1035793 0.7295697 0.2886617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2859 3559 -0.325099 -0.086295 0.960402 -0.2164067 -0.7478116 0.4939477 0.3872488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2860 2899 0.266141 -0.053344 1.138084 -0.4068209 0.3395318 -0.8444554 0.0781668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2860 3520 -0.366305 -0.857641 -0.125258 0.0166606 -0.1793496 -0.4751081 0.8612946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2861 2898 0.860615 -0.457240 -0.016538 0.5466986 0.3485528 -0.1367306 0.7489568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2861 3521 -0.100660 0.143087 1.046798 -0.6000812 -0.3125705 -0.3564508 0.6443175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2862 2897 0.740171 0.575153 -0.259474 0.5735705 -0.0222032 -0.8183249 0.0294658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2863 2896 0.521071 0.014049 -0.926955 0.5605134 -0.3096335 0.6130236 0.4627677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2863 3523 0.397794 -0.954210 0.080206 0.0646053 -0.3582321 0.8588858 0.3602931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2864 2895 0.971997 -0.338596 -0.146266 0.5618034 0.0731412 0.6647908 0.4869091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2864 3524 0.233544 0.213740 0.835225 -0.1271250 -0.2321556 0.0320619 0.9638024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2865 2894 0.295289 0.178454 -0.768996 -0.4194632 -0.7789604 -0.1106536 0.4527992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2865 3525 0.277719 1.100477 0.235018 -0.4127446 -0.7642094 -0.3701151 0.3296068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2866 3526 -0.781404 -0.306698 0.542079 0.3428421 0.2998267 -0.7077775 0.5400132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2867 2727 -0.623062 0.106475 -0.882417 0.7156088 0.1258844 0.6745861 0.1303483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2867 2892 -0.497429 0.584761 0.585185 -0.5392093 0.1983413 -0.5482710 0.6077113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2868 3528 0.365056 0.730270 0.489369 -0.3830909 0.2313192 -0.8032379 0.3931179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2869 2890 -0.324373 0.827522 -0.016853 0.2727675 -0.2483799 0.9287483 0.0364945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2869 3529 -0.744711 -0.694329 0.376400 0.4344861 -0.4724435 0.6519980 0.4036305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2870 2889 -0.986296 -0.475031 0.236978 -0.2495127 -0.1188651 0.5500351 0.7880837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2870 3530 0.474596 -0.242459 0.518889 0.4407523 -0.5557407 0.4246540 0.5626355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2871 2888 0.188608 1.031503 0.212882 -0.0635096 0.2740458 0.5904531 0.7564592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2871 3531 -0.341348 -0.280731 0.779134 -0.2360471 0.1504920 -0.3080353 0.9092570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2872 2732 -0.826610 -0.700099 -0.107598 -0.6141356 0.3149751 0.5502400 0.4699618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2872 2887 -0.361123 0.644823 0.190348 -0.4792104 0.2762328 0.7182535 0.4220957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2872 3532 0.689810 0.462869 0.136034 -0.3706433 0.1975115 0.1785282 0.8897980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2874 2885 -0.017293 0.863260 0.287661 -0.2356666 -0.7286057 -0.0033917 0.6431045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2874 3534 -0.750952 -0.124661 0.623964 0.4034547 0.4552826 -0.6256469 0.4883728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2875 2884 0.887907 -0.324990 -0.506718 0.1198269 0.9343407 -0.3292015 0.0653863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2875 3535 -0.338882 -0.908961 0.221647 -0.5734151 -0.7116809 0.3288833 0.2377839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2876 2736 0.074566 0.209109 -1.049452 0.4658468 -0.1937081 0.7858389 0.3576608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2876 2883 0.335854 -0.774874 -0.043825 0.5654660 -0.3079182 -0.2510214 0.7227883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2876 3536 -0.254019 -0.162330 0.870382 -0.2882484 -0.4771139 0.8208121 0.1246703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2877 2882 0.915517 0.311666 -0.246255 0.0624761 0.1773542 0.6368544 0.7477023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2877 3537 -0.104852 0.541027 0.960514 -0.0736124 0.2521492 0.8754447 0.4057076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2878 2841 0.977040 0.293150 -0.335941 -0.1744117 -0.3452002 0.1874305 0.9029326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2878 2881 -1.077615 -0.451481 0.382501 0.7144776 0.3508029 0.3468168 0.4961625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2880 2919 0.847792 -0.010476 -0.459850 0.2216566 0.2590313 -0.9083834 0.2420964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2880 3500 0.351832 0.451262 0.893830 0.0974999 0.5919687 0.7961751 0.0785631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2881 2918 -0.779087 0.420346 -0.643596 -0.4407360 0.7607758 0.0965516 0.4665295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2881 3501 0.114185 0.937581 0.121732 0.0087701 0.6843011 0.4417218 0.5801180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2882 2917 0.539670 -0.767977 0.110436 -0.7234615 -0.1244023 -0.6043009 0.3097546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2882 3502 0.275159 0.484993 0.716636 -0.2927312 -0.1957411 0.9159266 0.1925417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2883 2916 0.943682 -0.038516 0.101662 -0.0844153 0.4678503 0.3018081 0.8263789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2883 3503 0.063838 0.875359 0.691950 0.1935547 0.0414192 0.8384263 0.5078015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2884 3504 0.194044 -0.850466 0.601970 -0.2405456 0.1636716 -0.0846353 0.9529881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2885 2914 0.529381 0.771937 0.241660 0.5345474 -0.0856606 -0.5758862 0.6125981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2885 3505 0.593243 -0.481911 0.428347 0.3182625 0.5706676 -0.6823493 0.3277908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2886 2913 0.578458 -0.453320 0.813131 -0.2381493 -0.6589580 -0.6686146 0.2490258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2886 3506 0.561051 0.875149 -0.118757 -0.2573440 0.1455937 0.4638892 0.8350948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2887 2912 0.212443 -0.038785 1.182419 0.7924383 -0.1131677 -0.3528389 0.4844990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2887 3507 -0.154542 -0.874205 0.176739 0.1906649 0.5608225 -0.7987681 0.1053306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2888 2708 0.670625 -0.440128 -0.643600 0.0695042 0.1156867 0.8731997 0.4683033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2888 3508 -0.590163 0.281933 0.813518 0.3091360 -0.5379801 0.1789506 0.7635371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2889 2910 -0.631604 0.568733 0.624864 0.6022317 -0.2456454 0.4615207 0.6033025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2890 2909 0.624400 -0.535197 -0.443322 0.5572215 0.4566917 0.6362671 0.2758642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2890 3510 0.763640 0.607865 0.377039 -0.0342319 0.2980555 0.4781463 0.8254497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2891 2868 -0.475685 -0.339174 -0.769272 0.3526919 -0.7196901 -0.5601077 0.2096042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2891 3511 -0.847391 0.150328 0.560230 0.0008079 0.2428471 0.6321576 0.7357998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2892 2712 -0.664980 0.123478 -0.871342 -0.7753628 0.2846363 -0.3050328 0.4740778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2892 2907 -0.473039 -1.063505 0.057854 0.5214773 0.3851185 -0.5380614 0.5387346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2892 3512 0.763847 -0.475406 0.663987 0.4498806 0.2880577 0.7575216 0.3752216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2893 2866 0.167301 -0.363373 -0.920029 0.0689556 0.6699653 0.4575946 0.5805160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2893 3513 1.000730 -0.438519 0.401916 0.6987087 0.2282229 0.4791472 0.4797275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2894 3514 0.511416 0.754385 0.113011 -0.6637032 0.3229182 0.1808220 0.6500194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2895 2904 -0.323284 -0.557420 0.793158 -0.0550063 0.6430932 0.5830720 0.4933888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2895 3515 0.919933 0.054257 0.430926 -0.5692669 0.6132135 0.0744215 0.5425549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2896 2903 -0.732742 -0.707841 -0.139187 -0.2565968 -0.2116803 0.8709248 0.3617174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2896 3516 -0.051074 0.417394 0.795788 -0.6832183 0.0314502 -0.0713831 0.7260358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2897 3517 -0.159774 -0.751356 0.543709 -0.5292506 -0.4279825 0.7190173 0.1404952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2898 2901 0.501129 0.502238 0.555595 -0.0472972 -0.4659708 -0.0173412 0.8833648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2898 3518 -0.590730 0.704766 0.029302 -0.4982262 -0.4701678 0.7224454 0.0937312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2899 2719 -0.629267 -0.679820 -0.216158 0.4408936 0.6400846 0.5462043 0.3123545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2899 3519 0.688626 0.470030 0.204253 0.7525558 0.0433450 0.6478875 0.1096482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2900 2939 0.733257 -0.598279 0.418922 -0.2365323 0.8110791 0.3912610 0.3648533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2901 2938 0.884933 0.547982 -0.334518 -0.4936959 -0.2952982 0.8014338 0.1636066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2901 3481 -0.117611 0.518751 0.746292 -0.5058552 0.2833606 0.2571001 0.7731214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2902 2897 -0.084603 0.978830 0.575653 -0.3616641 -0.3387417 -0.2781917 0.8228381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2902 2937 -0.027347 -0.788222 -0.397295 0.1761864 -0.5552011 -0.4968391 0.6433203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2902 3482 -0.832475 -0.181399 0.413949 -0.0837846 0.3437409 0.8778141 0.3229005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2903 2936 -0.215779 0.828182 0.631857 -0.0286329 -0.7325214 0.1647944 0.6598753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2903 3483 -0.199490 -0.379326 0.925848 0.2718094 -0.3904578 0.8766833 0.0713360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2904 2935 -0.635091 0.675565 -0.385383 0.3807340 -0.3395436 0.4997330 0.7000134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2904 3484 -0.570826 -0.117037 0.649731 0.1183609 0.3215325 0.7918797 0.5055038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2905 2894 -0.807341 0.669224 -0.217608 0.1429634 0.0793389 0.9855497 0.0442570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2905 2934 0.678869 -0.563495 0.204546 0.2748766 0.2098083 0.5844283 0.7340756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2905 3485 -0.671429 -0.629850 0.744851 0.2494986 0.6401486 -0.7258572 0.0330382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2906 2893 -0.152447 0.623877 -0.588367 0.4901520 0.0660254 0.5769288 0.6500345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2906 2933 0.131713 -0.831745 0.467690 0.1765401 -0.0769412 -0.8020955 0.5652933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2906 3486 0.876247 0.626578 0.377994 -0.0614290 -0.1567090 -0.2388917 0.9563470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2907 2687 0.567888 -0.776301 -0.442404 -0.1048549 0.3237390 0.4706450 0.8140588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2907 2932 0.135991 -0.553009 0.772457 -0.4084187 -0.0283577 0.6106552 0.6778571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2907 3487 -0.385009 0.683199 0.342073 -0.5701408 0.7246303 0.1728658 0.3463637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2908 2931 0.909623 0.432017 -0.131938 -0.3788059 0.4289386 0.5176973 0.6360089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2908 3488 -0.007273 0.431902 0.822486 -0.1355536 0.2569372 0.2812548 0.9146060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2909 2930 -0.937167 -0.173355 0.406202 0.1108568 0.3723474 0.6571337 0.6459439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2909 3489 0.201360 0.080450 0.867378 0.2837163 -0.1784531 0.7120096 0.6170104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2910 3490 -0.077882 0.487078 0.853731 0.1787054 0.1448408 0.3887999 0.8921436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2911 2888 0.112367 -0.460753 0.905127 -0.5356080 0.4912993 0.4073133 0.5530325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2911 2928 -0.093622 0.484631 -0.685927 -0.4542537 0.1757737 0.1251645 0.8643443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2911 3491 -0.439689 0.848851 0.771764 -0.3216628 -0.1848854 0.1359263 0.9186264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2912 2927 -0.231148 0.702547 -0.478402 0.1946229 -0.4495736 0.8642183 0.1145960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2912 3492 0.542549 0.557493 0.682242 -0.7718501 0.2577118 0.4178036 0.4040696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2913 2926 0.074022 0.883707 -0.234983 -0.4230490 0.3295730 -0.1292670 0.8340871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2913 3493 -0.446473 0.444356 0.835153 0.6502346 -0.0048146 -0.7595474 0.0161073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2914 2694 -0.504843 -0.775193 -0.106333 0.0524314 -0.7801068 -0.4018406 0.4766639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2914 3494 0.494349 0.787250 0.069297 -0.9587096 -0.2822604 -0.0176129 0.0299112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2915 3495 -0.004356 0.731136 0.885681 0.3485802 0.4395699 0.7000912 0.4417493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2916 3496 -0.173356 0.611969 0.628151 -0.0205416 -0.1971447 -0.1786889 0.9637335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2917 2922 0.438849 0.894566 -0.100288 0.1455582 0.1925801 0.9380366 0.2486224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2917 3497 0.835056 -0.345388 0.416872 -0.0561943 -0.4699347 0.8792190 0.0545672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2918 2921 0.677640 0.652480 0.158062 -0.0751864 0.1459412 -0.6950037 0.7000128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2920 2959 -0.260840 -0.623141 0.745158 0.4476263 -0.2979115 -0.0654988 0.8405887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2920 3460 -0.874433 0.503848 0.152750 0.5823853 -0.0649099 -0.6078894 0.5358027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2921 2661 0.555538 0.871469 -0.144409 0.2340614 0.0286240 -0.9579508 0.1634814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2921 3461 -0.494511 -0.821251 0.296909 0.9390984 0.1456083 -0.1008580 0.2944828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2922 2957 0.180814 -0.919687 0.237269 -0.7028557 -0.0170123 0.0761159 0.7070437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2922 3462 -0.803506 0.253292 0.708468 -0.5381240 -0.2845584 -0.4705688 0.6387598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2923 2916 0.257731 0.289272 0.975879 0.7050002 -0.2899018 -0.2794277 0.5838252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2923 2956 -0.362053 -0.369717 -0.916863 0.7047132 0.0489806 -0.3506218 0.6148533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2923 3463 -0.661035 -0.375388 0.721051 0.7257709 -0.4477290 -0.4008500 0.3348352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2924 2915 0.399890 1.001128 0.144180 -0.1290212 -0.2012599 0.5134147 0.8241683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2924 2955 -0.514155 -0.699831 -0.185592 -0.5708825 0.5521185 0.5801047 0.1809334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2924 3464 -0.903920 0.128110 0.519509 -0.3928380 -0.6776674 0.0583367 0.6189039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2925 2914 -0.629955 1.031596 0.162070 -0.2602770 -0.6125679 -0.7375361 0.1142675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2925 2954 0.414187 -1.052723 -0.034583 -0.6285368 0.1174469 -0.5895072 0.4935879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2925 3465 0.004320 0.039177 0.866833 0.2950510 -0.5167727 -0.0740553 0.8002541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2926 2666 0.816682 0.600692 -0.241119 0.4282934 -0.6100494 0.6334171 0.2078155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2926 2953 -0.427049 1.053227 0.534763 0.2863913 -0.4433349 -0.7410959 0.4149833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2927 2952 -0.142081 0.117454 -0.996802 0.8781447 -0.2330022 -0.3981806 0.1265861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2927 3467 -0.331012 -1.061175 0.142136 0.7352419 -0.2467772 -0.4372272 0.4553600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2928 3468 -0.724559 0.066912 0.775076 -0.5966379 0.0146229 -0.4341893 0.6747511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2929 3469 0.331285 0.069059 1.015759 -0.5881798 0.1544251 0.1819324 0.7727211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2930 2670 0.264294 -0.243062 -1.026359 -0.2774009 -0.4091614 -0.8691809 0.0126550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2930 2949 -0.135580 1.057457 -0.375250 -0.4353112 0.5798765 0.5298257 0.4399229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2930 3470 -0.159568 0.245894 1.179448 0.2515517 -0.2576577 0.9281449 0.0942407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2931 2948 0.417737 -0.787124 0.339744 0.7594926 -0.3721971 -0.2738830 0.4578519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2931 3471 -0.654475 0.271402 0.828469 -0.1457925 0.1821337 0.8039422 0.5470364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2932 3472 0.447855 0.186250 0.999242 0.0404629 -0.6693273 -0.7139536 0.2015788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2933 2946 0.338746 0.615591 0.608692 -0.7843215 0.0179573 0.5270968 0.3266286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2933 3473 -0.778663 0.485924 0.014902 -0.3490129 -0.4652506 -0.7266476 0.3656709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2934 2945 -0.528638 -0.740195 0.640595 -0.4979702 0.1440387 0.8540241 0.0438334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2934 3474 -0.664910 0.763347 0.174126 -0.4360904 -0.4181427 -0.7321444 0.3145574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2935 2944 -0.068304 0.433488 -0.588797 -0.8824016 0.0979772 -0.2207514 0.4037781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2935 3475 0.427746 0.814591 0.565720 0.1594735 0.0223920 0.7188730 0.6762311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2936 2943 0.489466 0.727825 -0.198701 -0.1211386 0.1225840 0.3814622 0.9081769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2936 3476 0.809951 -0.656092 0.294482 0.5457605 -0.0135604 0.7744671 0.3196284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2937 2942 0.593946 -0.738759 -0.287362 0.6183134 0.0259911 0.2497711 0.7447331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2937 3477 0.704357 -0.136542 0.880941 0.1444898 0.5201721 -0.3201612 0.7784861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2938 2941 -0.018602 -0.350216 -1.099238 0.5030709 -0.2766924 -0.0988195 0.8127704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2939 3479 -0.474046 0.484333 0.648660 -0.7837291 -0.0040405 0.3776815 0.4930609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2940 2640 -0.541659 0.802370 -0.325631 0.7795049 -0.2348044 0.2905256 0.5028258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2940 3440 0.647119 -0.725679 0.359999 0.6477095 0.1940104 0.4874664 0.5524572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2941 2978 -0.271358 -0.957099 -0.188141 0.5981709 -0.0802296 -0.1420599 0.7845851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2941 3441 0.510567 -0.157337 0.792598 0.3904125 -0.2039581 -0.1000602 0.8921699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2942 2642 -0.861735 -0.563003 -0.293793 0.6378349 0.5820709 0.1865905 0.4685553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2942 2977 0.251436 -0.777030 0.714066 -0.0079532 0.3226451 -0.9415152 0.0968810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2943 2976 0.975689 -0.047462 0.118075 0.9306662 -0.2675247 0.0358519 0.2469931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2943 3443 -0.031591 -1.048203 0.080656 0.5911050 -0.2449073 0.6249714 0.4472428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2944 2975 -0.654756 0.351942 0.705929 0.6082333 0.2902431 0.6886675 0.2674850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2944 3444 0.276639 -0.818685 0.345710 0.2621813 -0.6906209 0.5807570 0.3420892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2945 2974 -0.435535 0.653672 0.439188 0.2635125 -0.2525834 0.5815713 0.7270059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2945 3445 0.239917 -0.673774 1.115513 0.5617970 -0.1285958 0.6928347 0.4333905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2946 2973 0.230651 -1.040106 -0.028268 -0.1926816 -0.7338468 0.6512950 0.0125530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2946 3446 -0.472039 -0.140449 1.059884 0.4924069 -0.0788027 -0.1039812 0.8605309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2947 2972 -0.664836 -0.426453 -0.348394 -0.1759497 -0.1106312 0.9628570 0.1723626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2947 3447 0.351091 -0.837674 0.281224 0.0181966 0.2864417 -0.5977592 0.7485346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2948 2971 0.740925 0.703531 -0.195212 -0.5733960 -0.6235038 -0.1600628 0.5067937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2948 3448 -0.719522 0.640376 -0.035396 0.1650423 -0.3584258 -0.1619761 0.9044643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2949 2970 0.339735 -0.063208 0.838674 -0.6261605 0.1921022 0.1396592 0.7426406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2949 3449 -0.633732 0.495484 0.112974 0.7281042 0.2322727 -0.5547687 0.3288547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2950 2929 1.003062 -0.108027 0.396320 -0.0945432 -0.2599611 -0.8724027 0.4029829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2950 2969 -0.890222 0.120724 -0.366180 -0.0802895 -0.2766636 -0.8841363 0.3678504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2950 3450 -0.321315 0.493565 0.928086 -0.0161258 -0.3066773 0.3718193 0.8760362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2951 2928 0.581966 0.595467 0.641969 0.1614248 -0.3821092 0.8811794 0.2268424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2951 2968 -0.567869 -0.504722 -0.554233 -0.8746402 0.1692208 -0.4010427 0.2133858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2952 2967 0.667831 -0.342177 0.485435 -0.6831266 0.6039957 0.4009419 0.0881641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2952 3452 0.234312 0.876370 0.108531 -0.8758189 0.1555665 0.3116572 0.3340809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2953 2966 -0.692701 0.095633 0.757294 0.1536002 0.4289354 -0.5633092 0.6892780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2954 2965 0.661443 0.711628 -0.005250 0.4050442 0.1905012 0.1422799 0.8828391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2954 3454 0.566299 -0.707010 0.051322 0.6088731 -0.2583208 0.7078275 0.2480405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2955 2964 0.837692 0.619548 -0.387689 0.4348954 -0.7538392 -0.4205215 0.2564254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2955 3455 -0.209102 0.792352 0.315067 0.3542945 0.3825808 0.8532852 0.0034191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2956 2963 0.313062 -0.668895 0.798935 -0.2462126 0.1545374 -0.7626043 0.5778687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2956 3456 -0.679013 0.303609 0.653338 0.1656860 0.3105413 0.1882064 0.9168918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2957 2962 -0.156713 -0.358515 -0.993794 0.4861477 -0.4496726 -0.1640278 0.7311292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2957 3457 -0.771802 -0.552519 0.540827 -0.0946135 0.0758129 -0.8510372 0.5109172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2958 2658 -0.813951 -0.351162 -0.522333 0.2997280 0.7022989 0.4119028 0.4972681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2958 2921 -0.031504 0.772181 -0.477773 -0.2632387 0.0786995 0.8767595 0.3947209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2958 2961 -0.034994 -0.745754 0.399808 0.1816155 -0.0178827 0.8475051 0.4984287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2958 3458 0.619447 0.425576 0.593085 -0.0974385 -0.1020797 -0.9470701 0.2883465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2960 2999 0.161867 0.172865 -0.696024 -0.5119332 -0.1181022 0.5303269 0.6653794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2960 3420 -0.496915 0.923857 0.305981 -0.5211667 -0.1162534 -0.4877923 0.6906005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2961 2998 -0.589035 0.681902 0.621977 -0.2060686 0.7454172 -0.6066272 0.1840985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2961 3421 -0.064081 -0.782599 0.513319 0.1512268 0.3486458 -0.4780902 0.7918373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2962 2997 -0.294511 -0.820059 0.208983 0.5658271 0.3247721 -0.0190360 0.7576281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2963 2996 0.906921 0.164362 0.507290 0.8213699 -0.3348812 -0.3844566 0.2557326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2964 2995 -0.885447 -0.589627 0.011046 -0.6269967 -0.2073375 0.4791375 0.5781985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2964 3424 -0.828705 0.671857 0.473320 -0.8137379 -0.0139010 0.0462489 0.5792222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2965 2994 1.011765 0.307475 -0.069455 -0.4867382 -0.2562399 0.5177799 0.6552335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2965 3425 0.177604 -0.480724 0.716060 -0.1042399 0.2157793 -0.0616403 0.9689034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2966 2993 -0.524111 -0.707954 0.033987 -0.0907277 -0.3834372 -0.8495625 0.3506965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2966 3426 -0.404180 0.855281 0.507391 -0.5481129 -0.0778060 -0.5351985 0.6380290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2967 2992 -0.036380 -0.181083 -0.857419 -0.3432862 -0.0947367 -0.0640205 0.9322451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2967 3427 -0.946609 -0.450829 0.470021 -0.6257434 -0.3763986 0.5912277 0.3423726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2968 3428 0.848875 0.678574 0.119211 -0.0984300 0.4575431 0.3463980 0.8130032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2970 2989 -0.137896 -1.042884 0.000213 -0.6354401 -0.5301115 0.2578458 0.4987115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2970 3430 -0.915453 0.161160 0.300899 -0.0834260 -0.8114763 -0.3933721 0.4240339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2971 2988 0.314710 0.820682 0.286221 -0.3231536 -0.3501479 0.8671189 0.1451651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2972 2987 0.350726 0.905272 0.096187 -0.4142780 0.8156606 0.2270507 0.3339453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2972 3432 -0.821898 0.536415 0.090067 -0.5048597 -0.4622615 0.0736258 0.7252656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2973 2986 -0.258220 0.044987 0.805932 0.2203548 0.4564394 -0.2533266 0.8239736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2974 2985 0.798844 0.571041 -0.225746 -0.2738098 0.3849196 0.8780833 0.0763858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2974 3434 0.348091 -0.196549 0.843583 -0.5068061 -0.1513845 -0.8324150 0.1652741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2975 2635 0.497966 -0.928229 -0.157557 -0.5277486 0.5582285 0.1442870 0.6237337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2975 2984 0.758220 0.589117 -0.518581 -0.5969595 0.3510722 0.2978172 0.6570332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2975 3435 -0.394508 0.951640 0.178325 -0.1150325 0.7337952 0.6310812 0.2237156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2976 2983 0.759515 -0.329825 -0.343214 -0.3169085 0.5614664 0.6810987 0.3470289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2976 3436 0.613882 0.808389 0.453188 -0.5038832 -0.2368471 0.2806248 0.7818279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2977 2982 0.052790 0.131821 0.843602 -0.4177933 0.5073397 0.7514522 0.0580931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2977 3437 -0.831191 -0.322920 -0.104421 0.2996591 -0.8304866 0.3902591 0.2611404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2978 2981 0.162941 -0.245452 1.024290 -0.1836591 0.2644027 -0.8992019 0.2963048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2978 3438 0.524533 0.933151 0.250061 -0.6633020 0.0667552 -0.7403912 0.0859945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2979 2940 0.572730 0.368629 0.423115 -0.2649047 -0.0761584 -0.9249904 0.2615688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2979 3439 -0.616873 0.498824 0.435207 0.0004162 0.2771112 0.0300256 0.9603685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2980 3019 -0.224557 -0.504903 -0.885617 0.8532929 0.0168620 -0.0433783 0.5193508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2980 3400 0.194038 -0.892338 0.389373 -0.3288247 0.9058015 -0.2606099 0.0589955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2981 3018 0.243710 -0.399332 0.980957 -0.1217832 -0.7943660 -0.3428947 0.4863894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2981 3401 -0.703674 -0.617106 0.120016 -0.0292781 -0.2364252 0.3114893 0.9199023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2982 3017 -0.899151 0.605490 0.301331 0.0240565 0.6480637 0.6865766 0.3287055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2982 3402 0.558609 0.889517 0.159401 -0.4698596 0.3228450 0.5806721 0.5812254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2983 3016 -0.263526 -0.961369 -0.723101 -0.4450024 0.0250588 0.8547585 0.2659563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2983 3403 -0.525482 -0.227593 0.636906 -0.0506878 -0.4158966 -0.9060641 0.0592333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2984 3015 0.902368 -0.309850 0.466583 -0.7583677 -0.2090174 -0.0776638 0.6125018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2984 3404 -0.142414 0.238676 0.885321 -0.6101374 0.3134822 0.6126350 0.3926061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2985 3014 -0.879152 -0.669073 0.100730 0.3547040 -0.2370775 -0.7330365 0.5297517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2986 3406 0.143335 -0.810941 0.722973 0.3975712 0.5648560 -0.6797013 0.2467407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2987 3012 -0.744770 -0.209892 0.730986 -0.5499380 -0.0592822 0.8212394 0.1400701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2988 3011 0.126822 -0.560755 -0.614025 0.4274375 -0.6428454 0.0041145 0.6356336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2989 3010 -0.955093 -0.170899 -0.127487 -0.2558254 0.2611059 0.1760062 0.9140016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2989 3409 -0.126387 -0.614944 0.533482 0.6605377 -0.3621418 0.4340085 0.4941456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2990 2969 -0.280930 -0.477156 0.660219 -0.4790001 0.2371252 0.8023902 0.2655193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2990 3009 0.250783 0.511866 -0.484764 -0.3023824 0.3058458 0.1729134 0.8860723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2990 3410 -0.885725 0.567281 0.347332 0.2942649 0.1995925 -0.9282327 0.1093393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2991 2968 -0.367626 -0.994325 0.083804 0.2403069 -0.7107939 -0.1698918 0.6388751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2991 3008 0.347696 0.959437 0.001315 -0.2827867 0.3603331 -0.5831049 0.6709548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2991 3411 -0.061882 0.061774 0.988161 0.0995923 -0.4048463 -0.2943932 0.8599497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2992 3007 -0.274988 0.388262 -0.837422 0.8043919 -0.1063389 -0.4787663 0.3353037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2993 2613 -0.202430 0.272807 -0.917734 0.0415298 0.5750923 0.7027359 0.4167809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2993 3413 0.108917 -0.408087 0.863918 0.7393490 -0.1519207 0.5372478 0.3763615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2994 3005 0.514860 -0.361062 -0.774868 0.8361549 -0.3693799 0.2630555 0.3085535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2994 3414 -0.638127 -0.673757 -0.000964 0.6679489 -0.1376458 -0.1192017 0.7215878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2995 3004 -0.669255 0.515917 0.481558 -0.3325244 0.3188157 -0.3720871 0.8058135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2995 3415 0.196424 -0.624712 0.974015 0.7303233 0.3480869 -0.4249730 0.4060313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2996 3003 -0.043647 -0.028419 -0.864639 -0.2095288 0.8635654 -0.1706001 0.4257323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2996 3416 0.728829 0.795216 0.090997 0.5800890 0.7549820 0.3056156 0.0099011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2997 3002 -0.709060 -0.282031 0.512793 -0.6900252 0.6099144 0.3852103 0.0590137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2997 3417 -0.354260 0.987830 0.002296 -0.2552320 -0.4614616 -0.8301412 0.1810399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2998 3001 0.082117 -0.374834 -0.845610 -0.3336405 0.0959674 -0.7780682 0.5235306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3000 2580 0.485543 0.692582 -0.159704 -0.5723645 -0.5721653 0.5028311 0.3036225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3000 3039 0.459348 0.033736 1.030189 0.5392560 -0.5982695 0.5553683 0.2069844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3000 3380 -0.565614 -0.724172 0.356477 -0.3890576 -0.5205545 0.7582111 0.0526600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3001 3381 0.816737 0.520979 0.493705 -0.7672553 0.1674875 0.0583554 0.6163294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3002 3037 -0.179819 0.917402 -0.177728 -0.3105416 -0.1083763 -0.1644083 0.9299400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3002 3382 -0.784950 0.069759 0.672416 0.4498456 -0.6927177 0.1110548 0.5526734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3003 3036 0.540805 0.412948 0.553564 0.4160031 -0.2687053 -0.8573676 0.1402132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3003 3383 -0.789892 0.501571 0.283194 -0.4560601 -0.1836607 0.3478797 0.7982842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3004 3384 0.175864 -0.746376 0.476574 0.2602280 0.3935936 -0.1968978 0.8594165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3006 2993 -0.174339 0.844675 0.309422 -0.2835722 0.3798703 -0.3006422 0.8275867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3006 3033 0.382271 -0.838864 -0.460313 0.3176308 -0.7663870 0.5288386 0.1791407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3006 3386 0.686996 -0.205281 0.707982 -0.6640970 0.2331081 -0.6628032 0.2555928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3007 3032 0.398622 -0.688588 0.458774 -0.3342844 -0.4287236 0.6819682 0.4892539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3007 3387 -0.096071 0.414704 0.886882 0.3201092 -0.2687862 -0.8033227 0.4242131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3008 3031 -0.797571 0.437098 0.132681 -0.0329879 -0.2769938 0.8047150 0.5240421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3009 2589 0.513347 -0.868987 -0.244099 -0.4044984 -0.0962752 0.0726655 0.9065494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3009 3030 0.920042 0.560663 0.106128 -0.2879254 -0.6138263 -0.0510050 0.7332903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3009 3389 -0.644727 0.695279 0.312732 -0.4541759 -0.5752577 0.5169249 0.4422572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3010 2590 0.712489 0.980561 -0.142984 -0.5210750 -0.5750697 0.4156474 0.4743554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3010 3029 -0.600910 0.122630 -0.676274 0.1080902 0.3988692 -0.7568669 0.5063322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3011 3028 -0.002840 -0.706053 0.282839 -0.3854476 0.2288203 -0.4908426 0.7470910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3011 3391 0.302367 0.485007 0.854946 -0.6549728 0.0602034 -0.0894579 0.7479194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3012 3027 -0.194403 0.205134 1.029484 -0.1422310 -0.7510883 0.4438712 0.4675628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3012 3392 0.219676 -1.002055 0.282812 0.8404846 0.3379814 -0.4162762 0.0778995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3013 2986 -0.912850 0.153782 0.090130 0.0665003 -0.5162884 0.8466046 0.1108363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3013 3026 0.957972 -0.118855 -0.245869 0.1472553 -0.1645304 -0.4912151 0.8425873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3014 3025 0.759126 -0.181484 0.383269 0.5831711 0.3028351 -0.4722988 0.5874830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3015 3024 0.957106 -0.117147 -0.530486 0.2057989 0.2620689 -0.5555755 0.7617759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3016 3396 -0.588828 0.415113 0.868979 -0.1284788 -0.5819795 0.6858521 0.4176123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3017 2597 0.049767 0.175907 -1.046783 -0.3806777 -0.0147403 -0.6988303 0.6053953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3017 3022 0.714359 0.789089 0.168653 -0.1512455 0.1738644 0.4435066 0.8661396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3017 3397 -0.182962 -0.201450 1.069284 -0.3351694 0.0369981 0.8767536 0.3429224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3018 3021 0.367149 0.471941 -0.803507 0.6849411 -0.6505880 0.2158416 0.2469886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3018 3398 0.559507 -0.691571 -0.088092 0.0225335 0.4064741 -0.4681591 0.7842819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3019 2599 -0.240328 -0.813868 -0.624859 -0.4322134 0.6759370 0.2524465 0.5408988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3019 3399 0.206357 0.825458 0.494297 -0.2290369 -0.4825362 -0.5724001 0.6221407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3020 3059 0.462776 -0.818273 -0.491244 -0.5420847 -0.1526503 -0.7807040 0.2708198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3020 3360 0.731609 0.150410 0.601962 -0.3099163 -0.2580494 -0.9126168 0.0670292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3021 3361 0.703216 -0.657863 0.481021 0.0856856 0.4056244 -0.5449239 0.7288242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3022 3057 0.836077 -0.044468 0.734411 0.3932020 -0.6236638 -0.1104992 0.6665024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3022 3362 -0.534775 -0.094656 1.014151 -0.5292706 -0.3054143 0.1526387 0.7767214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3023 3016 0.234600 0.186716 0.901007 -0.5977469 0.2501750 0.0743054 0.7580171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3023 3363 -0.453337 0.983695 0.019885 0.1595707 -0.6896669 -0.0382280 0.7052910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3024 3055 0.245693 0.807326 -0.223310 -0.3526838 0.5219428 0.2851599 0.7224082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3025 3365 -0.375053 -0.264982 0.727995 -0.3988027 0.1144205 0.0121979 0.9097888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3026 3366 0.375207 0.174359 0.764356 -0.0707279 -0.1167299 -0.9144214 0.3810580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3027 3052 0.740490 -0.743432 0.082803 0.5205895 0.4592752 -0.4647978 0.5495597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3027 3367 -0.819369 -0.568300 0.324831 0.5612739 -0.6691273 -0.0054188 0.4870430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3028 3368 -0.148661 -0.218806 0.760332 -0.1650494 0.2636406 0.7679567 0.5599060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3029 2569 -0.813585 0.335169 -0.604204 0.2246119 0.5449252 0.1994133 0.7828412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3029 3369 0.724583 -0.398138 0.609624 -0.0409213 0.5655999 -0.5853830 0.5794385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3030 3049 0.381839 0.867344 -0.239285 0.3893432 -0.4627461 0.6390444 0.4752896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3032 3047 -0.974308 -0.285240 0.064036 0.0175999 -0.3018054 0.6312970 0.7141904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3032 3372 0.457035 -0.914848 0.448666 0.8899452 0.0970234 -0.1331710 0.4252639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3033 3373 -0.128689 -0.955154 0.121219 -0.2411045 -0.7382978 0.2236321 0.5888749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3034 3005 -0.444172 -0.234147 -0.730685 -0.1125832 0.0736456 0.5634503 0.8151227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3034 3045 0.409915 0.195970 0.912969 -0.0788131 -0.3207292 0.8078017 0.4882394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3034 3374 -0.969237 0.384618 0.173650 -0.3484694 -0.5796005 -0.3196320 0.6636775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3035 3004 0.392860 -0.276869 0.891741 -0.0768366 -0.2572279 -0.5023421 0.8219382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3035 3044 -0.403664 0.368663 -0.705146 -0.3311079 -0.7692681 0.5398417 0.0846466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3036 3043 -1.028219 -0.009502 -0.163475 0.6191533 -0.1262793 -0.6965635 0.3398560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3036 3376 -0.053931 -0.429934 1.075582 0.2991906 0.6561546 -0.5316109 0.4442250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3037 3042 -0.264620 0.641476 0.250305 0.2532763 -0.5584553 0.6277773 0.4794523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3037 3377 -0.579037 -0.639608 0.647075 0.4291908 0.0143202 -0.3878924 0.8155548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3038 3001 0.432297 -0.741569 -0.118112 0.3755951 -0.6375016 0.5105095 0.4380640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3038 3041 -0.528165 0.791631 -0.015780 -0.2300333 -0.6587692 0.5612356 0.4451095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3039 3379 0.703724 0.450495 0.474036 -0.2499052 -0.2345118 -0.4423055 0.8288048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3040 3079 -0.515178 0.755505 -0.228332 0.4603881 -0.5460032 -0.5740028 0.4005547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3040 3340 -0.593675 -0.022879 0.809933 -0.3758596 0.0024006 -0.8645819 0.3334995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3042 3342 0.541927 0.083935 0.607232 0.3450831 -0.0756238 0.4674602 0.8103577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3044 2544 -0.255559 0.763283 -0.747905 0.3437363 -0.6548283 0.1791448 0.6488084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3044 3075 0.822936 0.423127 0.124850 0.6767876 0.2511299 -0.2663017 0.6387297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3044 3344 0.155690 -0.653522 0.529627 0.8556733 0.1045524 0.3436939 0.3725137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3045 3345 0.851406 0.287491 0.491082 -0.3815668 0.4163065 -0.7162019 0.4100617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3046 2546 -0.486619 0.749121 -0.593239 0.9487527 0.0463724 0.0415600 0.3098235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3047 3347 -0.586341 -0.894150 0.442429 0.6253049 0.1245717 0.3018696 0.7087668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3048 3031 -0.304784 0.333227 0.827017 0.3892733 0.4639919 -0.6173635 0.5020359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3048 3071 0.341615 -0.581208 -0.801261 -0.0676272 0.3545125 -0.3670620 0.8573290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3048 3348 0.250699 -0.693019 0.610483 0.0477370 -0.5180446 0.8397424 0.1555109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3049 2549 -0.897541 0.695385 -0.096861 -0.2852590 0.2800864 -0.1701001 0.9006913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3049 3070 -0.063553 -0.464850 -0.755442 0.1473433 0.9226649 -0.2914118 0.2050820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3049 3349 0.787866 -0.517911 -0.049908 -0.0882781 0.1151980 -0.9892379 0.0185687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3050 3029 -0.201099 -0.505937 -0.597011 0.7242248 -0.4324578 0.4350424 0.3149869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3050 3069 0.077634 0.703093 0.634976 -0.0081986 -0.1484979 -0.5733771 0.8056798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3050 3350 0.576151 -0.493287 0.649381 0.0990341 -0.4183516 0.2404920 0.8702516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3051 3068 0.951146 -0.082411 -0.104722 0.0865461 0.3077823 0.4167080 0.8509608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3051 3351 -0.022209 -1.035011 0.162653 -0.1603099 0.7560258 -0.6119738 0.1679693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3052 3067 0.223798 0.560239 0.762068 0.7524834 -0.4906834 0.3466431 0.2698834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3053 3026 0.043681 0.309115 0.908983 -0.0924935 0.2977643 -0.6510595 0.6920281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3053 3066 0.075143 -0.341995 -1.008028 -0.2174224 0.7058154 0.1397632 0.6595592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3053 3353 0.720131 -0.542314 0.335585 0.0341571 -0.1413374 -0.9623657 0.2295851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3054 3065 0.004359 0.676246 -0.671135 -0.1218282 -0.1829092 0.0920839 0.9711965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3054 3354 -0.931197 0.543490 0.440037 -0.4076372 -0.5529914 0.3177154 0.6535207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3055 3064 0.192170 -0.132899 1.011887 0.7069386 -0.0229332 0.5550846 0.4377134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3055 3355 -0.512760 -0.689021 0.172358 0.7018972 -0.5906282 -0.1870443 0.3514442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3056 3023 -0.900624 -0.313356 -0.171032 0.7032151 -0.2115960 -0.6288848 0.2553814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3056 3063 0.814041 0.263635 0.186675 -0.2285572 -0.3061157 0.6830315 0.6225132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3056 3356 -0.248259 -0.606883 0.848288 -0.3029956 -0.0115298 0.5551919 0.7744822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3057 3062 0.492984 -0.060447 -0.603217 -0.2331866 0.6991871 0.2675808 0.6206141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3057 3357 0.708783 0.333012 0.495925 0.4101520 0.6981523 0.4253192 0.4043047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3058 3061 0.605583 0.738453 -0.149281 0.1511440 -0.1294370 -0.3946306 0.8970330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3058 3358 -0.850506 0.520699 0.420377 0.4673695 0.1511584 -0.8710436 0.0001388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3059 3359 0.241083 0.120505 1.016196 0.6082761 0.1462426 0.5669627 0.5358793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3060 3320 -0.201594 -0.407651 0.901989 0.1564932 -0.5945736 0.4947632 0.6141674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3061 3098 -0.358748 0.795217 -0.312689 -0.1745356 -0.0435586 0.8331008 0.5230517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3061 3321 -0.628205 0.092561 0.585667 -0.5412645 -0.6593257 -0.0127215 0.5216901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3062 3097 0.530495 -0.521777 0.519280 -0.2197319 0.3098913 -0.8795227 0.2865748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3062 3322 -0.536404 0.066111 0.941035 0.1925915 0.0102601 -0.5542203 0.8097179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3063 3096 0.148705 -0.785125 -0.466278 -0.5468281 -0.5264850 0.6018464 0.2481402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3063 3323 -0.526247 -0.577373 0.847065 0.1350661 -0.2484660 -0.9226738 0.2620971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3064 3095 0.931603 0.531919 0.055797 -0.9679539 -0.1573721 0.1621632 0.1095551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3065 3094 0.240248 0.825700 -0.413270 -0.3011942 -0.2270173 -0.3792169 0.8449496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3065 3325 -0.522177 0.464260 0.491654 -0.1454886 -0.0573387 0.9859091 0.0594013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3066 3093 1.056435 -0.162970 0.054513 0.6052741 0.4363748 -0.1394304 0.6509835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3066 3326 -0.290109 -0.841969 0.220605 0.2697393 0.5249455 0.0590076 0.8051031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3067 3092 0.391192 -0.097664 -0.984022 -0.0686175 -0.6204001 -0.6026549 0.4971946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3067 3327 0.683969 0.562030 0.132149 -0.8787115 -0.3205804 -0.2189229 0.2777895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3068 3091 0.586518 -0.744847 0.355490 0.4778740 -0.4731200 -0.6488919 0.3559960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3070 3089 0.497692 -0.146498 0.859639 0.4846403 0.0638543 -0.5840443 0.6480268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3070 3330 -0.685334 -0.158156 0.430734 0.2784488 0.6632822 -0.6871150 0.1019609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3071 2531 -0.333360 0.479108 -0.877286 0.7083019 -0.0444928 0.2393029 0.6626182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3071 3088 0.916573 0.120820 -0.287141 0.6483317 0.4384587 0.0524994 0.6202127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3071 3331 0.327980 -0.521244 0.852259 0.2314898 -0.0649167 -0.1018998 0.9653055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3072 3047 -0.710656 -0.090035 -0.685391 0.1851445 0.1190018 -0.6742537 0.7049412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3072 3087 0.730010 -0.030027 0.929817 0.1549397 -0.2223247 0.8344248 0.4798966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3072 3332 -0.747923 0.185378 0.573167 0.5783230 0.0472797 -0.7281879 0.3647596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3073 3046 0.144840 0.583165 -1.038383 -0.3366048 -0.5403811 -0.6660644 0.3886434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3073 3086 -0.128350 -0.608789 0.884515 -0.0693163 0.8112909 0.5788610 0.0438438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3073 3333 -0.719768 0.475548 0.063247 -0.7131645 -0.2152025 -0.3933322 0.5388637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3074 3045 -1.099300 -0.099177 0.344004 0.1678440 0.3383357 0.5432298 0.7498392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3074 3085 0.910716 -0.087265 -0.200932 -0.8128456 0.4846668 0.2413175 0.2148159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3074 3334 0.313930 1.033377 0.253643 -0.1792569 -0.0321801 0.3348838 0.9244914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3075 3084 0.386198 0.723856 -0.494561 -0.5906075 0.3041422 -0.6511388 0.3670131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3076 3043 0.933768 0.095857 -0.148998 0.2111425 -0.4986073 -0.4086125 0.7347418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3076 3083 -0.993867 -0.420915 -0.098025 -0.4845310 0.0142921 -0.6929134 0.5337570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3076 3336 -0.160926 0.704727 0.373796 -0.4155305 -0.6864221 -0.5203209 0.2922762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3077 2537 0.736952 0.157053 -0.585366 0.2243093 0.7137308 -0.6481662 0.1419657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3077 3082 0.562469 -0.371784 0.741890 -0.8339052 -0.2689273 0.2580450 0.4070540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3077 3337 -0.673333 -0.429169 0.573054 0.5042137 0.2933237 -0.5512668 0.5965188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3078 3041 0.062843 -0.513442 -0.674955 0.0719281 -0.5107403 0.1591377 0.8418111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3078 3081 0.107059 0.462923 0.750288 -0.2736395 -0.7354383 0.2159600 0.5810450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3078 3338 -0.366302 -0.727902 0.489298 -0.0670445 0.1135390 -0.5163790 0.8461481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3079 3339 0.406986 0.600016 0.761483 -0.3285447 0.0594958 -0.0625006 0.9405383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3080 3119 0.481698 -0.773941 0.611296 -0.4627753 0.7948665 -0.3728517 0.1225069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3081 3301 0.001475 -0.874213 0.239475 0.1052174 0.0635685 -0.9578626 0.2595913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3082 3117 0.187830 -0.198075 -1.031849 0.1804707 0.9613336 -0.2079950 0.0024593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3082 3302 -0.924296 -0.469402 -0.039460 0.7250041 -0.2040911 0.1395144 0.6428465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3083 3116 0.362396 -0.614473 -0.909672 0.1108051 -0.0942670 0.5737525 0.8060050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3083 3303 -0.426106 -0.778126 0.680514 -0.0636529 0.5925424 -0.6648447 0.4503590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3084 3115 -0.923138 0.116317 0.394575 0.6170481 0.4383298 0.0187256 0.6532748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3084 3304 -0.080830 -0.918220 -0.103034 0.2831849 -0.0639565 -0.1267931 0.9484932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3085 3114 0.518197 -0.911063 -0.133386 0.3660485 -0.1379926 -0.5981985 0.6993747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3086 3113 0.182938 0.762589 -0.758363 -0.6036060 -0.4645355 -0.3814992 0.5237603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3087 2507 -0.841944 -0.415282 -0.348969 -0.4128017 0.0055466 -0.6212004 0.6660887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3087 3112 0.375655 -0.817736 0.647083 -0.6349190 0.4477025 0.1469426 0.6122485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3087 3307 0.718443 0.283244 0.077857 -0.1305604 0.7836581 -0.2613129 0.5482240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3088 3111 0.916550 0.270124 0.528106 -0.0287134 -0.5269256 -0.4001308 0.7492798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3089 3309 -0.510573 -0.298005 0.659770 -0.2790360 0.3371789 -0.8557752 0.2758588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3090 3069 -0.952840 0.277714 0.159219 0.5541115 0.7333259 0.2689189 0.2878823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3090 3310 0.123379 1.030143 0.196742 -0.3219140 0.6681610 -0.2689056 0.6145096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3091 3108 0.197498 0.573043 -0.835879 0.5245249 0.6358511 0.5508188 0.1310177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3091 3311 0.847240 0.300648 0.496209 0.3732753 -0.3145855 0.8699368 0.0700819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3092 3107 -0.947232 -0.601246 -0.418846 0.1098660 -0.3167961 -0.9344691 0.1197379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3092 3312 -0.691628 0.962784 0.337507 0.1204879 0.7393029 0.5046138 0.4292772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3093 3106 0.587208 0.594799 0.508155 0.2703817 -0.7237509 0.3384415 0.5371552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3093 3313 -0.606965 -0.314847 0.740969 -0.4284096 0.4894712 0.7161832 0.2529126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3094 2514 0.035744 0.239871 -0.883192 -0.3266422 0.1762696 -0.6284057 0.6836229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3094 3105 -0.506071 0.721979 0.087531 0.3398594 0.4246967 -0.1360719 0.8280173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3095 3315 -0.110932 -0.934738 0.106265 0.2531418 -0.1001894 -0.9616150 0.0343207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3096 3103 -0.464981 0.765631 0.300143 -0.4921314 -0.5929248 0.5434640 0.3330072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3097 2517 -0.506164 0.745646 -0.209232 0.3119272 -0.5771490 0.3974117 0.6416108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3098 3101 1.060560 0.165636 -0.085904 -0.5533814 0.5215774 -0.0678631 0.6458488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3098 3318 0.170174 0.619134 0.834112 -0.2166262 -0.2617247 0.9354897 0.0971194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3099 3060 -0.504918 0.813882 -0.154157 0.0788072 0.3186333 0.8925221 0.3093000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3100 2480 -0.473441 1.006911 -0.217378 0.1661651 -0.8650142 0.4446755 0.1624907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3100 3139 -0.700550 -0.200030 0.444680 0.2446268 -0.0521010 0.5147845 0.8200245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3100 3280 0.206978 -0.873164 0.309874 0.3828638 0.0576339 -0.6095294 0.6917858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3101 3138 0.599563 -0.168619 0.652118 0.4484420 -0.6653647 -0.4050637 0.4383070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3101 3281 -0.775786 -0.611033 0.252736 -0.7850583 -0.5358216 0.3107486 0.0037427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3102 3137 0.679703 -0.685899 0.126464 -0.1014362 0.1781003 0.6310303 0.7481923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3102 3282 -0.009293 0.284457 1.045119 0.3381418 -0.3367570 0.8486572 0.2281133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3103 3136 0.709979 -0.369455 0.306791 -0.0281591 0.2547052 -0.8734258 0.4140770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3104 3135 0.670605 -0.485841 -0.591887 0.2414935 -0.6356456 0.6919221 0.2426507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3104 3284 -0.035970 -0.784303 0.502453 0.0444257 0.4012494 -0.8862338 0.2271890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3105 3134 -0.462668 0.228118 -0.760871 -0.1889676 -0.1174968 0.8854562 0.4079866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3105 3285 -0.705428 0.137383 0.500440 -0.2360844 -0.5111865 -0.6598023 0.4976078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3106 3133 0.401875 -0.115653 -0.915769 -0.1732851 0.6909258 -0.3699002 0.5964626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3106 3286 0.850654 0.260087 0.383346 -0.4924458 0.4063287 0.1487047 0.7551696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3107 3132 0.927213 -0.098171 -0.411765 -0.4537788 0.2236659 -0.0489508 0.8611981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3107 3287 0.335373 -0.625698 0.869630 -0.2801063 0.7647437 -0.5776182 0.0553604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3108 3131 0.148218 -0.590503 1.024788 -0.5944558 0.5593343 0.4179858 0.3988173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3108 3288 0.098550 0.878435 0.518371 0.0317174 0.5927154 0.4949481 0.6345934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3109 3090 0.654518 0.519582 -0.342948 -0.0062894 -0.4513078 -0.7717436 0.4479882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3109 3130 -0.748444 -0.726184 0.153411 0.1067545 0.1115553 0.9283196 0.3382036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3110 3129 0.576345 -0.408834 0.718579 0.2998001 -0.8242393 0.2891480 0.3835921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3110 3290 -0.633339 -0.765685 -0.028698 -0.0253050 -0.7884282 0.5598381 0.2536179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3111 3128 0.598575 0.760958 -0.315249 -0.3669354 0.4624712 0.7986718 0.1166279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3111 3291 -0.238291 0.403858 0.912333 0.4305550 0.3877820 0.1324647 0.8041769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3113 2493 -0.618878 -0.711386 -0.339316 -0.8908895 0.1058433 -0.4340977 0.0816835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3113 3126 -0.361913 0.223345 0.754105 -0.7783037 0.4887054 -0.3919058 0.0426640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3113 3293 0.680820 0.558973 0.461920 0.0555908 0.5474315 -0.4158610 0.7240774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3114 3125 1.172925 0.303249 -0.101641 0.1952493 -0.4356764 0.3937491 0.7855097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3114 3294 0.273095 -0.511841 0.820061 -0.5280467 0.3261830 -0.2707072 0.7358593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3115 3124 -0.725137 -0.009749 -0.723092 -0.2219096 0.2467485 -0.7284447 0.5993661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3115 3295 -0.699810 -0.037395 0.606725 0.3694774 -0.3890689 0.5121598 0.6706744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3116 3296 -0.694385 0.221789 0.728659 0.2551710 -0.1527627 -0.8863936 0.3547643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3117 3122 0.160295 0.098936 1.042250 0.1616986 -0.2562786 0.7039258 0.6423887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3117 3297 0.397962 -0.852842 0.094490 0.3250117 0.5772124 -0.2589462 0.7029510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3118 3081 0.593011 0.655781 0.492708 -0.2755173 0.6292515 -0.5174435 0.5102794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3118 3298 0.086093 -0.619629 0.758938 0.2521526 0.4030005 -0.1747287 0.8622526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3119 3299 -0.898967 -0.672080 0.047273 0.2213029 0.7664605 -0.5204864 0.3043965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3120 3159 -0.392354 -0.803976 -0.297270 -0.2482421 0.4474116 -0.8463810 0.1477766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3121 3118 0.269529 0.946330 -0.413467 -0.5511930 -0.4002598 0.1661861 0.7129941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3121 3158 -0.171526 -0.978650 0.476029 -0.5941817 -0.3055449 0.4318327 0.6058968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3121 3261 -0.666132 0.514339 0.819228 -0.0677827 -0.3840544 -0.6939099 0.6053072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3122 3157 0.753984 -0.460010 0.721659 -0.4322053 -0.4059809 0.5996795 0.5373663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3122 3262 -0.613123 -0.458708 0.426556 0.6993014 -0.5528616 -0.1398146 0.4310146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3123 3116 -0.211368 -0.325732 -0.777615 0.7285378 0.2031330 -0.6540744 0.0125037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3123 3156 0.302509 0.362142 0.771913 -0.1787530 0.1420528 0.7821427 0.5797597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3123 3263 -0.809150 -0.554402 0.435557 0.5334581 -0.1378142 -0.2020593 0.8096924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3124 3264 0.289483 -0.956464 0.123148 0.3953951 -0.6427740 -0.0023505 0.6561240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3125 3154 0.262733 -0.497379 -0.789652 -0.0468641 0.0791771 0.0760009 0.9928538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3125 3265 0.428147 -0.426024 0.721444 0.0540416 0.7129920 -0.3783426 0.5878595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3126 3266 -0.173104 -0.862874 0.228110 0.1623393 0.0474965 0.8037396 0.5704321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3127 3112 -0.459160 0.151580 0.928292 -0.0345263 0.0674398 0.7707946 0.6325627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3127 3152 0.518022 -0.073812 -0.929408 0.5593456 0.7363595 0.1259051 0.3592423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3128 3151 -0.261596 -1.053435 0.244745 -0.3992072 0.5701973 0.6595695 0.2836842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3128 3268 -0.559614 0.312015 0.709936 0.3889440 0.1882575 -0.8785733 0.2034467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3129 3150 0.547331 -0.777146 -0.484164 0.6207756 -0.1222616 0.7207429 0.2832302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3129 3269 0.616739 0.369731 0.645891 0.2967578 -0.2265502 0.8522261 0.3664977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3130 2470 0.370201 0.053572 -0.878372 -0.0052537 0.1037041 -0.5585669 0.8229343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3130 3270 -0.349655 -0.012229 0.878681 0.1090391 -0.2178641 -0.1510873 0.9580283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3131 2471 0.694320 0.083755 -0.688119 0.0107671 0.6263685 -0.7787433 0.0332487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3131 3148 -0.526817 -0.205575 -0.961238 0.1229366 -0.6564251 -0.7026834 0.2454155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3131 3271 -0.675343 -0.186284 0.612147 0.0591256 -0.0275548 0.1571807 0.9854132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3132 3147 0.949184 0.260386 0.016472 0.7294293 -0.2335572 -0.4278358 0.4799379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3132 3272 0.038860 -0.938259 0.121131 0.2043022 0.9731391 -0.0503212 0.0934278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3133 3146 0.645669 0.600605 0.727595 -0.1381698 0.0936048 -0.1107595 0.9797345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3133 3273 -0.457934 -0.142407 0.717002 -0.2064490 0.3047633 0.5813785 0.7256013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3135 2475 -0.451745 0.240313 -0.720129 -0.4137542 -0.1520505 -0.6855955 0.5793504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3135 3144 -0.956358 0.379579 0.334306 0.7987170 -0.0457656 0.3592113 0.4805455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3135 3275 0.562278 -0.235533 0.892207 0.1337421 -0.5046187 -0.3585407 0.7739002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3136 3143 -0.354373 0.645569 1.001071 -0.1647378 -0.1713456 0.0602296 0.9694713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3137 3142 -0.699537 -0.793606 0.233566 -0.3305790 -0.6262936 0.5099789 0.4882574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3137 3277 -0.045270 0.400779 0.810564 -0.2620367 -0.4686962 -0.4236940 0.7294820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3138 3141 0.272963 0.511588 -0.863261 0.3327149 0.7402098 -0.3100615 0.4952293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3138 3278 0.867310 0.281181 0.361808 -0.6148424 0.0957215 -0.3662164 0.6918756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3139 3279 -0.425071 -0.444323 0.591380 0.6510834 -0.1663346 0.4869950 0.5579060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3140 3179 0.944583 0.364449 0.299365 -0.0180605 -0.8098135 0.0889417 0.5796252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3140 3240 -0.569926 0.761333 0.511830 0.0440653 -0.0927654 -0.0994626 0.9897272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3141 3178 0.771242 0.650666 -0.089227 -0.2275233 -0.1056206 -0.1192202 0.9606581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3141 3241 -0.634839 0.790861 0.098722 -0.2261656 0.8633416 0.4167734 0.1725985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3142 3177 -0.283063 -0.224766 0.966130 0.8021462 0.3347957 0.0525491 0.4916420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3142 3242 0.591291 -0.952622 0.112298 0.2063046 0.0292397 -0.7029621 0.6800204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3143 3176 -0.042180 0.371660 0.970182 0.0196268 0.4294061 -0.8710849 0.2375634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3143 3243 0.845580 -0.734389 0.289964 0.0530237 0.3785717 0.6877666 0.6171297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3145 3134 -0.781757 -0.360731 -0.469122 -0.3661193 -0.5273948 0.0090062 0.7666357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3145 3174 0.868558 0.602807 0.425371 -0.1983048 0.8012297 0.4747180 0.3055306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3145 3245 -0.472915 0.788617 0.292624 -0.6276468 -0.2205359 0.7148553 0.2154190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3146 3173 0.340927 0.627043 0.818580 0.0198120 -0.3095409 -0.6867213 0.6574236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3146 3246 -0.619442 -0.294851 0.478093 0.4737819 -0.3802514 0.5301009 0.5915511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3147 2447 -0.662208 -0.522503 -0.248469 -0.3023846 0.8078059 0.0953015 0.4969213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3147 3172 0.382141 -0.052825 -0.802511 0.1580930 0.0922251 0.9693990 0.1636057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3147 3247 0.767722 0.418878 0.375853 -0.1901086 0.4233159 -0.4278939 0.7756089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3148 3171 0.612980 -0.934879 0.348479 0.8314370 -0.4507250 0.3238882 0.0256099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3149 2449 -0.804710 0.119785 -0.357797 -0.4362144 0.7883048 -0.2076751 0.3810035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3149 3130 0.049438 -1.022127 -0.134380 0.1747541 0.5928853 0.0421745 0.7849645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3149 3170 0.156534 0.930875 0.182348 0.0865321 0.0991455 0.7711081 0.6229564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3149 3249 0.906416 -0.087112 0.522964 0.1393433 -0.1279031 0.9758242 0.1095050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3150 3169 -0.559835 0.486921 0.652383 0.5976890 0.3841692 0.6034624 0.3619600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3150 3250 0.623981 -0.346785 0.688557 0.0740905 0.8697487 -0.3467740 0.3432136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3151 3168 0.011058 0.667893 -0.955266 -0.8601733 0.1066504 0.0904371 0.4904576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3151 3251 -0.318139 0.872790 0.392031 -0.5462572 -0.6560800 0.2024722 0.4797574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3152 3167 0.290861 0.098356 1.183991 0.5819851 0.3998814 0.6663053 0.2396363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3152 3252 -0.290931 1.042866 -0.029669 -0.8983110 0.1844827 0.1149628 0.3818208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3153 3166 0.830795 0.244764 -0.344187 0.1222910 0.0183262 -0.9398696 0.3183619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3153 3253 0.187221 0.405332 0.836757 0.4362945 -0.4137450 -0.4153728 0.6825889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3154 2454 -0.185074 0.598387 -0.909312 0.4808567 0.4569527 -0.2884419 0.6904870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3154 3165 0.442871 -0.524444 -0.575371 0.0130110 0.7716595 -0.3989196 0.4952126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3154 3254 0.233927 -0.495311 0.651255 0.7634413 0.3939911 -0.2825292 0.4267385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3155 3124 -0.584068 -0.543048 -0.129968 0.1599630 -0.6797882 0.3215525 0.6394558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3155 3164 0.790116 0.702224 0.249184 0.3685486 0.5047775 0.7305604 0.2750511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3156 3163 -0.091826 -0.234779 0.887814 -0.0567346 -0.1820307 0.0368487 0.9809629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3157 3162 -0.548640 -0.874581 -0.255215 -0.3356408 -0.5634720 0.5600675 0.5061315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3157 3257 -0.592481 -0.126620 0.819460 -0.1488044 -0.0069248 -0.4445195 0.8832960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3158 3161 -1.012864 -0.221322 -0.059869 -0.3425332 0.4243484 -0.7789491 0.3095768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3158 3258 -0.157319 -0.355584 0.922505 -0.2758875 -0.7197374 0.4829243 0.4155097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3159 3259 0.227414 -0.475496 0.738570 -0.2850015 -0.4694834 0.6511047 0.5238531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3160 3220 -0.728437 -0.528826 0.087309 0.4874067 0.4878595 -0.3268483 0.6462183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3161 3221 0.686537 -0.450294 0.530848 -0.0875663 0.9058902 -0.3988368 0.1123577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3162 3197 -0.798533 0.329659 0.667565 0.3592548 0.4013961 -0.1810566 0.8228218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3163 3196 0.216233 -0.330234 0.947026 -0.5523446 0.4160540 0.4918242 0.5290779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3163 3223 -0.334796 1.112574 0.441207 0.4444212 -0.3383870 -0.8293944 0.0094291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3164 3195 0.101215 -0.009373 0.974942 0.3964210 -0.8092269 -0.4035868 0.1584925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3164 3224 -0.505282 0.894403 0.224723 0.3386227 -0.4342806 -0.4869260 0.6779662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3165 2425 0.471531 0.936137 -0.448161 0.0575319 -0.7600924 0.3466015 0.5466415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3165 3194 0.444618 0.014360 0.874005 0.3091951 0.2649369 -0.9121647 0.0465015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3165 3225 -0.633104 -0.682346 0.438343 0.5415473 0.1269506 0.6070225 0.5675682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3167 2427 -0.912770 0.576999 -0.222084 0.4236932 0.3394427 0.4733936 0.6936578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3167 3227 0.810281 -0.557712 0.190242 0.1963153 0.4477258 0.6559924 0.5750443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3168 3191 0.073103 0.544601 0.911539 0.5804629 -0.0786331 -0.7004804 0.4076849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3168 3228 -0.591678 -0.710551 0.564039 0.1057326 -0.3137135 -0.1119633 0.9369465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3169 3190 0.602028 0.510140 -0.747718 -0.0823426 -0.5355020 -0.2316058 0.8079703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3170 2430 0.309311 0.736284 -0.631210 -0.1222456 -0.1050127 -0.9724596 0.1683767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3170 3189 1.136954 -0.354219 0.161713 -0.2280389 -0.2026405 0.3588137 0.8821495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3170 3230 -0.190580 -0.542226 0.828630 0.3840712 0.4474321 -0.8061162 0.0497047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3171 3188 0.953399 0.129723 0.242708 -0.0859756 0.5537434 -0.6627256 0.4967607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3171 3231 0.132193 -0.940959 0.058332 0.4737429 0.1511922 0.5309887 0.6861192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3172 3187 -0.373463 -0.356387 -0.745215 0.2351941 0.1756504 -0.6501660 0.7007959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3172 3232 -0.314751 -0.605580 0.730920 0.2430624 -0.6338983 0.6649491 0.3113458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3173 3186 -0.175216 0.494848 0.685478 0.4770070 0.2266065 0.8434349 0.0986478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3174 2434 -0.176306 -0.982941 -0.271701 -0.6767640 0.0034643 -0.3055911 0.6697705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3174 3185 -0.738141 -0.002492 0.518197 -0.8717979 -0.2880136 -0.2560434 0.3024209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3174 3234 0.089648 0.849824 0.454203 0.2772493 -0.1374306 -0.9156051 0.2567352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3175 3184 -0.431655 0.609382 -0.874188 0.4269860 -0.7662769 0.1184545 0.4652647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3175 3235 -0.960619 -0.467654 0.202730 0.5766902 -0.1481339 -0.4493737 0.6659940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3176 3183 -0.192368 -0.708935 0.327466 -0.1509852 0.4793113 0.3668990 0.7828469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3176 3236 -0.635442 0.619974 0.936566 0.2885216 0.4419533 -0.8345493 0.1579874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3177 3182 -0.777843 0.540679 -0.616367 -0.2007465 0.7083168 0.5436165 0.4030747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3177 3237 -0.413429 0.685016 0.681667 0.1123356 0.0221457 -0.9912826 0.0651854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3178 3181 0.621300 0.802757 0.135438 -0.0770899 0.0545421 -0.3612101 0.9276905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3179 2439 -0.869639 -0.355683 -0.198291 -0.4363693 0.4344566 0.2996692 0.7287165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3179 3239 0.948298 0.676020 0.298368 0.4293077 0.3017846 0.8466618 0.0882316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3182 2402 0.380879 -0.589154 -0.263728 -0.2572287 0.0757393 -0.7708956 0.5777689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3182 3202 -0.381030 0.714341 0.440820 -0.7209666 -0.4311025 -0.5103732 0.1840573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3183 3203 -0.199277 0.776059 0.363588 0.5482422 -0.0419681 -0.7565251 0.3540325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3184 3204 0.804369 0.366506 0.832070 -0.4030409 0.3542974 0.2153208 0.8158850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3185 3205 0.657630 -0.584617 0.381157 0.6993364 -0.0527229 -0.2795333 0.6557516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3186 3206 -0.180506 0.839280 0.730798 0.1267204 0.1326471 0.7066299 0.6833892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3187 3207 0.255803 -0.468581 0.879475 -0.0591686 -0.4160624 0.3084989 0.8533578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3188 3208 0.798445 0.121472 0.860337 0.3778256 0.3986918 -0.6115300 0.5694942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3189 3209 -0.730236 -0.418061 0.509970 0.5261725 0.1489517 -0.2541400 0.7977273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3190 2410 -0.356632 -0.813497 -0.504190 -0.4288008 0.2993956 0.4632038 0.7154959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3190 3210 0.414775 0.619845 0.756048 -0.6228610 -0.3560901 -0.6834540 0.1346645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3191 2411 -0.006343 -0.470298 -0.869463 -0.2964195 0.0734843 0.9223393 0.2366978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3191 3211 0.021631 0.451184 0.884363 0.4697272 -0.0325276 -0.2334888 0.8507534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3192 2412 0.682654 0.460022 -0.745396 0.4124575 -0.1712321 0.7291910 0.5184967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3192 3212 -0.434057 -0.394424 0.704444 0.2950733 -0.0987152 -0.4633834 0.8297366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3193 3166 -0.567744 0.219719 0.754047 -0.0624677 -0.3841109 0.8944998 0.2200605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3193 3213 0.449262 -0.678413 0.496730 -0.1047954 0.5164050 0.1941171 0.8274432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3194 3214 0.184716 0.304251 0.913366 0.0303834 -0.4860835 -0.8607245 0.1481656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3195 3215 -0.283416 0.627916 0.720948 0.2314507 0.1120861 0.7536592 0.6048678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3196 3216 -0.351830 0.362387 1.013089 0.0324645 0.5390999 0.3634520 0.7590916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3197 3217 -0.438582 -0.173723 0.931160 0.3847532 0.0272271 0.2632609 0.8842609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3198 2418 0.103004 -0.766889 -0.379636 -0.5540068 0.2646163 0.7183536 0.3271435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3198 3161 1.101256 0.203886 0.011846 0.3332764 0.1132546 0.9281885 0.1206911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3199 3160 -0.829262 0.556126 0.276141 0.2320998 0.7229657 -0.4872797 0.4312874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3199 3219 0.152161 -0.327419 0.826187 0.5875857 -0.0287389 -0.7801893 0.2126541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3200 3180 0.023363 -0.074355 -0.904725 -0.3964391 0.5465477 -0.6296680 0.3842395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3200 3239 -0.073590 1.004710 -0.098712 -0.0921358 -0.0844309 0.2431153 0.9619134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3200 3980 -0.048632 -0.116254 0.855484 -0.0631487 0.0698104 -0.7606706 0.6422764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3201 3181 0.389417 -0.683135 -0.346702 -0.8441881 0.3377679 0.3708354 0.1890513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3201 3238 0.931603 0.612568 0.143098 -0.0027580 -0.6903441 -0.7187392 0.0826520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3202 3237 -0.440619 -0.504951 -0.641385 0.4521338 -0.4364604 0.6353836 0.4487372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3204 3984 0.020375 -0.407122 0.919248 0.2148119 0.0031849 0.8753303 0.4331772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3205 3234 -0.199187 0.318508 -0.877718 -0.3252934 0.3270551 -0.8648483 0.1981330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3205 3985 0.758004 0.478619 0.448246 -0.2269848 0.2050880 0.7158701 0.6276519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3206 3233 0.132253 0.561426 -0.634447 -0.3579623 0.4120744 -0.8378391 0.0091261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3206 3986 0.650168 0.290934 0.620472 -0.3111767 0.1902482 0.0999979 0.9257295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3207 3232 0.033779 0.864509 0.613624 0.5633510 -0.4524338 0.6820749 0.1127525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3207 3987 0.330365 -0.555318 0.707685 0.2646091 0.7433292 -0.4002374 0.4661050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3208 3231 0.913905 0.773550 0.124787 0.4292635 -0.3771862 -0.5792642 0.5813057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3208 3988 -0.518007 0.743553 0.193434 -0.1579163 -0.0666639 0.2453195 0.9541681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3209 3230 -0.784896 0.274581 -0.602435 0.5235183 0.2443206 -0.8113149 0.0894660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3209 3989 -0.780042 0.010821 0.743418 0.1769181 -0.4603856 -0.3482112 0.7971788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3210 3229 0.323527 0.860042 -0.219786 0.2824911 0.2069807 -0.1826628 0.9186904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3210 3990 0.800581 -0.172626 0.576821 0.5774982 -0.4481285 0.5456970 0.4097456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3211 3228 1.024081 0.169635 -0.198575 -0.4057925 0.2409705 0.8671019 0.1593735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3212 3227 -0.560318 0.520533 0.120428 0.1846923 0.5043407 -0.3474041 0.7686609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3213 3226 -0.867325 0.591779 -0.208202 0.7134382 0.1217665 0.2072359 0.6582038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3213 3993 -0.464156 -0.602987 0.318700 0.6181063 0.3113083 -0.2899442 0.6610326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3214 3225 -0.852690 0.002274 -0.220215 0.1940204 0.3358375 0.0273801 0.9213141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3214 3994 -0.308758 0.772175 0.831003 -0.4831481 -0.2918566 -0.1974741 0.8014934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3215 3224 -0.474205 0.371625 0.719520 -0.1710096 0.4348598 -0.7084814 0.5288731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3215 3995 0.825292 0.592679 0.298748 0.7735834 -0.2332925 0.5131021 0.2896023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3216 3223 -0.041343 -0.104936 1.152643 -0.5776032 -0.2169278 -0.2700763 0.7391723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3216 3996 -0.910742 0.757430 0.328975 -0.5511503 -0.0769995 -0.4765801 0.6805702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3217 3222 0.805536 -0.137005 0.687335 0.5673375 -0.6883856 -0.3730078 0.2551837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3217 3997 -0.477433 0.696884 0.702038 0.2179437 -0.0021201 -0.0748936 0.9730812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3218 3198 -0.321293 0.928995 -0.204221 0.8624946 0.3122943 0.0262889 0.3973465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3218 3221 1.010826 0.272931 -0.331281 0.0010088 -0.1772091 0.5593274 0.8097832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3218 3998 0.390373 -0.658880 0.364175 0.2339673 -0.7639864 0.5946815 0.0890958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3219 3999 -0.670861 0.388764 0.212123 -0.7312371 0.0834690 -0.3216841 0.5956883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3220 3259 0.722962 -0.212144 0.495866 0.4050409 0.6832413 -0.1790624 0.5805686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3220 3960 -0.426861 -0.752474 0.384450 0.0236590 0.1507814 -0.3776966 0.9132636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3221 3258 0.517499 -0.467117 -0.678219 -0.1709329 -0.5299838 -0.1235850 0.8213561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3221 3961 -0.342854 -0.914371 0.345756 -0.1627187 0.3741261 -0.5512210 0.7278102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3222 3162 0.647320 -0.727982 -0.154089 0.3107830 -0.1447549 -0.9247874 0.1650096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3222 3257 -0.116655 -0.099045 -0.825974 -0.8547551 -0.2356461 0.0811459 0.4552801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3222 3962 -0.651245 0.643810 0.095256 0.5360580 -0.2275666 -0.7126968 0.3910481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3223 3256 0.638118 -0.686472 -0.047620 0.0665825 0.2269163 0.5053057 0.8299048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3223 3963 -0.388834 -0.322615 0.779804 0.2999823 0.3448203 -0.2718215 0.8468900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3224 3255 -0.523869 -0.856876 -0.277097 -0.1292198 -0.4262978 0.1613554 0.8806457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3224 3964 -0.841772 0.360302 0.509746 -0.3914191 -0.3202978 0.8600815 0.0667848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3225 3254 -0.672523 -0.287979 -0.716766 -0.0553974 0.0404147 -0.0993713 0.9926848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3225 3965 -0.467121 0.917299 -0.090879 0.0755878 -0.6958207 -0.7030287 0.1259790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3226 3166 0.704031 -0.601425 -0.473477 0.6142413 -0.2121323 -0.7165608 0.2534721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3226 3253 -0.655432 -0.142149 -0.837362 0.5622472 -0.7299786 -0.1536577 0.3569295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3226 3966 -0.728093 0.450908 0.360495 0.1998206 -0.1340629 -0.9630630 0.1208655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3228 3251 -0.466305 -0.650768 -0.588829 -0.1083899 -0.2279843 -0.3954735 0.8831056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3228 3968 0.243602 -0.433362 0.628412 0.3436014 -0.0384655 -0.8192356 0.4575057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3229 3169 -0.456311 -0.602975 -0.891103 -0.0804572 -0.5805562 -0.7617725 0.2760143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3229 3969 0.512476 0.428810 0.957887 0.2372824 0.6583858 0.6815038 0.2139573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3230 3249 0.834044 -0.385572 0.434496 0.5639447 0.2376916 -0.6231955 0.4869255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3230 3970 -0.738992 -0.157060 0.911611 0.4662410 -0.3137526 0.6789802 0.4724030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3231 3248 -0.779071 0.229261 -0.632016 -0.5598077 0.1732719 0.5827198 0.5630540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3231 3971 -0.810398 -0.095777 0.700378 -0.0946157 0.0528745 -0.9174625 0.3827724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3232 3247 0.145417 -0.746357 -0.523543 0.3399040 0.5969702 0.3066011 0.6588533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3232 3972 0.645130 -0.131822 0.769780 0.2027758 0.4887707 0.8272099 0.1889681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3233 3173 0.276803 0.697727 -0.448905 -0.0261266 0.1530499 -0.6543526 0.7400783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3233 3973 -0.146528 -0.512865 0.721398 -0.7509352 -0.2007471 0.6276080 0.0436488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3234 3245 -0.537110 -0.048418 -0.775378 -0.3184037 -0.8605996 0.3190893 0.2370009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3234 3974 -0.655420 -0.759983 0.497045 0.0168678 0.4738143 -0.6867831 0.5509486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3235 3204 -0.408832 -0.881622 -0.087471 -0.2023562 -0.2244083 0.7644002 0.5695482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3235 3975 -0.065679 0.085898 1.018762 0.1409155 0.2147449 0.9657795 0.0360209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3236 3203 -0.005731 0.112793 1.035895 -0.0276466 -0.3468665 0.3807574 0.8567048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3236 3243 -0.228497 -0.062077 -1.175566 0.2605791 0.2244376 0.4012182 0.8489701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3236 3976 0.149120 -1.265875 0.163292 -0.0067036 0.4375286 -0.8671823 0.2377365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3237 3242 -0.565279 0.550389 0.312472 0.6784399 -0.4158895 0.4834879 0.3646843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3237 3977 -0.135680 -0.420410 0.637617 0.2983636 -0.2541684 0.5506565 0.7369905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3238 3178 -0.408342 -0.513613 -0.622283 0.1526556 0.2384051 -0.5706544 0.7708520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3238 3978 0.333754 0.380252 0.819118 -0.2880003 -0.5716402 -0.6853560 0.3472325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3239 3979 0.004589 -0.147115 0.780413 -0.2259343 -0.1628456 0.9329496 0.2281227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3240 3279 -0.580741 -0.554549 -0.141076 0.2713813 -0.4496052 0.1906580 0.8293714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3241 3278 0.730826 0.170439 -0.676358 -0.1222406 0.1497488 0.6813880 0.7059340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3241 3941 0.154354 0.850384 0.292639 -0.7086999 0.5534640 0.3323063 0.2845956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3242 3277 0.019028 0.278541 -0.990756 -0.6696936 -0.0275831 -0.1620179 0.7242236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3243 3276 0.251204 -0.467233 -0.709734 -0.5482931 0.0141929 0.7850519 0.2878659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3243 3943 -0.831454 -0.652512 0.190251 0.0606659 -0.4579035 0.5792149 0.6716800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3244 3235 -0.673900 -0.629353 0.569306 -0.0173300 0.5717188 -0.2346314 0.7859932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3244 3275 0.602500 0.579773 -0.568466 0.4539572 -0.2173390 -0.2454585 0.8285148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3244 3944 0.810041 -0.345453 0.730682 0.0419724 -0.3544511 0.8981017 0.2569360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3245 3274 0.393553 0.703576 0.848807 0.3851686 0.5815965 -0.7081659 0.1090494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3245 3945 0.122583 -0.993498 0.665410 -0.2282689 0.3470443 -0.0961316 0.9045508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3246 3233 0.929021 -0.207351 -0.058460 -0.7294067 0.3630075 -0.2680006 0.5141664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3246 3273 -0.910043 0.405889 0.416316 -0.2172177 0.7829215 0.0251352 0.5824248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3246 3946 0.421517 1.008482 0.288748 -0.4853350 0.4708747 0.3696680 0.6372382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3247 3272 -0.381462 -0.764308 0.161027 -0.2807244 0.3088824 -0.5961632 0.6858388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3247 3947 -0.585217 0.419572 0.581732 0.2345760 -0.3229884 -0.0007810 0.9168708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3248 3148 0.679827 -0.441984 -0.503243 0.0192935 -0.8795334 -0.3060531 0.3638409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3248 3271 0.479601 0.682546 0.361051 -0.4408804 0.0440255 0.1789631 0.8784409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3249 3270 -0.180784 0.961390 0.036184 -0.3033560 0.0270046 0.9474198 0.0981919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3249 3949 -0.581011 -0.221960 0.751612 -0.3024850 -0.0593173 0.4277823 0.8496979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3250 3229 -0.057674 -0.324807 -1.035666 0.5634942 -0.5986493 -0.1919889 0.5359418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3250 3269 0.092818 0.287972 1.018679 -0.2586175 -0.7810863 0.1340564 0.5523134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3250 3950 -0.862160 -0.532786 0.184838 0.4175658 -0.4999576 0.7499400 0.1152004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3251 3268 -0.497094 -0.807666 -0.659516 0.0141208 0.3902602 0.3551067 0.8493508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3251 3951 0.747840 -0.235872 0.373116 0.0377756 0.3979793 0.7070459 0.5833280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3252 3227 -0.025456 -0.765052 -0.688062 0.5716460 0.5454378 -0.4032636 0.4616242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3252 3267 0.108768 0.478930 0.691692 0.5589044 0.1665070 -0.7402051 0.3346607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3253 3953 -0.181561 1.016081 0.138591 -0.6104687 0.2481227 -0.1613246 0.7346683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3255 3264 -0.667065 -0.641865 -0.114961 -0.3647256 0.4033857 -0.8382706 0.0394668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3256 3156 0.709281 -0.317548 -0.596925 -0.5078440 0.6465255 0.4238899 0.3800219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3258 3261 -0.202254 -0.227868 -0.960280 0.3918951 -0.5757053 0.4225601 0.5800212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3259 3959 -0.507695 -0.528495 0.405352 0.9278357 -0.2073667 -0.2843724 0.1235001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3260 3920 0.846385 -0.609760 0.364998 0.0872144 0.2944775 -0.4494336 0.8388600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3261 3298 -0.835234 0.078283 0.058566 -0.1583207 0.1551212 0.6494391 0.7273932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3261 3921 0.097269 -0.321548 0.860411 0.3692954 -0.3063351 0.6077439 0.6327931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3262 3257 0.722040 0.350773 -0.813963 -0.3725785 0.2222632 0.8400834 0.3256442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3262 3297 -0.732580 -0.195429 0.615520 -0.3223426 -0.3404025 -0.8220838 0.3231092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3262 3922 0.292780 0.695722 0.496917 0.2439339 -0.5750282 -0.7806984 0.0186759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3263 3256 0.042306 1.036942 0.051158 0.1411176 0.3100048 0.1121186 0.9334946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3263 3296 0.156834 -0.907966 -0.031002 -0.2441419 -0.1404592 0.7520963 0.5958332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3263 3923 -0.595749 0.165235 0.840836 -0.1588470 -0.4954569 -0.4796840 0.7065362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3264 3295 0.901990 0.430347 0.277564 0.9001495 0.0853480 0.3027247 0.3013376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3264 3924 0.705279 -0.847389 0.215030 0.4429994 0.1598433 0.2153164 0.8554768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3265 3254 0.683066 0.251452 0.837014 0.4722669 0.2233823 0.4000923 0.7529876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3265 3925 -0.560971 -0.418869 0.868808 0.2889354 0.0408359 0.6191992 0.7290001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3266 3293 0.425136 0.232126 0.723326 0.1636637 -0.3460735 -0.0171403 0.9236631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3266 3926 -0.902114 0.519935 0.231916 -0.2450113 -0.7547401 -0.0997073 0.6003293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3267 3127 0.258526 -0.481910 -0.801172 0.0641307 -0.5778204 0.2243061 0.7821110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3267 3292 -0.966131 -0.290809 -0.218420 -0.3288242 0.2212810 -0.0756947 0.9149752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3267 3927 -0.269326 0.153981 0.948335 -0.5635913 -0.1654813 0.7541196 0.2937421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3268 3291 -0.157120 -0.480922 -0.764677 0.7018975 0.2588825 0.5041669 0.4314342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3268 3928 -0.234487 -0.684942 0.725359 0.0012248 0.2035520 -0.7948674 0.5716213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3269 3290 0.846390 -0.224054 -0.427434 -0.0489492 0.2288249 -0.6651732 0.7090753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3270 3930 0.168804 0.212291 1.044600 -0.4154343 -0.0281453 -0.5027823 0.7575171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3271 3288 0.606615 -0.122587 0.748045 0.2233382 -0.4476394 0.2004840 0.8423450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3271 3931 -0.738261 0.108081 0.537959 0.3024914 -0.5992450 -0.2261352 0.7058805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3272 3287 0.812769 -0.604195 -0.030978 0.0573668 -0.3119303 -0.3383688 0.8859543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3272 3932 -0.728684 -0.677019 -0.091534 0.1749610 -0.7459309 -0.3113259 0.5621849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3273 3286 -0.061317 0.419964 -0.901393 -0.3649752 -0.3267113 -0.5871033 0.6444863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3273 3933 -0.761372 0.518695 0.451829 -0.5065841 0.0707128 0.0432757 0.8581955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3274 3134 0.530936 0.119632 -0.857915 0.1528774 -0.5309117 0.2163809 0.8049476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3274 3285 -0.387926 -0.656072 -0.486458 -0.0496166 0.3753492 -0.9223932 0.0764324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3276 3136 0.209381 -0.823303 -0.487168 -0.1062421 -0.0513610 0.8936773 0.4329152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3276 3283 0.493608 0.615035 -0.808198 0.0429400 -0.5930924 0.1422386 0.7913064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3277 3282 -0.082864 0.824533 0.250645 0.5958347 -0.2768939 0.5657905 0.4981886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3277 3937 0.796794 0.060655 0.705082 -0.3940945 0.8003039 -0.3310390 0.3075978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3278 3938 0.414395 -0.070777 0.697164 -0.6638179 0.4700740 -0.5105261 0.2788178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3279 3939 0.172595 0.969996 0.268026 0.2290909 0.4567336 0.6614165 0.5490356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3280 3319 0.478384 0.528590 -0.760241 -0.5714118 -0.2757713 -0.4063036 0.6575379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3281 3278 -0.634730 0.305987 -0.927800 0.1424016 -0.7931127 0.2960283 0.5128949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3281 3318 0.478173 -0.300919 0.678703 -0.1039177 -0.0484544 -0.2359158 0.9649855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3281 3901 -0.823911 -0.601603 0.417141 0.4287494 0.4272789 -0.6342655 0.4809510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3282 3317 0.292852 0.180461 -0.860171 0.6578159 0.2198131 -0.3867598 0.6077642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3282 3902 0.692669 -0.562314 0.365382 0.4317547 -0.2966996 0.3327805 0.7841010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3283 3103 -0.592984 -0.833290 -0.396476 -0.6133758 0.3330690 -0.5823604 0.4167632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3283 3903 0.690090 0.871914 0.189820 0.6438483 0.1609459 0.5874929 0.4630420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3284 3315 0.033068 -0.950985 0.148687 0.5750616 -0.0880048 -0.2253717 0.7815158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3284 3904 0.136849 0.014992 1.066077 0.6679462 0.2381244 0.6808120 0.1834113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3285 3314 0.563886 0.731481 -0.033472 0.8190290 0.1365954 0.3212061 0.4553678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3285 3905 0.784435 -0.479605 0.523079 0.6905558 -0.5334554 0.4283041 0.2347630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3286 3313 -0.919998 0.032337 -0.207490 0.1484101 0.3100041 0.9198018 0.1893057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3286 3906 0.067482 -0.572799 0.694494 0.7418227 -0.3266272 0.2153159 0.5446585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3287 3312 0.772667 0.115253 -0.418571 -0.7432983 0.1223822 -0.6348596 0.1717079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3287 3907 0.216954 -1.114399 0.273465 0.7679823 -0.2556100 -0.1327712 0.5720477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3288 3311 1.006304 -0.264965 -0.038496 -0.6282435 0.1766087 -0.3554043 0.6691840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3288 3908 0.040355 0.686679 0.678101 -0.4325742 0.5405592 -0.1377354 0.7083109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3289 3109 0.496874 0.152404 -0.632588 0.1142022 0.0054581 -0.9598695 0.2560831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3289 3270 0.382081 0.706596 0.298749 0.2692324 -0.3184319 -0.3217573 0.8500513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3290 3309 0.320123 0.934270 0.100315 -0.2701505 -0.1272336 -0.0912048 0.9500063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3290 3910 0.426919 -0.333840 0.779974 -0.2091948 0.2040027 0.1047246 0.9506068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3291 3308 -0.990791 -0.300845 0.221129 0.1428501 -0.4763938 -0.7237994 0.4782857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3292 3112 0.611231 0.163550 -0.557220 -0.3954717 -0.6796945 0.4657466 0.4058294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3292 3307 -0.745401 0.099288 -0.651447 -0.4392460 -0.0646802 0.6058127 0.6602048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3292 3912 -0.643811 -0.318787 0.419123 -0.1218390 -0.9279467 0.2784849 0.2156765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3293 3913 -0.464056 0.532682 0.532022 -0.4244933 0.0050703 0.8676419 0.2587997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3294 3265 0.343644 0.319327 0.624040 0.2989598 -0.0103281 0.5593354 0.7730849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3294 3305 -0.369262 -0.485756 -0.790228 0.3743422 -0.1683942 0.7083876 0.5741936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3294 3914 0.382311 -0.754637 0.271223 0.4480015 -0.2384873 -0.6380117 0.5791024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3295 3304 1.008135 -0.459053 0.102970 -0.7781050 0.0839259 -0.0339821 0.6215741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3296 3303 -0.889145 0.386975 0.059977 -0.4460500 0.1011687 -0.5001896 0.7352650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3296 3916 -0.011646 -0.214998 0.919615 0.0280435 -0.3845835 0.9225709 0.0131151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3297 3917 0.112004 -0.089151 1.060235 -0.3641075 -0.0898156 -0.7974239 0.4727303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3300 3080 0.678936 -0.054307 -0.677151 0.2902471 0.3650666 0.8701052 0.1593737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3300 3880 -0.743651 0.074437 0.741252 -0.0354266 -0.6129531 0.6537334 0.4423416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3301 3298 -0.855004 0.311025 -0.601516 -0.0581947 -0.2602284 -0.8756954 0.4025571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3301 3338 0.743089 -0.383981 0.333216 -0.8789321 -0.0081910 0.0853386 0.4691786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3301 3881 0.154990 0.903395 0.449693 -0.0137085 -0.2217872 -0.7564706 0.6151217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3302 3297 -0.309983 -0.738147 0.383410 -0.4949980 -0.1227490 0.5900531 0.6258969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3302 3337 0.455948 0.918404 -0.268722 -0.6914550 -0.0426328 0.7211604 0.0003540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3302 3882 -0.724562 0.658027 0.530321 -0.3444193 0.4151668 0.7404280 0.4009716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3303 3336 -0.753300 -0.619090 -0.344594 0.7395798 -0.2868981 0.4474520 0.4129140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3303 3883 0.364799 -0.785354 0.490704 0.1944557 0.9308860 -0.1958954 0.2392973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3304 3335 0.852184 -0.001628 -0.532013 0.2297717 0.8068673 -0.0615276 0.5407258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3304 3884 0.203585 -0.880300 0.624063 -0.1134878 0.4663275 0.3150515 0.8187806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3305 3085 0.758737 -0.207269 -0.886127 -0.5660330 0.0721608 0.1833372 0.8004917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3305 3334 -0.701830 0.089102 -0.578221 0.2861961 -0.5727261 0.1910562 0.7440256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3305 3885 -0.471007 0.159196 0.948044 -0.0800394 -0.5115932 0.7582611 0.3961140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3306 3086 -0.839487 0.591015 -0.477914 0.8274124 -0.0747338 0.3625660 0.4223144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3306 3293 -0.568643 0.022827 0.853735 0.5223076 0.5478204 -0.4259569 0.4956293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3306 3333 0.444267 -0.012538 -0.832027 -0.0677989 0.8860627 -0.4497532 0.0895445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3306 3886 0.561496 -0.529947 0.255253 0.4693440 -0.3448454 0.6153738 0.5311430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3307 3332 0.236528 1.198243 0.016669 -0.7669654 -0.1128596 0.4991592 0.3871264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3308 3088 0.501108 0.275497 -0.813523 -0.5324739 0.2673918 0.7666338 0.2392609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3308 3331 0.655661 -0.305691 0.380812 0.0485870 -0.2665452 0.9577019 0.0969535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3308 3888 -0.550287 -0.109498 0.647423 -0.0044125 0.2516064 -0.8458460 0.4703395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3309 3330 0.435566 0.762295 0.429882 0.1368632 -0.2409080 0.3230591 0.9049114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3309 3889 0.671991 -0.680913 0.391697 0.6721449 -0.4045753 0.5461593 0.2936837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3310 3289 0.393758 -0.088788 0.919532 0.3709445 -0.2623699 -0.5105847 0.7299764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3310 3329 -0.379325 0.119843 -1.128729 -0.2308525 0.0867207 0.9675761 0.0546173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3311 3328 0.832502 0.159029 0.444060 0.3610787 -0.6026566 0.6827250 0.2007831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3311 3891 -0.214326 -0.780338 0.707322 -0.3087033 -0.3849982 0.5932737 0.6360070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3312 3327 -0.564055 0.381444 0.920955 -0.8825248 -0.3526817 -0.2624910 0.1669255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3312 3892 0.641944 0.890141 0.155864 0.8206881 -0.0985541 0.5154560 0.2259717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3313 3893 -0.082264 0.923984 0.192597 -0.0492901 -0.7242827 -0.0189616 0.6874776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3314 3094 -0.533906 -0.503717 -0.450581 -0.4230506 0.3514998 0.2415004 0.7994708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3314 3325 0.897977 -0.571249 -0.134065 -0.6172150 -0.0099754 -0.7638011 0.1885577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3315 3324 0.677726 -0.130474 0.641249 0.0738000 -0.1924914 -0.8650814 0.4573126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3315 3895 0.085401 0.922210 0.049727 -0.7779828 0.4533211 0.2918237 0.3226169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3316 3283 0.123483 0.586550 0.952831 0.2978181 -0.0666820 0.9409837 0.1463133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3316 3896 -0.453433 -0.620828 0.337873 -0.2033900 -0.6092207 0.7109790 0.2863416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3317 3097 -0.244542 -0.914032 -0.275099 -0.6317971 -0.1557929 0.5767483 0.4938851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3317 3322 0.949641 -0.350169 -0.086791 -0.2875640 0.5419005 0.7472638 0.2554361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3317 3897 0.196662 0.678639 0.305512 -0.2799000 -0.4945393 -0.6581216 0.4939259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3318 3321 0.776258 -0.003198 0.775180 -0.0656964 -0.9340950 0.0675641 0.3443626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3319 3099 -0.770280 -0.352797 -0.489994 0.3509745 0.0729220 -0.0846891 0.9296919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3320 3359 -0.375116 -0.848510 -0.147502 0.8224129 -0.1539436 0.1130456 0.5358722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3320 3860 0.708017 -0.451802 0.716815 -0.0343993 -0.4203236 0.0759863 0.9035324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3321 3861 0.266174 -0.975672 0.091093 0.1699666 -0.3867211 -0.2100346 0.8817276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3322 3357 -0.713391 -0.478280 -0.517852 0.1763784 0.1795157 0.9119410 0.3240809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3322 3862 -0.335320 -0.376562 0.838250 -0.6167575 -0.5823799 0.5279242 0.0417116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3323 3356 -0.338700 -0.333216 0.691203 -0.4110611 0.5048035 0.6895989 0.3172625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3324 3355 -0.312887 0.829300 0.763590 0.2208715 -0.1955702 -0.9551301 0.0263529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3324 3864 -0.909469 -0.427913 0.459736 -0.3212917 -0.5391830 -0.3601025 0.6902025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3325 3354 -0.134058 0.803848 0.620210 -0.3281925 0.2371233 -0.8271984 0.3896216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3325 3865 0.405294 -0.679678 0.907759 0.7057394 0.2915962 0.5855759 0.2720377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3326 3313 0.249425 -0.055071 0.997206 -0.3559706 0.2237494 0.8393940 0.3444398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3326 3866 -0.615154 -0.747014 0.375815 -0.9058029 -0.0780283 0.3657415 0.1991631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3327 3352 0.562463 -0.765058 -0.568915 0.6427194 0.5450351 -0.2066489 0.4971366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3327 3867 0.799657 0.090764 0.425385 -0.2530251 0.2663163 0.5833477 0.7244028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3328 3068 -0.585413 0.225252 -0.506267 -0.3665694 0.0571698 0.8305821 0.4153214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3328 3868 0.673907 -0.079574 0.686058 0.8063488 0.0544007 0.0886825 0.5822179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3329 3069 -0.634837 0.254661 -0.640835 0.3294130 -0.2499893 -0.2551967 0.8739949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3329 3350 0.615715 -0.331981 -0.618855 0.3346107 -0.5904952 0.4926992 0.5446087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3329 3869 0.596765 -0.204732 0.646434 0.6493266 -0.5499062 0.4747084 0.2250114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3330 3349 0.934060 0.292266 -0.099072 0.3352790 0.2347223 0.8110497 0.4179614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3330 3870 0.299434 -0.737566 0.156377 0.4773502 0.0077979 0.1152638 0.8710857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3332 3347 0.791928 -0.483156 0.563078 0.1864588 0.1236829 0.4990166 0.8372085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3333 3346 -0.740028 0.532446 0.639595 -0.5807558 -0.2511870 0.7558492 0.1682848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3333 3873 -0.464109 -0.848747 0.257768 0.8846603 0.1931702 -0.0534409 0.4209579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3334 3345 -0.734910 0.749018 0.235922 -0.3877126 0.6245886 -0.1690910 0.6564879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3334 3874 0.728316 0.562169 0.553673 -0.5596429 0.1799665 0.3767850 0.7158526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3335 3075 0.953936 0.607022 -0.341552 -0.3847919 -0.1071903 0.8553331 0.3299253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3335 3344 0.286303 0.362672 0.957827 -0.6566520 0.3489157 0.6686276 0.0017805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3335 3875 -0.803552 -0.504540 0.318434 0.2792286 0.0479983 -0.8711480 0.4010346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3336 3876 0.629240 0.328789 0.780736 0.2211714 0.3414248 0.8303140 0.3809082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3337 3342 0.316398 -0.748921 -0.428204 -0.1869742 0.4005921 -0.8939108 0.0740946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3337 3877 -0.227426 -0.578463 0.685221 0.2202982 -0.0773077 0.9549845 0.1830211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3338 3341 0.650844 -0.011976 -0.530350 0.6706640 -0.2514395 -0.4390643 0.5424118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3338 3878 0.244559 -0.921103 0.493150 -0.3365729 -0.6654867 0.6658881 0.0209544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3339 3300 -0.599501 -0.851872 0.279841 -0.2376320 0.2975872 0.8634852 0.3307057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3339 3879 0.216977 0.119271 1.087469 0.0218814 -0.6622923 -0.7345016 0.1462789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3340 3379 0.581885 1.000341 0.416574 -0.4026952 0.0790949 -0.7187981 0.5611683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3340 3840 0.959433 -0.404296 0.035555 0.3568981 0.4072207 0.5096467 0.6686219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3341 3378 0.634664 -0.561562 -0.351725 0.6773045 0.3192792 0.5261680 0.4030715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3341 3841 0.624684 0.784892 0.258132 0.3070088 0.6640450 0.3229999 0.6003840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3342 3377 -0.271235 0.873598 0.463774 0.3262289 0.1999205 0.8614875 0.3338349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3342 3842 0.732521 0.141121 0.677823 -0.3595024 0.6506208 -0.5005122 0.4437772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3343 3043 -0.011173 -0.686567 -0.547730 -0.2152217 0.6953120 0.0848209 0.6804603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3343 3336 0.802161 -0.014096 0.014879 -0.2313102 -0.0262863 0.4561360 0.8589206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3343 3376 -0.941040 -0.227889 0.081944 -0.8468901 0.3804344 0.2571962 0.2681362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3343 3843 -0.174057 0.879092 0.451478 -0.3657816 -0.0445579 0.7827631 0.5014980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3344 3844 0.247840 1.003700 0.432151 -0.6794552 0.4872016 0.0714795 0.5439355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3345 3374 -0.944159 0.235258 -0.467572 0.0081056 -0.2569030 -0.3905096 0.8839895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3345 3845 -0.465579 -0.303653 0.992125 -0.3852900 0.3548357 0.7828450 0.3358526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3346 3046 0.493708 -0.337355 -0.908689 -0.4066309 -0.4320593 0.6462609 0.4799198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3346 3373 0.019232 -1.061621 0.577055 -0.8112597 -0.1890859 0.5500260 0.0597963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3347 3847 -0.739836 0.651491 0.518614 -0.6061342 -0.3599616 0.1580046 0.6914214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3348 3331 -0.566238 1.057336 0.090472 0.1532315 -0.4072016 0.8261176 0.3581014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3348 3371 0.410179 -0.992093 0.034424 0.2884300 -0.4355651 0.8284593 0.2018573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3349 3370 -0.196876 -0.737402 0.683711 0.2723416 -0.4887852 -0.1684405 0.8115090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3349 3849 -0.794708 0.338833 0.467294 0.0375345 -0.2165525 -0.2378353 0.9461134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3350 3369 -0.833115 -0.418702 -0.269719 0.4971739 0.5343901 -0.0044869 0.6835387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3350 3850 0.560894 -0.974928 0.074795 0.4179735 -0.0661364 0.3597765 0.8315558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3351 3328 -0.979908 0.334671 0.393860 0.4203306 -0.3415730 0.4826459 0.6882609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3351 3368 0.799789 -0.281335 -0.479878 0.4686357 0.4515105 -0.2538244 0.7156061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3352 3367 0.411084 -0.117744 0.933346 0.0475148 0.7659400 0.4670593 0.4392424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3352 3852 -0.082292 1.009977 -0.093986 -0.6199534 -0.1518672 -0.2066830 0.7415364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3353 3366 -0.157194 -0.110589 0.950674 -0.1983319 -0.5126574 -0.4114044 0.7270442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3353 3853 -0.464922 0.954215 -0.101348 0.1528993 -0.1695573 -0.2662398 0.9364766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3354 3365 -0.316755 -1.029385 -0.012439 -0.3354554 0.6753367 0.0352498 0.6558562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3354 3854 0.508263 -0.011874 0.857404 0.0533260 0.2870154 0.1240531 0.9483614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3355 3364 -0.242523 -0.346460 0.762365 0.0484677 0.6428675 -0.0462807 0.7630402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3355 3855 0.739877 0.559352 0.390183 0.0891240 -0.6928244 -0.6280029 0.3430213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3356 3856 -0.809738 -0.310147 0.433862 -0.7136050 -0.1237594 0.6310442 0.2779116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3357 3362 0.242304 0.483796 -1.002495 -0.7849607 0.2807027 -0.3449530 0.4313353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3357 3857 0.260220 1.026844 0.558351 -0.5213673 -0.5202742 -0.3009728 0.6057279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3358 3321 -0.130350 -0.919831 -0.734752 0.2333372 -0.8738555 0.4236725 0.0493136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3358 3361 0.075060 0.821533 0.689214 0.4025188 -0.0472408 -0.1786493 0.8965664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3358 3858 0.164624 -0.734362 0.698838 -0.2599944 -0.6082428 0.7488803 0.0402727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3359 3859 0.775941 0.495704 0.352209 -0.0260760 0.9172993 0.3973205 0.0042927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3360 3820 -0.199543 0.504061 0.946681 0.2848323 -0.4263300 -0.3694636 0.7749903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3361 3398 -0.271161 0.922537 -0.158212 -0.4550092 -0.2012871 -0.8328739 0.2424279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3361 3821 0.129047 0.105749 1.089029 -0.5253394 -0.0755831 -0.3306374 0.7803747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3362 3397 -0.533917 0.587683 0.680891 0.2646156 -0.0004712 0.4149347 0.8705214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3362 3822 -0.336663 -0.920074 0.437724 0.5714272 0.1369535 -0.0713559 0.8059920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3363 3356 -0.759734 -0.354039 0.388974 -0.1338825 -0.0313124 -0.7540553 0.6422582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3363 3396 0.962788 0.351772 -0.231211 0.4483676 0.4845074 0.7460898 0.0870007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3363 3823 -0.298087 1.007434 0.253703 -0.1534277 -0.0003005 0.5492226 0.8214709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3364 3024 0.383627 -0.598296 -0.443082 -0.5420091 -0.4553644 -0.1521486 0.6897247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3364 3824 -0.063656 0.726555 0.678517 -0.7508243 0.3139350 0.4321464 0.3885321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3365 3394 0.319149 -0.490716 -0.725131 0.4458315 -0.1497249 -0.4961515 0.7298290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3365 3825 -0.864558 -0.843255 0.320559 0.6730615 -0.5701965 0.2916941 0.3698361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3366 3393 0.952924 0.074131 0.440352 -0.0123827 -0.3604600 -0.7797351 0.5117895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3366 3826 -0.372436 0.125873 0.965091 -0.7117797 -0.3941338 -0.0455251 0.5796169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3367 3392 -0.683279 0.614497 0.064652 0.0470286 0.8971560 0.4368888 0.0450279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3367 3827 0.522014 0.639654 0.601022 -0.4650776 -0.0425999 -0.0118353 0.8841652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3368 3391 0.863774 0.443846 0.416231 -0.4415786 -0.3031901 -0.6353798 0.5562163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3368 3828 -0.829408 0.481469 0.360433 -0.3318128 -0.0266792 0.3579464 0.8723892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3369 3829 -0.195958 -0.250550 1.097489 0.0014550 -0.6396757 0.5893395 0.4934489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3370 3030 0.345457 -0.461594 -0.646693 -0.0714800 0.0930024 0.7474556 0.6538741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3370 3389 0.886629 -0.131979 0.390330 0.3352512 0.1670675 0.9170953 0.1364968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3370 3830 -0.318928 0.515962 0.842374 -0.6153373 -0.5373074 -0.1292387 0.5621016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3371 3388 -0.453885 0.006404 0.819809 0.5234589 0.2671412 -0.5474116 0.5957910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3372 3347 -0.900937 0.074926 0.400302 -0.2571266 0.8736127 0.2273802 0.3449421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3372 3387 0.705413 -0.100389 -0.516005 -0.3044826 0.7799531 0.5182216 0.1743843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3372 3832 0.307541 0.925287 0.603030 0.5010695 -0.0495898 0.7858216 0.3591025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3373 3386 -0.683472 0.606583 -0.062461 0.3350009 0.2040736 -0.7988903 0.4559634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3374 3385 -0.908491 -0.498648 0.163737 0.7143184 -0.1729932 -0.2203481 0.6413028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3374 3834 0.140258 -0.458353 0.952443 0.4941943 0.0104634 0.6894837 0.5294098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3375 3035 0.144577 0.097880 -0.973732 0.0301722 0.4828914 -0.1593037 0.8605393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3375 3344 -0.952145 0.819572 -0.011498 0.1031037 0.3677634 0.8961124 0.2260579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3375 3384 0.702177 -0.532238 -0.001937 0.0831189 0.2230845 -0.8187807 0.5224200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3375 3835 -0.188097 -0.257728 1.007221 -0.0256927 -0.2657678 -0.9634026 0.0237248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3376 3383 -0.565708 0.844482 0.020501 0.5767968 -0.4004530 -0.0604262 0.7094304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3376 3836 -0.896296 -0.630772 0.105988 -0.0837403 -0.1403298 -0.2328193 0.9586920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3377 3382 0.809162 -0.281566 0.086479 0.6200953 -0.1728952 0.3248134 0.6928819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3377 3837 -0.070707 -0.195713 0.930951 0.4377672 0.0231394 0.6163044 0.6542120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3378 3038 -0.799746 0.322355 -0.564603 -0.1598251 0.5815509 -0.7899850 0.1103547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3378 3838 0.954153 -0.191111 0.498147 -0.1813708 0.2457609 -0.9473513 0.0960815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3379 3839 0.542925 0.863738 0.195154 -0.4131216 0.4389628 -0.4850685 0.6335225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3380 3419 0.587931 0.808569 0.091562 -0.2709151 0.0998510 -0.9570253 0.0271539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3380 3800 -0.258803 0.031257 1.023804 0.3878402 -0.2023239 0.6832561 0.5846419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3381 3378 0.132026 0.436495 0.793606 0.7683522 -0.4388266 0.2049836 0.4183871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3381 3418 -0.050980 -0.466984 -1.040395 -0.0955172 0.0084887 0.2552564 0.9621063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3381 3801 0.437555 -0.715457 0.573780 0.4874340 0.3849078 -0.5713623 0.5364691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3382 3417 0.645052 -0.565231 0.449108 -0.0129847 0.3377447 0.8155296 0.4697568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3382 3802 0.465347 0.795949 0.244934 -0.3760757 0.5319861 0.1265953 0.7480183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3383 3416 -0.688248 0.484940 -0.153405 0.3663371 0.1184590 0.5977308 0.7031945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3383 3803 -0.078678 0.205131 0.971731 -0.3448788 0.5712989 0.7152994 0.2074197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3384 3415 0.108672 1.079245 0.460263 0.2221278 0.5649456 0.3894520 0.6926924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3384 3804 0.010895 -0.419677 0.916094 -0.3523051 -0.1064151 0.8766608 0.3098755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3385 3414 -0.479903 -0.168527 0.807105 -0.3454270 0.6082625 0.5496495 0.4567081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3386 3413 -0.061023 -0.837427 -0.163287 -0.7100474 -0.1309514 -0.6409393 0.2605403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3386 3806 0.625224 -0.191673 0.834409 -0.3242966 0.1333096 -0.0334965 0.9359157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3387 3412 -0.377752 -1.007385 -0.137476 -0.3542126 -0.2068437 0.6856986 0.6013041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3387 3807 -0.803582 0.456000 0.478701 0.4009092 0.2854201 -0.5948102 0.6356163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3388 3008 0.386764 -0.940892 -0.221366 -0.2611333 -0.1171221 -0.8891545 0.3570660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3388 3808 -0.372911 1.060679 0.308472 -0.7821377 -0.5623069 -0.2550834 0.0836903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3389 3410 -0.442611 0.005162 0.859677 -0.0753344 -0.1083606 0.3961778 0.9086396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3389 3809 0.731956 0.095001 0.632354 0.2362652 -0.3839151 0.8909130 0.0553359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3390 3010 0.251068 0.459371 -0.576948 -0.3988586 0.0698899 0.0662898 0.9119391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3390 3369 -0.770027 -0.102250 -0.646321 -0.2674753 -0.3216488 0.8847750 0.2053588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3391 3408 0.111595 0.491920 0.777083 0.5792629 0.1140027 -0.6995974 0.4025188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3392 3812 -0.289656 0.893145 0.161217 0.4050853 -0.5423192 -0.5033182 0.5370908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3393 3013 -0.319360 -0.192243 -0.759540 -0.2640520 0.1303852 -0.4753176 0.8290654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3393 3406 -0.449871 0.948267 -0.115068 -0.1451973 0.4929593 -0.1147053 0.8501480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3393 3813 0.307480 0.171945 0.892752 -0.1079927 -0.3388801 -0.9050508 0.2331970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3394 3014 -0.005018 0.387286 -0.820172 -0.2701248 -0.3715581 0.8116266 0.3608870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3394 3405 0.852581 -0.654840 -0.407216 0.6355352 0.2542024 0.4884500 0.5411957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3394 3814 0.194484 -0.444676 0.899160 0.8099467 -0.0866882 0.3202369 0.4836525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3395 3015 0.626409 0.418550 -0.584598 -0.0270875 0.4419789 -0.5353610 0.7192423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3395 3364 -0.317341 -0.393963 -0.975293 -0.6434239 0.0895018 0.7560450 0.0799445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3395 3404 0.265249 0.340127 0.861504 0.2456903 0.0553541 0.2534154 0.9339983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3395 3815 -0.650126 -0.630011 0.555914 0.9010886 -0.0209662 -0.3679997 0.2284207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3396 3403 -0.462156 -0.029128 0.759183 0.2548017 -0.0268888 -0.4945960 0.8304986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3396 3816 0.927024 -0.388088 0.463364 0.4572992 0.1183511 -0.7869444 0.3969748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3397 3402 0.250810 0.977397 0.162757 -0.2073683 -0.4617504 0.8616711 0.0361647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3397 3817 -0.933446 0.147933 0.752719 0.1132077 0.0542703 -0.7188466 0.6837385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3398 3401 -0.110527 -0.879816 0.422650 -0.1420294 0.5000258 0.7321626 0.4401589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3398 3818 0.632710 0.057503 0.755665 0.6918079 0.2775886 0.6665923 0.0010130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3399 3360 0.844282 0.088482 0.022781 0.0645801 -0.3228498 -0.8859666 0.3265893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3399 3819 0.027434 0.584070 0.920881 -0.5847004 0.0554953 0.7298119 0.3498862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3400 3439 -0.359707 -0.265132 -0.911238 -0.6609260 -0.5253426 0.5290731 0.0852857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3400 3780 0.376004 -1.260049 0.193835 0.4656647 -0.2740137 -0.1550538 0.8270618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3401 3438 -0.563753 0.684806 -0.760503 -0.2133052 -0.2151503 -0.5173732 0.8003350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3401 3781 -0.725014 0.157786 0.490007 -0.7132520 0.2612286 0.5510168 0.3455599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3402 3782 0.703830 -0.709834 0.721208 -0.2207117 0.4809204 0.1505292 0.8350706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3403 3436 -0.349463 -0.217152 0.739698 -0.0990191 0.0877232 0.5126626 0.8483378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3403 3783 0.691418 0.726648 0.234647 0.1275407 -0.0676806 0.9891366 0.0275962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3404 3435 0.329441 0.532259 0.678382 0.2730351 -0.6941681 -0.1335549 0.6524918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3405 3434 -0.282715 -0.349156 0.906048 -0.4456783 -0.7813908 -0.4011633 0.1728213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3405 3785 -0.044729 0.979840 0.297882 0.2774356 0.7997266 0.3836382 0.3691728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3406 3433 -0.503249 0.810744 -0.336072 0.3120572 -0.5397648 -0.1534326 0.7666373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3406 3786 -0.722485 -0.165679 0.573892 -0.6848048 -0.1588341 0.5556789 0.4438863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3407 2987 0.536811 -0.807461 -0.122014 -0.3159547 0.8108405 0.1844077 0.4568415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3407 3392 0.932198 0.532563 0.243023 0.5866487 -0.7883415 -0.1648398 0.0847873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3407 3432 -0.615905 -0.608934 -0.144642 -0.6019127 -0.3946034 -0.0662256 0.6910886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3408 2988 0.121012 -0.868324 -0.343851 -0.7537715 0.4502841 0.4709694 0.0852093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3408 3431 -1.219687 -0.004861 -0.162051 -0.1108594 0.3065062 0.9430301 0.0667717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3409 3390 -0.391894 0.690433 0.089031 -0.5421488 0.3955492 -0.5811579 0.4602944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3409 3789 0.604047 0.368289 0.690836 -0.6459387 -0.6565607 -0.3701522 0.1211555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3410 3429 -0.179182 0.246272 0.849941 -0.5675157 0.4295998 -0.6618971 0.2350793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3410 3790 0.493741 -0.804231 0.304549 0.0744261 0.6965865 -0.4063051 0.5866380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3411 3388 -0.482696 0.880929 -0.074092 0.4140816 0.6911483 0.2801938 0.5218638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3411 3428 0.522004 -0.787362 0.015557 0.0255409 0.0441725 0.4182310 0.9069064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3411 3791 0.368768 0.484971 0.699617 -0.4496844 -0.3736084 -0.7760995 0.2363688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3412 2992 -0.244080 0.005842 -1.037908 -0.5486150 -0.2232611 0.7294237 0.3422240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3412 3427 -0.845023 0.740476 0.235462 0.1207429 0.3092216 -0.7969733 0.5046153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3412 3792 0.073510 0.182130 0.977472 0.4275219 -0.0925990 0.8776908 0.1957275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3413 3426 -0.203509 0.847835 -0.443709 -0.7155624 0.5726296 -0.0179682 0.3996785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3413 3793 0.968845 0.368895 0.288860 0.0611219 -0.0759421 -0.6188500 0.7794367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3415 3795 -0.837455 0.322849 0.151460 0.1648182 -0.1629306 0.1696341 0.9578689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3416 3423 0.517269 0.389609 -0.687077 -0.7876273 0.2015484 0.1212198 0.5694974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3416 3796 0.599702 0.518190 0.582335 0.1804839 0.5881118 0.6623701 0.4275698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3417 3422 -1.074156 -0.227680 0.244832 -0.2456771 0.1978012 0.3820669 0.8686439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3417 3797 0.348074 -0.695485 0.916809 -0.0541775 -0.1863469 0.9654448 0.1739425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3418 2998 -0.124020 1.136500 -0.096370 0.3361608 -0.8730568 0.2890583 0.2030101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3418 3421 -0.394168 -0.163263 -0.990702 0.1201313 0.6957764 -0.5064762 0.4949197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3419 3799 0.512182 -0.094569 0.702066 0.6734138 0.5349218 0.4081172 0.3062890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3420 3459 0.878155 -0.662798 0.076615 -0.3683619 -0.3625214 -0.2464542 0.8198464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3420 3760 -0.506657 -0.510905 0.724039 -0.6432913 -0.2562661 0.6815334 0.2366775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3421 3458 1.168625 0.126090 -0.068210 -0.2017345 0.0975594 0.9050831 0.3613999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3422 2962 0.769362 0.673348 -0.297421 0.1559623 -0.5548810 0.5053234 0.6422080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3422 3457 -0.868779 0.818204 -0.021845 0.0383474 -0.5432802 -0.5630915 0.6215336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3422 3762 -0.594557 -0.858530 0.279578 -0.5682646 -0.2750029 0.7748848 0.0316585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3423 3456 0.650094 0.245021 0.866993 0.8825637 0.3916738 -0.0827262 0.2466359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3423 3763 0.127824 -0.904044 0.595738 0.7567304 0.5403963 -0.0081504 0.3677831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3424 3415 -0.726496 0.486551 -0.319769 0.8359727 0.1578056 0.0388144 0.5241569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3424 3455 0.747567 -0.510414 0.603959 0.1158684 -0.4952020 -0.4309846 0.7453870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3425 3414 0.877686 0.156252 0.385994 0.1029227 -0.1724042 0.5832947 0.7870521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3425 3454 -1.021764 -0.381515 -0.335258 0.0763354 -0.3111126 0.8335954 0.4500007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3425 3765 -0.022755 -0.648887 0.818735 0.3534896 0.3143927 0.8750075 0.1027818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3426 3453 -0.349136 0.418521 0.847204 -0.2478397 -0.1103027 0.8944397 0.3555088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3426 3766 -0.239324 -0.846202 0.258137 0.0302790 0.5539258 -0.6276403 0.5461840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3427 3452 -0.057717 -0.916158 -0.191901 -0.2869097 -0.6319959 0.7188979 0.0380764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3427 3767 -0.562208 -0.178600 0.729154 -0.4340775 -0.2422946 -0.2860488 0.8191740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3428 3451 -0.488510 -0.967932 0.058602 0.4904843 0.1026308 -0.7172295 0.4842252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3428 3768 0.346906 -0.098485 0.926679 0.1606343 0.6777798 0.0411655 0.7163216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3429 2969 -0.815323 -0.062616 -0.596661 0.4987404 0.0607462 0.8581423 0.1056393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3429 3450 0.212966 -0.740430 -0.130113 -0.0625926 0.1548821 -0.1697801 0.9712201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3429 3769 0.964765 -0.019615 0.601125 -0.1131007 -0.4513318 -0.6270653 0.6247375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3430 3409 0.494046 -0.621933 -0.412900 -0.7482473 -0.2173188 -0.5647093 0.2720331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3430 3770 0.743369 0.173143 0.543043 0.2387933 0.1988152 0.5387235 0.7830883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3431 2971 -0.006881 0.463052 -1.037337 0.2046318 -0.4979671 0.7426080 0.3983566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3431 3448 0.962507 0.215974 0.267357 0.0813295 0.4028237 0.7025003 0.5810438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3431 3771 0.086386 -0.511221 0.896614 -0.1540192 -0.3530751 0.8676868 0.3142224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3432 3772 -0.120373 -0.218560 1.209295 -0.3372859 -0.4564634 -0.7865072 0.2434867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3433 3446 -0.831378 0.534047 0.135565 0.1318316 0.3959138 0.0271101 0.9083709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3433 3773 0.391601 0.466925 0.842440 -0.1231524 0.4856499 0.8262623 0.2574261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3434 3445 0.529077 0.334541 -0.822773 -0.6722727 -0.3783377 -0.6158873 0.1599776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3434 3774 0.745365 0.286240 0.541813 -0.2752592 -0.0583762 0.8970145 0.3408659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3435 3775 0.414236 0.581753 0.773975 -0.1834500 0.5685702 0.6786815 0.4271596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3437 3402 0.515600 -0.392406 -0.602794 -0.7612142 0.2542920 -0.5486367 0.2342782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3437 3442 -0.551402 0.452007 0.650297 -0.2024994 -0.4114010 -0.8877543 0.0404412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3437 3777 0.919450 0.348278 0.452523 0.4679134 -0.4518473 0.7461611 0.1418969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3438 3441 -1.041805 -0.217402 -0.227791 0.6755822 -0.3257155 0.6464920 0.1398080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3438 3778 -0.125306 -0.859531 0.474617 0.6349991 -0.4224781 -0.4226550 0.4895417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3439 3779 -0.903012 0.532966 0.216166 -0.6145370 0.0383501 0.2978149 0.7295066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3440 3479 0.436983 0.842422 -0.326366 -0.6319429 0.0461498 0.7497522 0.1907614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3440 3740 -0.194344 0.263358 0.788333 -0.2691776 -0.5556701 0.3091319 0.7233337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3441 3741 0.910891 0.511786 0.294100 -0.0988923 0.3026272 -0.2552386 0.9129569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3442 2942 0.468539 -0.341614 -0.635471 0.0183021 -0.8022933 -0.3717222 0.4667045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3442 3477 0.890071 0.090214 0.479892 0.6210107 -0.2677106 -0.7269062 0.1195166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3442 3742 -0.445949 0.323536 0.737609 -0.6958166 0.1746638 0.1144313 0.6871953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3443 3436 0.209090 -0.767706 0.291654 -0.4991567 -0.5437018 -0.3055823 0.6015401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3443 3476 -0.165965 0.932549 -0.426024 -0.1177145 0.0964065 0.1698671 0.9736500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3443 3743 -0.326470 0.297496 0.800547 -0.4754329 -0.5175188 -0.4438305 0.5560147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3444 3435 0.937023 -0.138711 -0.151175 0.5045700 -0.1587997 0.7378412 0.4192638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3444 3475 -0.985073 -0.010121 0.141102 0.1522241 -0.4443689 -0.0873379 0.8784852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3444 3744 0.142138 -0.613383 0.775556 -0.1651382 0.6777741 -0.5427395 0.4677451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3445 3474 -0.949328 -0.118264 0.634553 -0.5432483 -0.0432025 0.3659476 0.7543853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3445 3745 0.747362 0.453950 0.765967 0.0514539 -0.2855837 -0.0259531 0.9566195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3446 3473 -0.678462 0.425697 -0.700136 -0.2366478 0.1519598 -0.9582247 0.0520714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3447 3432 0.576859 -0.693224 -0.246841 -0.3523294 0.2839554 -0.5205101 0.7240874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3447 3472 -0.635652 0.856444 0.342528 0.3924646 0.0115541 -0.5276449 0.7532788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3447 3747 0.577428 0.339917 0.725887 -0.2214510 -0.2693038 -0.8160353 0.4610003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3448 3748 -0.691260 0.495509 0.264064 -0.3378826 0.0358260 -0.5374466 0.7718180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3449 3430 -0.858973 0.366290 -0.527427 0.0856388 0.2406645 -0.8763087 0.4084479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3449 3470 0.892796 -0.597140 0.518598 0.0766148 0.2421753 -0.6850663 0.6827631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3449 3749 -0.462085 -0.889514 0.234809 0.6609890 -0.0449698 0.3752942 0.6482480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3450 3469 0.857893 -0.797672 -0.359976 0.3976047 -0.5330606 0.7459363 0.0365499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3450 3750 0.582637 0.017532 0.797890 -0.3809054 0.2504526 -0.2722422 0.8473894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3451 2951 0.725231 -0.584463 -0.258271 -0.4766015 -0.3495905 -0.7264340 0.3506153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3451 3468 0.428582 0.126887 0.823590 -0.9183346 -0.3509028 0.1153072 0.1422430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3451 3751 -0.712840 0.495129 0.057045 0.8056269 0.0959559 -0.5362002 0.2329099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3452 3467 -0.088320 0.240667 0.830644 0.6753005 -0.2675853 -0.2553651 0.6380878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3452 3752 0.256537 -1.006119 0.401988 0.8601109 -0.1392857 -0.0292154 0.4898522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3453 2953 0.672909 -0.282778 -0.476548 -0.2308615 -0.7902305 -0.1996040 0.5314104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3453 3466 0.315599 -0.441445 0.750553 0.3271457 -0.0241274 -0.2134786 0.9202285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3454 3465 0.115708 0.790326 -0.032629 0.0804204 -0.5994279 -0.2766666 0.7467760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3454 3754 -0.084871 0.043200 1.022229 -0.4553215 -0.2500648 -0.8537348 0.0358741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3455 3464 0.774395 0.397882 -0.654238 -0.1848879 0.2478658 -0.0665119 0.9486597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3455 3755 0.612937 -0.559026 0.565265 0.3867697 -0.1717365 0.6317035 0.6495125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3456 3463 0.359252 0.397547 -0.660103 0.1342565 -0.5622374 0.2448890 0.7783917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3456 3756 -0.687243 0.664595 0.139442 0.3067672 -0.3822985 -0.3296986 0.8068709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3457 3462 -0.210226 -0.330613 0.821442 -0.0481304 0.1247076 0.3518286 0.9264708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3457 3757 0.737765 -0.391431 0.213108 -0.4514223 -0.1654828 -0.6113850 0.6285234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3458 3461 -0.614902 -0.736573 -0.085052 0.7081035 -0.4539638 -0.5204391 0.1471372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3458 3758 -0.634344 0.323250 0.705348 -0.7272056 0.2313457 0.6421935 0.0723785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3459 2959 -0.204867 1.003467 -0.136259 -0.1755787 -0.0069418 0.9422380 0.2851516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3459 3759 0.110238 -0.883475 0.179008 0.8936474 0.0072747 0.4456749 0.0521075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3460 3499 -0.024142 -0.639431 -0.859788 0.1877836 0.6379429 -0.7463836 0.0260326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3460 3720 -0.628396 -0.532626 0.440333 -0.0330226 -0.0422666 0.6630282 0.7466704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3461 3498 0.610417 0.581494 0.184920 -0.0480969 0.0298005 0.0625328 0.9964378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3461 3721 -0.671646 0.605418 0.390935 0.6601347 -0.6785400 -0.2998350 0.1179178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3462 3497 -0.599318 -0.018846 0.804284 0.0399128 -0.2346137 0.7799286 0.5788564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3462 3722 0.045272 -0.876777 0.346078 -0.3247742 0.4723462 -0.7351263 0.3619393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3463 3496 -0.454521 0.198952 -0.686899 -0.3242793 -0.0513550 -0.0867031 0.9405786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3463 3723 0.101971 0.831976 0.444382 0.1163381 0.6886624 0.5495229 0.4585130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3464 3495 0.854743 0.719783 -0.091684 -0.5425365 -0.0684236 -0.8115111 0.2059662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3464 3724 0.567891 -0.448445 0.764850 0.2704566 0.3208379 0.8748901 0.2418337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3465 3494 -0.443201 0.735903 -0.065855 0.5122251 -0.1143849 0.5284017 0.6673329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3465 3725 0.718528 0.581537 0.348005 -0.5516844 0.6142059 -0.5228022 0.2123048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3466 2926 0.818152 -0.590899 -0.183199 -0.9221513 -0.0531011 0.0563150 0.3790065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3466 3726 -0.745689 0.441839 0.279117 -0.5814658 0.4122938 0.7012550 0.0123608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3467 3492 -0.397531 0.803355 -0.175290 -0.3712537 0.5641014 -0.7373517 0.0165162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3467 3727 0.628421 0.566535 0.691323 -0.0053332 -0.2576488 0.8963543 0.3607458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3469 3729 -0.188710 -0.900238 0.211335 -0.1922540 -0.4289622 0.2425289 0.8486516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3470 3489 0.219729 0.552952 0.705362 -0.6419189 0.4070243 -0.5929823 0.2657880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3470 3730 0.713955 -0.484616 0.319233 0.3611240 0.7442526 0.1364042 0.5450426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3471 3448 -1.006508 0.101410 0.199450 -0.2028710 0.7602852 0.2812138 0.5492982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3471 3488 0.894586 -0.131549 -0.075546 0.1603368 -0.4502131 -0.8447681 0.2407635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3472 3487 -0.956680 -0.177863 0.108529 0.4272887 -0.6973488 -0.2998814 0.4911213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3472 3732 -0.176935 0.863165 0.212783 0.4279430 -0.2289740 -0.7788280 0.3973194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3473 3486 -0.171244 -0.417056 -1.067754 -0.6164949 0.0949157 -0.7644089 0.1631078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3473 3733 0.495198 -0.898377 0.229527 0.2710168 -0.1219106 0.3751620 0.8780325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3474 3485 -0.825457 -0.311783 0.501411 -0.2661787 0.7737137 -0.5666164 0.0972713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3474 3734 0.508133 -0.888187 0.352267 0.4158678 0.1149452 0.9001403 0.0599081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3475 3484 -0.582656 -0.123311 0.823855 0.5260789 0.2146461 -0.4908493 0.6604808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3476 3483 0.078209 1.003070 -0.177085 -0.2085573 -0.4783478 -0.0980358 0.8473938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3477 3482 -0.581657 0.226713 -0.763109 0.3635344 -0.7689796 -0.4558928 0.2620589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3477 3737 -0.826402 0.285100 0.672533 0.4110074 -0.4651236 0.4195228 0.6623697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3478 2938 0.909969 0.591585 -0.294013 0.0813489 0.1469992 -0.4087291 0.8970586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3478 3481 0.330057 -0.153999 1.009019 0.7704419 0.3307974 -0.5164967 0.1738493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3478 3738 -0.703155 -0.540465 0.236000 -0.5436755 0.0505218 0.8280113 0.1275218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3479 3739 -0.520133 -0.294853 0.547791 0.3541974 0.4451602 -0.6334446 0.5245232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3480 3519 0.412253 -0.872501 -0.441132 -0.1093879 -0.2211557 0.3656235 0.8974653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3480 3700 0.486660 -0.313757 0.708544 0.5675922 0.1667748 -0.0809574 0.8021665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3481 3518 -0.795584 0.264673 -0.513178 -0.1046863 -0.8394030 0.3709785 0.3831688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3481 3701 -0.800376 -0.081904 0.784441 -0.1831578 0.0963909 0.7391381 0.6409656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3482 3517 -0.039769 -0.255829 1.002055 -0.4993855 0.6958690 -0.0386923 0.5146682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3482 3702 0.314619 0.776332 0.344876 0.4926311 0.5968158 0.3709809 0.5133212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3483 3516 -0.157010 0.931250 0.339390 -0.3952898 -0.1020129 0.5374847 0.7378682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3484 3515 -0.956805 -0.265724 0.380394 -0.4046277 0.2395629 0.8812676 0.0474711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3485 3514 0.798309 0.036106 -0.312353 0.1462526 -0.0628938 0.1056659 0.9815749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3485 3705 0.210325 -0.722517 0.586898 0.7604136 0.3324751 0.3584767 0.4274646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3486 3513 -0.942482 0.475455 -0.294966 -0.4526191 -0.3429590 -0.5314309 0.6285669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3486 3706 0.523197 0.777987 0.421983 -0.1593332 0.5028864 -0.3036613 0.7934154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3487 3512 0.413203 0.171634 0.814918 -0.4145295 -0.1059797 0.2637914 0.8644927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3488 3511 -0.903922 0.265028 -0.648896 0.2938589 0.3289317 0.3744392 0.8156262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3488 3708 -0.330861 0.215303 0.969841 0.4008155 -0.4114582 -0.4819092 0.6616741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3489 3709 0.419824 -0.129804 0.656534 0.2175808 0.2916615 0.0929809 0.9267938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3490 3469 0.737538 0.125163 -0.568434 -0.5462097 -0.0206526 0.7877017 0.2841734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3490 3509 -0.665054 -0.130504 0.796556 -0.4728463 0.2899429 0.4095642 0.7242973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3490 3710 0.083923 1.091153 0.550696 -0.1736697 0.4266336 0.6391748 0.6158557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3491 3468 -0.119166 0.831561 -0.155615 -0.7280110 0.1563383 -0.0473802 0.6658178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3491 3508 0.141793 -0.903749 0.335903 0.4831510 0.2463474 0.4259902 0.7241619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3491 3711 0.069673 0.259573 0.952770 -0.0403373 0.0543053 0.7274250 0.6828445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3492 3507 -0.218862 0.069479 -0.930529 -0.2652173 -0.5196327 0.8030568 0.1214143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3492 3712 -0.545394 -0.767107 0.069197 -0.9125571 0.0240255 0.4010575 0.0762576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3493 3466 0.135793 -1.017195 0.073035 -0.4363302 0.1623180 0.5430120 0.6988611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3493 3506 -0.363859 0.978680 0.133412 0.1026618 -0.8457633 0.3849649 0.3548902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3493 3713 -0.701792 -0.317053 0.536389 0.5684221 0.1514741 -0.4845011 0.6474647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3494 3505 0.230549 0.305814 -0.907395 0.5036982 0.7592255 0.2134600 0.3525616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3494 3714 0.774097 -0.565123 0.162531 0.7701279 0.4426493 0.0557566 0.4559120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3495 3504 -0.418310 -0.247195 0.650908 0.6190510 -0.3150610 0.7139417 0.0883164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3495 3715 0.531064 0.583075 0.657801 -0.2943087 0.3184597 -0.8360456 0.3361451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3496 3503 -0.719673 0.432309 -0.502407 -0.0356872 -0.2787657 0.7612707 0.5843655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3496 3716 -0.074256 0.634460 0.743011 -0.7640516 0.2172917 0.5661321 0.2202363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3497 3502 0.271016 0.512560 0.813687 -0.6265008 -0.4157805 0.0081976 0.6592087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3497 3717 -0.948866 -0.188571 0.407354 -0.4817816 -0.6381238 0.4527755 0.3945616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3498 2918 0.711956 -0.789379 -0.529750 -0.6534536 0.5546977 0.4509910 0.2488290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3498 3501 0.660889 0.553769 0.435213 -0.1997012 0.6240350 0.7265126 0.2070732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3498 3718 -0.631166 0.717617 0.522188 -0.6823549 0.5355290 0.4496199 0.2131723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3499 2919 -0.320054 0.247226 -0.646508 -0.3575645 -0.1374468 0.8263538 0.4127898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3499 3719 0.525289 -0.275347 0.848441 0.5429897 0.0259258 -0.0567115 0.8374209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3500 3539 0.818258 0.212730 0.057813 -0.0844248 -0.7166472 -0.5168578 0.4605944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3500 3680 -0.033250 0.552263 0.820158 -0.3824181 -0.2772822 0.5937352 0.6514211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3501 3538 -0.991432 -0.133277 0.421896 -0.7527678 0.1879535 0.1810812 0.6043374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3501 3681 0.269540 0.649308 0.769363 -0.2678291 -0.3011253 0.3576826 0.8424098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3502 3537 0.888057 -0.237671 0.146295 0.4784041 0.2238600 -0.6612429 0.5327044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3502 3682 -0.399280 -0.941407 0.381346 -0.0914767 0.0983569 0.9697289 0.2039210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3503 3536 0.554166 0.644791 -0.645199 0.0906399 0.1547200 0.6629088 0.7269099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3504 3535 0.812327 0.249933 -0.184552 0.1769564 0.1502402 0.5564984 0.7977617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3505 3534 0.508053 -0.197477 0.837646 -0.2450394 0.0830560 -0.5880381 0.7663345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3506 3533 0.342925 0.797846 -0.453599 -0.3370170 0.1141933 0.5598989 0.7482597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3507 3532 0.629970 0.694300 -0.199781 0.1787875 -0.1975681 0.7262516 0.6336881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3507 3687 0.138850 0.284350 0.959381 0.1832124 -0.3515475 -0.9094395 0.1255684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3508 3531 -0.857699 0.066223 0.576264 -0.5462088 0.0547270 -0.7887866 0.2765441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3508 3688 0.239768 0.887470 0.219813 -0.3134865 0.2475625 0.6703160 0.6253923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3509 2889 -0.068657 0.235301 -1.046925 0.0633498 0.7177580 -0.6634510 0.2016013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3509 3530 -0.894791 0.392929 0.380515 -0.4960169 0.1577188 -0.7136004 0.4688993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3509 3689 0.024919 -0.227870 1.090291 -0.1808371 -0.2009661 0.6980301 0.6630720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3510 3489 0.008686 -0.979845 -0.472300 -0.5990275 0.2106645 -0.7613421 0.1309379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3510 3529 0.022240 0.834576 0.234819 -0.2617970 -0.2814324 -0.7674045 0.5131749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3510 3690 0.671240 -0.150582 0.700179 -0.0035682 -0.2428553 0.6243739 0.7424054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3511 3528 -0.182943 0.239163 -1.008358 -0.8767731 0.2179471 0.2757502 0.3282220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3511 3691 -0.041033 0.953255 0.259105 0.1419772 -0.7043241 -0.3387524 0.6074676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3512 3527 0.654323 -0.747667 0.510791 -0.1152970 -0.7954305 -0.2855965 0.5219498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3512 3692 -0.297430 0.429358 0.500152 -0.5375435 -0.3927905 -0.3804863 0.6418666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3513 3526 -0.689331 -0.655922 0.544230 -0.0407999 -0.2201171 0.9726927 0.0612605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3513 3693 0.242420 0.367981 1.151237 -0.4784449 -0.0140420 0.7040326 0.5246250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3514 3525 0.823481 -0.458424 -0.376917 0.4752865 -0.2135190 -0.3679505 0.7701460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3514 3694 0.271803 -0.442882 0.781504 0.4944186 -0.7015483 0.4526572 0.2418298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3515 3524 0.412953 0.457632 0.892375 0.1198469 0.0874344 -0.7764982 0.6124071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3515 3695 -0.256590 -0.918104 0.444134 0.2327292 0.0232692 0.9602625 0.1522880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3516 3523 0.615666 0.018578 0.638773 0.5183436 0.0309498 0.5328280 0.6681739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3517 3522 -0.611726 -0.803024 -0.197926 0.6907601 -0.4856805 -0.3004418 0.4435083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3517 3697 -0.836703 0.105855 0.463724 -0.1954770 -0.5610364 0.8040645 0.0225234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3518 3521 0.150988 0.521270 0.629950 -0.6699832 0.4680855 -0.1561021 0.5546626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3518 3698 0.648080 -0.671090 0.270711 -0.0081416 -0.0342736 -0.8162350 0.5766451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3519 3699 0.516107 -0.709182 0.672998 -0.5205185 0.5734270 -0.2140903 0.5953212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3520 3559 -0.432157 -0.593203 -0.978061 -0.4598498 0.8844403 -0.0515749 0.0603624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3521 3558 -0.286905 -0.842370 0.345257 -0.3391076 -0.2059266 -0.6369992 0.6609328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3521 3661 0.861352 -0.400725 0.313152 0.5443031 0.4966148 0.1608545 0.6566839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3522 2862 0.398665 -0.784952 -0.439443 -0.2345378 0.7187223 0.2672023 0.5975226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3522 3557 0.448468 -0.218083 0.888422 -0.8763827 -0.1296976 0.4424352 0.1392227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3522 3662 -0.476097 0.822745 0.495382 -0.0785827 0.2728894 0.8626695 0.4185181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3523 3556 0.642264 0.148742 0.691193 0.1550206 0.3979353 -0.8578611 0.2858153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3523 3663 -0.890521 0.007944 0.743314 0.2878674 -0.4034172 0.1952096 0.8463333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3524 3555 -0.644841 0.179374 0.612006 -0.0326879 0.7906984 -0.2483700 0.5586053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3524 3664 0.666521 -0.318952 0.779399 0.0725591 -0.3072139 -0.9325019 0.1754852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3525 3665 0.578245 0.741431 0.550137 0.0241409 0.8791995 0.1803989 0.4403200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3526 3553 0.570856 0.408879 0.792915 -0.0003524 -0.5666517 0.7320669 0.3781320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3526 3666 -0.320084 -0.733171 0.431263 0.2560133 0.3123474 0.1943007 0.8939483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3527 2867 -0.792647 -0.711318 -0.067922 -0.0416622 0.3943337 0.5421237 0.7408557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3527 3552 0.236797 -0.207602 -0.825346 -0.8153747 -0.3290123 -0.4610179 0.1199058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3527 3667 0.762958 0.656116 0.217135 -0.4653451 0.3575202 0.6457355 0.4885272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3528 3551 0.315395 0.344324 0.817732 0.4050005 0.1621953 0.0238203 0.8994998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3528 3668 -0.495531 -0.711157 0.638585 -0.4327503 -0.1526992 0.6391414 0.6171778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3529 3550 -0.468591 -0.449990 0.970081 0.2199564 0.7469938 0.3840679 0.4960961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3529 3669 0.417459 0.706648 0.594332 0.0593522 0.1455807 0.1813019 0.9707797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3530 3549 -0.210508 -0.818284 -0.604833 0.2326699 0.5166285 0.8212479 0.0671692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3530 3670 0.646776 -0.382727 0.422565 0.6594549 0.2426158 0.5163831 0.4894949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3531 3548 0.758145 -0.418197 -0.366696 0.3076072 0.2629872 0.8364547 0.3695390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3532 3547 0.472722 -0.517218 -0.650366 0.1692633 -0.4554546 0.3368474 0.8065016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3532 3672 0.675294 -0.171919 0.651693 0.6785138 0.0877464 0.6590981 0.3122647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3533 2873 -0.068248 0.849583 -0.005262 0.5282819 0.5769368 0.0127430 0.6228160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3533 3546 0.959753 0.041808 0.177093 -0.2058741 -0.5981836 0.6859941 0.3594500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3533 3673 -0.160909 -0.954263 0.178827 0.7636675 0.2950891 -0.5400582 0.1951191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3534 3545 0.687192 -0.004583 0.520099 0.7415500 0.3199161 -0.0352463 0.5886552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3534 3674 -0.332499 -0.737326 0.370950 0.7819361 -0.1330726 -0.0405206 0.6076394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3535 3544 0.586819 -0.812133 0.287378 0.1046185 -0.0384144 0.9759389 0.1874104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3535 3675 -0.882650 -0.531678 0.214473 -0.1193619 -0.1418713 0.3678361 0.9112200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3536 3543 0.739121 -0.403548 -0.227432 -0.0144055 0.3264620 0.9062423 0.2682164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3537 3677 0.084472 -0.177223 0.920516 0.2502714 0.0364139 -0.9608793 0.1129127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3538 2878 0.143854 0.879384 -0.573993 -0.1722445 0.6207104 -0.7646056 0.0207058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3538 3541 -0.978364 0.011369 -0.303909 -0.5345125 0.0915261 0.8266658 0.1501434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3538 3678 -0.096594 -0.932744 0.491212 0.3999251 0.1731658 -0.5422450 0.7183619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3539 2879 -0.685192 -0.629370 -0.477941 0.5182570 0.5018613 0.3470189 0.5992685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3539 3679 0.441514 0.900587 0.440309 -0.2635955 0.2965509 -0.1657852 0.9028235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3540 3579 -0.885443 -0.164332 -0.576975 -0.1249997 -0.3460391 0.0923676 0.9252569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3540 3640 -0.370849 0.684798 0.544351 -0.4550533 0.0983654 0.8779472 0.1116217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3541 2841 0.619226 -0.687621 -0.047600 -0.7734161 -0.6095423 -0.0044637 0.1739709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3541 3578 0.460471 0.254635 0.888372 0.0956304 -0.8745620 0.1315617 0.4568233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3541 3641 -0.454196 0.807965 0.034555 -0.2771169 -0.5730390 -0.6089185 0.4733400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3542 3537 0.835935 -0.437047 0.585492 -0.3528345 0.1394615 0.5540118 0.7410326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3542 3577 -0.959058 0.361690 -0.393500 -0.4443371 -0.0149974 -0.6672833 0.5975555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3542 3642 -0.158127 0.722513 0.678078 -0.7913601 0.0848800 0.5793880 0.1756534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3543 2843 0.423549 -1.057360 -0.082944 0.2300309 0.3907260 0.8629017 0.2232032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3543 3576 -0.788754 -0.330751 -0.483997 -0.4583215 -0.4852783 -0.7270095 0.1609459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3543 3643 -0.298587 0.881167 0.105669 -0.0027252 0.4771791 0.6988887 0.5327732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3544 3575 -0.775838 0.601780 0.233345 -0.2971861 0.1770189 0.3791515 0.8582475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3544 3644 0.739730 0.695577 -0.016731 -0.5655097 0.7332631 0.2882373 0.2438099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3545 2845 0.867845 -0.188702 -0.182440 -0.0839698 -0.1241281 -0.9530276 0.2632104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3545 3574 0.119413 0.889426 -0.166780 -0.3520270 -0.2974325 -0.0225401 0.8871882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3545 3645 -0.919139 0.497320 0.337150 0.2856403 -0.7390243 0.0820856 0.6045782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3546 3573 -0.802469 -0.373255 -0.801398 -0.3416329 -0.6351523 -0.1083255 0.6842033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3546 3646 -0.661743 -0.060248 0.550359 0.0888193 -0.1420899 0.1778186 0.9696918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3547 3572 -0.501297 -0.822235 -0.248124 -0.1489807 0.6235004 -0.6969774 0.3213635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3548 2848 0.342416 -0.903240 -0.034364 0.1612532 -0.8498719 -0.2005064 0.4599048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3548 3571 -0.792311 -0.328652 0.164227 -0.6585652 0.1431905 -0.1035065 0.7314881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3548 3648 -0.374469 1.014696 0.140912 -0.7899777 0.4153030 0.4087843 0.1906674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3549 3570 -0.307370 -0.151672 -0.813384 0.4818103 -0.0440783 -0.8748117 0.0249086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3549 3649 -0.738793 0.860080 0.009919 -0.0096895 0.2044784 0.7212195 0.6617682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3550 3569 -0.634443 0.330992 -0.584436 -0.5471063 0.0464034 -0.1046370 0.8291999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3550 3650 -0.240709 0.797173 0.601195 -0.2925187 -0.8263926 -0.1530928 0.4561476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3551 3568 0.076913 0.999884 0.451191 -0.0353852 -0.1264360 0.2266935 0.9650761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3551 3651 -0.678444 -0.024379 0.720796 -0.0159969 -0.6073629 0.5752031 0.5477188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3552 3652 0.660006 -0.012675 0.941522 -0.3041095 0.5637342 0.2418738 0.7288472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3553 3566 0.079170 -0.813058 -0.266781 -0.1311324 -0.5761977 -0.0461789 0.8053993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3553 3653 -0.086524 -0.380739 0.835038 -0.0443811 0.5581486 -0.1082666 0.8214492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3554 3525 0.837081 -0.461047 -0.471978 0.6034764 0.5167368 0.6011321 0.0862530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3554 3565 -0.591211 0.316999 0.281507 -0.4550731 -0.7474614 -0.4538703 0.1679633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3554 3654 0.523590 0.372983 0.695056 -0.5523572 -0.3421474 -0.6458805 0.4008428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3555 3564 -0.507721 -0.187594 -0.812021 -0.3013125 -0.9050975 0.2896244 0.0782748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3555 3655 -0.804741 -0.327567 0.398381 0.3497103 0.3573503 -0.8464271 0.1832066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3556 3563 -0.874740 -0.174722 0.655475 0.7573416 -0.4561173 0.4613528 0.0744600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3556 3656 0.153270 -0.843291 0.120424 0.1474042 0.9349203 -0.2561700 0.1964000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3557 3657 -0.185276 -1.025022 0.214314 0.6241283 0.3634407 0.0046115 0.6916311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3558 3561 0.717533 -0.384123 -0.453212 0.6535137 0.6466861 0.3451139 0.1887149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3558 3658 0.513342 0.762769 -0.100225 0.4071716 0.1691364 0.8961158 0.0507994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3559 3659 0.475754 -0.770630 -0.011445 0.8035895 0.1923530 -0.4519340 0.3361545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3560 3620 -0.539782 -0.413765 0.606201 -0.6619573 0.0028135 0.7262802 0.1852609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3561 3598 -0.898544 -0.086439 0.813625 0.1520411 0.3775153 -0.3883267 0.8267817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3561 3621 0.586606 0.461446 0.472786 -0.0010213 -0.3770050 -0.4195102 0.8257587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3562 3557 -0.467489 -0.837123 -0.519434 0.3361565 0.7533905 -0.5416494 0.1612997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3562 3597 0.367065 0.913731 0.543457 0.1883886 -0.2129385 0.6062720 0.7426986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3562 3622 -0.434773 -0.374276 0.669327 0.3118570 -0.3266762 -0.8883585 0.0827465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3563 3596 0.204505 0.468794 -0.907559 0.7324932 -0.0467602 0.6790765 0.0110644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3563 3623 0.893481 0.547169 0.321140 0.4139102 0.5457493 0.1496597 0.7130483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3564 3595 0.134273 0.139105 1.099331 -0.1041916 0.9441101 -0.1000714 0.2962867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3564 3624 0.527174 -0.991956 -0.008991 -0.1526363 0.7603840 -0.1841417 0.6038296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3565 3594 1.043635 -0.346397 0.102684 -0.5005238 -0.6777605 -0.0381735 0.5372703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3565 3625 0.349559 0.829495 0.036844 -0.5954166 0.3028027 0.3141146 0.6746271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3566 3626 0.973297 -0.384415 0.368422 0.1562176 -0.3792087 0.6854996 0.6015706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3567 2827 -0.504652 0.875494 -0.493436 0.5687512 -0.3119451 -0.4482897 0.6150193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3567 3552 -0.857222 -0.623121 -0.234997 -0.2630662 0.2725794 -0.8052407 0.4561623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3567 3592 0.838872 0.695216 0.258274 -0.2306032 0.3921974 -0.5194812 0.7232861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3567 3627 0.322721 -0.776442 0.665020 0.1397588 0.6931860 -0.3045437 0.6381331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3568 2828 0.497007 -0.275315 -1.038062 -0.1790096 0.3350574 -0.8324481 0.4033884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3568 3591 0.745434 0.529203 0.192311 -0.3922654 -0.0352649 0.4906510 0.7772682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3568 3628 -0.431448 0.194391 0.936924 0.2670647 0.0508783 -0.5215363 0.8087569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3569 3590 -0.688468 0.777995 0.007357 -0.1351697 0.2080595 -0.9288201 0.2751975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3569 3629 -0.162234 -0.105643 1.017335 -0.4458834 -0.4107223 -0.4247478 0.6723723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3570 3589 0.963836 -0.050787 -0.322502 -0.1349220 0.2541716 -0.5282349 0.7988496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3570 3630 0.224442 -0.687598 0.644265 -0.1182469 -0.1270699 -0.7049175 0.6877225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3571 2831 0.595047 0.092986 -0.868734 0.0160378 -0.4267839 0.6997824 0.5726280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3571 3588 -0.775203 0.094946 -0.449389 0.4692922 0.1749258 -0.5746987 0.6472150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3571 3631 -0.484138 -0.020237 0.748838 0.2976612 0.3004487 -0.6590990 0.6218657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3572 2832 0.286170 -0.319190 -0.884616 -0.4690746 0.4449897 0.7219088 0.2465782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3572 3587 1.041410 0.205800 0.378995 -0.5587845 -0.5262330 -0.0530756 0.6387657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3572 3632 -0.270862 0.461104 0.803262 -0.0434814 0.2150779 0.9753711 0.0224067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3573 3586 -0.882042 -0.216097 0.169256 -0.0337920 0.1954514 -0.9190132 0.3406929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3574 3585 0.302501 0.905112 0.312243 0.4496256 -0.3974037 0.4697024 0.6475236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3574 3634 -0.203644 -0.125316 1.027463 -0.1346297 0.3153723 0.7756334 0.5299132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3575 3584 -0.288144 0.874675 0.385944 0.0679749 0.5940305 0.7479325 0.2882779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3575 3635 0.699589 -0.259336 0.787324 -0.2855571 -0.1830802 0.9149891 0.2184806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3576 2836 -0.430676 0.567213 -0.668821 -0.0298896 0.1610803 -0.6790742 0.7155544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3576 3583 0.098848 -0.748721 -0.607042 -0.1670461 -0.2540333 0.9350709 0.1822228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3577 2837 0.269126 0.313143 -0.715028 0.0544723 -0.0782373 -0.9616512 0.2571744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3577 3582 -0.582315 -0.549372 -0.724253 0.0861202 -0.8092497 0.5710091 0.1079207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3577 3637 -0.218085 -0.515926 0.876900 0.2680188 0.6519577 -0.6091419 0.3634051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3579 3639 0.236724 0.222115 1.061046 -0.5264623 -0.3865264 -0.0438154 0.7559861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3580 3600 -0.422303 -0.229865 1.014884 0.1040007 -0.2642337 -0.1623388 0.9449923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3581 3578 -0.253778 0.530039 -0.749416 0.5465240 -0.7780513 -0.2717278 0.1487004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3581 3601 -0.960644 0.175634 0.332420 0.7109121 -0.4714989 0.0291122 0.5210041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3582 3602 0.472063 -0.939572 0.207274 0.6122171 0.4819923 -0.2438920 0.5773996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3584 3604 -0.949356 0.425380 0.331586 0.5274102 -0.5429915 0.0466772 0.6517821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3585 3605 0.621968 0.242519 0.495582 -0.1454209 0.0642926 0.1731489 0.9719767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3586 2806 -0.192411 -0.570877 -0.768532 -0.2644423 -0.5150194 -0.8153639 0.0026443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3586 3606 0.099509 0.566970 0.653909 0.0893458 0.2858790 0.0078040 0.9540595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3587 3607 0.702084 -0.543637 0.168849 -0.2856594 -0.3144342 -0.9052668 0.0046756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3588 3608 -0.662374 -0.333479 0.536398 -0.2259220 -0.3594504 0.7578180 0.4954457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3589 3609 0.628529 -0.312171 0.600983 0.0288885 0.7429957 -0.0388123 0.6675451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3590 3610 0.252773 -0.366181 0.755689 -0.3544999 -0.0794773 -0.2575659 0.8953619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3591 3611 -0.573088 -0.097725 1.001771 0.5691999 -0.0202673 -0.5433115 0.6167766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3592 3612 0.553423 -0.474760 0.534942 -0.1631532 0.8126492 -0.5173652 0.2128747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3593 3566 0.114441 -0.668058 0.534518 -0.2659721 -0.0760994 -0.9548625 0.1081912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3593 3613 -0.893178 0.323800 0.557514 0.2477174 -0.0560549 -0.0587591 0.9654229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3594 3614 0.749138 0.513895 0.388278 -0.1764958 0.7600148 0.1636384 0.6036963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3595 3615 -0.251095 -1.010624 0.046472 0.1821668 -0.2326374 0.2507636 0.9218529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3596 3616 0.503359 -0.574455 0.642582 0.5144911 -0.3552841 0.3912760 0.6752594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3597 3617 -0.007496 0.545629 0.797666 -0.7901788 0.2534744 0.3339209 0.4470626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3598 3618 -0.317055 0.769441 0.555319 -0.5783483 -0.2519987 -0.6502526 0.4232983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3599 2819 0.243764 0.130504 -0.950776 -0.4024124 -0.1856768 0.7701694 0.4587238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3599 3560 0.935585 0.255376 0.463532 0.3386655 0.4074502 -0.5899224 0.6093289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3599 3619 -0.281790 -0.126239 0.918425 0.3712673 0.0125587 -0.5796507 0.7252640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3600 3639 0.121162 -1.088695 0.131172 -0.6186324 -0.0201873 -0.6439173 0.4497298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3601 3638 -0.901257 -0.256249 -0.115323 -0.2099140 0.3199087 -0.0140056 0.9237956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3601 4381 -0.190078 0.856473 0.014377 0.0677068 0.3663766 0.2897443 0.8816077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3602 3637 0.346906 -0.951365 0.206312 -0.5348842 -0.2109882 0.7242473 0.3805900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3602 4382 -0.403686 0.149225 1.102814 -0.1468757 -0.4840410 0.4505832 0.7355995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3603 3636 0.213220 -0.838032 -0.263610 0.3786842 0.5567318 -0.4031062 0.6198010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3604 3635 -0.565632 -0.302965 0.697318 0.8635041 -0.3967720 -0.3109203 0.0161616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3604 4384 -0.150481 0.977097 0.117493 0.2119874 0.0700400 0.9307912 0.2894537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3605 3634 -0.616047 0.112515 0.582709 0.4391633 0.6884494 0.1325480 0.5617865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3605 4385 0.705254 -0.191811 0.792857 -0.1501926 -0.2571162 0.2297366 0.9265822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3606 3633 -0.586128 0.135424 -0.982756 -0.4041446 -0.2310790 -0.8743044 0.1373374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3606 4386 -0.376454 0.938038 0.406775 0.1326376 -0.1349539 -0.4532093 0.8710890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3607 3632 0.837901 0.458067 -0.199032 -0.5854590 -0.2697348 0.3368843 0.6862870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3607 4387 -0.562045 0.630162 0.197709 -0.9221578 0.0762627 0.0664464 0.3733550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3608 3631 1.045953 0.242911 -0.014824 0.0365706 0.4757525 -0.7422678 0.4704899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3609 4389 -0.818977 -0.358360 0.653525 0.2222118 0.0760834 -0.5649559 0.7909855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3610 3629 -0.174680 -0.052508 1.137016 0.7363456 -0.5809392 0.1690674 0.3028547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3610 4390 0.819930 -0.592799 0.217974 -0.0336354 -0.5300136 0.8115866 0.2434780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3611 3628 -0.466808 -0.643042 -0.145661 0.1735444 -0.0534107 -0.4280486 0.8853271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3611 4391 -0.367261 0.332524 0.647234 -0.3747192 0.1124414 -0.8201067 0.4175733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3612 3627 0.007550 0.537740 0.919924 -0.2922672 -0.6502127 0.5887050 0.3810902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3612 4392 -0.289965 -0.653538 0.385372 0.8487469 -0.3261397 0.3772202 0.1759731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3613 3626 0.349040 -0.242869 0.801945 -0.7423096 -0.2065464 -0.2593726 0.5822722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3613 4393 -0.642837 0.538550 0.475726 0.2974333 -0.7864402 -0.4930940 0.2233910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3614 3625 -0.855808 -0.747926 -0.319637 -0.3454744 -0.2099848 0.6311088 0.6620087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3614 4394 -0.407437 0.150335 0.701020 -0.5484884 -0.4413080 -0.5832521 0.4052465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3615 3624 0.966334 -0.240769 0.282561 -0.2458094 -0.0187372 -0.3367610 0.9087457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3616 3623 0.254954 -0.548991 -0.603528 0.6069119 0.3956900 0.6844223 0.0815681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3616 4396 0.648445 -0.236067 0.704964 -0.0185529 -0.3888782 0.6600070 0.6425109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3617 3622 -0.608947 0.661499 0.173268 0.3921915 -0.3947244 0.7127356 0.4270673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3618 3621 -0.169081 0.528721 0.945889 0.9306699 -0.0293569 0.0199779 0.3641326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3618 4398 0.404025 -0.646904 0.570022 -0.1252741 0.1796269 -0.5682497 0.7931790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3619 4399 -0.384755 0.221275 0.932637 -0.3378593 -0.0855441 -0.6418669 0.6830375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3620 3659 0.188137 -0.603388 0.825121 0.2164576 -0.1811136 0.3181640 0.9050501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3621 3658 0.160391 0.322421 -0.897962 -0.5287695 0.3284560 0.7242322 0.2966600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3621 4361 0.382651 1.095405 0.023000 -0.5339985 -0.3349193 -0.6868253 0.3618643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3622 3657 0.716750 0.409304 -0.773507 -0.2881493 0.1055580 -0.6222935 0.7201238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3622 4362 0.214318 0.614760 0.536177 -0.4093219 0.1179128 0.8963505 0.1229145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3623 3656 -1.045694 0.296009 0.197403 -0.7967678 0.2592111 0.4192593 0.3495602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3623 4363 0.195515 0.732215 0.632557 -0.6154623 -0.4735800 -0.3834856 0.4998668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3624 4364 0.127243 -1.034984 0.684547 0.3338752 0.3871151 0.1367930 0.8485027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3625 3654 -0.650151 0.828129 0.648053 0.2788896 -0.2811113 0.0241395 0.9179403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3626 3653 0.815049 -0.395182 -0.231847 -0.6064336 -0.6950930 0.3735635 0.0976439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3626 4366 -0.412306 -0.734999 0.138344 0.7357611 -0.4126169 -0.4046814 0.3530380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3627 3652 0.420830 -0.693903 -0.368551 0.1468870 0.2664039 -0.2514981 0.9188046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3627 4367 -0.529129 -0.413608 0.773760 0.4202967 0.2365751 0.2996491 0.8231606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3628 3651 0.306112 -0.800062 0.288850 0.0071406 -0.3554202 0.8479310 0.3932409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3628 4368 -0.530421 -0.042202 0.784377 0.1841684 0.0543139 0.7951116 0.5752647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3629 3650 0.451127 0.302841 -0.853079 0.2576343 -0.0023864 -0.5042420 0.8242323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3630 3649 0.309315 -0.916451 0.403450 0.5620686 0.1971092 0.0399999 0.8022636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3631 3648 -0.436838 0.734238 0.289969 0.6495146 0.4752558 -0.5740672 0.1506970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3631 4371 -0.681356 -0.821836 0.501904 0.0025200 -0.2761083 -0.3973991 0.8751182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3632 3647 0.831873 -0.022767 -0.040615 0.1568455 0.3630863 0.7042226 0.5896086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3632 4372 0.089696 -0.027775 0.784109 -0.2729261 -0.0497193 -0.7805297 0.5601899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3633 3573 -0.558228 0.811581 -0.372994 -0.4118315 0.5411754 -0.3385730 0.6503017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3633 4373 0.462293 -0.806409 0.382877 -0.2120714 0.7187761 -0.6620939 0.0042718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3634 3645 -0.299423 0.340817 -0.976112 -0.0501390 0.8156904 0.5736260 0.0555743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3635 3644 -0.461946 0.787100 -0.613760 0.8540363 0.3740903 -0.2284394 0.2801678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3636 3576 0.558787 -0.727679 -0.345807 -0.0925055 -0.2937999 -0.9406272 0.1426355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3636 3643 0.406214 -0.330961 1.016278 -0.0567259 0.0356698 0.7319410 0.6780650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3636 4376 -0.528585 0.788478 0.141397 -0.8613342 0.2256024 0.1225252 0.4384000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3637 3642 -0.824375 0.314010 -0.326829 0.0690562 0.4843953 -0.1235224 0.8633277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3638 3578 0.308792 -0.984895 -0.415306 0.0329592 -0.8206509 -0.0784418 0.5650598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3638 4378 -0.246821 0.900690 0.401579 -0.6397707 0.4368998 0.2862307 0.5638120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3639 4379 0.760736 -0.513226 0.117808 0.5855115 0.2073351 -0.4401548 0.6484229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3640 4340 -0.214048 -0.091447 0.954553 0.5521627 0.2139331 0.0362867 0.8050045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3641 3638 0.495375 0.841547 0.303456 0.4394315 0.3884017 0.6284138 0.5110188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3641 3678 -0.341257 -0.894752 -0.435716 0.1532517 -0.1958368 0.9685637 0.0067951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3642 4342 -0.715101 -0.809201 0.103440 0.3053415 -0.1164443 0.1545153 0.9323799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3643 3676 -0.349519 -0.404616 0.912908 -0.5760454 0.0457639 -0.4947745 0.6490574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3643 4343 0.910800 0.212489 0.427367 0.0546900 0.8552097 -0.2541779 0.4483515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3644 3675 0.515727 -0.961056 -0.132709 0.9052395 0.1242542 -0.3827083 0.1365162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3644 4344 -1.031234 -0.271640 0.377242 0.4251350 -0.3297844 -0.0594649 0.8408130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3645 3674 0.617692 -0.783368 0.568802 -0.0329138 0.5362321 0.2520449 0.8048883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3646 3633 -0.917539 -0.095337 -0.408178 -0.2595271 -0.6323992 0.5762374 0.4479591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3646 3673 0.821729 0.105875 0.496657 -0.0850806 0.3707852 0.5655566 0.7317276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3646 4346 -0.701778 -0.039104 0.782354 -0.1687653 0.5650898 0.5854322 0.5562921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3647 3547 0.325029 -0.374207 -0.678085 0.4978619 0.0133943 0.8638084 0.0760869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3647 3672 0.062608 -0.776510 0.686146 -0.2940029 -0.6448158 -0.5212327 0.4754907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3648 3671 0.184740 -0.972488 -0.253503 0.6350298 0.1195146 -0.6956792 0.3138215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3648 4348 -0.811824 -0.290875 0.587365 0.6189389 -0.0028890 -0.1311831 0.7744013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3649 3670 -0.184902 0.108184 1.144062 -0.5645925 -0.4286914 -0.6293479 0.3184027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3651 3668 -0.666287 0.257220 0.640521 -0.1449313 0.6211126 0.5194720 0.5686501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3652 4352 -0.681571 -0.641613 0.633863 0.8346733 -0.4353106 -0.2143749 0.2605159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3653 4353 -0.829865 -0.319910 0.353196 -0.2192419 0.0740480 0.7423091 0.6288299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3654 3665 -0.527119 0.798346 -0.006141 0.3343464 0.6884200 -0.0789510 0.6387934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3654 4354 0.569666 0.132061 0.837143 0.2944210 0.3857630 0.2190265 0.8464813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3655 3624 0.883886 0.407452 -0.110556 0.1398249 -0.6960288 0.7016258 0.0609436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3655 3664 -0.791510 0.035080 0.186891 0.5385986 0.4854887 0.3183617 0.6106211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3655 4355 0.278985 -0.507367 0.921463 -0.3554295 0.0107891 0.5396618 0.7630980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3656 3663 -0.653748 0.506133 0.479837 0.8710167 -0.1257117 -0.3592618 0.3105761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3657 3662 -0.361196 0.912996 0.093312 0.0171885 -0.4068657 0.7851711 0.4665524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3657 4357 -0.721184 -0.028552 0.645017 -0.3921183 0.2112028 0.7105892 0.5447014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3658 4358 0.020451 -0.646711 0.850142 0.3277251 0.6765803 -0.6577349 0.0471189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3659 4359 0.292677 0.747833 0.256569 -0.8506477 0.2934612 0.3308762 0.2842533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3660 3699 -0.505841 0.883224 0.349570 -0.7983718 0.2670549 0.3091169 0.4424147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3660 4320 0.875327 0.411395 0.002833 -0.7309754 -0.2143116 -0.6364292 0.1212574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3661 3658 -0.963688 -0.033380 -0.125328 -0.5679202 -0.0467044 0.1888316 0.7997674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3661 3698 0.890479 0.032171 0.046110 0.5033923 -0.4104288 -0.0552123 0.7583508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3661 4321 0.018899 0.205733 1.032556 0.3662278 0.0516472 -0.5905198 0.7172838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3662 3697 0.747910 -0.243525 -0.566776 0.1450961 -0.2968196 0.5253318 0.7841376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3662 4322 0.628949 0.106952 0.864879 0.2479788 -0.2868479 0.6282021 0.6794019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3663 3696 -0.953335 0.140829 0.096998 -0.3838754 -0.2640587 -0.3721305 0.8027649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3663 4323 0.143072 0.753332 0.451632 -0.8580940 -0.1928191 -0.2464042 0.4071614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3664 3695 -0.420378 -0.185897 -0.862726 0.0257560 0.0923739 0.4843511 0.8696020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3664 4324 -0.405215 0.515207 0.403466 -0.7239468 0.2896739 0.6069789 0.1535144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3665 3694 0.097340 0.510668 -0.636321 -0.3115574 -0.4968271 0.7909374 0.1746791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3665 4325 -0.723894 0.540367 0.386410 -0.4488534 -0.5983572 -0.1429874 0.6481157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3666 3693 -0.294078 -0.768706 -0.573574 0.1653659 0.0399271 -0.5150116 0.8401328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3666 4326 -0.791840 -0.112941 0.380293 -0.0404629 0.3243153 0.7381127 0.5902305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3667 3652 0.868832 -0.231297 -0.448375 -0.2470918 -0.7399913 0.5962186 0.1894251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3667 3692 -0.726052 0.211942 0.621755 0.1323929 -0.0353485 -0.3211206 0.9370721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3667 4327 0.001285 -1.008972 0.498315 0.5850971 0.5604223 -0.2062422 0.5486824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3668 3691 -0.433668 0.871780 -0.173660 -0.0527903 0.0048042 0.5387492 0.8407969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3668 4328 -0.692239 -0.032595 0.531529 -0.3156832 -0.0974344 -0.7998656 0.5010645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3669 3650 -0.659836 -0.265161 0.777603 0.0777718 -0.3352259 0.0169202 0.9387699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3669 3690 0.749515 0.194732 -0.811850 0.3986718 -0.1345715 0.9046298 0.0677956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3669 4329 0.513760 0.607047 0.563369 -0.0482708 -0.7648620 -0.5048156 0.3972621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3670 3689 1.121433 0.042086 -0.095505 -0.3476677 -0.0046215 0.8944435 0.2812058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3670 4330 0.074439 0.369385 0.796764 0.0987229 -0.5582607 -0.0990380 0.8177960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3671 3688 0.484196 0.782308 0.523394 -0.0794480 -0.5009665 0.7657727 0.3953640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3671 4331 -0.479718 -0.130864 0.775866 -0.1219814 -0.3233279 0.8819124 0.3206402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3672 3687 0.819060 -0.000741 -0.670297 0.0491538 0.4183610 -0.3875245 0.8199895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3672 4332 0.730747 0.144608 0.600106 -0.2555783 0.6636567 -0.6868539 0.1499039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3673 4333 -0.554827 0.524419 0.342231 -0.5733794 0.0103383 0.6174678 0.5383890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3675 4335 -0.846266 0.152576 0.566832 0.5034328 -0.0442277 -0.4551080 0.7331276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3676 3536 -0.431264 -0.042344 -0.881404 -0.0445622 -0.3527506 0.9152050 0.1896868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3676 4336 0.462986 -0.063819 1.047106 0.0185446 0.5133354 -0.8424143 0.1627296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3677 3642 -0.235329 -0.920904 -0.344816 0.6330129 0.4717021 -0.5707926 0.2258042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3677 4337 -0.514100 -0.009894 0.771310 -0.2294509 0.1486831 -0.3452119 0.8978164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3678 3681 0.421626 0.871180 -0.125359 0.2880588 -0.4087302 0.5250040 0.6887181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3678 4338 0.277097 0.103753 0.979459 -0.5346191 0.0940310 -0.8012623 0.2516335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3679 3640 -0.775349 0.240053 -0.268807 -0.3459211 0.0787514 0.7995285 0.4846556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3679 4339 -0.204131 0.313210 0.957457 -0.6299581 0.3429706 0.4700258 0.5143926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3680 3719 -0.530250 0.458069 0.944572 -0.1143048 -0.0005435 -0.8889196 0.4435720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3680 4300 0.402565 -0.659613 0.614865 0.8868212 -0.0726594 0.4284142 0.1572580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3681 3718 0.618394 -0.174325 -0.897711 0.2856978 0.6307671 -0.5787361 0.4307832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3681 4301 0.911302 -0.299387 0.492033 0.6755838 -0.2905135 0.6772062 0.0240880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3682 3677 -0.959567 -0.006813 -0.149421 -0.3340585 -0.1684830 -0.5831180 0.7211045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3682 3717 1.012894 0.025179 0.104785 -0.4206500 -0.3030843 -0.8348174 0.1851307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3682 4302 0.076144 0.882282 0.212149 -0.9067201 0.0508730 -0.1220729 0.4004607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3683 3503 0.516921 -0.621757 -0.611446 -0.2487415 -0.5367460 0.5294108 0.6080754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3683 3676 0.045550 0.818213 -0.622465 -0.2620941 -0.4768821 -0.1576521 0.8240364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3683 3716 -0.111061 -0.991533 0.724421 -0.8374614 0.1884673 0.2728875 0.4343627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3683 4303 -0.434404 0.448866 0.642122 0.1742542 -0.5549986 -0.6386847 0.5036804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3684 3504 -0.042494 -0.483922 -0.828491 -0.1213869 -0.4220632 0.8677017 0.2328553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3684 3675 -0.607224 0.722783 -0.244959 0.3122954 -0.0083431 -0.8053102 0.5038625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3684 3715 0.778559 -0.630248 0.253464 0.3364236 0.0520940 -0.9376543 0.0700706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3684 4304 0.213413 0.551493 0.701270 -0.4074693 0.0765260 -0.6889409 0.5945359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3685 3505 -0.232001 0.081574 -0.917770 0.3508460 0.3794383 -0.5388470 0.6652650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3685 3674 -0.085502 -0.964091 -0.262897 0.0616331 -0.1389033 -0.9213385 0.3578303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3685 3714 -0.115965 1.103349 0.240192 0.2484195 0.0346163 -0.4790214 0.8412062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3685 4305 0.212443 -0.131030 0.897344 0.4355797 -0.0678168 -0.1454778 0.8857242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3686 3506 0.686505 0.588365 -0.709058 0.2011377 -0.5703930 -0.5425741 0.5829312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3686 3713 -0.629058 0.294186 -0.852834 -0.6030159 -0.4400943 0.6233701 0.2325910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3687 3712 0.679425 0.699198 -0.101494 0.5703416 -0.5058605 -0.3890816 0.5171374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3688 3711 0.449468 -0.757340 -0.461557 0.0025438 0.2491306 -0.4824395 0.8397497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3688 4308 0.464751 -0.320630 0.764057 0.5614369 -0.2226980 0.6014728 0.5229003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3689 3710 -0.480265 -0.479490 -0.623175 0.3024043 -0.0276036 -0.5217174 0.7972456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3689 4309 -0.217817 -0.578548 1.031729 0.5041873 -0.1061289 -0.4000346 0.7579606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3690 3709 -0.950809 -0.183301 -0.111522 0.2304921 -0.4006974 0.8128367 0.3544171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3690 4310 0.169471 -0.843576 0.363949 0.4583342 -0.3984797 0.6470347 0.4609661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3691 3708 0.973468 0.555527 -0.004791 0.1184765 -0.2355250 -0.1240775 0.9566065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3691 4311 -0.393839 0.606771 0.441889 -0.1076792 -0.7453131 -0.6530581 0.0801795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3692 3707 -0.795478 -0.321579 0.540668 0.2651455 0.1964719 0.7398890 0.5862259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3692 4312 0.489302 -0.406106 0.525677 0.3356220 -0.6126162 0.5747709 0.4262602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3693 3706 0.688936 -0.511715 -0.317827 0.6828589 0.1536194 0.1455992 0.6992179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3693 4313 -0.309839 -0.765884 0.753388 0.0062533 -0.3601413 0.7112850 0.6035999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3694 3705 0.252451 0.575638 -0.828102 0.2704144 0.2530141 -0.8446242 0.3866134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3694 4314 0.992721 -0.276394 -0.078162 0.1145359 0.2310346 -0.4276298 0.8663933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3695 3704 -0.168196 0.445081 -1.126055 -0.4031382 -0.3851254 0.0790721 0.8263811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3696 3516 -0.349007 -0.232311 -1.047309 -0.7192747 0.0655173 0.1349723 0.6783317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3696 4316 0.160065 0.124417 0.928945 0.4120500 0.1560427 -0.3659577 0.8197197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3697 4317 0.711538 -0.621150 0.185803 0.2695532 0.0700759 0.8970991 0.3429922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3698 4318 0.237176 0.881547 -0.038018 -0.9011696 0.0532829 0.3729217 0.2144383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3699 4319 0.247720 -1.032711 -0.084663 0.8008681 0.1187173 0.5190099 0.2741261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3700 4280 -0.056576 0.820795 0.523164 0.0452380 0.5471512 0.1761314 0.8170415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3701 3698 0.463711 0.812088 -0.305625 0.0160341 -0.8589297 -0.5100277 0.0430624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3701 3738 -0.475198 -0.749575 0.192434 0.2987117 -0.6251721 -0.5782941 0.4307053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3701 4281 -0.419943 0.405745 0.899552 0.1874150 -0.6459118 -0.5053710 0.5406235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3702 3697 -0.631042 0.679689 -0.127616 -0.4966026 0.0290723 0.5111001 0.7009403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3703 3696 0.257252 0.657366 0.385714 0.2639556 -0.4435753 0.2208680 0.8275178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3703 3736 -0.149386 -1.002578 -0.644080 0.4693260 -0.4553948 -0.3780122 0.6553285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3703 4283 -0.717199 -0.324523 0.637516 0.1763467 -0.4365720 0.7791425 0.4138160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3704 3484 -0.834293 -0.516991 -0.320103 0.4955024 0.7883721 0.1631873 0.3260625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3704 3735 -0.404164 0.846442 -0.181441 0.3656991 0.1611747 -0.1202157 0.9087547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3705 3734 -0.210638 0.252705 -0.892212 0.1088861 -0.7669340 -0.1819457 0.6056829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3705 4285 -0.206116 1.042124 0.053138 -0.3928945 0.8907426 0.0436571 0.2242893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3706 3733 0.258458 -0.264183 0.731231 -0.1357178 -0.1959925 -0.7774004 0.5820792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3706 4286 -0.577040 0.524359 0.502602 0.0913456 -0.2498817 -0.3922541 0.8805407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3707 3487 0.563331 -0.010578 -0.661840 0.7430423 -0.0822637 -0.2682643 0.6075813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3707 3732 -0.049094 0.994981 -0.285065 0.3089812 0.3863728 -0.5742474 0.6522933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3707 4287 -0.595790 0.103115 0.787131 -0.4012515 -0.0299157 0.4702254 0.7854873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3708 3731 0.243509 0.637751 -0.773508 0.1322152 -0.6175927 0.0128752 0.7751985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3708 4288 -0.467207 0.771800 0.492155 -0.4959689 -0.3488273 -0.7777370 0.1657091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3709 3730 0.344021 1.035205 -0.184775 -0.3943180 0.3249926 0.8285111 0.2290468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3711 3728 1.110052 0.082298 -0.195425 0.1057672 0.6277747 0.3411707 0.6916031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3711 4291 0.078901 -0.036346 0.999066 0.3866083 -0.0024877 -0.8139156 0.4336695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3712 3727 -0.435988 -0.096119 -0.775030 -0.9692255 -0.0915860 -0.1562471 0.1667357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3713 3726 0.739750 0.263934 0.818494 0.1875041 -0.3398377 0.2985482 0.8719068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3713 4293 -0.716027 -0.342319 0.691845 -0.4803044 -0.3499856 0.6046688 0.5302767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3714 3725 -0.885572 0.439297 -0.451344 -0.6147372 -0.0024857 0.7436543 0.2628122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3715 3724 -0.656987 0.902293 -0.097065 0.3435746 -0.0406921 0.5659414 0.7483388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3715 4295 -0.562503 -0.535044 0.429809 0.3621538 -0.4156972 0.7581730 0.3481582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3716 3723 -0.409447 0.063648 -1.066833 0.4074543 -0.6784556 0.3956836 0.4659544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3716 4296 -0.864179 -0.399386 0.320111 0.8949464 -0.4288790 -0.0770208 0.0959243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3717 4297 0.146299 -0.786640 0.678110 0.6244199 -0.3368665 0.1382969 0.6910099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3718 3721 0.621787 0.814864 0.404034 -0.1093847 0.1520918 0.1966646 0.9624064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3718 4298 -0.856315 0.501793 0.415476 -0.8871018 -0.1278593 0.1728084 0.4084601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3720 3759 0.652609 0.082619 0.662838 0.2400677 -0.8786007 -0.0500429 0.4097852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3720 4260 -0.537337 0.694223 0.367660 0.4770609 -0.5388949 -0.5252798 0.4539673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3721 3758 0.726023 0.371489 0.587358 -0.8142937 0.3418441 0.3818485 0.2725071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3721 4261 -0.886776 0.566064 0.438568 0.0403326 -0.1647760 0.5361848 0.8268784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3722 3757 -0.367497 0.743236 0.280770 0.4435351 -0.1077744 -0.2847438 0.8429604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3723 4263 0.519412 0.638747 0.555733 -0.1803782 0.0958721 -0.1514984 0.9671197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3724 4264 -0.324476 0.606714 0.519142 -0.1347805 0.0735082 -0.5783183 0.8012358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3725 3754 0.509933 0.088347 1.017799 0.4729461 -0.5395571 -0.5158185 0.4681148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3725 4265 -0.489534 -0.657536 0.447718 0.1107475 -0.9469675 0.0872781 0.2887389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3726 4266 0.057459 0.313640 0.933458 -0.7275931 0.1415824 -0.0466928 0.6696137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3727 3752 -0.830434 0.197687 0.543509 0.2669423 0.1573023 -0.9244829 0.2221018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3727 4267 -0.109803 -1.212829 -0.023849 0.4269449 -0.4963733 0.1129187 0.7473827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3728 3468 0.893432 -0.342022 -0.343293 0.2610554 0.1786579 -0.8142936 0.4866799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3728 3751 0.202811 -0.508948 1.022735 -0.2584112 -0.0227738 -0.5112997 0.8193154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3728 4268 -0.918362 0.513963 0.391795 -0.4837150 -0.3300498 -0.2744782 0.7627245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3729 3710 0.266575 -0.151076 1.152893 0.6660218 0.0912425 -0.5343336 0.5124231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3729 3750 -0.153029 0.234587 -0.911430 0.3868366 -0.5585977 0.0330759 0.7329612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3729 4269 -0.583272 -0.960691 0.091786 0.1997600 -0.5375404 0.5499211 0.6072339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3730 3749 0.026939 -0.790030 0.449409 -0.5265495 0.2326340 0.5647875 0.5913055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3730 4270 -0.750233 0.269811 0.579734 -0.0422682 -0.3246823 -0.3397205 0.8816942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3731 3471 -0.157594 -0.928037 -0.263411 -0.2803372 -0.2981359 -0.3705719 0.8337880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3731 4271 0.390246 0.892324 0.474781 -0.2061503 0.0695656 -0.8279061 0.5169470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3732 3747 -0.396722 0.118266 -0.900462 0.0492610 -0.2944726 0.8369164 0.4587268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3732 4272 -0.852244 -0.540422 0.232812 0.6429001 -0.0109839 -0.6360841 0.4265627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3733 3746 0.727717 0.694490 0.612468 0.1271502 0.0590601 -0.4165791 0.8982241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3733 4273 -0.260669 -0.746881 0.749995 0.3527134 -0.2799872 -0.8928457 0.0051905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3734 3745 -0.847061 -0.201889 0.304130 0.4132963 0.6839956 0.5533511 0.2348165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3734 4274 -0.276343 1.001034 0.460507 -0.6696858 -0.1260035 -0.5336877 0.5008208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3735 3475 -0.503217 -0.997168 -0.130370 0.1872711 0.2770018 0.6516185 0.6808766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3735 4275 0.684547 0.891681 0.081137 -0.8650514 0.2273009 -0.4262571 0.1353709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3736 3476 -0.252517 -0.370665 -1.016306 -0.1126491 0.3822984 0.1826057 0.8987843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3736 3743 0.543672 -0.802478 0.317334 -0.5773800 -0.3532201 -0.2475444 0.6932457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3737 3702 -0.826895 0.399933 -0.159056 -0.0808710 -0.0023405 0.1174762 0.9897746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3737 3742 0.764752 -0.420942 0.205029 -0.0023742 -0.0694845 -0.9697998 0.2337831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3737 4277 0.668738 0.788378 0.252550 -0.3058374 -0.9129913 -0.1688065 0.2107479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3738 3741 0.989305 -0.085567 -0.177122 -0.1010638 0.4768378 0.4276650 0.7612585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3738 4278 0.032451 0.908418 0.546728 0.2027432 -0.2037584 -0.8272232 0.4827830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3739 3700 0.360575 0.614174 0.762112 0.2672059 0.0782152 0.9268893 0.2517132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3740 4240 0.873962 -0.354749 0.387417 -0.1283863 -0.2599810 0.6825054 0.6709047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3741 3778 0.153108 -0.662258 0.548519 -0.3141063 -0.8517437 -0.3462793 0.2365598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3741 4241 -0.190747 0.606558 0.809315 0.0624504 0.4138558 0.3345590 0.8443303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3742 4242 -0.828430 -0.528994 0.222892 0.2371447 -0.2167615 0.1773125 0.9302350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3743 3776 0.379741 0.052232 -0.739125 -0.2602161 0.0001794 0.8289159 0.4951625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3743 4243 0.810952 -0.205803 0.484716 0.6826938 -0.5633273 0.4488540 0.1229700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3744 3775 -0.395212 0.337739 0.661912 0.6870256 0.3192718 -0.0805492 0.6477446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3744 4244 0.025205 -0.733418 0.428305 0.7835710 0.3319728 -0.0719653 0.5202227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3745 3774 0.423979 0.038770 -0.839263 -0.6858994 0.6663261 -0.2441003 0.1611417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3745 4245 0.905551 0.550521 0.343482 0.2241546 0.8263967 -0.0881052 0.5089801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3746 3446 0.004583 0.486303 -1.092803 0.1016935 0.2841443 0.9365508 0.1783058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3746 3773 -0.060221 0.789331 0.353497 0.2353157 0.3555063 -0.7331487 0.5298440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3746 4246 0.264837 -0.209320 0.805142 0.5757477 0.4178141 -0.4500409 0.5398233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3747 3772 -0.181518 0.782524 -0.725769 -0.2549094 -0.8053709 -0.2048834 0.4943902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3747 4247 0.154875 0.691673 0.857640 -0.0238041 0.1362351 -0.1885651 0.9722739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3748 3731 0.695238 -0.762751 0.127448 0.6718967 -0.5721901 0.3540499 0.3095191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3748 3771 -0.651079 0.738220 -0.064757 -0.2800468 -0.6331502 0.4023469 0.5990088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3748 4248 -0.821020 -0.702984 0.114043 0.2120266 -0.8182352 -0.3024133 0.4405474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3749 3770 -0.643404 0.090405 -0.594012 -0.2441000 -0.4345665 -0.6349227 0.5902883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3749 4249 -0.699775 0.498042 0.620867 0.0713340 0.1489326 0.7732671 0.6121998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3750 3769 -1.138989 -0.081054 0.078705 0.5887478 -0.3066399 -0.4435916 0.6021416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3751 3768 0.585552 -0.321007 0.892301 0.7343170 0.1027077 -0.0166834 0.6707842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3751 4251 -0.602635 -0.748483 0.189687 -0.5642542 0.0731678 0.7633538 0.3058672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3752 4252 0.412338 0.665961 0.457286 -0.1982742 -0.0187895 0.2358695 0.9511571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3753 3726 -0.159357 0.206882 0.931353 0.4315988 0.5145767 -0.3666725 0.6438048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3754 3765 -0.173824 0.605126 -0.615648 -0.4937571 -0.6444495 -0.3943087 0.4305920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3755 3764 0.178721 0.835768 0.439495 0.1526336 0.1057826 0.5896402 0.7860264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3755 4255 0.479219 -0.376215 0.818001 0.4951807 0.2769846 -0.0162800 0.8232925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3756 3723 -0.476005 -0.167669 -0.789301 -0.2221706 0.5252994 0.8212947 0.0132568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3756 3763 0.646989 0.157414 0.764814 -0.4655255 0.3171591 0.3082305 0.7666095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3756 4256 -0.860800 0.294420 0.506307 0.3532665 -0.5656385 -0.2221537 0.7112690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3757 3762 -0.803749 0.474972 -0.207572 -0.4251127 0.4873140 -0.1547846 0.7468909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3758 3761 -0.279579 -0.830358 -0.246499 -0.5389230 0.4707970 0.6394580 0.2810794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3758 4258 -0.730190 0.172227 0.750201 0.1399346 0.1050672 -0.2176026 0.9602231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3759 4259 0.216085 1.036132 0.129687 -0.5554327 -0.8177267 -0.0909838 0.1205798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3760 3799 0.558404 -0.574348 0.645071 0.5274599 -0.2295190 0.4509812 0.6824390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3761 3421 0.377274 -0.873464 -0.348378 -0.2112588 -0.3429981 -0.8184711 0.4096671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3761 3798 0.514204 0.568005 -0.542525 -0.1080095 0.6299436 0.7690915 0.0017894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3761 4221 -0.591645 0.638575 0.471015 -0.5182642 -0.0677269 -0.3756468 0.7653135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3762 3797 -0.778220 0.503261 -0.525672 0.1318307 -0.1470261 -0.4967239 0.8451446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3762 4222 -0.220286 0.343523 0.873975 -0.5091330 0.2726788 -0.6450292 0.5003671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3763 3796 -0.143984 -0.692165 0.518810 -0.5450809 0.3911023 0.7109867 0.2107695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3763 4223 -0.963810 0.497276 0.345757 0.0522215 0.0186331 -0.9983262 0.0164494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3764 3424 0.373592 -0.055797 -0.854099 0.4112975 0.4154996 -0.7651857 0.2696022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3764 3795 0.916486 0.320658 0.379700 -0.4393038 0.5027337 0.6676227 0.3294706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3764 4224 -0.463633 0.162117 0.934385 0.1697446 0.1315476 -0.9584546 0.1877411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3765 4225 0.373722 0.781683 0.049280 -0.4583856 0.2148288 -0.3860873 0.7711471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3766 3793 0.732930 0.718262 0.197505 0.6638697 0.4760839 0.4528388 0.3571528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3766 4226 0.544374 -0.527521 0.853623 0.4797753 -0.6729235 0.5363684 0.1711683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3767 3752 -0.000905 -0.511156 -0.820680 -0.2875734 0.0709990 -0.9403299 0.1674523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3767 3792 -0.082018 0.355529 0.931240 0.2019151 0.0980474 -0.5711967 0.7895260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3767 4227 0.309698 -0.936797 0.498844 -0.4455312 0.4012327 -0.5048754 0.6209791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3768 3791 0.618161 0.929747 0.384393 -0.1588989 0.1342193 0.9347979 0.2879049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3768 4228 -1.030106 0.141870 0.554013 0.4604511 -0.0932802 -0.6851352 0.5566627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3769 3790 -0.446405 0.115456 0.794698 -0.2976442 -0.4479034 -0.8177394 0.2051652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3770 3789 -0.222291 -1.103930 -0.140100 0.3169715 -0.4141853 -0.4983675 0.6925384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3771 3788 0.586923 0.611209 0.551918 0.5945081 -0.0619902 -0.5783920 0.5551397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3771 4231 -0.354020 -0.318815 0.924526 -0.5175978 -0.0507917 0.2946432 0.8016845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3772 3787 -0.527021 0.439095 0.724363 0.9206052 0.0112861 0.3241384 0.2174697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3772 4232 0.900963 0.669787 0.141263 -0.6986507 0.5816083 -0.3345762 0.2483501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3773 3786 -0.604160 -0.451192 -0.508136 -0.3541192 0.1767710 -0.0163731 0.9181958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3773 4233 -0.532883 0.092718 0.609564 -0.4848515 0.1885885 0.3628638 0.7730998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3774 3785 -0.110455 0.197150 1.040985 -0.1858921 0.1432551 -0.9714535 0.0346435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3774 4234 -0.471404 -0.923347 0.076110 0.4101115 0.6158353 -0.0251553 0.6722519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3775 3784 -0.436520 0.472726 -0.582132 -0.1230832 0.4139310 -0.8264847 0.3611573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3775 4235 -0.490910 0.239899 0.919054 -0.1550622 -0.7228498 0.3260982 0.5891552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3776 3436 0.732032 0.604152 -0.097399 0.2435360 -0.0869397 -0.7950414 0.5486719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3776 3783 0.184947 -0.294649 -0.883520 -0.1203364 -0.3550941 -0.0345211 0.9264101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3776 4236 -0.509880 -0.647780 0.106190 0.7465697 0.4788243 -0.4586243 0.0549973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3777 3742 0.926887 -0.361951 -0.501465 0.1403328 0.2824396 0.3560764 0.8796273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3777 4237 0.121526 -1.018255 0.269396 0.7207285 -0.1241845 0.6499480 0.2066307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3778 3781 -0.052415 -0.090336 -1.016082 -0.1985175 -0.2405002 -0.8278682 0.4662453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3778 4238 0.634628 0.399793 0.014556 -0.3738349 0.0049814 -0.7592636 0.5326739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3779 3740 0.199612 -0.903736 0.470658 -0.3630883 -0.2024904 -0.8226323 0.3878669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3780 3819 0.479287 0.809993 -0.007160 0.1174887 -0.5410763 0.8069871 0.2054378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3781 3818 -0.574505 -0.122995 -0.800015 0.0852401 -0.8588222 -0.4306710 0.2639718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3781 4201 -0.871751 0.496703 0.439041 0.0234919 -0.9507305 -0.0776626 0.2992125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3782 3817 -0.615682 0.401357 0.667061 -0.1281532 -0.7813742 0.3535401 0.4980366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3782 4202 -0.562569 -0.899316 0.304721 -0.0523236 -0.1725040 -0.1092347 0.9775338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3783 3816 -0.488760 -0.116285 -0.853246 0.0043857 0.1442941 0.8821272 0.4483431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3783 4203 -0.678824 -0.608694 0.373299 0.0568823 -0.2652165 -0.1444786 0.9516042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3784 3404 -0.117222 0.834374 -0.198111 0.2724468 0.0620793 0.7078455 0.6487478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3785 3814 0.555782 -0.594136 0.783028 -0.5030889 -0.8353009 -0.1707043 0.1415418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3786 3813 -0.680143 0.123294 -0.669439 -0.0828316 -0.2066410 0.7593823 0.6113730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3787 3407 -0.983769 0.529369 -0.125163 0.5155119 0.5822359 -0.6037533 0.1753019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3787 3812 0.088572 0.104284 -1.174810 0.4704073 0.7456832 0.1064973 0.4597084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3787 4207 0.683070 -0.634320 0.197562 -0.1140695 -0.1761221 -0.9752489 0.0697041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3788 3408 0.434973 -0.776516 -0.815453 -0.0715306 0.6822551 0.5638022 0.4599331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3788 3811 -0.557254 0.484744 -0.641489 -0.3558110 -0.2334143 0.8903629 0.1617719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3789 3810 0.780309 -0.450443 0.231333 0.2637229 0.1618282 0.8748060 0.3727954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3789 4209 0.629060 0.908873 0.190312 -0.5790792 0.6178482 0.4023545 0.3479105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3790 3809 0.680697 0.351477 0.328229 0.2659404 0.5207839 -0.7468962 0.3165531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3790 4210 -0.220586 -0.302307 1.011960 0.3994068 0.0524624 -0.8882949 0.2205768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3791 3808 0.011393 -0.927410 0.321588 0.6222287 -0.2031436 0.6744787 0.3415298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3791 4211 0.426732 0.400548 0.735254 0.1999230 -0.2353847 -0.0132584 0.9510253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3792 4212 0.631180 -0.195668 0.559948 -0.3613157 0.0500824 0.5244815 0.7693256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3793 3806 0.916300 0.039780 0.608859 -0.4214706 -0.4371091 -0.7870087 0.1091580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3793 4213 -0.377597 1.125077 0.313649 -0.1173147 0.4208858 0.0166188 0.8993421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3794 3414 -0.349735 -0.125776 -0.985740 0.0243672 0.1069164 0.9704112 0.2151216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3794 3805 -0.135490 0.977759 -0.121270 -0.1999410 -0.2908268 0.4360091 0.8278523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3795 4215 -0.529357 0.849568 0.318999 -0.9371322 -0.0399213 -0.0744374 0.3385981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3796 4216 0.110916 0.415488 0.802411 -0.0782532 0.5064657 0.0956209 0.8533613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3797 4217 -0.446045 0.492803 1.062203 -0.2078758 0.4642954 0.8609371 0.0021636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3798 3418 -0.284834 -0.156115 -0.968299 0.1211104 -0.5338263 0.8111000 0.2061035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3798 3801 -0.342428 -0.946998 0.493435 0.2363333 0.5153342 0.4518949 0.6887440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3798 4218 0.290967 0.205233 1.039137 0.3553541 -0.3507059 -0.8345887 0.2327888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3799 4219 0.434148 0.929807 0.153347 -0.6364523 -0.1143215 0.2338767 0.7260583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3800 4180 0.582741 0.179535 0.649173 -0.0795588 0.6108969 0.6377084 0.4623888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3801 3838 -0.971578 0.166763 -0.288863 -0.4568552 0.1979116 -0.1026712 0.8611463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3802 3837 0.082826 1.026510 -0.163124 0.3503836 -0.2500661 0.1276561 0.8935336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3803 3796 0.995901 0.231616 0.868479 -0.3820740 -0.0359180 0.4278544 0.8183337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3803 4183 -0.783137 0.795121 0.482400 0.1443963 -0.5592111 -0.7795235 0.2424371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3804 3835 -0.283023 0.966248 -0.119962 -0.1263669 0.2501617 0.9171388 0.2833849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3804 4184 -0.826630 -0.186008 0.778944 -0.2289489 -0.7048554 -0.2327362 0.6297580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3805 3385 -0.613819 0.531620 -0.501180 0.8339974 0.0456580 -0.2278919 0.5004288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3805 3834 0.814106 0.588886 0.028345 0.6200131 -0.0479846 0.7436013 0.2456387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3805 4185 0.490774 -0.770859 0.522782 -0.0593892 0.1674017 0.9741866 0.1393198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3806 3833 0.038534 0.552585 0.739169 0.0565075 -0.2616581 -0.5832235 0.7669370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3806 4186 0.510796 -0.574493 0.533970 -0.1406305 0.0681717 -0.3677652 0.9166921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3807 3792 0.647113 -0.367410 0.795360 0.3424772 -0.7947160 0.0390694 0.4996093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3807 3832 -0.479577 0.283163 -0.909509 0.0388239 0.7343512 -0.5596000 0.3821895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3807 4187 -0.790481 -0.658858 0.230153 -0.0224954 -0.7997291 0.5156549 0.3066387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3808 4188 0.725450 -0.358698 0.129496 -0.6241122 0.0711771 -0.6973366 0.3451657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3809 3830 -0.921866 0.454641 -0.014628 -0.1496301 -0.4348630 -0.3697401 0.8073396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3809 4189 -0.510659 -0.419578 0.510754 0.0144179 0.0534219 -0.9834157 0.1727186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3810 3390 -0.117190 0.762127 -0.469848 0.1774263 0.6329114 -0.2542327 0.7094426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3810 3829 -0.678910 -0.024276 0.798784 -0.4951726 0.7026926 -0.4445356 0.2518239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3810 4190 0.385193 -0.907052 0.451292 0.5272057 -0.6408438 0.3999027 0.3891673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3811 3828 0.760949 0.050658 0.028535 0.1443277 0.4039821 -0.8935600 0.1323572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3811 4191 0.219875 -1.010820 0.502581 0.7110935 -0.2913774 -0.1937323 0.6098467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3812 3827 0.476356 -0.636073 0.625101 -0.1134253 -0.5931405 -0.2130219 0.7680760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3812 4192 -0.765374 0.303709 0.756137 -0.1376331 0.5161409 0.6387925 0.5537146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3813 4193 0.059715 0.718642 0.852977 -0.7535659 -0.3824502 -0.3377585 0.4144749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3814 3825 -0.260942 0.229169 -0.887499 0.0248748 0.2202397 -0.0421867 0.9742156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3814 4194 0.498217 0.809566 0.121906 0.1665046 -0.0578468 0.9173033 0.3570499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3815 4195 -0.695225 0.753696 0.173575 0.5341768 -0.5693714 -0.6213062 0.0667079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3816 4196 -0.354521 0.947325 0.078405 -0.9260677 0.3026927 -0.1397650 0.1767524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3818 3821 -0.118483 -0.788382 0.664838 -0.7988856 0.1187098 -0.2740366 0.5221050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3818 4198 0.678963 0.549227 0.736832 0.6314806 0.2979979 0.3047240 0.6477443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3819 4199 -0.627959 -0.535396 0.380526 -0.0469321 0.1427327 -0.7575205 0.6352853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3820 4160 0.031299 0.899408 0.618555 -0.5867251 -0.0551513 0.7937933 0.1503466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3822 4162 -0.486453 0.063659 1.050858 -0.4347520 0.5723866 0.6734527 0.1727013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3823 3816 0.666563 -0.720729 -0.558844 0.3631903 0.8507775 0.0793115 0.3714568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3823 3856 -0.797462 0.708627 0.308646 -0.1911584 0.7294066 -0.0841082 0.6514218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3823 4163 0.693231 0.366615 0.609844 -0.1964389 0.3705159 0.7428154 0.5218765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3824 3815 -0.230718 1.206734 -0.099530 0.7506700 -0.0775984 -0.0120831 0.6559931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3824 3855 0.285730 -0.817293 0.062864 0.2057982 0.1695424 0.5674318 0.7790530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3824 4164 -0.738333 -0.403551 0.721416 0.6402852 -0.1253371 0.0718277 0.7544311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3825 3854 0.191320 0.360066 -0.894895 -0.4911857 0.3762942 0.0377517 0.7846745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3825 4165 0.465653 1.086578 0.323081 -0.5497292 -0.7447123 -0.1332082 0.3541991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3826 3813 0.754684 0.193411 -0.516520 0.7299547 -0.0986480 0.5796320 0.3485132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3826 3853 -0.682921 -0.440233 0.604418 0.7051716 0.6588683 0.2478856 0.0847244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3827 4167 0.643143 0.096071 0.785721 -0.6748541 0.1314920 0.0268108 0.7256466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3828 3851 -0.659000 0.737322 -0.345299 0.0367724 -0.1942511 0.4250265 0.8833271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3829 3850 0.462173 -0.426420 -0.964607 -0.0294474 0.5679367 -0.0111817 0.8224693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3829 4169 0.698180 -0.710452 0.525159 -0.4738548 0.5327322 0.0624762 0.6983944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3830 3849 -0.458848 -0.460412 0.820374 0.3790135 0.6158807 0.4414324 0.5312036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3831 3848 0.370621 0.961541 0.036740 0.0162014 -0.3351759 -0.8984841 0.2830566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3832 4172 0.674074 -0.872944 -0.123976 0.1248462 0.6508741 -0.5084744 0.5497546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3833 3373 -0.809029 -0.562275 -0.026756 0.2446336 -0.3163241 0.9164626 0.0137739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3834 4174 0.277024 0.411705 0.894384 -0.5971722 0.4800371 -0.3996383 0.5032286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3835 3844 0.671760 -0.477460 0.213718 -0.4078504 0.5586147 -0.0683159 0.7189858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3836 3843 0.924809 -0.358394 -0.408396 0.2254026 -0.6218883 -0.0332778 0.7492271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3836 4176 -0.561403 -0.767974 0.379484 0.1690341 0.2709999 0.1137633 0.9407680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3837 3842 -0.147312 0.742528 -0.711665 -0.5746273 0.4269812 0.4914181 0.4959826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3837 4177 0.364120 0.733177 0.522649 -0.5929976 -0.0346743 0.2122735 0.7759456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3838 3841 -0.825425 0.346060 -0.545929 0.1498936 -0.0447927 0.7600963 0.6306974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3839 3800 -0.002333 -1.179879 -0.121985 0.2709037 -0.6664920 -0.4153671 0.5566595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3840 3879 -0.736097 -0.312891 -0.384271 -0.0881760 0.3827860 0.9092399 0.1377774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3840 4140 -0.167943 -0.451218 0.939172 0.7625959 0.3039853 -0.0970806 0.5626863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3841 3878 0.221087 0.500445 -0.548457 -0.3903686 0.3853576 0.8154131 0.1849687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3841 4141 0.429643 0.540426 0.688723 0.4707630 0.1502640 0.6428755 0.5852470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3842 3877 0.716432 0.108595 0.721604 0.5665676 -0.3500963 0.5685134 0.4829351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3842 4142 -0.609756 -0.627007 0.636019 -0.1009550 -0.4750379 -0.1993594 0.8511186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3843 3876 -0.137351 -0.660223 -0.585369 0.4587192 -0.0282489 0.6021509 0.6528346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3843 4143 0.668762 -0.690088 0.681508 -0.1977165 0.5175936 -0.7763617 0.3004455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3844 3875 0.628235 -1.006702 0.353022 0.0653403 -0.5487180 -0.4453810 0.7044679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3844 4144 -0.674988 -0.365194 0.634624 0.0216704 -0.4762988 -0.8439637 0.2457540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3845 3834 0.908901 0.464081 0.245362 -0.0521087 -0.7740895 -0.4101223 0.4794474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3845 3874 -0.876639 -0.442245 -0.503045 -0.2935518 -0.2701082 -0.8538456 0.3343899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3845 4145 -0.596595 0.787828 0.261551 0.1978391 -0.7312172 -0.4029064 0.5136609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3846 3346 -0.730371 -0.381546 -0.085148 -0.3852805 -0.4865490 -0.7700915 0.1476079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3846 3833 -0.290995 0.813583 -0.696015 0.5931527 0.4174736 0.0490592 0.6866432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3846 3873 0.434284 -0.533969 0.597601 -0.1265583 0.3267899 -0.7312327 0.5852265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3846 4146 0.975621 0.421778 0.172371 -0.3032027 -0.2328598 -0.8507281 0.3607023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3847 3832 -0.158384 -0.865008 -0.407967 -0.0721889 -0.7209191 0.2030690 0.6586557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3847 4147 -0.051569 -0.504604 0.900709 -0.2790880 0.0771200 0.7367228 0.6110662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3848 3348 -0.451513 -0.423689 -0.953461 -0.2390735 0.2625851 0.6718722 0.6499851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3848 3871 -0.590604 -0.344831 0.225181 0.1230626 0.4186888 -0.8633800 0.2532395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3848 4148 0.333570 0.371244 1.020779 0.0142815 0.0462195 -0.8520291 0.5212544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3849 3870 -0.311123 0.611064 -0.532163 -0.1194420 -0.4565352 -0.3515356 0.8085369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3850 3869 1.098433 -0.337668 -0.178545 -0.2807516 -0.3270770 -0.2855461 0.8559571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3850 4150 -0.071193 -0.682704 0.916177 0.0578201 -0.0792397 -0.6517078 0.7521003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3851 3351 -0.346657 -0.377208 -0.890161 -0.4717023 0.0570519 -0.4209732 0.7726730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3851 3868 -0.316618 1.044569 -0.295886 0.6853936 0.1086491 0.3802049 0.6114533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3851 4151 0.351276 0.428044 0.765854 0.1672094 -0.4046808 -0.8890759 0.1334859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3852 3827 0.666530 -0.681449 0.406026 0.1776882 -0.0731278 0.9489327 0.2502117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3852 3867 -0.663789 0.676574 -0.321975 -0.5034716 -0.1967303 0.3191447 0.7784345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3853 3866 -0.335002 -0.359790 -0.926030 0.0482238 -0.0192748 0.0457542 0.9976019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3854 3865 0.671926 0.760272 0.042790 0.2098918 -0.6229014 -0.6659409 0.3527917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3854 4154 -0.153165 -0.037046 0.952602 -0.0338777 0.1726020 0.2996374 0.9376984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3855 3864 -0.761574 -0.400530 0.349047 -0.8477153 -0.3460904 -0.3432584 0.2092220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3855 4155 -0.542944 0.813736 0.123561 -0.1615273 -0.9014523 -0.1311745 0.3795865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3856 3863 -0.602451 0.390740 -0.602664 -0.2544670 -0.2918057 -0.7670537 0.5115903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3856 4156 -0.675025 0.060751 0.537021 -0.3972505 0.4324201 0.6460179 0.4877148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3857 3822 -0.487899 0.656757 0.538345 -0.1919637 0.6234642 0.0201961 0.7576507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3857 3862 0.598196 -0.777967 -0.516447 -0.4638838 0.1715881 0.8184635 0.2923813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3857 4157 0.677099 0.361498 0.582595 0.6326259 0.2288494 0.6624729 0.3294574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3858 3861 0.090825 0.726137 0.429591 -0.3066136 -0.6372482 -0.3192078 0.6308797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3858 4158 -0.639333 -0.392090 0.789515 -0.1828941 0.0189930 -0.7959976 0.5766948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3859 3820 0.388175 1.001299 -0.384793 -0.1314842 -0.0500785 0.5030946 0.8527015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3859 4159 -0.881076 0.381868 0.464917 -0.7780438 -0.0763299 0.6217330 0.0476406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3860 3899 0.768377 0.834522 -0.147175 -0.2781138 0.7033462 -0.4491527 0.4756245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3860 4120 0.737525 -0.410046 -0.110479 0.6559829 0.6302054 0.4029672 0.1007222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3861 3898 0.709713 0.721817 0.656974 -0.7914586 -0.0426989 -0.5614087 0.2378872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3861 4121 0.630929 -0.743581 0.122084 0.1101700 0.0225584 -0.5901310 0.7994367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3862 3897 -0.199669 -0.105510 -0.925815 0.7962387 -0.2140234 -0.2991583 0.4803146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3862 4122 -0.660703 -0.805274 -0.030508 -0.3035940 -0.4810458 0.8194057 0.0707099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3863 4123 0.729998 -0.552071 0.574027 0.9402957 0.0598228 0.3292444 0.0621553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3864 4124 0.088124 -0.952045 0.314705 0.8328344 0.3863238 -0.2863505 0.2741244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3865 3894 -0.869129 0.008777 0.123300 -0.6972745 0.4143151 -0.1654051 0.5610637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3865 4125 -0.085766 0.979668 0.247784 0.3898029 0.4893607 0.3997480 0.6699114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3866 3893 -0.245303 -0.362205 -0.861832 0.3665757 -0.9209970 -0.1244188 0.0436663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3867 3892 -0.006997 0.484952 1.011644 -0.2115875 0.2317072 -0.2978578 0.9015671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3867 4127 -0.227301 -0.938245 0.494145 -0.1933117 -0.5329819 0.2276366 0.7916707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3868 3891 0.069471 -0.323983 -1.058827 -0.5823132 0.4297015 -0.6502097 0.2312906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3868 4128 0.837914 0.681715 0.041590 0.7085824 0.5510536 0.3849811 0.2145703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3869 3890 0.397941 0.467120 -0.779075 0.0010787 0.2923736 -0.6113105 0.7354019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3869 4129 0.613283 -0.815248 0.233154 0.7664543 0.2159984 0.3740802 0.4753489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3870 3889 -1.013986 0.021167 0.225014 0.1352211 -0.3028627 0.4315711 0.8388896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3871 3331 0.860603 0.495637 -0.408435 0.2774473 -0.6531316 -0.2439228 0.6610173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3871 3888 0.656177 -0.613998 0.618291 -0.1259133 -0.7602246 0.1018283 0.6291545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3871 4131 -0.714419 -0.620750 0.528443 0.5940537 -0.0947114 0.1673690 0.7811002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3872 3332 -0.499574 0.432029 -0.758396 -0.1055831 -0.4771740 0.8668360 0.0987554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3872 3847 -0.863895 0.112236 0.600106 -0.1806054 0.4804185 -0.6185405 0.5949684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3872 3887 0.956845 -0.092302 -0.570805 -0.2629535 0.6789341 0.2690352 0.6304951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3872 4132 0.307736 -0.443905 0.840061 0.7188388 0.2387192 0.4800084 0.4425788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3873 3886 0.328485 0.004787 0.804963 -0.2925315 -0.5728834 -0.5343421 0.5483689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3873 4133 -0.848051 0.594514 0.396055 0.3060059 -0.5898321 -0.3460978 0.6623253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3874 3885 0.637868 -0.199265 -0.574925 0.4294259 -0.5342855 0.2644888 0.6783643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3874 4134 0.198802 -0.856387 0.519200 0.4258732 0.0105604 -0.5816086 0.6930021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3875 4135 0.513870 -0.231211 0.803444 0.3088864 0.2460307 0.4770850 0.7851420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3876 4136 -0.128099 0.218591 0.921352 0.4819073 -0.0221113 -0.8658700 0.1324600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3877 3882 0.725685 -0.805960 0.103881 -0.2949780 -0.5553032 -0.7040824 0.3299914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3877 4137 0.533467 0.462203 0.508986 -0.5358603 -0.5020880 -0.6147245 0.2878805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3878 4138 -0.774905 -0.217019 0.493632 -0.4674265 -0.5250555 0.3521933 0.6178908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3879 4139 -0.016377 0.930915 0.354969 -0.5284494 -0.0096646 -0.7064026 0.4707901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3880 3919 0.698804 0.544881 -0.658508 0.7215320 0.1149308 0.6105986 0.3055352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3880 4100 0.857111 -0.278418 0.555452 0.2909518 0.0022154 0.1797141 0.9397047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3881 3878 0.383610 0.937152 0.187382 0.0927780 -0.0339985 -0.3691577 0.9240990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3881 3918 -0.245208 -0.862162 -0.140730 0.3315752 -0.2129380 0.6272584 0.6717605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3881 4101 -0.969964 0.248741 0.583530 0.3591092 -0.4243192 -0.4175772 0.7187649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3882 3917 -0.434943 0.692627 -0.674747 0.4235466 0.2781580 0.8524286 0.1288483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3882 4102 0.093124 0.591329 0.719240 -0.2625311 -0.2570022 0.2138549 0.9051483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3883 3876 0.558817 -0.660505 0.305588 0.5813801 -0.4160412 -0.2257865 0.6617609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3883 3916 -0.356915 0.692118 -0.485963 0.1526457 -0.4882068 -0.3016957 0.8045701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3883 4103 -0.781019 -0.589622 -0.018233 0.3652442 0.0291941 -0.8349871 0.4105374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3884 3875 0.550454 -0.535988 0.384268 0.2253005 0.6096948 -0.7478873 0.1348203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3884 4104 -0.713152 -0.599017 0.018244 0.1083168 -0.4439186 -0.6210234 0.6368153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3885 3914 -0.428282 -0.852278 0.090707 0.9213809 -0.0562118 0.2897729 0.2528420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3885 4105 0.688911 -0.479048 0.658906 -0.1197354 -0.6208160 0.7446602 0.2138507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3887 3912 0.450275 -0.651001 0.489489 -0.0008678 -0.9563136 -0.2199523 0.1925735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3887 4107 -0.978714 -0.794263 -0.132756 0.5430916 -0.1977587 -0.6287983 0.5201497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3888 3911 0.256232 -0.404393 -0.824794 0.7106698 0.0695180 -0.6321082 0.3009233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3888 4108 0.333717 -0.629116 0.662964 0.4000733 0.1472053 -0.2463806 0.8703841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3889 3910 -0.344152 0.768200 0.694240 -0.4091662 0.5928007 -0.6317663 0.2864291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3889 4109 0.599826 -0.191743 0.649686 0.3181588 -0.0436961 -0.7476015 0.5813413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3890 3310 -0.695415 -0.293678 -0.690812 -0.0660483 0.7759093 0.5967637 0.1935860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3890 3909 0.117054 0.742043 -0.470896 -0.2654335 0.2080649 0.1424160 0.9305760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3890 4110 0.598692 0.129579 0.680144 0.1181546 0.4790769 0.8237269 0.2792825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3891 4111 -0.449677 -0.691983 0.522982 0.6998518 -0.3321037 -0.1022844 0.6240613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3892 3907 -0.438761 -0.218680 0.686758 0.7535028 -0.1058526 -0.2640836 0.5926960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3892 4112 0.318081 -0.860088 0.106123 0.6800822 -0.4466849 0.5512119 0.1847330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3893 3906 0.392454 -0.411962 0.948434 -0.3715667 -0.3403088 -0.0352509 0.8630675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3893 4113 0.325102 0.996895 0.191423 0.4459053 0.5790138 0.5613977 0.3882578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3894 3314 0.719132 0.061512 -0.898398 0.3529022 -0.5299615 0.2168942 0.7399715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3894 3905 -0.691946 0.299889 -0.597278 -0.1327509 -0.7772573 0.5149396 0.3362819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3894 4114 -0.685701 -0.068925 0.735774 -0.0741007 0.3700799 0.4040479 0.8332438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3895 3904 0.390020 0.674018 0.759660 0.4966811 -0.2545997 0.7923472 0.2463183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3895 4115 -0.404975 -0.535448 0.831121 0.7483323 -0.4965978 -0.1741426 0.4038116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3896 3863 -0.406556 0.807460 0.481405 0.0383673 -0.5286546 0.2766997 0.8015545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3896 3903 0.172155 -0.885741 -0.383357 -0.5191955 0.4960417 -0.6922174 0.0722064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3896 4116 0.003096 -0.379518 0.977256 0.1615383 -0.4218122 0.0751869 0.8890033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3897 3902 0.236248 -0.768732 0.434140 -0.4155831 -0.0076400 -0.8916197 0.1795732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3897 4117 -0.076182 0.296435 0.947768 -0.1011748 -0.3433273 -0.4282706 0.8297435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3898 3901 0.481656 -0.624860 0.699080 -0.7730805 0.2826088 -0.1451592 0.5490060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3898 4118 0.592427 0.773984 0.478017 -0.0667538 0.2458365 0.5107610 0.8211160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3899 3319 -0.077393 0.247763 -1.125829 -0.4087285 -0.0686720 -0.8850180 0.2120573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3899 4119 0.140288 -0.354711 0.994509 0.1008341 -0.1882869 0.1303522 0.9681884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3900 3280 0.635082 0.667552 -0.213857 0.5390529 -0.7023985 0.2413022 0.3972802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3900 3939 0.281123 -0.548029 -0.935633 0.5402729 -0.6023635 -0.3201775 0.4926965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3900 4080 -0.710544 -0.817398 0.048680 0.3941566 0.7986407 -0.1690921 0.4221628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3901 3938 0.592403 -0.518695 -0.536260 0.0270925 -0.6638618 0.1381190 0.7344907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3901 4081 -0.079632 -0.705366 0.737053 0.6393059 0.4246354 -0.5157512 0.3807538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3902 3937 0.367565 0.659185 0.385740 -0.1265819 0.0178752 0.6291212 0.7667229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3902 4082 0.639426 -0.853501 0.410971 0.7056265 0.6207658 -0.1244637 0.3181979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3903 4083 0.740686 -0.530668 0.259023 0.3565486 0.1610985 0.9076152 0.1521676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3904 3935 0.242702 -0.774991 0.061586 0.1031915 0.6421294 0.2278908 0.7246289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3904 4084 0.900416 0.383757 0.189773 -0.2699511 -0.1934642 -0.8020061 0.4964718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3905 3934 0.392303 0.721319 0.611703 0.2349025 -0.2961939 0.3424713 0.8601183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3905 4085 0.708371 -0.753755 0.181670 -0.1070802 0.5209094 -0.6339610 0.5614986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3906 3933 0.597632 -0.754234 -0.036526 -0.2958763 0.7539271 0.2408684 0.5348210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3906 4086 0.679623 0.628651 0.522171 -0.9355987 0.1255196 -0.2895387 0.1583263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3907 3932 -0.615501 0.798759 -0.013964 -0.3978290 -0.1001190 0.3039729 0.8598306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3907 4087 0.706089 0.367138 0.619551 0.1041690 0.6838681 0.0014442 0.7221296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3908 3891 0.529423 -0.372972 0.705528 -0.4681794 -0.2788607 0.2474541 0.8011312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3908 4088 -0.918174 -0.239622 0.480161 0.0177577 0.0199426 -0.1193942 0.9924878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3909 3930 0.205147 0.987716 -0.072252 -0.3413916 0.3340495 -0.6343700 0.6078136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3909 4089 0.258225 -0.298934 1.104548 0.3375525 0.2208801 0.9149456 0.0120403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3910 3929 -0.393892 -0.377646 -0.741624 0.3019230 -0.5549589 0.5171059 0.5774640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3910 4090 0.214790 -0.645053 0.446265 -0.3316470 0.6835857 -0.6087302 0.2284040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3911 3291 0.432493 -0.839700 -0.188776 0.1185189 -0.1693070 0.0845272 0.9747531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3911 3928 0.821581 0.418986 0.089616 -0.0011082 0.5062910 0.8452031 0.1711721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3911 4091 -0.336896 0.587741 0.108677 -0.8132967 -0.1040103 0.3703374 0.4365552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3912 3927 -0.296584 -0.537979 -0.850006 0.3235417 0.3477002 0.4859463 0.7336767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3912 4092 0.668037 -0.570931 0.066136 0.2467056 0.7420594 0.2534522 0.5694262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3913 3886 -0.428233 -0.849172 -0.055210 0.0489994 -0.1443894 0.1741362 0.9728450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3914 3925 -0.577755 1.063974 0.130579 -0.4119104 -0.7039282 -0.4633786 0.3465475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3914 4094 0.847742 0.593023 0.187647 -0.3895742 -0.4405740 -0.3326823 0.7371899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3915 3295 0.648380 -0.798511 -0.176318 -0.1627561 -0.4292790 0.3584780 0.8128490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3915 3924 -0.558153 -0.343289 -0.857618 -0.5618047 -0.5498108 -0.2536254 0.5637000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3915 4095 -0.733401 0.771000 0.284834 -0.9044964 -0.3427583 0.2513077 0.0353203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3916 3923 -1.058556 0.276788 0.286450 0.3426501 -0.3372281 -0.0159585 0.8767060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3916 4096 0.106598 -0.556877 0.832504 -0.0176857 -0.4234880 0.5764951 0.6985689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3917 3922 0.108081 -0.973071 -0.433178 0.1871894 0.6390980 0.4128124 0.6213693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3917 4097 0.962726 -0.068803 0.528828 0.2479051 0.8632391 0.1733083 0.4041356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3918 3921 -0.675050 0.427967 0.576342 -0.7783656 -0.2423799 -0.2450462 0.5247392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3919 3299 -0.362325 -0.364831 -1.000583 -0.0743191 -0.4028257 0.6696635 0.6194828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3919 4099 0.403428 0.394106 0.947205 -0.6821638 0.2513571 -0.6866284 0.0036829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3920 3959 -0.154769 -0.722681 0.262347 0.2486908 -0.3506164 -0.6946499 0.5767864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3920 4060 0.465670 0.112397 0.892696 0.2229891 -0.0545829 -0.1207142 0.9657767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3921 3958 -0.172114 -0.992676 0.029394 0.7123991 -0.1332044 0.6379300 0.2603641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3922 3957 -0.482937 -0.757690 -0.368213 -0.0071801 0.1552167 -0.7370112 0.6577771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3923 3956 -0.530330 0.658682 0.489533 0.2720081 0.4085559 -0.0669429 0.8686843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3923 4063 0.682989 -0.135806 0.686037 -0.5163363 -0.4038933 -0.6167820 0.4357143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3924 4064 0.368789 -0.552695 0.773702 -0.0720995 -0.4663144 0.2144910 0.8551878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3925 3954 0.519634 -0.176550 0.858256 -0.4606074 0.7147950 0.2286734 0.4739381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3925 4065 -0.113142 0.812763 0.361425 0.0853485 -0.5283644 -0.1068581 0.8379308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3926 3913 0.793389 0.280352 -0.512389 0.2299067 -0.0883521 0.8654561 0.4362596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3926 3953 -0.809797 -0.276695 0.468204 -0.0903916 0.3632242 0.8246887 0.4240119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3926 4066 0.460287 0.001071 0.768824 -0.5932633 -0.2314911 -0.7649235 0.0966567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3927 3952 -0.047869 -0.718668 -0.780792 0.1727947 -0.6377323 -0.0078659 0.7505849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3927 4067 -0.342903 -0.555753 0.605917 0.5227758 0.0674955 -0.8404135 0.1259166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3928 3951 -0.655010 -0.251121 0.412494 -0.1156677 -0.2032358 0.9471590 0.2195585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3928 4068 0.489930 -0.119199 0.612137 -0.3167318 -0.3948744 0.8167521 0.2768957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3930 3949 -1.034078 0.072628 0.476347 0.3624588 0.4892376 -0.2827839 0.7411501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3930 4070 0.282315 -0.374717 0.908410 0.6222161 0.0249885 0.6520038 0.4325665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3931 3908 0.578015 0.581618 -0.570914 -0.5694655 0.5372350 0.2984476 0.5459089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3931 3948 -0.802039 -0.431328 0.574111 -0.0391985 -0.6735325 -0.1724891 0.7176803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3932 3947 0.008869 0.465551 0.957805 0.7244413 0.4260572 0.0287443 0.5411412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3933 3946 -0.064114 -0.937604 0.193715 0.0563659 -0.3152377 -0.2326522 0.9183251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3933 4073 -0.853494 0.212064 0.588900 -0.8002736 -0.1154460 0.2395305 0.5374565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3934 3274 -0.482711 0.686951 -0.331719 0.4187208 0.6476240 -0.0344615 0.6356638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3934 3945 0.936165 0.341185 -0.170629 0.0594511 -0.4030605 0.2727130 0.8715707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3934 4074 0.468575 -0.818228 0.506052 -0.6594574 0.3102813 -0.6838818 0.0338697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3935 3275 0.173761 -0.538490 -1.079899 0.3858587 -0.3175109 0.2829177 0.8186925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3935 3944 -0.434503 -0.893686 0.511089 0.1892647 0.1605778 -0.9322351 0.2633087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3935 4075 0.006826 0.463079 0.791519 -0.0115571 0.5275251 -0.6834220 0.5044979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3936 3276 -0.181675 0.367625 -1.040106 -0.1022622 0.2516658 0.9616287 0.0384330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3936 3903 -0.306162 -0.952914 -0.294378 -0.4114624 -0.2832521 -0.2934052 0.8150952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3936 3943 0.379078 0.726333 0.392448 0.2979180 0.1469194 0.5950856 0.7318010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3936 4076 0.065006 -0.187687 0.974848 0.2821151 -0.4428454 0.6738732 0.5198017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3937 4077 -0.609619 -0.917914 0.184373 -0.1482175 -0.5204143 -0.2293931 0.8090608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3938 3941 -0.424603 -0.449924 -0.632946 0.0122954 -0.1527313 0.8014997 0.5780313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3940 3240 -0.605092 0.484108 -0.234482 0.5578587 0.6986063 -0.2662569 0.3603475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3941 3978 -0.484295 0.823459 -0.449339 0.5723421 -0.6311128 0.2562701 0.4565598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3942 3242 0.699033 -0.245873 -0.664474 -0.0737322 -0.5713971 -0.8172916 0.0101618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3942 3937 0.065454 -0.935166 0.019567 -0.7824970 -0.3127151 0.2341773 0.4848389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3942 3977 0.151118 1.046194 -0.032907 0.4091741 -0.1756304 -0.8904397 0.0940619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3944 3975 0.426329 0.176879 0.938520 0.5201663 -0.5390036 -0.1846723 0.6362376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3944 4044 -0.766620 -0.589079 0.598459 0.0700026 -0.3994895 0.8708617 0.2776827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3945 3974 0.132107 -0.418029 -0.874811 0.3568936 -0.9014112 0.2155363 0.1167429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3945 4045 0.024567 -0.945417 0.139447 0.5388024 -0.6671112 0.0199873 0.5140575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3946 4046 -0.350929 -0.176691 0.773514 -0.5017553 0.1699725 -0.2466267 0.8114963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3947 3972 -0.127249 0.671976 -0.755817 -0.2229748 0.7021127 0.5443461 0.4012572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3948 3971 0.663594 -0.589647 0.509310 0.5883926 0.0657497 0.7537639 0.2851510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3948 4048 0.535339 0.803979 0.126051 0.2695668 0.9250063 0.2577228 0.0726363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3949 3970 -0.690428 -0.690163 -0.562587 0.2042755 0.0694008 0.9217426 0.3222509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3949 4049 -0.485072 0.247492 0.762346 0.2021928 0.1262695 -0.9635968 0.1210591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3950 3929 0.668050 -1.039488 0.095928 -0.6810711 0.3242109 0.0854047 0.6509497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3950 3969 -0.660838 0.741255 -0.047211 0.0347055 0.5982500 -0.1177993 0.7918433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3950 4050 0.887823 0.646022 -0.074735 0.6080421 -0.3289906 0.6858552 0.2272720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3951 4051 -0.778189 -0.236319 0.678730 0.4181903 0.0200378 0.2736195 0.8659375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3952 3252 -0.593489 0.136462 -0.696735 -0.1883339 0.6358449 -0.0395665 0.7474397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3952 3967 -0.501772 -0.640048 0.155478 0.7041794 -0.0583589 0.1659883 0.6878760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3952 4052 0.561778 -0.241645 0.801598 0.0887250 -0.1345505 -0.8802666 0.4462676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3953 3966 -0.076360 0.923248 0.036057 -0.1420459 -0.2861261 -0.6871251 0.6525442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3953 4053 -0.619008 0.118675 0.713033 0.7124186 0.4432242 -0.5190241 0.1631752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3954 3254 0.721849 -0.525735 -0.410956 0.7046921 -0.6004956 -0.1609250 0.3419316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3954 4054 -0.799941 0.596848 0.379256 -0.3518805 0.6547826 0.4584956 0.4870540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3955 3255 -0.475432 0.543488 -0.817704 0.1859220 0.3379949 -0.6990000 0.6021556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3955 3924 -0.567864 0.439411 0.761583 0.3354350 -0.4375543 0.6981226 0.4567871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3955 3964 0.522558 -0.708938 -0.703696 0.1782387 -0.2040641 0.3389110 0.9009596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3955 4055 0.262361 -0.752435 0.592822 -0.6156229 0.5339025 -0.5350383 0.2229138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3956 3256 0.015133 -0.421217 -0.751725 -0.2694410 0.5259370 0.3309713 0.7356968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3956 4056 -0.238826 0.401137 0.671014 0.4668480 -0.5989829 -0.2869001 0.5839185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3957 3257 0.220953 0.745423 -0.592379 0.0195750 -0.4233049 0.3098002 0.8511484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3957 3962 0.892757 -0.417706 -0.063257 0.4347415 0.7036069 -0.5009567 0.2549107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3957 4057 -0.032332 -0.813880 0.654176 -0.0918535 -0.3857140 -0.0183953 0.9178504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3958 3961 -0.061052 0.657826 0.507769 -0.8125129 0.4525678 -0.2244316 0.2909220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3959 4059 -0.311712 1.004984 0.180828 0.3739761 0.3319552 0.8659534 0.0085044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3961 3998 -0.580487 -0.573652 -0.119314 -0.2233885 0.8385199 -0.4838880 0.1132889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3961 4021 0.721883 -0.854226 -0.088979 -0.0877199 0.7665549 -0.4661649 0.4328847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3962 3997 -0.469982 0.852295 0.084887 0.9113848 -0.1055257 -0.1255555 0.3774625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3962 4022 -0.760050 -0.271135 0.503449 0.0221753 -0.4775964 0.7856777 0.3925819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3963 3956 0.623691 -0.140745 0.785667 0.2136586 -0.3305256 0.3820387 0.8361515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3963 3996 -0.665288 0.033611 -0.805088 -0.3796413 -0.0679035 0.0242309 0.9223201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3963 4023 -0.740751 -0.219390 0.583131 -0.0884720 -0.6679898 -0.2665887 0.6891246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3964 3995 -0.088127 -0.922372 -0.723698 0.2370537 -0.7916527 0.3677246 0.4264623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3964 4024 0.238029 -0.510648 0.944782 0.6572101 -0.0586391 0.7301123 0.1776863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3965 3954 0.714174 -0.785175 -0.204462 0.5296857 0.1951809 -0.5970444 0.5699785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3965 4025 0.141675 -0.277539 0.986435 0.0939849 0.1378719 -0.7487066 0.6415579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3966 4026 0.337594 -0.355639 0.757485 0.6910225 0.2803585 0.6622946 0.0724768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3967 3992 -0.576395 0.501775 0.564650 0.2873771 0.8381923 0.4600299 0.0567504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3967 4027 0.861101 0.533780 0.386017 -0.4122749 0.2091562 -0.8834622 0.0760111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3968 3991 -1.039859 0.234043 -0.265797 0.4056457 0.5598326 0.6918868 0.2081624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3968 4028 0.163698 0.735881 0.662737 -0.3349469 -0.1120548 0.8376253 0.4166991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3969 4029 0.088916 0.852989 0.587715 -0.8452257 -0.1310631 -0.2991274 0.4230116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3970 3989 -0.116065 0.568769 -0.805271 0.0246128 0.3052041 0.2764935 0.9109314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3971 3988 -0.029808 0.576302 0.773321 0.4878635 0.2412041 -0.7471550 0.3815354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3971 4031 0.383979 -0.638053 0.314472 0.6110751 -0.4412976 0.5840996 0.3011168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3972 3987 0.545569 -0.128151 0.642364 -0.3628765 0.1606905 -0.2733090 0.8762428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3972 4032 -0.608073 0.613278 0.763457 -0.8952865 0.1647019 0.2581475 0.3235665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3973 3946 0.406051 0.244886 0.857884 0.4194544 -0.3405529 -0.7136623 0.4458338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3974 3985 -0.517719 -0.164942 0.803890 0.0407764 0.3088725 0.0626650 0.9481604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3974 4034 0.313947 -0.896802 -0.076058 0.2274288 0.5473610 0.4709121 0.6533864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3975 3984 0.160081 0.812227 -0.611148 0.1258448 0.3103136 0.3835878 0.8606561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3975 4035 0.444696 0.586478 0.834250 -0.2427077 0.0936605 0.7029135 0.6619919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3976 3983 -0.356075 -0.798798 0.521697 0.0440391 -0.7582304 -0.5903256 0.2732453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3976 4036 0.337532 0.450914 0.567474 0.4327977 0.7551457 0.3237342 0.3709949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3977 3982 -0.470839 -0.887093 0.017516 0.3213675 0.0531004 -0.6276419 0.7070849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3977 4037 -0.128908 0.020833 1.042992 -0.1219557 -0.5129304 0.6822570 0.5065121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3978 4038 0.327756 0.731871 0.516645 -0.5527050 0.0366328 -0.3173545 0.7697151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3979 3940 -0.071533 -1.003973 -0.147484 -0.1257959 -0.8004163 0.4009863 0.4274566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3980 4000 -0.080884 -0.125756 1.113682 0.0311785 -0.0475076 0.7519744 0.6567385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3981 3201 0.552087 0.588509 -0.280051 0.6624373 -0.0420647 0.3742233 0.6475835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3981 3978 0.328542 0.170456 0.924610 0.4788556 -0.3281307 0.7035425 0.4099458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3981 4001 -0.507485 -0.541210 0.573398 0.4296683 -0.5931430 0.5126096 0.4481049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3984 4004 0.057162 0.504808 1.064668 0.0750204 -0.0333911 0.1554179 0.9844299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3985 4005 0.314046 -0.712060 0.555520 0.0939420 0.2622793 -0.1890326 0.9416216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3986 3973 0.432839 0.828180 0.229728 0.1483129 0.6599253 0.5700907 0.4663673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3986 4006 0.626485 -0.424205 0.606718 -0.2370866 0.7746475 -0.3780476 0.4480973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3987 4007 -0.862474 -0.159256 0.681186 -0.1527403 0.5511326 0.8197656 0.0301263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3988 4008 -0.335969 0.814323 0.425724 -0.2973781 0.8245474 0.2554711 0.4079489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3989 4009 0.399332 0.235907 0.832265 0.2646757 0.0192207 0.9369092 0.2275487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3990 3969 -0.207396 -0.648743 -0.848888 0.7152186 0.3429473 -0.2832622 0.5390844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3990 4010 0.739993 -0.720422 0.272714 0.7318692 -0.2632388 0.2275014 0.5859317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3991 3211 -0.806295 -0.499016 -0.482476 -0.2322771 -0.8803868 -0.4134022 0.0080693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3991 4011 0.701509 0.520145 0.543994 -0.8378013 0.0094003 -0.2895607 0.4627691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3992 3212 0.345609 -0.925175 -0.428937 -0.5835970 0.2215336 0.5856314 0.5170815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3992 4012 -0.371364 0.776134 0.495798 -0.0413843 -0.0932907 0.0924395 0.9904742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3993 3966 -0.326798 -0.807517 -0.546780 -0.0134369 0.0129216 -0.8142905 0.5801581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3993 4013 -0.743176 -0.316481 0.921679 -0.0821411 0.4712621 -0.8573698 0.1899524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3994 3965 -0.908039 -0.370561 -0.048085 -0.0931971 0.1550340 -0.7491207 0.6372573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3994 4014 0.232650 -0.220171 0.759854 -0.0932397 -0.3883138 0.4274661 0.8110435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3995 4015 0.704137 -0.617413 0.038732 -0.4605255 0.7612497 -0.2798958 0.3606569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3996 4016 -0.783845 -0.448275 0.264941 0.3854729 -0.7329118 0.3267059 0.4555373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3997 4017 -0.329501 0.557531 0.170900 -0.3851246 -0.4368424 0.7848575 0.2117697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3998 4018 0.016834 -0.737303 0.521408 0.1834916 -0.7171911 0.2782379 0.6120060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3999 3960 0.467865 -0.582176 -0.636955 0.2101924 0.7273768 -0.4398992 0.4829398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4000 4039 0.269151 1.096199 0.077251 -0.3303467 -0.4019862 0.6944548 0.4970017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4000 4780 -0.044957 -0.076143 0.878454 -0.0288425 -0.5459973 -0.1637491 0.8211220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4001 4038 0.972952 -0.526578 -0.304778 -0.3217462 0.2617990 -0.2270474 0.8811300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4001 4781 0.673725 0.491165 0.663616 -0.3963041 -0.2722937 -0.7236780 0.4950651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4002 3982 0.127592 -0.793126 -0.470061 0.4177081 -0.6513095 -0.6271900 0.0891550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4002 4037 0.777179 -0.244417 0.732400 -0.8556412 -0.3342831 0.0978821 0.3828211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4002 4782 -0.278615 0.785292 0.405727 -0.4236802 0.3307201 0.2053612 0.8178913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4003 3983 1.095346 0.429222 -0.253086 0.6511491 -0.2341499 0.3532959 0.6295718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4003 4036 -0.152972 -0.637837 -0.822055 0.8035429 -0.5240597 -0.2470665 0.1365226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4003 4783 -0.704866 -0.449275 0.432972 -0.3085519 0.1691968 0.8287556 0.4351234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4004 4784 0.241146 0.618341 0.679663 -0.2847767 -0.3095348 0.7442019 0.5188969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4005 4785 0.198184 -0.776197 0.796878 -0.3739242 0.0434529 0.0713819 0.9236867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4006 4033 -0.795393 0.481386 0.241238 0.7844796 -0.2920081 -0.2091689 0.5055406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4006 4786 -0.379947 -0.838067 0.289199 0.0436204 -0.0265969 0.2059847 0.9772206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4007 4032 0.899496 -0.707933 0.208674 -0.2286400 0.3574232 -0.8923221 0.1540573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4008 4031 -0.599821 -0.411954 0.713711 -0.4417136 -0.0291079 0.7133282 0.5433274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4008 4788 -0.466167 0.843522 0.142778 -0.9218671 0.2760928 0.2038948 0.1798909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4009 4030 0.531420 0.720606 -0.026536 -0.5589994 -0.0741167 -0.1509693 0.8119327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4010 4029 -0.687130 -0.366014 0.612631 -0.6668780 0.5551022 -0.4666344 0.1714283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4010 4790 0.701006 -0.140873 0.562555 -0.4897160 0.2713286 0.2527800 0.7890889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4011 4028 -0.512526 -0.927249 -0.206943 -0.1491051 0.0913013 0.2166327 0.9604697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4011 4791 0.725467 -0.595482 0.617495 -0.4083490 0.1355223 -0.6129922 0.6626653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4012 4027 -0.809474 -0.233107 0.513204 -0.6787066 0.2242594 0.5515445 0.4299579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4012 4792 -0.020015 0.881837 0.751039 -0.4417064 -0.3371179 -0.8215085 0.1279480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4013 4026 0.863016 0.896437 0.076337 -0.3729431 -0.1919911 -0.7831562 0.4590416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4013 4793 0.517074 -0.975214 0.407002 0.6029227 0.4757136 0.0232684 0.6400307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4014 4794 0.371307 -1.008966 0.523180 0.7219062 -0.2775304 0.5727115 0.2717163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4016 4023 0.258395 -0.985728 0.095437 -0.7219296 0.0428712 -0.3840634 0.5739991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4016 4796 0.694293 -0.014843 0.628184 -0.3049700 0.1520971 -0.6844456 0.6445106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4017 4022 -0.224206 -0.933754 -0.793671 0.7795959 0.0265563 0.4085249 0.4739540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4017 4797 0.889293 -0.558657 -0.033578 -0.7156423 -0.2124956 -0.5830528 0.3205482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4018 4021 0.021852 0.436158 0.908103 0.1074314 0.5203402 -0.0642351 0.8447357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4018 4798 0.616632 -0.490229 0.347556 -0.4179352 -0.2326156 -0.8737426 0.0882839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4019 3999 -0.137422 1.065164 -0.211628 0.3362430 0.8729654 0.0473173 0.3501901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4019 4799 0.067990 -1.001519 0.270728 0.2379715 0.2164439 -0.9029745 0.2848836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4020 4059 0.397143 0.064727 0.874439 -0.5841469 -0.7581069 0.0435729 0.2866142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4021 4058 -0.909687 0.337382 -0.046400 -0.1449877 0.1093591 -0.9678991 0.1737543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4022 4057 -1.138373 0.023995 0.368570 -0.4667308 -0.2096151 0.4104135 0.7548408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4022 4762 0.099885 -0.081765 0.938378 0.2616777 -0.2330781 0.6499698 0.6743431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4023 4056 0.719557 0.492763 -0.697895 0.6818533 0.1716025 -0.5222356 0.4825958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4023 4763 0.610726 -0.438427 0.640313 -0.0277741 0.4684787 0.5982970 0.6494590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4024 4055 0.739383 -0.921545 -0.134066 -0.4065486 -0.1215279 0.3377799 0.8401511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4024 4764 0.714710 0.412501 0.619235 -0.9252750 0.1810511 -0.1230963 0.3097322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4025 4014 -0.647549 -0.831800 0.086396 -0.3733405 0.1302745 -0.6965312 0.5987401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4025 4054 0.752011 0.851038 -0.142925 -0.0611002 0.5926748 0.7933135 0.1251277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4025 4765 -0.105750 0.076355 1.054637 0.0354530 -0.6203896 0.7775582 0.0962454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4026 4766 0.440378 0.782020 -0.018631 0.6142414 0.6702101 0.2755482 0.3124086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4027 4052 -0.757846 0.595260 0.341738 0.8522026 -0.1114154 -0.1904323 0.4744185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4027 4767 -0.339843 -0.833280 0.518939 -0.2706227 -0.0767457 0.7746928 0.5663254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4028 4051 -0.624850 -0.749705 -0.592310 0.6176711 0.4090829 0.4723749 0.4774888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4028 4768 0.119041 -0.712744 0.401825 0.2414391 -0.1462703 -0.5096717 0.8127404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4029 4050 0.590803 -0.078420 -0.726938 -0.1326028 0.8985555 -0.1932229 0.3710518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4029 4769 0.268385 -0.976423 0.366071 0.8570055 0.3783981 0.3191023 0.1432832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4030 3970 -0.572467 0.756668 -0.191194 -0.4792709 0.2226893 -0.7208890 0.4483613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4030 4770 0.499646 -0.836025 0.298932 0.0702893 -0.6276030 0.6596824 0.4074225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4031 4048 -0.686763 0.194026 0.647186 -0.1239165 -0.3622966 -0.9047343 0.1866595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4031 4771 0.403382 -0.272609 0.600575 0.1582414 -0.4166847 -0.7929279 0.4154502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4032 4772 -0.865808 -0.415369 0.095457 -0.5744743 -0.8024076 0.1457682 0.0698062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4033 3973 -0.342648 -0.724562 -0.505880 0.2694974 -0.5389398 -0.7298531 0.3228458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4033 4046 -0.898776 0.164618 0.288477 -0.8769329 0.2142137 0.2406555 0.3566316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4033 4773 0.366337 0.783968 0.466093 -0.4562340 -0.2841698 -0.8326425 0.1334340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4034 4005 -0.531131 0.863637 -0.116896 0.2099330 -0.1311590 -0.6107465 0.7521397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4034 4045 0.371328 -0.897374 0.057688 0.0304407 -0.2130742 -0.8598282 0.4629991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4034 4774 -0.783125 -0.285548 0.155909 -0.1623899 -0.0616754 0.5836471 0.7932097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4035 4004 1.086703 -0.194889 -0.293763 0.5441833 -0.0848697 -0.1896966 0.8128203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4035 4044 -0.750658 0.295818 0.093542 0.5163716 -0.3129861 0.4639049 0.6482224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4035 4775 -0.123575 -0.539058 0.816904 0.2884177 -0.7235269 0.3279994 0.5345470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4036 4776 0.022747 1.045832 0.098557 0.0589144 0.9798784 0.1009478 0.1617927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4037 4042 0.414485 -0.010934 -0.797588 -0.1370693 0.9654287 -0.0463604 0.2168180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4037 4777 0.379089 -0.725356 0.435505 0.0951058 -0.0692449 -0.8661848 0.4856788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4038 4041 0.954245 0.007642 -0.018724 0.3997874 0.1370824 -0.7482159 0.5114210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4039 3979 -0.001096 0.830105 -0.417758 0.1246100 -0.2374640 0.5218868 0.8097638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4039 4779 -0.209671 -0.762978 0.404130 0.6755364 -0.3889779 0.3184347 0.5393942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4040 4079 -0.660341 -0.666256 -0.714549 -0.1802515 0.0244366 -0.9558768 0.2306766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4040 4740 -0.801926 0.139611 0.665545 0.0632624 -0.4822197 -0.0668450 0.8712025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4041 3941 0.695011 -0.496307 -0.519448 -0.8059754 -0.0308652 0.5819298 0.1039648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4041 4741 -0.778611 0.322913 0.755099 -0.6060853 -0.3077266 -0.3757530 0.6299006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4042 3942 0.298851 0.930937 -0.043481 -0.4210480 -0.5444737 0.6385279 0.3443096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4042 4742 -0.188701 -0.857247 0.128186 0.4475746 -0.7752875 -0.0255324 0.4449207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4043 3943 0.719554 -0.680332 -0.475320 -0.5299700 0.2688012 0.5091570 0.6226050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4043 4036 0.305288 0.440579 -0.717640 0.2684659 -0.5896561 0.1988835 0.7353076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4043 4076 -0.351537 -0.483078 0.973777 -0.2995855 0.0645287 0.9179705 0.2518228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4043 4743 -0.502589 0.816460 0.096406 0.5634948 0.1752315 -0.7978100 0.1235585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4044 4744 0.640009 0.251007 0.665409 -0.3999856 0.5884488 -0.6330052 0.3050312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4045 4745 0.702643 -0.403947 0.420692 0.3161738 -0.4951123 0.8063980 0.0679721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4046 4073 -0.921709 0.169564 0.164413 -0.4395581 -0.6620991 0.4118278 0.4458826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4046 4746 -0.064861 -1.037171 0.044538 0.4881485 -0.1225688 0.4543869 0.7349970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4047 3947 -0.264450 -0.778765 -0.338108 -0.0234795 0.5873600 0.1949587 0.7851421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4047 4032 -0.980579 0.387541 -0.230065 -0.3240859 0.2960878 -0.8464242 0.3014406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4047 4072 0.927864 -0.477610 -0.091329 -0.1129048 0.5869306 0.7902173 0.1353570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4048 4071 0.819250 -0.173300 0.745243 -0.5541063 -0.0219495 -0.1356373 0.8210280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4048 4748 -0.165570 0.902438 0.355174 0.0175688 0.1850074 0.3808196 0.9057814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4049 4030 0.979239 0.281259 -0.124372 0.1998814 -0.6550081 0.5462325 0.4823296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4049 4070 -0.983267 -0.430753 -0.090456 0.3148466 -0.0823264 -0.3744507 0.8682630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4049 4749 0.270992 -0.501766 0.890162 -0.3025338 0.1049162 -0.8299449 0.4567903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4050 4069 0.044456 0.230648 0.880897 0.5202536 0.2631570 -0.7941416 0.1715333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4050 4750 -0.143562 -0.831922 0.257329 0.3912015 0.5328761 -0.7456758 0.0834990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4051 4751 -0.698514 0.699709 0.304882 -0.7938463 -0.0529556 0.1223983 0.5933148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4052 4067 -0.825589 -0.048940 -0.126230 -0.1952385 -0.1774563 -0.1971671 0.9442014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4052 4752 -0.151883 0.986182 0.418629 0.0354051 -0.4008612 0.0360191 0.9147455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4053 4066 -0.349548 0.410401 0.705355 0.4619379 -0.2537360 -0.7666998 0.3666098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4053 4753 -0.780719 -0.817610 0.050185 0.3024269 -0.2302787 0.8355521 0.3966892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4054 4065 -0.577335 -0.439795 0.942453 -0.0512777 0.4315424 0.1348294 0.8904846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4054 4754 -0.049825 0.997536 0.335712 0.1677025 -0.2939009 -0.4352935 0.8342767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4055 4755 0.737155 -0.523838 0.327075 0.2508903 0.3509690 -0.7032898 0.5650294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4056 4063 0.586521 -0.016376 -0.812625 -0.3613635 -0.6909024 0.1288781 0.6127486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4057 4062 -0.571982 0.088002 0.743176 0.2252137 -0.0831271 0.8981850 0.3682829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4057 4757 0.356612 -0.894784 0.422674 0.1961126 0.1835675 0.8900544 0.3683014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4058 3958 -0.289756 0.023709 -0.661468 0.0180203 -0.2961045 0.2202633 0.9292370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4058 4758 0.568303 0.025350 0.878368 0.3684397 0.5249426 0.7635883 0.0749690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4059 4759 0.794410 -0.852310 0.314354 0.6093328 0.4427737 -0.6511159 0.0933439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4060 4720 0.541773 0.579177 0.387852 -0.5058879 -0.3208016 -0.5961638 0.5345582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4061 3921 -0.877866 0.155677 -0.603366 -0.6603285 0.1463661 -0.6488301 0.3486584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4061 4098 0.347615 -0.820176 -0.557761 -0.7496640 0.0703855 -0.6160105 0.2314752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4061 4721 0.763419 -0.277137 0.627512 0.5750496 0.1413725 -0.1028076 0.7992261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4062 3922 0.467161 -0.648590 -0.720973 -0.0067448 0.0541054 -0.3472538 0.9361848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4062 4097 0.937235 0.388544 0.141391 0.4016742 0.1149830 -0.2582770 0.8710509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4062 4722 -0.418213 0.570879 0.862836 -0.7380529 -0.4839753 0.2300207 0.4100444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4063 4096 -0.581775 0.939297 -0.435765 -0.5718284 0.0668888 -0.8116226 0.0990303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4063 4723 0.618400 0.838222 0.375714 0.1546450 -0.7098632 -0.6393663 0.2517735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4064 4055 -0.352609 0.296134 0.914382 0.2404697 -0.2840466 -0.1469209 0.9164639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4064 4095 0.442433 -0.155021 -0.759311 -0.0903169 -0.1334578 0.2707498 0.9490661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4065 4094 -0.763578 0.045412 0.114641 0.1667598 0.7487697 0.2506284 0.5905256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4065 4725 -0.013583 0.832092 0.300668 -0.7853477 -0.1199527 -0.6058582 0.0421449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4066 4726 0.571034 0.360931 0.582321 -0.0187051 -0.1019266 -0.0516201 0.9932756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4067 4092 -0.936271 -0.771327 -0.257107 -0.6195216 0.1652133 0.5529200 0.5321438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4067 4727 -0.143527 0.548562 0.824568 0.5611246 -0.4300023 -0.7027268 0.0800764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4068 4051 0.193757 -0.038486 0.856553 0.6104025 -0.0882269 0.4183874 0.6667659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4068 4091 -0.191826 0.014240 -1.038908 -0.1250670 -0.7330446 0.2508151 0.6197546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4069 3929 0.267231 -0.496713 -0.509357 -0.2720898 -0.1499129 -0.8664062 0.3909395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4069 4090 -0.843626 -0.651614 0.052818 -0.6055681 -0.4039538 -0.1293327 0.6733362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4069 4729 -0.046723 0.393113 0.668048 -0.3976389 -0.4979894 0.2584075 0.7260272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4070 4089 -0.414519 -0.588236 0.521363 0.2653369 0.6538557 0.6931901 0.1468213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4070 4730 0.428908 0.606499 0.787509 -0.3869608 0.5852703 0.6024786 0.3804466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4071 3931 0.360458 0.161422 -0.925746 0.3758334 -0.3663340 -0.3889522 0.7571426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4072 3932 0.536553 0.141639 -0.988987 -0.2995508 -0.0112092 -0.8137134 0.4980102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4072 4087 -0.874360 0.039551 -0.441717 0.6011228 -0.1359415 -0.5603013 0.5533838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4072 4732 -0.482750 -0.326247 0.595529 0.5553276 0.5417578 -0.4930368 0.3937315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4073 4086 0.394933 -0.427438 0.883984 0.1520362 0.9246875 -0.3328160 0.1052214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4073 4733 -0.893598 -0.858111 0.319496 -0.4918654 -0.5982483 0.6212991 0.1189739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4074 4085 0.404513 0.661636 -0.671316 0.0676509 0.4705135 0.2754254 0.8355724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4074 4734 0.661286 0.213930 0.617341 -0.2226394 0.0146273 0.9675701 0.1184308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4075 4044 0.472466 -0.591786 0.674164 0.1960964 -0.7579444 0.4967316 0.3745987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4075 4084 -0.311033 0.558696 -0.593366 0.9024181 -0.0869361 -0.2641368 0.3291131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4075 4735 -0.887583 -0.483133 0.091277 -0.0282212 -0.0756750 0.5329951 0.8422548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4076 4083 -0.459540 0.582318 0.727599 0.4697077 0.5946338 -0.1128616 0.6426878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4076 4736 0.542783 -0.364414 0.775113 0.2515068 -0.3458200 0.3818153 0.8193717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4077 4082 -0.888152 0.009844 0.538693 -0.6964328 -0.3403158 0.6302734 0.0438402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4078 3938 0.274604 0.348812 -0.805830 -0.3134375 0.5038006 -0.7289675 0.3413915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4078 4041 -0.223250 0.948211 0.157684 -0.4793174 -0.0398300 0.8714555 0.0960919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4078 4081 0.362387 -0.833035 -0.486607 0.0513680 0.2389098 0.4374436 0.8654054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4079 3939 -0.850592 0.550684 -0.266547 -0.2741334 0.2345677 -0.5931641 0.7197120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4079 4739 0.920425 -0.461549 0.197171 0.4376803 0.0719413 -0.4242425 0.7894800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4080 4119 -0.526333 0.081246 -0.955918 0.4258814 0.2673279 -0.5849636 0.6363792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4081 4118 -0.347948 -0.849016 -0.275886 0.1315729 -0.1874921 -0.9731584 0.0223144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4082 4117 -0.310331 -0.409267 0.374367 -0.4520229 0.0249631 0.6454517 0.6151782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4083 4116 -0.632574 0.151299 -0.714619 -0.2810906 -0.4741223 0.6185347 0.5600097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4083 4703 -0.743197 0.471416 0.592015 -0.5538365 -0.0793285 -0.4018673 0.7248964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4084 4704 -0.637858 0.555973 0.573364 -0.5972776 0.1098871 0.1000774 0.7881426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4085 4114 1.061868 -0.261490 -0.103036 -0.0997358 0.7385687 0.3234073 0.5830753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4086 4113 -0.715154 -0.535707 -0.385633 0.0726056 0.2735385 -0.5745778 0.7679619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4086 4706 0.537859 -0.948788 -0.115821 0.0294306 0.4992914 0.0526236 0.8643337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4087 4112 0.071409 -0.616399 0.560612 -0.1997911 -0.0666366 0.7253513 0.6553690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4087 4707 -0.581491 0.386232 0.704915 0.5374427 -0.3119288 -0.4193305 0.6618291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4088 4071 -0.773506 0.125378 -0.664133 0.1116010 -0.3022455 0.0859596 0.9427639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4088 4111 0.796626 -0.117946 0.765038 0.3711233 -0.2748522 0.5354398 0.7071266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4088 4708 -0.746476 -0.482105 0.662461 -0.6135724 0.1250514 0.7579510 0.1827602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4089 4709 0.303687 0.693762 0.786384 -0.9172156 0.0381568 -0.1115752 0.3805397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4090 4710 0.582101 -0.546006 0.392956 -0.3428435 0.7938837 -0.4920764 0.1003382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4091 4108 -0.930589 0.571618 0.360771 0.4112659 -0.1191576 -0.0407801 0.9027729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4091 4711 -0.151457 -0.498413 0.700232 0.2715788 0.3837059 -0.8334842 0.2903769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4092 4107 -0.458115 0.776871 0.080136 0.1884519 0.0048627 -0.8623889 0.4698378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4092 4712 -0.850099 -0.483189 0.527564 -0.0586467 -0.8466351 0.4118684 0.3318645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4093 3913 -0.665021 -0.408532 -0.719146 -0.5728429 0.0367248 -0.7043560 0.4175942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4093 4066 0.474596 -0.884883 -0.031850 -0.2860320 -0.2818116 -0.2953330 0.8669177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4093 4106 -0.534058 0.464316 0.026835 -0.4445030 0.2581147 0.1816983 0.8383195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4093 4713 0.485457 0.472326 0.790322 0.0817482 -0.2122816 -0.4955301 0.8382742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4094 4105 0.302563 0.085073 -0.916411 0.1041171 -0.1764215 -0.9521670 0.2267447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4094 4714 0.286088 1.160437 0.213646 -0.2093692 -0.0226623 -0.0130470 0.9774870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4095 4104 0.121009 -0.157315 -0.998181 -0.0614809 0.4566574 -0.4197058 0.7820046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4095 4715 -0.189237 -1.001521 -0.053600 -0.2528015 0.9410603 -0.2224399 0.0318974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4096 4103 -0.356370 -0.614191 -0.664588 0.2881343 -0.5378227 0.7860508 0.0992441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4096 4716 -0.087039 -0.671923 0.555513 -0.1246121 -0.5990624 -0.0385466 0.7900064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4097 4102 0.344725 0.862962 -0.203587 -0.3320326 0.1427351 0.8983524 0.2496880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4097 4717 -0.937435 0.321268 0.275683 0.7446999 -0.3707797 -0.4257115 0.3559693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4098 3918 -0.911530 0.200361 -0.668067 0.8053575 0.3250978 0.2456745 0.4305286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4098 4101 -0.087032 0.969625 0.136296 0.0933551 0.3936849 -0.4916380 0.7710960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4098 4718 0.745977 0.045292 0.853339 0.3698105 0.4331100 0.4833577 0.6648468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4099 4060 0.906854 0.836454 0.105026 -0.8045056 0.1298692 -0.5652282 0.1281477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4099 4719 0.458997 -0.816704 -0.035337 -0.2547019 0.4899400 -0.2990210 0.7782495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4100 4139 -0.660122 0.285543 0.897777 -0.2509274 0.6420755 -0.7148262 0.1174646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4101 4138 -0.808745 0.589099 -0.490622 -0.5146443 -0.1339013 0.7438508 0.4048427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4101 4681 -0.184357 0.446574 1.002447 0.1584357 0.3098742 0.1069024 0.9313689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4102 4137 0.108217 -0.925750 -0.137371 0.2462556 0.1358358 0.0261328 0.9592830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4102 4682 0.669865 0.082006 0.507391 0.2195435 -0.0571527 -0.9506769 0.2115364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4103 4136 0.075503 0.799357 0.158092 0.1771152 0.5908761 -0.6194866 0.4855224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4104 4135 0.364885 0.692859 -0.467297 -0.0525229 0.5240000 -0.6374881 0.5623827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4104 4684 0.686324 -0.566731 0.272508 0.5272369 -0.3578757 0.1493663 0.7560661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4105 4134 -0.334400 -0.286781 -0.750232 0.4874764 -0.6126794 0.3852776 0.4884178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4105 4685 -0.672504 -0.784016 0.247829 0.3341794 -0.3810077 -0.3570961 0.7846270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4106 3886 0.029366 0.479499 -0.699379 -0.1435232 0.2600039 -0.6890343 0.6610830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4106 4133 -0.441391 0.610948 0.564435 0.3717138 0.0965057 -0.8723713 0.3024630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4107 4132 -0.396193 -1.157007 0.017670 0.3554471 0.4039385 0.8427801 0.0145872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4107 4687 0.390588 -0.027627 1.033292 -0.1211186 -0.6060588 0.7659472 0.1770537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4108 4688 0.057202 0.177115 0.850033 -0.1620958 -0.2294041 -0.8206583 0.4976129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4109 4130 1.109145 0.069997 -0.349507 -0.8000579 0.0908641 0.5848669 0.0978863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4109 4689 -0.015280 0.853646 0.425056 -0.3426906 0.0349258 0.1045819 0.9329555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4110 4089 0.614548 -0.606099 0.345240 0.2920046 -0.0810947 0.4187975 0.8560173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4110 4129 -0.589189 0.634580 -0.379173 0.1219730 -0.1456887 0.1857418 0.9640526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4110 4690 -0.423867 0.117004 0.962256 -0.3420885 -0.1833262 -0.3266227 0.8617915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4111 4128 0.617169 -0.485969 0.443404 -0.3733944 -0.6095535 -0.3636846 0.5972894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4111 4691 -0.110970 0.672320 0.610701 0.0055844 0.1424708 0.1617457 0.9764780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4112 4692 0.499357 0.033507 1.064641 -0.1297046 -0.1248865 0.8980066 0.4014527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4113 4126 0.609385 -0.928334 -0.096215 -0.3161074 0.3810559 0.5580763 0.6659004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4113 4693 0.859451 0.220389 0.546473 -0.8918854 0.2623581 -0.1307506 0.3444023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4114 4694 -0.891562 0.555509 0.147624 0.5078753 -0.3706703 -0.7643267 0.1430765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4115 4124 0.557077 -0.080919 0.718763 0.0996336 -0.9116955 -0.3913936 0.0754682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4115 4695 0.281380 0.758290 0.237553 0.2086035 0.5136112 0.5689907 0.6074024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4116 4123 0.319666 1.127537 0.013270 0.8854474 0.2663665 0.3798452 0.0273767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4116 4696 0.892270 -0.175491 0.759314 -0.0678166 -0.0295103 -0.9971258 0.0164375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4117 4122 -0.620462 0.108162 0.344687 -0.1321417 -0.0255747 -0.5257571 0.8399190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4117 4697 0.303861 0.136107 0.932737 0.4757019 0.6263604 0.5151699 0.3405588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4119 4699 0.275741 -0.133709 0.834671 -0.1068388 0.5853012 -0.7210522 0.3550939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4120 4159 -0.571313 -0.235250 -0.708643 0.2388746 -0.2431479 -0.8612755 0.3768587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4120 4660 -0.617187 0.782575 0.161935 0.5668214 -0.4557598 -0.3444847 0.5935712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4121 4118 -0.697582 0.748601 0.299830 -0.7839855 0.0463343 -0.1641172 0.5968965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4121 4158 0.545297 -0.676366 -0.154393 -0.7578453 0.1389874 0.1368028 0.6226058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4121 4661 0.788368 0.790607 -0.045846 0.2590117 0.0901626 0.8040545 0.5275225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4122 4157 -0.397243 -0.794748 0.269952 -0.4526623 -0.2985550 -0.7360664 0.4051764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4123 4156 0.524813 -0.661734 0.219976 0.1896403 0.9472396 0.2163712 0.1412701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4123 4663 0.835578 0.749233 0.047584 -0.0471585 -0.0774400 -0.6597950 0.7459556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4124 4664 -0.637310 0.508844 0.447008 -0.3466088 -0.2236662 -0.0888604 0.9066089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4125 4114 -0.078846 0.353796 -0.792974 -0.0469682 0.5301280 -0.6626660 0.5269080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4125 4154 0.170665 -0.293728 0.980671 -0.2110737 0.7835662 0.1646985 0.5606659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4125 4665 0.763549 0.673895 0.116614 0.0080562 0.3048897 -0.4009918 0.8638188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4126 3866 0.247507 0.717713 -0.599474 0.9196824 0.1904600 -0.3280887 0.1013271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4126 4666 -0.394086 -0.764631 0.645398 0.3131601 -0.8404652 0.4420929 0.0101432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4127 4112 0.918540 -0.104016 0.378970 0.6797344 -0.3261738 -0.1687430 0.6348996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4127 4152 -0.847048 0.019318 -0.445975 0.4292810 0.4839376 0.1246652 0.7523170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4127 4667 -0.168761 -1.109708 0.081058 -0.1263025 0.0239108 -0.5920726 0.7955665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4128 4151 0.596333 0.398326 -0.804721 0.0876131 0.4204006 -0.6314073 0.6456873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4128 4668 0.481782 0.166828 0.647476 -0.2834902 0.5095239 -0.7076886 0.3989930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4129 4150 -0.304911 0.957854 -0.485424 -0.3879568 -0.2667905 -0.7962697 0.3798248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4130 3870 0.284093 0.966418 -0.304833 0.4748880 0.1922866 -0.3475717 0.7853032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4130 4149 0.512053 -0.464491 -0.625124 0.2450849 -0.0064890 0.6746965 0.6961867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4130 4670 -0.372838 -0.850795 0.197422 0.1236097 -0.6701939 0.5569431 0.4747368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4131 4108 0.742486 0.172654 0.610018 -0.2118523 -0.2428374 0.3597182 0.8756434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4131 4148 -0.721694 -0.265837 -0.484234 -0.3527928 -0.0414621 0.1778174 0.9177141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4131 4671 -0.588672 0.385529 0.481893 -0.5033695 0.1122366 -0.0864157 0.8523816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4132 4672 0.286328 0.882928 0.526977 -0.3015740 -0.3386818 -0.8302437 0.3241036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4133 4673 -0.313310 0.469425 0.749737 -0.7532324 -0.1321482 -0.1030706 0.6360458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4134 4145 -0.823394 0.095143 0.547837 0.1405423 0.6085068 0.2701370 0.7327983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4134 4674 0.619068 0.684396 0.682967 0.2805719 0.5210735 0.7707883 0.2358966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4135 4675 0.051224 0.084816 1.008811 0.1612833 0.6529989 0.2238717 0.7053095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4136 4676 -0.899469 -0.096879 0.676646 -0.3407388 -0.7924729 -0.2950818 0.4108656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4137 4142 0.205715 -1.045063 0.350355 -0.2359038 -0.1487487 0.6258137 0.7284095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4137 4677 0.510259 0.578117 0.971753 -0.1022463 -0.3669348 -0.9214539 0.0763365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4138 4141 0.894998 0.335709 0.362062 0.0209120 -0.2778095 -0.7531309 0.5959685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4139 4679 -0.309090 -0.568982 0.673523 -0.5814341 -0.1583665 0.7964420 0.0503452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4140 4179 0.591534 0.744287 -0.197996 -0.4259973 -0.8074306 0.2040006 0.3535052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4140 4640 -0.705957 0.476642 0.168158 0.0383198 -0.4370814 -0.4017008 0.8038208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4141 4178 -0.358586 0.870433 0.385347 -0.2902075 0.5859032 -0.6477552 0.3910373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4141 4641 0.904785 0.146569 0.554380 -0.3395812 0.0942563 -0.9206620 0.1678743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4142 4177 -0.963367 -0.418769 0.137094 -0.0645854 0.3718414 -0.2713660 0.8853943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4142 4642 0.320443 -0.935142 0.366716 -0.0269810 0.2735524 0.4573126 0.8457578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4143 4136 0.674191 0.841375 0.195068 -0.0682224 0.3276583 0.4809146 0.8103746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4143 4176 -0.721512 -0.726571 -0.101307 -0.5191955 -0.0480196 0.5765308 0.6290806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4143 4643 -0.095660 -0.087554 0.872109 0.3767018 -0.1107718 0.0546910 0.9180601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4144 4135 0.078261 0.850967 -0.540217 0.4777861 0.3656330 0.7223980 0.3408433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4144 4644 0.767923 0.246851 0.353674 0.4086207 -0.2767572 0.8644409 0.0957946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4145 4645 0.003631 0.716005 0.724810 -0.0136462 -0.3401529 -0.3707750 0.8640808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4146 4133 0.514877 0.621591 -0.014107 0.0594154 -0.2174134 -0.0915246 0.9699611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4146 4173 -0.467073 -0.794486 -0.050208 0.3180584 -0.2072632 0.6868612 0.6197601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4147 4132 0.511827 -0.617473 0.818436 0.1634563 -0.1424868 0.7108653 0.6690665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4147 4647 -0.941778 -0.087628 0.405764 -0.0965832 -0.3933061 -0.2651831 0.8750199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4148 4171 -0.613116 0.603653 -0.310761 0.3424567 -0.2016750 -0.8937152 0.2081435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4148 4648 -0.583801 -0.065981 0.865248 -0.4229252 -0.0994662 0.7555134 0.4903471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4149 3849 1.085049 -0.270998 -0.396650 0.4872506 -0.3054135 -0.4417082 0.6886242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4149 4649 -0.694000 0.271808 0.315772 0.0561639 0.2875654 -0.9246989 0.2430715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4150 4169 -0.577198 -0.834363 0.336936 -0.4049982 -0.1727172 0.4549263 0.7740719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4150 4650 0.615487 -0.045980 0.764725 0.7003154 0.3245557 0.3822288 0.5080581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4151 4168 -0.060511 0.903216 -0.622567 -0.7608211 0.4343935 0.4134287 0.2480529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4151 4651 -0.666374 0.258441 0.620433 -0.1660143 -0.2701654 0.2420342 0.9169893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4152 3852 0.726981 0.497956 -0.577789 0.5509846 -0.0432511 -0.4905969 0.6736913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4152 4167 -0.370494 -0.465833 -0.949806 -0.3840212 -0.7134384 -0.0887446 0.5793598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4152 4652 -0.546623 -0.604943 0.524278 -0.0068146 0.5790053 -0.8050132 0.1290740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4153 3853 -0.521744 0.329458 -0.625336 0.4583339 0.7935466 -0.0412109 0.3981400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4153 4166 0.746849 0.084160 -0.741996 -0.3169581 0.0409071 0.7944129 0.5165001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4153 4653 0.656134 -0.347283 0.676547 0.4668903 -0.1292338 0.8186699 0.3083695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4154 4654 -0.403890 0.055585 0.902166 -0.5398088 0.3430860 0.7130944 0.2870450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4155 4124 0.575864 -0.827403 -0.001883 0.0937513 0.6304682 -0.1841377 0.7482071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4155 4164 -0.529982 0.716115 0.123784 0.1163790 0.5948706 -0.2733824 0.7468915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4155 4655 0.648823 0.612849 0.741815 -0.1417570 0.5156161 0.8323482 0.1457447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4156 4163 -0.848181 -0.196029 -0.255211 -0.4592898 -0.1977315 -0.5259806 0.6879677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4156 4656 -0.528759 0.714399 0.235272 -0.2530020 0.1612574 0.3144584 0.9006120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4157 4162 0.671771 0.037058 -0.684203 0.4962371 0.7138103 -0.0848652 0.4868485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4157 4657 0.796518 -0.000546 0.743754 0.7593615 0.5444518 0.3246821 0.1467099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4158 4161 0.501564 0.104767 -0.732382 -0.0244543 -0.3227526 0.8978957 0.2983555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4158 4658 0.810084 -0.262553 0.531142 0.4882577 0.2939291 0.0133952 0.8216025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4159 4659 -0.142201 -0.485738 0.932414 -0.1471028 -0.4028503 0.8767954 0.2174907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4160 4199 0.189065 -0.289949 -1.054606 0.2696783 -0.9003486 0.1389345 0.3119988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4161 3821 0.827276 0.483810 -0.524212 -0.1235633 -0.8070352 0.1527070 0.5568724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4161 4198 -0.591678 0.003026 -0.741892 0.0494374 -0.3697933 -0.9185625 0.1305821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4161 4621 -0.605021 -0.431573 0.455294 -0.0763039 -0.0364998 -0.8950539 0.4378630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4162 4197 0.637172 0.119429 0.718764 0.5478825 -0.4507896 -0.6404818 0.2939330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4162 4622 -0.569239 1.014720 0.351486 0.6328908 -0.6785817 -0.3600841 0.0965173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4163 4623 -0.091992 -0.553771 0.910902 -0.0828302 -0.8473452 0.4980287 0.1646594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4164 4195 -0.451844 0.276919 -1.007138 -0.5293715 0.5076099 0.6771580 0.0596241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4164 4624 -0.573218 0.750897 0.426845 -0.7089579 0.6269438 0.3112034 0.0864446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4165 4154 -0.402272 0.465426 0.984296 0.2908212 0.4231125 0.8498352 0.1190756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4165 4194 0.424285 -0.436761 -0.810849 0.8267497 -0.3668570 0.4081642 0.1237046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4165 4625 0.858954 0.391164 0.265485 0.0078327 0.8707869 -0.0296752 0.4907017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4166 3826 0.921879 0.445800 -0.234793 0.0310733 0.2141962 -0.6568256 0.7223119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4166 4626 -0.727113 -0.382893 0.144187 0.6355673 0.5184998 -0.2544498 0.5123158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4167 4192 -0.983085 -0.224064 0.404883 -0.1511287 -0.0050153 -0.9873286 0.0481383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4167 4627 0.476667 -0.812791 0.054003 0.7360937 -0.2358723 0.6312910 0.0632617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4168 3828 0.601300 -0.540069 -0.357836 -0.0486079 -0.4481256 -0.0426241 0.8916299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4168 4628 -0.991371 0.503319 0.183289 -0.2550730 -0.2978353 0.8563344 0.3360407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4169 4190 -0.901101 -0.236820 -0.115638 0.4253626 0.0241906 -0.2781024 0.8608952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4169 4629 0.269362 -0.781731 0.066830 0.9858101 -0.1119856 -0.1062780 0.0658983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4170 3830 0.690889 -0.045131 -0.830140 -0.2453177 0.2694056 -0.9258706 0.1000171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4170 4189 -0.861209 -0.234764 -0.439483 0.2124530 -0.4494203 0.4721274 0.7279978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4170 4630 -0.486099 0.055581 0.697685 -0.1756740 -0.3416763 0.6339233 0.6712207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4171 3831 0.192570 -0.401081 -0.974251 -0.1467546 0.1928453 0.3589550 0.9013463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4171 4188 0.243048 -0.749935 0.320010 -0.1774796 -0.5812125 -0.7866147 0.1092260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4171 4631 -0.214976 0.257744 0.780929 -0.3878514 -0.0315789 0.9144206 0.1113956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4172 4147 -0.203952 0.988940 -0.138942 -0.4909965 0.1988660 0.7596949 0.3771450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4172 4187 -0.025601 -1.177283 0.039876 -0.0714069 -0.3056645 0.0296905 0.9489935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4172 4632 -0.092860 0.202049 0.959395 0.1097578 0.2318676 -0.7641486 0.5918341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4173 3833 -0.552745 -0.857686 -0.174826 0.7134557 0.6335632 0.1569952 0.2548160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4173 4186 -0.690493 0.296274 0.253044 0.7319222 0.2642124 0.5925247 0.2083175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4173 4633 0.626553 0.870635 0.066059 0.5905928 0.6070826 0.0750267 0.5263286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4174 4185 -0.996418 0.452878 -0.054235 0.1453909 -0.0079971 0.8066135 0.5728632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4174 4634 -0.293056 -0.909148 0.205008 0.6550088 -0.5197085 0.0638363 0.5447857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4175 3835 -0.513809 -0.708808 -0.406951 0.0454214 0.4858242 0.3282450 0.8088059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4175 4144 0.805138 -0.093169 -0.594559 -0.4494065 -0.4322442 -0.0066596 0.7817637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4175 4184 -0.739017 -0.000574 0.710529 -0.8591835 -0.2524011 -0.3691054 0.2487139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4175 4635 0.365630 0.727419 0.227765 0.0536737 0.1664782 -0.1430269 0.9741393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4177 4182 -0.410242 -0.631284 -0.384619 0.2229460 -0.6326575 0.6242234 0.4004806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4177 4637 0.393919 -0.506363 0.625060 0.3644068 0.1901621 -0.3082404 0.8579242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4178 3838 0.597236 0.178824 -0.813332 0.6529034 0.1063107 -0.6502479 0.3736212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4178 4638 -0.845209 -0.251437 0.738255 -0.5171867 -0.3911974 0.2051303 0.7330785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4179 3839 -0.900604 0.144869 -0.362357 0.0099517 -0.0088986 0.9866762 0.1621475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4179 4639 0.760168 -0.173818 0.494791 -0.4115193 0.2153749 -0.3999612 0.7901244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4180 4219 -0.665914 -0.838171 -0.357418 -0.0834454 -0.4224710 0.7708557 0.4694003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4180 4600 -0.785551 0.092323 0.634186 0.1428194 -0.0469275 -0.1036313 0.9831892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4181 3801 0.225924 0.903849 -0.764758 -0.0661321 0.0573848 0.9959060 0.0224685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4181 4178 0.968673 -0.125534 -0.359076 0.3713713 0.5061128 -0.1066089 0.7710822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4181 4218 -0.948059 0.335757 0.093766 0.7968930 0.3435808 -0.2371203 0.4366781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4181 4601 -0.146720 -0.940107 0.599272 0.0693064 -0.5345553 0.4376875 0.7196367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4182 3802 -0.215593 0.876810 -0.416401 0.0340750 0.4403406 -0.8931222 0.0852753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4182 4602 0.164140 -0.742202 0.580809 0.5488395 -0.2863276 -0.4249187 0.6604815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4183 4176 0.913466 -0.638406 -0.078939 -0.4793494 0.5352937 -0.1052744 0.6874607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4183 4216 -0.666451 0.889708 0.143855 0.3455867 0.0154146 -0.8460642 0.4055952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4183 4603 0.333309 0.081218 0.883342 0.1433989 0.5723807 -0.7953131 0.1389036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4184 4604 0.847253 -0.432695 0.365537 0.7361919 0.2019976 0.2244360 0.6056790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4185 4214 0.495737 0.869648 -0.180900 0.8755560 -0.0389075 -0.4797475 0.0415946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4185 4605 -0.548326 0.860779 0.400385 0.5989191 -0.6505454 -0.2385994 0.4014435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4186 4213 0.535216 -0.237838 -0.535501 0.1899381 -0.2187833 -0.8859948 0.3620369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4186 4606 0.594013 -0.230021 0.594398 -0.4447004 0.7147274 -0.0378497 0.5384921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4187 4607 0.396425 -0.143387 0.820647 -0.4356907 0.6203747 -0.5885070 0.2810131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4188 4211 -0.175014 0.639399 -0.421389 0.0614057 -0.1300588 0.0734323 0.9868747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4188 4608 0.476258 0.610456 0.618931 0.1279508 0.3153586 -0.4835300 0.8064591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4189 4609 0.587789 0.165987 0.699224 -0.3809341 -0.3285447 -0.7918452 0.3463073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4190 4209 -0.674750 -0.473716 0.156392 0.0357058 -0.2207451 0.8721941 0.4350565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4191 4168 0.752351 -0.414547 -0.552273 0.0949128 -0.1522058 -0.8352524 0.5197869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4191 4208 -0.716220 0.248089 0.693006 -0.5684414 -0.4908160 -0.6477137 0.1282221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4191 4611 0.572088 0.708576 0.404882 -0.6989863 -0.5583435 -0.3940332 0.2107332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4192 4207 1.135381 0.041826 -0.055468 -0.1687039 0.5234565 -0.1443875 0.8226084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4192 4612 -0.236856 1.128413 0.281896 0.2676190 -0.4534467 -0.4723790 0.7068410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4193 4166 -0.178954 -0.113194 1.075414 0.0323278 0.2098083 0.7477311 0.6291531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4193 4206 0.216230 0.166837 -0.997391 0.3100417 -0.7865000 0.4578812 0.2750210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4193 4613 0.717942 -0.588087 0.183855 0.5092100 0.6426437 -0.3701214 0.4367200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4194 4205 -0.253484 0.016273 0.915436 0.0144336 0.7009021 -0.5353352 0.4711095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4194 4614 0.296121 -1.058248 0.240097 -0.4539466 -0.3841372 0.7984567 0.0940106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4196 4203 0.072949 -0.160408 -0.757595 0.5102167 0.6376961 -0.4861485 0.3109377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4197 3817 0.556312 0.112871 -0.732997 -0.1418274 -0.1165946 -0.3721652 0.9098262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4197 4202 -0.576125 0.644608 -0.432432 0.1816543 0.5801070 -0.6339760 0.4780710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4197 4617 -0.618581 -0.266390 0.715922 0.4261018 -0.5336493 -0.6558399 0.3217603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4198 4201 0.501791 -0.770873 -0.373702 -0.4206544 -0.3282517 -0.1321328 0.8353692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4198 4618 0.798021 0.558374 0.227262 0.3095844 0.8200964 0.2214077 0.4272915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4199 4619 0.804841 -0.646522 0.202551 0.2947938 0.2143153 0.8244210 0.4330076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4200 3780 -0.160760 0.386617 -0.977597 -0.4211210 -0.0706847 -0.5896970 0.6855058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4200 4239 -1.005094 0.255326 0.094352 0.2016923 -0.4285545 0.0897498 0.8761314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4200 4580 0.086698 -0.324843 0.861912 -0.1110918 -0.2371201 -0.6329546 0.7285610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4201 4238 0.164122 0.021386 -0.820568 0.0766112 0.9071522 0.3039712 0.2807261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4202 4237 0.356928 -0.102914 -0.816457 0.8551727 -0.2137007 0.4296484 0.1959947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4203 4236 0.849047 0.405605 0.393163 -0.3239886 -0.4841128 0.7737192 0.2490477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4203 4583 0.103276 -0.846385 0.606517 0.6704081 0.4672235 0.2222286 0.5318549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4204 4195 0.734259 0.073399 0.813159 0.2810872 -0.7624505 -0.5372521 0.2258745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4204 4235 -0.756022 -0.307794 -0.526945 0.3782215 0.6557680 0.6521246 0.0406244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4204 4584 -0.523436 0.730443 0.096444 0.4303613 -0.8090105 -0.1614853 0.3663517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4205 3785 -0.074450 0.599347 -0.759889 0.6888155 0.1440562 0.6973563 0.1359234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4205 4234 -0.716639 -0.747329 -0.265218 0.0691890 0.7752216 -0.5082019 0.3687482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4205 4585 0.273758 -0.344061 0.857463 0.3066666 0.5715611 -0.7544891 0.1000986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4206 4233 -0.599641 0.605420 0.285428 -0.6301033 -0.4957454 0.5908094 0.0902811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4206 4586 -0.311335 -0.862961 0.358715 -0.1260189 0.3638931 -0.8189884 0.4253928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4207 4232 0.356951 0.322177 1.068101 -0.2809119 -0.2534745 -0.6741292 0.6343414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4207 4587 -0.674063 0.721011 -0.158870 -0.6207427 -0.7280456 -0.0326315 0.2890734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4208 3788 -0.206010 -0.358977 -0.749043 0.0311046 0.5016150 0.1291335 0.8548330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4208 4231 1.013157 -0.176497 -0.108778 0.2062385 0.2033684 -0.9571347 0.0004577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4209 4230 0.116519 0.637672 0.701388 -0.1567998 0.0780333 -0.9253943 0.3361101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4209 4589 -0.552884 -0.710926 0.585607 -0.1793549 -0.3708560 -0.0067517 0.9111817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4210 4189 -0.782628 0.069357 -0.476782 -0.0517416 -0.5044040 -0.8456944 0.1664345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4210 4590 -0.447161 0.129803 0.803337 0.5593907 -0.1232071 -0.5740167 0.5851554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4211 4228 -0.394259 0.803833 -0.654158 -0.1527940 0.6180280 0.6949865 0.3341993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4212 4227 0.449191 -0.348000 -0.634587 -0.2694760 0.2298770 -0.5527509 0.7543246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4212 4592 0.073597 -0.928344 0.437555 0.2766523 0.2211443 -0.2588129 0.8986516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4213 4226 0.047866 0.086917 -0.880320 -0.8107944 -0.3222459 0.4224431 0.2455848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4213 4593 -0.197804 0.994059 0.169614 -0.1818873 -0.5112586 -0.5508777 0.6340863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4214 3794 0.823306 0.586358 -0.550346 0.3463492 -0.5804775 0.0410616 0.7358002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4214 4225 0.408174 -0.830262 -0.393021 0.7677638 0.1240817 -0.6285804 0.0054030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4214 4594 -0.715951 -0.475973 0.470366 -0.2154960 -0.3029301 -0.3940389 0.8405523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4215 4184 -0.654433 0.299097 -0.460016 0.2163202 -0.8652593 -0.0106804 0.4521260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4215 4595 -0.582163 -0.744219 0.225231 0.2944919 0.4551955 -0.6893417 0.4804994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4217 4182 1.097489 -0.002667 -0.058969 -0.4877374 -0.1392312 0.6599382 0.5542639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4217 4597 0.104421 0.723726 0.612374 -0.2597663 -0.3658985 -0.6859709 0.5727859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4218 4221 -0.542058 -0.826397 0.010387 -0.0649837 -0.2952101 -0.5706973 0.7635003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4218 4598 -0.723571 0.650018 0.153555 0.0560553 -0.8206224 -0.5108221 0.2499949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4220 3760 0.658070 -0.063468 -0.663760 0.0967523 0.0140079 -0.2248012 0.9694881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4220 4259 -0.465426 0.759358 -0.380204 0.3317872 -0.1352434 0.8069317 0.4695612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4220 4560 -0.677099 0.020211 0.700748 -0.4844122 -0.2796662 0.6443443 0.5214902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4221 4258 0.301640 -0.763948 -0.179790 0.6909654 0.2428290 -0.6790819 0.0494853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4221 4561 -0.429350 -0.286432 0.829509 0.1694675 -0.4181064 -0.8272194 0.3349267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4222 4217 -0.792585 0.046325 -0.525176 0.1574866 0.3917943 -0.8828749 0.2054922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4222 4562 -0.093225 -1.216566 0.229627 0.9484371 0.0466848 0.2744736 0.1514983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4223 4216 0.231273 0.778180 0.604416 0.3788945 0.8228138 0.1283239 0.4036699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4223 4256 -0.179438 -0.851771 -0.557886 0.6395030 0.4477566 0.1868656 0.5963482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4223 4563 0.718055 -0.505082 0.198262 -0.9024474 -0.0729386 -0.4115028 0.1045666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4224 4255 1.029248 -0.088065 -0.071078 0.1803029 0.1657594 0.6984149 0.6724815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4224 4564 -0.068218 -0.148466 1.077375 0.1721866 -0.1624347 -0.9706603 0.0422519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4225 4565 -0.539688 0.305611 0.694314 -0.2772798 -0.4651930 0.6143427 0.5738418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4226 4253 0.533265 0.780719 0.507534 -0.0341761 -0.6011228 0.7353707 0.3109875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4227 4252 0.368450 0.857794 -0.177521 0.1948575 0.2313063 -0.3708788 0.8780529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4227 4567 0.901939 -0.478900 0.268162 -0.5703524 0.2492093 -0.6178774 0.4804377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4228 4251 1.033845 -0.226906 0.394734 0.6209336 0.0392713 0.0560425 0.7808703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4228 4568 -0.383384 -0.246345 0.845023 -0.4619438 -0.3379633 0.8189989 0.0403676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4229 3769 0.215854 0.341200 -0.713834 0.4793553 -0.5236742 -0.6251829 0.3242377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4229 4210 -0.691309 0.427638 0.033564 0.4270743 0.1523572 -0.2353651 0.8596500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4229 4250 0.751039 -0.829436 -0.226945 0.2579192 -0.5210865 -0.6459847 0.4946213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4229 4569 -0.059150 -0.386259 0.968727 0.7596003 -0.1226462 0.1852905 0.6112550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4230 4249 -0.334424 -0.690233 0.700360 0.2852453 0.1172189 -0.3018747 0.9020901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4230 4570 0.832507 -0.073018 0.579900 -0.5770251 0.5359804 -0.5535300 0.2708720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4231 4248 -0.784339 0.334988 -0.429969 0.0573947 0.2773919 -0.8888486 0.3601495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4231 4571 -0.684024 -0.708457 0.233880 0.2871659 -0.4423271 -0.3695619 0.7650532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4232 4247 0.617465 0.420097 0.817911 -0.0703110 -0.1108173 0.8090680 0.5728742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4232 4572 -0.548585 -0.548500 0.396991 0.2057004 0.3455255 -0.2368648 0.8844176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4233 4246 0.411850 -0.856603 0.618276 0.5341648 0.0116482 -0.0003206 0.8453001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4234 4245 0.798815 -0.365267 0.355045 -0.5178263 0.0090901 0.8128045 0.2666874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4234 4574 -0.576662 -0.739472 0.238177 0.9307989 -0.0102665 -0.2537450 0.2629098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4235 4244 -0.130269 -1.115579 -0.332256 0.3027760 0.6347236 -0.4356478 0.5618395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4235 4575 0.789420 -0.103400 0.540851 0.3798789 -0.6075392 0.6540698 0.2424476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4236 4243 -0.545809 -0.739820 -0.523365 -0.1779604 0.2297232 -0.8076304 0.5131184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4236 4576 -0.655687 -0.110710 0.817143 0.5399222 -0.5312297 0.2288642 0.6114739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4237 4242 -0.429749 -0.153061 0.662358 -0.3047831 0.0824208 -0.6053345 0.7306738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4237 4577 0.108484 1.017892 0.365484 -0.3275638 -0.7684765 -0.0294580 0.5488880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4238 4241 0.463258 -0.474197 0.645613 0.4218653 -0.5675661 -0.3723223 0.6010611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4239 4579 0.708772 -0.098418 0.496738 -0.5035691 0.6709945 -0.2229318 0.4964736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4240 4279 0.769265 -0.255940 -0.769873 0.2262002 -0.9133856 -0.2223425 0.2551942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4240 4540 -0.412027 -0.943596 0.100260 0.7809257 -0.4192951 -0.3214267 0.3332141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4242 4277 0.188871 -1.088480 0.213110 0.6120344 -0.5030084 0.0190548 0.6099454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4242 4542 -0.616149 0.166991 0.857873 0.3136181 0.5715539 -0.6732245 0.3489106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4243 4276 0.554054 0.240351 -0.421615 0.8430262 0.1467402 0.4403924 0.2717145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4244 4275 0.523819 -0.290253 0.928102 -0.6522506 -0.1518643 -0.3903623 0.6317623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4244 4544 -0.658749 0.434132 0.753202 0.0166466 0.0145634 -0.8793291 0.4757007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4245 4274 -0.470481 0.026470 -0.731475 -0.7333013 -0.0722739 0.4806784 0.4753883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4245 4545 -0.524024 0.847778 0.355748 0.0340778 0.6799962 0.7257344 0.0987596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4246 4273 0.320698 -0.032743 0.926338 0.4978488 -0.4494010 0.1527604 0.7258441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4247 4272 0.145396 -0.734357 0.569280 -0.3348707 0.2778373 0.8919103 0.1231425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4247 4547 -0.492221 0.590025 0.785790 0.0426253 0.2010136 0.6203961 0.7568919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4248 4271 0.227820 -0.539533 -0.753451 -0.0251698 0.7610592 -0.5184477 0.3890595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4248 4548 0.678612 -0.158702 0.528731 0.4861634 0.3194426 -0.3565003 0.7311013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4249 4270 -0.095774 -0.411858 0.779776 -0.2701412 0.4744742 0.6439781 0.5359012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4249 4549 0.472411 0.710675 0.394104 -0.5692331 -0.0221403 0.2097571 0.7946606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4250 3750 -0.414357 -0.956037 -0.409689 -0.3845198 0.3727720 0.3998998 0.7438184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4250 4550 0.357202 0.695550 0.171111 -0.2900867 0.1878736 -0.7470049 0.5679233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4251 4268 0.801382 0.420516 0.430251 0.0800176 -0.1375562 -0.9172110 0.3652388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4251 4551 -0.661934 0.695736 0.174863 -0.6086101 -0.6569211 0.0692480 0.4396056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4252 4267 0.133251 0.578349 -0.378358 0.3525007 -0.0731781 0.8844533 0.2968679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4252 4552 0.742404 0.318860 0.609155 -0.2256699 -0.1318696 0.4887415 0.8323552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4253 3753 0.811469 0.671685 -0.553280 -0.0998819 -0.8842753 0.4515542 0.0646504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4254 3754 0.654241 -0.558705 -0.478455 0.0429992 -0.2012794 0.8011833 0.5619101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4254 4265 0.740321 0.066735 0.443521 -0.3247831 -0.1802566 -0.9160785 0.1510754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4254 4554 -0.606183 0.641515 0.517013 -0.5204644 -0.4383039 0.7047737 0.2007496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4255 4264 0.037042 -0.968490 0.663695 -0.0539487 0.2710068 -0.5757093 0.7695477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4256 4263 -0.410210 -0.767703 0.490981 -0.1772546 -0.3935158 -0.7582189 0.4887027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4257 4262 -0.619142 0.786990 0.384872 -0.7426986 0.4720667 0.2577565 0.3988902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4258 4261 -0.232973 1.252137 -0.136278 0.5519127 -0.6941065 -0.0644997 0.4576552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4260 4299 0.027854 -0.867545 0.553578 -0.4229872 -0.3002359 0.5968015 0.6121831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4261 4521 0.576315 1.113363 0.248014 0.0224064 0.4036028 -0.3287196 0.8535491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4262 3722 0.083753 0.720824 -0.405028 -0.2148552 0.3156326 -0.8516741 0.3589771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4262 4297 -0.846894 0.199543 0.308695 0.0288971 0.0207119 -0.8714430 0.4892065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4262 4522 -0.109428 -0.782312 0.582277 -0.1871035 -0.6457792 0.5312577 0.5154869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4263 4296 1.039311 0.011805 0.176287 0.4470274 -0.3885602 -0.5289897 0.6077477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4263 4523 0.072619 0.279394 1.028249 0.4617695 -0.0103029 -0.7552574 0.4650258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4264 4295 0.507121 -0.790088 0.564604 0.2363323 -0.3134827 0.8488211 0.3540881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4264 4524 -0.982234 -0.224003 0.437869 0.3352650 -0.2250773 -0.9136128 0.0474252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4265 4294 0.102498 0.346422 0.924983 0.8467446 0.4183251 -0.2491810 0.2143280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4265 4525 0.842941 -0.538475 0.178664 0.2668601 0.2649888 0.9064366 0.1921960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4266 4253 0.925229 -0.156447 0.116807 0.4905428 0.6343198 -0.0849407 0.5914315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4266 4293 -0.907996 0.191997 -0.395685 0.1282146 -0.4263546 0.5191247 0.7295836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4266 4526 -0.218867 -0.963090 0.197170 -0.3801309 -0.7340926 0.5425603 0.1491204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4267 4292 0.037159 -0.874231 -0.436719 -0.1562029 -0.1731455 0.8331770 0.5014353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4268 4291 -0.798529 0.508861 0.290634 -0.5417500 -0.2204033 0.8079509 0.0717263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4268 4528 -0.327845 -0.924101 0.557133 0.5914530 0.2569431 0.0682859 0.7612493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4269 4290 0.503953 -0.650458 0.270605 -0.2313756 -0.5881176 -0.5434281 0.5525114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4270 4289 -0.923441 0.467249 0.124367 0.1168252 0.3304696 0.1021367 0.9309725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4271 4288 0.298513 0.563656 0.812098 -0.1397462 -0.8448860 0.0240735 0.5158092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4271 4531 -0.890762 -0.111739 0.578440 0.1825344 0.2229016 0.8245813 0.4868898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4272 4287 -0.595404 0.867326 -0.016191 0.0935112 0.2437635 -0.5684819 0.7801688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4272 4532 -0.127360 0.017112 1.194653 -0.4184530 0.0574932 -0.8583210 0.2913359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4273 4286 0.953676 0.215651 -0.082163 0.3755679 -0.6506866 -0.6053400 0.2629051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4274 4285 -0.131192 0.766955 0.700249 0.8541723 0.1463043 -0.3832655 0.3195189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4274 4534 -0.059081 -0.628236 0.769768 0.2180365 0.1082713 -0.8822544 0.4029449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4275 4535 -0.112635 -0.890030 0.401464 0.2884436 -0.7212209 0.2157108 0.5917006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4276 3736 0.115873 -0.935429 -0.576441 0.0145765 0.6253090 0.7285907 0.2791626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4276 4283 0.203045 -0.481390 0.950847 -0.4026285 -0.5198794 -0.2133949 0.7225498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4276 4536 0.113353 1.157113 0.542239 -0.4503678 0.4171827 -0.6371551 0.4660051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4277 4282 0.733761 0.059032 0.455647 -0.3577296 -0.4250556 -0.6818296 0.4758841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4277 4537 0.202066 1.218088 0.194846 -0.5382673 -0.4311127 0.1331932 0.7118073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4278 4241 -0.479816 0.657404 -0.409024 0.6811822 -0.4412133 -0.3985546 0.4271719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4278 4281 0.602242 -0.482798 0.496439 -0.2379205 0.2222901 0.8677000 0.3756031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4278 4538 -0.887403 0.113337 0.527349 0.0758453 -0.0601752 -0.9440570 0.3152505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4279 3739 -0.818775 0.561450 -0.335537 0.4656831 -0.6103179 0.5725528 0.2878102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4279 4539 0.932856 -0.429398 0.193436 -0.7923312 0.4170859 -0.3651702 0.2547576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4280 4319 -0.828005 -0.435793 0.662091 -0.1138438 -0.3001201 -0.1498660 0.9351511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4280 4500 -0.142016 0.809478 0.486880 0.4408400 -0.4957671 -0.6756032 0.3216138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4281 4318 -0.777733 0.158584 0.039693 -0.9168076 -0.0312088 -0.1798896 0.3551472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4282 3702 0.233898 0.001199 -1.162359 0.2015195 -0.6568406 -0.3356778 0.6444151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4282 4317 -0.057354 0.947398 0.130546 -0.2797605 0.2448690 0.7362657 0.5654079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4282 4502 -0.178015 -0.061646 0.894325 0.0111314 0.4287810 0.7386127 0.5200714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4283 4316 0.827149 -0.620955 -0.265461 0.0729188 -0.3182330 -0.8111133 0.4852894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4283 4503 0.437510 0.127684 0.996896 0.1317787 -0.0828402 0.1255809 0.9797966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4284 4275 0.253595 -0.068245 0.794341 0.5103917 0.4041671 -0.7496738 0.1189057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4284 4504 -0.766298 0.397290 0.636613 0.5141740 -0.4720501 -0.1824375 0.6924669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4285 4314 -0.502884 -0.213593 -0.942732 -0.2960607 -0.9107531 -0.1973982 0.2095490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4285 4505 -0.624535 0.898549 0.158683 -0.5627869 0.0244744 -0.4143507 0.7148324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4286 4313 -0.662147 -0.235827 -0.524848 -0.5146798 0.1112564 0.8454573 0.0890429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4286 4506 -0.578837 0.200098 0.812177 -0.1207578 0.3913700 0.8966311 0.1682253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4288 4311 0.548566 0.399361 -0.523689 0.5089296 0.1330055 -0.1486278 0.8373828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4288 4508 0.863291 -0.377302 0.482889 0.3682970 0.3235228 -0.8145478 0.3101649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4289 3709 0.850473 0.091806 -0.596840 0.3969634 -0.3544975 -0.7039546 0.4703184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4289 4310 -0.406701 0.523920 -0.370793 0.2185263 -0.3128581 -0.8346959 0.3970501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4290 3710 -0.700360 -0.400435 -0.442496 -0.4072700 0.2353770 -0.5628310 0.6796691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4290 4510 0.999217 0.091085 0.635336 -0.7152880 0.0334859 -0.0102409 0.6979519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4291 4308 0.195550 -0.893784 0.652376 -0.0923800 -0.7048864 -0.4784854 0.5154152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4291 4511 -0.672214 0.313191 0.370026 -0.5300585 -0.1187321 -0.1778667 0.8205511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4292 3712 0.590699 0.287357 -0.638335 -0.4934261 0.3215804 0.7441011 0.3153256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4293 4306 -0.199043 0.820374 0.117585 0.4287041 0.2001376 -0.1260335 0.8719365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4293 4513 -0.418213 -0.151781 0.840418 0.4359035 0.0356136 0.8409538 0.3186167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4294 3714 -0.096226 -0.983349 -0.142976 -0.1048821 0.8592160 0.4335514 0.2505609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4294 4305 -0.376593 -0.061238 -0.945023 -0.0994220 -0.9361622 -0.3358436 0.0304095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4295 4304 -0.367772 -0.516429 0.762598 -0.5717244 0.4177500 0.1107488 0.6973886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4295 4515 0.568438 0.601860 0.457145 -0.2124789 0.4827534 0.3670213 0.7662227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4296 4516 -0.240477 1.077566 0.073086 -0.8154368 0.1251642 -0.2727752 0.4949652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4297 4302 0.017811 -0.943003 0.338892 -0.2395252 0.1329673 0.7149246 0.6432963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4297 4517 0.743136 0.298454 0.548245 0.3465466 0.2407061 -0.0803120 0.9030593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4298 4261 0.909353 -0.789666 0.131301 0.7804833 -0.4331692 0.1778752 0.4142110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4298 4301 -0.869477 0.480452 -0.281763 0.0677228 0.5876277 -0.8012401 0.0901200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4298 4518 -0.493375 -0.744235 0.412473 0.2570162 -0.1398851 -0.1898214 0.9371994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4299 3719 -0.225675 0.303676 -0.944453 0.4915657 0.1122385 0.8132316 0.2905513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4300 4339 -0.251802 0.306705 0.765006 -0.0947793 0.5105636 0.8539478 0.0333898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4301 4338 0.829117 -0.352645 -0.601638 -0.2664157 -0.0447629 -0.3069204 0.9125891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4301 4481 0.462563 -0.361839 0.741032 -0.3451130 0.1485071 -0.1449388 0.9153335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4302 4337 -0.773240 0.253244 -0.355606 0.2428017 0.7494577 -0.3133038 0.5302840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4302 4482 -0.188954 -0.802933 0.715483 0.2623826 -0.5607964 0.2252001 0.7522949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4303 4296 1.012070 0.404829 -0.006072 0.1233768 0.7458678 0.4764302 0.4488582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4303 4336 -0.778493 -0.331011 0.111107 -0.3395386 0.2609478 -0.5299317 0.7319783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4303 4483 -0.007357 0.470504 0.837524 -0.6035442 0.1289536 -0.7837586 0.0694824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4304 4335 -0.673321 -0.569985 -0.672346 0.5041243 0.5217228 -0.6235777 0.2912299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4304 4484 -0.228148 -0.735742 0.634983 0.7485907 0.2392149 0.1145185 0.6076790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4305 4334 0.358126 -0.734671 0.669894 0.2917639 0.4431828 0.7840425 0.3220874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4305 4485 0.289205 0.876716 0.428328 -0.2647270 0.2950901 0.3796452 0.8358893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4306 4333 -0.245864 0.734358 -0.622848 -0.5034187 -0.2858073 0.7357887 0.3514240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4306 4486 -0.771656 0.077571 0.503611 0.5454602 -0.4845753 -0.3895040 0.5620912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4307 3687 0.824104 0.007391 -0.752694 0.6008820 -0.1710205 -0.7758767 0.0877961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4307 4292 -0.165148 -0.933041 -0.283073 0.3234186 0.0941175 -0.5006696 0.7974160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4307 4332 0.221704 0.812140 0.412396 -0.7553703 -0.4683981 0.4167592 0.1906061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4308 4331 0.859385 0.391738 -0.623714 -0.3916133 0.2762882 -0.5759945 0.6622191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4308 4488 0.692254 -0.104021 0.731460 0.2750471 -0.4718317 0.6036058 0.5808477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4309 4290 0.070116 -0.824593 0.245746 0.1529985 -0.2274985 0.5527610 0.7869505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4309 4330 -0.243625 0.867009 -0.576025 -0.2170616 -0.7334579 -0.5453662 0.3427820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4310 4329 0.052188 -1.178984 0.033182 0.4377578 -0.3147958 -0.6260951 0.5632732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4310 4490 0.393443 -0.100243 0.805947 -0.4686502 -0.3224762 0.6481572 0.5062295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4311 4328 0.700480 -0.159586 -0.530415 -0.7834696 -0.0357362 0.1793352 0.5939168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4312 4327 -0.841558 -0.505386 -0.306579 -0.2635003 -0.4785467 0.8300702 0.1120007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4312 4492 0.323552 -0.954972 0.633799 0.4180442 -0.6795975 0.3542303 0.4877572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4313 4326 1.089194 0.258617 0.298976 0.2963722 0.4428335 0.5758721 0.6200269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4313 4493 -0.047159 0.052409 0.864440 -0.0027046 0.4885979 -0.7971693 0.3546631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4314 4494 0.904219 0.101423 0.317241 0.1054561 0.0025642 0.9494995 0.2955048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4315 3695 -0.250711 0.865165 -0.111517 -0.2001262 0.1118354 -0.9411886 0.2482061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4315 4284 -0.267161 -0.041743 -1.117016 0.6805926 0.6688676 -0.2060121 0.2167231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4315 4324 0.192310 0.177685 1.020526 0.3961208 0.7476714 -0.4407122 0.2997473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4315 4495 0.208128 -1.150701 0.171879 0.5423573 0.2588918 0.6212664 0.5028436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4316 4496 -0.506051 0.797646 0.305791 -0.2770261 -0.3082589 -0.4998541 0.7605122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4317 4322 0.619406 -0.338463 0.712988 -0.1976423 -0.1633635 -0.8571910 0.4466245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4317 4497 -0.612856 0.236507 0.621702 0.3477508 -0.1133506 0.2964272 0.8822425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4318 4498 0.344387 -1.089127 -0.019809 0.1349696 0.8366014 -0.1708897 0.5026709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4319 4499 -0.243409 0.726225 0.621173 -0.4138108 0.5409280 0.6932496 0.2357171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4320 4359 -0.281720 0.830779 0.105567 -0.5412279 0.0989890 0.5165796 0.6560633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4320 4460 0.242634 0.243185 0.895584 0.5230752 -0.3809570 0.7421935 0.1743929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4321 4358 -0.081054 -0.872784 0.375921 -0.1613220 -0.0115621 -0.5242317 0.8360758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4321 4461 -0.790494 0.204087 0.485232 -0.3005393 -0.2674672 -0.7827679 0.4747756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4322 4357 0.481636 0.847348 0.648054 0.4240500 0.4840485 -0.6310215 0.4332326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4322 4462 0.576778 -0.608070 0.630388 0.2711629 -0.2014069 -0.1672300 0.9262505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4323 4316 -0.714809 -0.622579 -0.079788 0.7343865 0.3519595 -0.4900243 0.3109294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4323 4356 0.722218 0.463603 0.165218 -0.1228962 0.0847116 -0.0460027 0.9877268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4323 4463 0.387574 -0.769558 0.360516 0.7839717 -0.4338654 0.4165221 0.1538134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4324 4355 -0.668417 -0.171202 -0.463331 0.2040779 0.4536509 -0.5337191 0.6838837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4325 4354 0.536830 -0.737489 -0.344876 0.4662339 0.1892952 0.4228096 0.7536746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4325 4465 0.185973 -0.110428 1.080287 -0.1912236 0.6137707 -0.1539380 0.7503480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4326 4466 0.004689 0.906906 0.164056 -0.5497029 0.3391018 -0.2808318 0.7099086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4327 4467 -0.765685 0.083548 0.650311 -0.4668272 -0.0925065 0.2044981 0.8553920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4328 4351 0.836264 0.312983 -0.207433 0.0374143 -0.3361792 0.5118672 0.7896681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4328 4468 0.602979 -0.836762 0.011945 0.3345338 0.5257079 -0.4917295 0.6082108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4329 4350 1.001509 0.103724 0.353664 -0.8605366 0.4260290 0.0822965 0.2668394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4329 4469 -0.257918 1.020335 0.169980 -0.2959898 -0.2655480 0.4665443 0.7900701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4330 4349 0.006352 -0.248835 0.847464 -0.3048118 -0.4032946 -0.8448363 0.1751993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4331 4348 -0.389137 1.022206 0.207098 0.4076076 0.4229805 -0.3331730 0.7375224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4331 4471 -0.024834 -0.133454 1.063987 0.3366784 -0.4283070 -0.7832210 0.2996091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4332 4472 -0.707809 -0.834404 0.070702 0.3690705 -0.5412170 0.6974966 0.2904645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4333 4346 0.954125 0.114868 -0.081744 0.7047964 0.0004589 -0.4551378 0.5441612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4334 4345 -0.530008 0.935591 0.044083 0.2929717 0.6171263 0.4893629 0.5420762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4335 4344 0.431720 -0.260223 0.655653 0.5213230 -0.0840854 -0.7898511 0.3119091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4336 4343 0.384881 -0.906799 -0.670105 0.8794609 0.1911039 -0.4256157 0.0942290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4336 4476 -0.600299 -0.737051 0.599835 -0.8004039 0.1128305 0.5810603 0.0948250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4337 4477 -0.564212 -0.843777 0.525708 0.0644164 0.1948557 -0.9773892 0.0509134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4338 4478 0.567193 -0.285247 0.591466 0.3058156 0.2785306 0.9070450 0.0785297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4339 4479 -0.817585 -0.437168 0.490556 -0.1944280 -0.5049991 0.5180175 0.6624436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4340 4440 -0.630873 0.733230 0.488697 0.3504148 -0.2194253 0.0464675 0.9093419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4341 3641 0.174674 -0.952430 -0.515063 0.0650894 -0.3741352 -0.9239833 0.0451771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4341 4338 0.457670 0.274561 -0.972700 0.4247291 0.4229970 0.8004060 0.0053880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4341 4378 -0.424986 -0.393676 0.666796 -0.4295365 0.1487641 -0.1416707 0.8793731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4341 4441 -0.335606 0.839778 0.428704 -0.7217829 0.4630921 0.2128090 0.4682815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4342 4337 -0.521211 -0.630609 -0.654693 -0.6530333 -0.4582477 0.4383617 0.4139995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4342 4377 0.501460 0.651528 0.838624 0.5472889 0.0996023 -0.7058317 0.4385839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4342 4442 -0.729697 -0.271940 0.706792 -0.7495751 -0.5028359 0.4176398 0.1042598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4343 4376 0.461326 0.843240 0.471126 -0.2120743 -0.0614557 -0.2833716 0.9332461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4343 4443 -0.834153 0.320389 0.396782 -0.7368583 0.1317571 0.6324210 0.1993078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4344 4375 -0.451718 0.695416 -0.567383 0.4771166 0.1537279 0.3652608 0.7844183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4344 4444 -0.394260 0.191992 1.047994 -0.3819647 -0.5112670 0.3699456 0.6751661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4345 4374 0.774491 0.287226 -0.372097 -0.0507336 -0.2208908 -0.8900300 0.3955754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4345 4445 -0.114055 0.649846 0.652104 0.4308830 -0.2470059 -0.8580244 0.1308510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4346 4373 0.672243 0.401034 -0.653489 0.4095333 -0.2288880 -0.8750477 0.1190977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4346 4446 -0.400437 0.870493 0.105259 -0.2268460 0.2645369 0.8905314 0.2924295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4347 3647 -0.130712 -0.885552 -0.710676 0.0622857 -0.7651485 -0.6356051 0.0816969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4347 4332 -0.204296 0.445200 -0.788595 -0.7062022 0.4563902 -0.4061335 0.3578295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4347 4372 -0.055319 -0.535698 0.898394 -0.6139828 -0.2021165 -0.0753852 0.7592701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4348 4371 -0.480262 0.453927 -0.749791 0.1200376 0.1855362 -0.9705992 0.0954177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4348 4448 -0.754678 0.437595 0.604524 0.7976801 -0.4914089 -0.3487479 0.0244684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4349 3649 0.549351 -0.034427 -0.975274 0.4318348 -0.6557791 0.0491648 0.6172967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4349 4370 0.928354 0.618456 0.293821 0.2532411 0.2000020 0.5130144 0.7954146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4349 4449 -0.419719 -0.196811 0.976228 0.1231849 -0.5515710 -0.5245823 0.6367168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4350 4369 0.245870 -0.983687 0.046534 -0.0265967 -0.7129130 0.6103146 0.3443310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4350 4450 -0.770744 -0.350034 0.697270 0.1766052 0.1213291 -0.4230570 0.8804048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4351 3651 0.544565 0.905523 0.042589 0.4503710 -0.0986393 -0.6334044 0.6214781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4351 4368 0.427920 -0.431345 -0.794642 0.7026438 -0.1099507 -0.6605699 0.2405201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4351 4451 -0.358711 -0.810462 0.248035 0.0675393 -0.8994984 0.1408604 0.4080435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4352 4367 -1.238510 0.102807 0.651363 -0.4628252 0.8655544 0.1513782 0.1170171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4352 4452 -0.074452 0.907018 0.014654 0.6863894 -0.3846278 -0.5922499 0.1736984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4353 4326 0.982507 0.347728 0.309100 0.3202113 -0.7878517 -0.1115575 0.5141103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4353 4366 -1.099336 -0.351919 -0.317667 -0.0297714 -0.4842791 0.3176443 0.8146714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4354 4365 -0.435048 -0.640076 0.558230 -0.4036589 -0.1821660 0.8753725 0.1939019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4355 4364 0.751411 -0.813211 -0.107116 -0.2620869 -0.5381424 0.4045169 0.6914328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4355 4455 -0.589564 -0.661787 0.426427 0.7961140 -0.0667723 -0.5299185 0.2844826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4356 3656 -0.472200 0.768238 -0.258071 -0.0320608 -0.5308362 0.4686343 0.7053842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4356 4363 0.847784 0.452205 0.377219 0.3826154 0.0121541 -0.3993644 0.8330461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4356 4456 0.265412 -0.835077 0.211313 0.4326074 0.3903896 -0.7919449 0.1824007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4357 4362 -0.786595 0.095018 -0.806825 -0.8502313 -0.1398116 0.3714027 0.3458606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4357 4457 -0.519959 0.421929 0.705247 -0.1856856 0.4715786 0.0849738 0.8578543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4358 4361 0.855901 -0.706981 -0.004715 0.2323552 -0.0542778 -0.3404184 0.9094945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4358 4458 -0.440746 -0.689246 0.719590 0.3069809 -0.0132997 0.9365795 0.1685370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4359 4459 -0.524001 -0.682230 0.196443 0.1792937 -0.7017338 0.3644738 0.5853053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4360 3620 0.882491 0.472130 -0.513673 0.7108353 -0.1489592 -0.0461105 0.6858558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4360 4399 -0.136895 0.894818 0.593971 -0.2122145 -0.8202153 0.3859070 0.3650858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4360 4420 -0.759202 -0.520739 0.078246 -0.4512243 0.5418827 0.7090423 0.0043305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4361 4398 1.109785 0.042314 -0.022559 -0.0360795 -0.4540661 -0.0965298 0.8849883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4362 4397 -0.096049 0.314553 0.871764 0.2311159 0.2345652 0.6209399 0.7113355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4362 4422 -0.498116 -0.875405 0.409306 0.4458505 -0.0114362 -0.8629087 0.2376451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4363 4423 0.687489 -0.014421 0.853791 0.0287021 0.6191538 -0.5788699 0.5298438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4364 4395 -0.674590 -0.239120 -0.653351 0.0906556 -0.1697290 0.0095349 0.9812659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4365 3625 0.222690 1.017723 -0.175530 0.0644325 0.6823778 -0.7279925 0.0153572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4365 4394 -0.585000 0.442473 0.776499 0.2094787 -0.6228631 -0.2710616 0.7033390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4365 4425 -0.170067 -0.948399 0.208330 -0.1927567 -0.8359042 0.2280962 0.4605226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4366 4393 -0.720737 0.281753 0.643370 -0.3656291 -0.3234523 -0.4661512 0.7378327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4366 4426 0.586740 0.613461 0.323813 -0.1902592 0.0861161 0.7374486 0.6423044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4367 4392 0.317229 0.655301 -0.396664 0.2038434 -0.9486661 -0.2374716 0.0456924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4367 4427 -0.819170 0.413201 0.311715 -0.2028098 0.0898167 -0.0143656 0.9749845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4368 4391 0.973942 -0.032577 -0.440422 0.5089824 -0.2013410 0.8157434 0.1869796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4368 4428 0.257975 0.726196 0.531400 -0.4200065 0.3543929 -0.5469678 0.6315271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4369 3629 -0.734669 0.359384 -0.927161 -0.1499361 -0.3601000 0.1478388 0.9088404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4369 4390 -0.894919 -0.310184 0.547220 -0.1574754 0.4847258 0.5852459 0.6306580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4369 4429 0.720884 -0.186902 0.855230 0.1719823 -0.5761197 0.7449793 0.2889879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4370 3630 0.066226 -1.057183 -0.591967 -0.4172275 -0.7664267 -0.4709280 0.1293759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4370 4389 0.704472 -0.019218 0.619969 -0.4810880 0.1846845 0.8569348 0.0104303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4370 4430 -0.146585 0.923996 0.480310 -0.6606947 0.5304426 0.5166564 0.1232044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4371 4388 0.750405 -0.171339 -0.724633 0.0000000 0.0000000 0.0000000 1.0000000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4371 4431 0.319505 -0.761059 0.662333 0.7060384 -0.6236469 0.3198965 0.1011951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4372 4387 0.353278 -0.966733 -0.390271 -0.2692797 -0.0205856 0.8638335 0.4252720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4372 4432 0.548840 -0.277441 0.891048 0.4065496 -0.4008826 0.7903300 0.2222365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4373 4433 -0.009967 -0.684103 0.661290 0.3055683 0.0746221 -0.1983952 0.9282774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4374 3634 0.406808 0.394875 -0.744266 0.6250302 -0.1386777 -0.7433799 0.1936286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4374 4434 -0.372185 -0.468258 0.883986 0.2239557 0.7024943 -0.6101646 0.2899049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4375 3635 0.086288 -1.114144 -0.117205 0.7365483 -0.3989196 -0.5327996 0.1203510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4375 4384 0.057451 0.221120 -1.199097 0.4024754 0.1470175 0.8248627 0.3687830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4375 4435 0.088051 0.820140 0.030047 -0.5704869 0.5525133 0.4809086 0.3714846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4376 4383 0.239819 0.586780 0.957652 0.7180308 -0.3002804 -0.0151171 0.6277220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4376 4436 -0.811195 -0.290863 0.557998 -0.4447158 -0.3744892 0.5335602 0.6142468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4377 3637 0.679045 0.146935 -0.885593 -0.4873722 -0.4172596 0.7654698 0.0491821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4377 4437 -0.522804 -0.224912 0.932836 0.1304863 -0.6653303 0.1806951 0.7125014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4378 4381 -0.208640 -0.984893 0.057849 0.5277949 -0.6769809 0.0001960 0.5129613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4378 4438 -0.641498 0.019854 0.701281 -0.3428363 0.0481498 -0.5881202 0.7309306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4379 4340 0.449862 -0.048770 -0.880667 0.0115402 -0.7448371 -0.6224320 0.2401310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4379 4439 0.696105 0.826397 0.227221 0.0581101 -0.2508174 -0.9473119 0.1905625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4380 3600 -0.894560 -0.146474 -0.668099 -0.4638559 -0.1237618 -0.8765224 0.0350601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4380 4400 0.896816 0.126140 0.484682 -0.4713892 -0.1282923 -0.8716303 0.0399242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4381 4401 0.210425 0.969783 0.167187 0.5688786 0.7304872 0.3763545 0.0335078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4382 4377 -0.569892 -0.931240 -0.008075 -0.0310323 0.5205101 -0.7054214 0.4800905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4383 3603 0.417964 -0.843015 -0.509518 -0.4251884 -0.6082188 0.1288694 0.6577822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4383 4403 -0.297855 0.840239 0.438565 0.3170995 -0.1635080 -0.0315491 0.9336582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4384 4404 0.834605 -0.739639 0.297420 0.0497327 0.4971119 -0.8145918 0.2946976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4385 4374 -0.199256 0.105010 1.102011 0.4440230 -0.2260154 0.8006484 0.3327502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4385 4405 1.074303 -0.566094 0.100039 0.4712392 0.8004090 0.2983356 0.2197155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4386 4373 -0.564503 -0.793644 -0.351733 -0.6466635 -0.2661882 0.7090939 0.0903105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4386 4406 -0.882490 0.438506 0.644325 0.4143144 0.2275061 -0.5718835 0.6704729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4387 4407 -0.656890 -0.575359 0.254365 0.1740132 -0.0666037 -0.6294851 0.7543421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4388 3608 -0.560838 0.581678 -0.571415 0.3609110 -0.3187690 0.8581668 0.1779869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4388 4408 0.488386 -0.573473 0.626207 0.3556259 0.4272379 -0.3924682 0.7327801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4389 4409 -0.628476 -0.725650 0.670288 -0.2862906 -0.1689531 0.6775356 0.6560777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4390 4410 -0.806669 -0.400937 0.412100 -0.2542689 -0.8485708 0.0683585 0.4589140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4391 4411 0.542917 -0.849920 -0.020385 0.4668789 -0.6699552 0.2453233 0.5224947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4392 4412 0.481228 0.847587 -0.329040 0.5109135 0.7011558 0.2974353 0.3985977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4393 4413 0.037642 0.707536 0.651600 -0.4040915 0.0438960 0.8850949 0.2266940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4394 4414 0.952681 -0.336444 0.266450 -0.2970919 0.0635777 -0.5417976 0.7836770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4395 3615 0.125430 0.125497 -0.876038 -0.2329661 -0.0322898 0.3073138 0.9220859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4396 4363 -0.906321 -0.088910 -0.243586 0.3711429 0.0451882 -0.5920320 0.7139391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4396 4416 -0.037617 -0.983862 0.225213 0.7315553 -0.6102409 0.2563747 0.1634163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4397 4417 -0.881213 0.468599 0.079351 0.8773983 -0.0927426 -0.3480114 0.3169527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4399 4419 0.266588 -0.880488 0.684145 0.6538622 0.2606929 -0.6996758 0.1222998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4400 4439 0.008665 -1.209613 0.150831 -0.4468578 0.2971067 0.3770284 0.7549141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4400 5180 0.087579 -0.051903 0.951674 -0.0122887 -0.0098690 0.8206330 0.5712381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4401 4438 0.092118 -1.019040 0.264268 -0.0177212 -0.1748916 0.8773815 0.4464309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4402 4382 0.817363 0.112445 -0.623352 -0.0714594 -0.7408082 0.1092996 0.6589009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4402 4437 0.071529 -1.103812 -0.206071 0.0942018 -0.7455173 -0.4114011 0.5158286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4402 5182 -0.854321 -0.114065 0.461961 -0.1773525 -0.3996704 0.0488631 0.8980101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4403 4436 0.096910 0.020436 1.053314 0.4641560 -0.5323164 -0.7043162 0.0716734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4403 5183 -0.415339 0.970279 0.224589 -0.7438799 0.1774649 -0.1857781 0.6169566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4404 4435 -0.993860 -0.371235 0.060746 -0.3805769 0.1154491 0.1575903 0.9038794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4404 5184 -0.225566 0.496252 0.859662 -0.2243757 0.2268256 0.8338074 0.4505230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4405 4434 0.281300 0.534246 -0.681621 -0.4685645 -0.1481358 -0.5661990 0.6617566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4405 5185 -0.733709 0.534819 0.139232 0.4506102 -0.3898745 -0.4731071 0.6489361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4406 4433 0.479929 -0.718449 0.598879 0.6686017 0.1934203 -0.5884904 0.4113872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4406 5186 -0.710405 -0.525670 -0.058911 -0.9293293 -0.1409118 0.3200433 0.1185886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4407 4432 0.411392 0.904468 0.627918 0.2560489 -0.5552566 0.6396094 0.4658636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4407 5187 0.337641 -0.721829 0.845113 0.5307469 -0.0270609 0.8454463 0.0528780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4408 4431 -0.879780 -0.426856 -0.118214 -0.6023301 0.0457038 -0.7946306 0.0605960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4408 5188 -0.357809 0.374405 0.860413 -0.5389092 0.1360757 -0.5571893 0.6169282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4409 4430 -0.422798 -0.823864 -0.404771 0.6643008 0.0797791 -0.5633143 0.4847853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4409 5189 -0.751892 -0.014599 0.633877 -0.6131035 -0.2166994 0.4039751 0.6433892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4410 4429 -0.342185 -0.585003 -0.905914 0.0428689 -0.1304410 0.3577589 0.9236644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4410 5190 0.469017 -0.745261 0.447725 0.1115328 0.1450376 -0.4150468 0.8912130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4411 4428 -0.606007 -0.668000 -0.491006 0.1935422 0.5048146 0.1972566 0.8177980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4411 5191 0.459906 -0.664006 0.627698 0.0009686 -0.0408233 0.6689699 0.7421670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4412 4427 -0.279023 -0.486248 0.868941 -0.0919987 0.6841050 -0.4072845 0.5980435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4413 4426 0.999820 -0.296865 -0.167456 0.0379023 -0.6590455 0.1008898 0.7443411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4413 5193 -0.212075 -0.982791 0.685442 -0.5106787 -0.7456342 0.3961480 0.1621841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4414 4425 0.340593 0.221925 -1.035987 0.4806744 -0.3981912 0.7722659 0.1183266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4414 5194 0.862920 0.538227 0.235467 0.3306190 -0.0343760 0.6150421 0.7150053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4415 4395 0.557697 -0.022201 -0.709205 0.1425005 -0.1833290 -0.4787864 0.8466686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4415 5195 -0.542933 -0.119914 0.797580 -0.3290828 -0.0466416 -0.8167874 0.4715798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4416 4423 -0.384100 0.919598 -0.022523 0.0728825 0.5037340 0.8558592 0.0918984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4416 5196 0.708873 0.415925 0.455344 0.3779340 -0.2664753 0.8287773 0.3150951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4417 4422 0.244803 0.031208 0.989255 0.5374858 -0.5532159 0.1876903 0.6081394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4418 4398 0.288084 -0.844405 -0.405726 -0.6166323 -0.5369579 0.0771036 0.5705224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4418 4421 -0.921328 0.066792 -0.334989 0.0614017 -0.5826674 -0.7580029 0.2866359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4418 5198 -0.246934 0.933251 0.606292 -0.2621865 0.4046189 0.1525208 0.8627161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4419 5199 -0.825568 0.555741 0.135471 -0.2547491 0.7468063 0.5844375 0.1892509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4420 4459 0.501928 -0.229192 -0.960327 -0.7441765 -0.2816751 -0.5832742 0.1632532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4420 5160 0.467520 0.830223 0.081275 -0.7911071 0.5299495 0.3019514 0.0461361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4421 4361 0.161307 -0.119233 -0.970565 -0.1851879 -0.0900580 0.8963619 0.3925943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4421 4458 0.744498 -0.867451 0.200183 0.2546397 -0.5586729 -0.2651537 0.7434626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4422 4457 0.854654 0.113058 -0.352689 -0.2697175 0.8373351 0.2440884 0.4080970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4422 5162 0.047415 0.639620 0.770487 0.3617173 0.2803323 0.6288359 0.6286015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4423 4456 0.489288 -0.511507 0.926757 0.3240862 -0.1547727 0.0662000 0.9309302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4423 5163 -0.695143 0.163810 0.435076 0.5077413 0.4454299 -0.6644598 0.3198189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4424 4364 0.249560 0.773867 -0.287644 0.1195932 -0.2524375 0.3664527 0.8875163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4424 4415 -0.080623 -0.537003 -0.962984 -0.1454323 -0.3890946 0.6916557 0.5908191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4424 4455 0.002356 0.332386 0.970055 0.4735488 0.2362040 -0.8427632 0.0985363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4425 4454 -0.974914 0.298590 -0.205756 0.4023014 -0.4499969 -0.0850476 0.7927315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4425 5165 -0.180617 -0.786396 0.336991 -0.0147068 0.1028395 -0.0244570 0.9942885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4426 4453 -0.054139 -0.561826 -0.830492 0.7031072 -0.1029994 -0.4004205 0.5785282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4426 5166 0.375676 -0.794188 0.449147 0.3936037 0.3580263 0.7852489 0.3166661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4427 4452 -0.312548 -0.893851 -0.139333 -0.3656392 0.0537085 -0.3678900 0.8532763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4427 5167 -0.743292 0.298598 0.260005 0.0735287 -0.5016925 0.0227114 0.8616161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4428 5168 -0.838627 -0.283648 0.475009 0.3352380 0.1330918 0.7694911 0.5270536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4429 4450 -0.895029 -0.294980 -0.344465 0.0056554 -0.0685867 0.2914204 0.9541163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4429 5169 0.054241 -0.860753 0.350880 0.4955309 0.4209897 -0.6853085 0.3279772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4430 5170 -1.005500 -0.160973 0.448178 0.5284417 0.0839513 -0.7823077 0.3188984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4431 4448 0.303290 0.365650 -0.795165 0.1096962 0.1843365 -0.9703789 0.1111376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4431 5171 0.867236 -0.547262 -0.086858 0.4001683 0.1118399 0.7808464 0.4665149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4432 4447 0.545961 -0.433691 -0.865857 -0.4486085 0.2362261 -0.2667530 0.8196282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4432 5172 0.404342 -0.811899 0.586739 0.2298326 0.3135949 0.3105077 0.8674215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4433 4446 -0.245247 1.014354 0.152926 -0.0735742 -0.3872810 -0.0487074 0.9177297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4433 5173 -0.308014 -0.133184 1.035848 -0.5291019 -0.0003156 0.6844933 0.5015177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4434 4445 -0.931568 0.582410 0.211869 -0.1208116 -0.4444575 0.4559602 0.7615526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4434 5174 -0.403393 -0.823034 0.255645 0.0518808 -0.0867563 0.4140951 0.9046032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4435 4444 -0.970621 0.178937 -0.416595 -0.2938230 -0.1016149 -0.7013741 0.6414178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4436 4443 -0.659040 0.588212 -0.307141 -0.1507506 -0.0660150 0.5447082 0.8223194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4436 5176 -0.451261 0.037237 0.950153 -0.1691062 -0.3663500 0.8948817 0.1907291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4437 4442 0.401280 -0.766811 -0.322889 -0.1795285 0.8034926 -0.5597364 0.0941505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4437 5177 0.882839 -0.079147 0.501049 -0.7876343 0.2868370 -0.4917363 0.2356948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4438 4441 -0.789437 0.149614 0.788875 -0.2518631 -0.4696803 0.6741638 0.5113399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4438 5178 -0.150977 -1.088673 0.411479 0.6012177 -0.2850742 0.6661415 0.3369356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4439 5179 -0.771302 -0.402665 0.332772 0.5948893 0.1297730 -0.0889091 0.7882644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4440 4479 -0.512087 -0.517983 0.660990 -0.5844577 0.2304568 0.5424399 0.5577256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4441 4478 0.550187 -0.043992 0.815552 0.6114377 -0.3168032 -0.2317199 0.6870848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4441 5141 -0.844760 -0.051179 0.633926 -0.1356911 -0.3790037 0.6337080 0.6605742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4442 4477 -0.163843 0.222762 0.925334 -0.0055628 -0.5086909 0.8515568 0.1267030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4442 5142 -0.553447 -0.489291 0.064176 0.3140020 0.5440918 -0.7178231 0.3001614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4443 5143 -0.561395 0.017153 0.891824 0.3791024 0.3195424 0.6650900 0.5584168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4445 4474 0.384097 0.610809 0.722170 -0.1715603 -0.7234494 -0.1328493 0.6553924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4445 5145 -0.770145 -0.496854 0.824537 0.1946953 0.4309109 -0.8313485 0.2920090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4446 5146 0.619771 -0.234649 0.640378 -0.1106913 0.7180598 -0.6870696 0.0085447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4448 4471 -0.150629 0.124290 -0.971327 -0.2287325 0.2844829 0.3752833 0.8520055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4448 5148 -0.607661 0.597337 0.181981 0.7187597 0.4721131 -0.5039885 0.0805564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4449 4430 -0.336897 0.810998 -0.169650 -0.0695629 0.4150998 -0.7813106 0.4608762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4449 4470 0.185940 -0.971935 0.358702 -0.1390689 -0.5360507 -0.5486183 0.6263605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4449 5149 0.391227 0.343188 0.577059 0.5043213 0.2579183 0.7837079 0.2548337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4450 4469 -0.777432 0.433199 -0.321764 0.5912644 -0.6478145 0.0839332 0.4729673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4450 5150 -0.452170 -0.709507 0.560671 0.3763765 -0.6074663 0.2228434 0.6630734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4451 4428 -1.027208 -0.239378 0.223558 -0.0868216 -0.2419558 0.8024935 0.5384456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4451 4468 0.977420 0.125365 -0.433681 0.5351970 -0.2179568 0.6680939 0.4687318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4451 5151 0.328503 -0.848337 0.608392 0.4556679 -0.5395813 0.5549943 0.4395453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4452 4467 0.396032 -0.611522 -0.662492 -0.4650921 -0.5387746 0.3335306 0.6181979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4452 5152 -0.772232 -0.656923 0.255008 0.4467930 -0.2358094 -0.3389701 0.7936430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4453 4353 -0.509799 -0.786004 -0.095410 -0.0792992 -0.1275584 -0.5066921 0.8489426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4453 4466 0.838243 -0.623683 0.554681 0.0395750 -0.5119624 -0.7978475 0.3158601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4453 5153 0.527232 0.782194 0.232605 0.1005346 0.2825094 0.8942948 0.3321415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4454 4354 -0.552149 0.526162 -0.920625 0.6100939 0.2662250 0.4655879 0.5832131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4454 4465 -0.777267 0.541245 0.736812 -0.2408720 0.6238513 0.0392315 0.7424629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4455 4464 -0.551526 -0.651227 0.160288 -0.1401985 -0.3666120 0.9162734 0.0798941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4455 5155 -0.231345 0.499587 0.745440 -0.5668208 0.0794709 0.8045868 0.1582360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4456 4463 0.676753 -0.070717 0.719483 -0.2711472 -0.7124547 -0.6204152 0.1843162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4457 4462 -0.208385 -0.558578 0.850443 -0.2898040 -0.7442976 0.4157905 0.4349171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4457 5157 -0.812734 0.508807 0.127659 0.8798390 0.1329668 -0.4067962 0.2066883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4458 4461 0.680798 -0.249380 -0.546472 0.5180464 0.1414969 0.8039664 0.2554302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4459 5159 0.363141 -0.257675 0.939866 -0.1020079 -0.0261288 0.3184162 0.9420843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4460 4499 -0.197234 0.405334 0.931442 0.1775680 -0.2045830 0.9588692 0.0847664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4460 5120 0.661920 -0.284457 0.416148 0.1237607 -0.8262663 0.5495046 0.0034494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4461 4498 -0.684286 -0.286049 0.383395 -0.0178504 -0.0657857 0.5263019 0.8475612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4462 4497 -0.133976 -1.058904 0.274216 0.4670604 0.6824205 0.5565371 0.0801459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4462 5122 0.832541 0.001642 0.684749 -0.0004446 0.7419968 -0.5155678 0.4285211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4463 5123 0.750616 -0.030555 0.673553 0.3895100 0.6370059 -0.2264256 0.6254893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4464 4495 0.579095 0.422121 1.032366 -0.3867447 -0.4366223 0.7980141 0.1515357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4464 5124 0.321909 -1.066193 0.228240 0.2815651 -0.3069096 0.5671403 0.7105487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4465 5125 -0.709228 -0.784553 0.355898 0.5807921 -0.1500108 -0.0107864 0.8000381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4466 4493 0.026455 0.908639 -0.184194 -0.6733021 -0.5801744 0.4578298 0.0213033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4466 5126 -0.794814 0.068788 0.617773 -0.2571576 0.0811027 0.9201253 0.2840100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4467 4492 -0.487694 0.521777 -0.407063 -0.0827257 0.2264326 -0.8764644 0.4167671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4467 5127 -0.743232 -0.450089 0.732918 0.0583040 -0.4795959 0.4824610 0.7306297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4468 4491 -0.222487 -0.963709 0.159311 -0.0207856 0.1432280 -0.4895997 0.8598522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4468 5128 0.028025 0.441416 1.200545 -0.7536720 0.0314647 -0.6120446 0.2374655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4469 4490 -0.475682 0.691699 0.380725 0.1020940 -0.3000357 0.8902862 0.3270257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4470 4330 -0.028304 -0.970306 -0.201891 -0.1008574 -0.3359247 0.1378651 0.9262697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4470 4489 0.737134 0.034299 -0.667101 -0.4652426 -0.2353635 -0.6452368 0.5584110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4471 5131 -0.179965 1.074450 0.165444 0.4255443 -0.2096286 -0.8221565 0.3146849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4472 4447 -0.766894 -0.221692 0.538696 -0.6501966 -0.2767533 0.3192836 0.6314348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4472 4487 0.954030 0.304295 -0.564492 -0.3667316 -0.4971221 -0.3346549 0.7116064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4472 5132 0.331423 0.476775 0.914967 0.2366943 0.6169278 -0.0622007 0.7480020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4473 4333 -0.156477 -0.833439 -0.259223 -0.6725715 0.1859334 0.2009368 0.6875323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4473 4446 0.954432 0.040607 -0.624002 -0.2194349 0.2589515 0.7554430 0.5604448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4473 4486 -0.621388 -0.069868 0.458374 0.0315269 -0.8097108 -0.5779920 0.0964356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4473 5133 0.074962 0.911014 0.380290 -0.7223342 -0.4532652 -0.5184092 0.0635282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4474 4485 0.657766 0.591544 -0.220874 0.3107161 0.4812953 -0.1165257 0.8113150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4475 4444 0.728227 -0.649957 -0.455890 -0.2695123 0.3795618 -0.6347373 0.6167694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4475 4484 -0.790695 0.453455 0.347690 0.3131483 0.2908950 0.7225255 0.5433923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4475 5135 -0.012614 -0.740528 0.919265 -0.2545295 0.6975884 -0.5697938 0.3520231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4476 4443 0.654209 0.443106 -0.008150 -0.6366745 0.5139811 0.5713232 0.0637081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4476 5136 -0.587596 0.729444 -0.023390 0.4963858 -0.0514655 -0.8369964 0.2244760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4477 4482 0.415106 -0.774725 0.280153 -0.5460656 -0.0034204 -0.0436301 0.8365985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4477 5137 0.504131 0.497264 0.803726 -0.1327596 0.0217048 -0.7019628 0.6993940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4478 5138 -0.492261 0.740528 0.563628 -0.4479833 0.6342963 0.2013457 0.5970252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4479 5139 -0.039089 0.106353 0.924831 0.2869582 0.5822193 0.1859074 0.7376410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4480 4300 0.767695 0.170810 -0.931561 0.2005379 0.4419939 0.8712005 0.0737274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4481 4478 0.939694 0.273620 -0.110382 0.3139464 0.1299403 0.9171886 0.2081305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4481 4518 -0.809102 -0.259867 0.196694 -0.1658680 0.6463227 -0.7316815 0.1392732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4481 5101 0.483847 -0.550161 0.416556 0.4101831 0.2573356 0.2549176 0.8369858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4482 4517 0.367927 -0.732462 -0.571211 -0.0413886 -0.1980788 -0.8457033 0.4937992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4482 5102 0.485462 -0.374211 0.759755 -0.5646620 0.3677762 -0.6774040 0.2949937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4483 4476 0.486401 0.336443 -0.607961 0.6513039 0.5231570 -0.5208998 0.1754236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4483 4516 -0.480046 -0.374752 0.814252 0.0091389 0.9312447 -0.2957660 0.2126553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4483 5103 0.637387 -0.712465 0.134427 0.4950968 0.2276446 -0.7454233 0.3839287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4484 4515 0.810998 0.486050 -0.136062 -0.6017442 -0.0493540 0.3271768 0.7269274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4484 5104 -0.593007 0.939947 0.518575 -0.0324440 -0.8514087 -0.2723416 0.4470802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4485 4514 0.744977 0.796902 0.163969 -0.1368051 0.0373463 -0.0138472 0.9897969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4485 5105 -0.068708 -0.012141 1.001153 0.0299182 0.3515036 -0.3795791 0.8552601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4486 4513 0.885860 0.351688 -0.275755 -0.1148817 -0.8235198 -0.4968583 0.2484937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4486 5106 -0.141211 0.473088 0.860106 -0.8538181 0.2434725 0.1350150 0.4398712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4487 4307 -0.661998 -0.442608 -0.436439 -0.1476572 -0.0148562 -0.9565183 0.2510965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4487 5107 0.643352 0.592572 0.436774 -0.0403968 -0.1656761 -0.8599748 0.4810019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4488 4471 -0.469451 -0.579387 -0.686815 0.9153816 0.3752016 0.0008222 0.1459439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4488 5108 0.757746 -0.712016 0.113232 -0.1267067 0.4426131 -0.7397456 0.4907296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4489 4309 0.216672 0.437532 -1.086254 0.2031396 -0.1830575 -0.9532051 0.1289350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4489 4510 -0.611342 0.787362 -0.004200 -0.4804053 0.1774993 -0.7876303 0.3425539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4489 5109 -0.272556 -0.322814 0.813456 0.1893043 0.6229109 -0.5844668 0.4842979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4490 5110 -0.232336 -0.892212 -0.093745 0.1418213 0.8215840 -0.4092443 0.3706826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4491 4311 0.312136 -0.005787 -1.212684 0.3076083 0.0576199 0.8876582 0.3378164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4491 5111 -0.098490 0.036766 1.070305 -0.4095151 0.1109049 0.1126752 0.8984997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4492 5112 0.789082 -0.606122 0.309769 0.9028519 0.0194372 0.2059001 0.3769428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4493 4506 0.902617 -0.077663 -0.097666 0.3554396 -0.3959432 0.8466206 0.0111881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4494 4465 -0.158051 0.734116 0.655869 -0.4410291 -0.3543942 0.5134992 0.6451486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4494 4505 -0.061189 -0.776053 -0.517776 0.4116910 0.5343384 -0.3265013 0.6621102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4494 5114 -0.282526 -0.514397 0.661724 -0.3165225 0.7311533 -0.6011228 0.0622869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4495 4504 -0.410444 -0.672690 -0.351246 -0.5643329 0.5638466 0.5891387 0.1285340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4495 5115 -0.927861 0.412510 0.433183 -0.5836838 -0.3245674 -0.3741312 0.6434245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4496 4463 -0.785233 0.396014 -0.279332 -0.1992654 -0.3506281 -0.8027256 0.4393004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4496 4503 0.989122 -0.159196 0.141427 -0.2525327 -0.2780481 -0.8981435 0.2285929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4496 5116 -0.281238 -0.083874 0.897731 0.1413578 0.1723041 -0.8218650 0.5242778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4497 4502 -0.471838 0.233497 -0.740244 -0.0542591 -0.0207346 -0.1103850 0.9921901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4498 4501 -0.566311 0.517379 0.484346 0.2809841 -0.2377744 -0.9267306 0.0753769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4500 4539 -0.476566 -0.701766 -0.690626 -0.0011752 -0.8234612 -0.0684466 0.5632276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4500 5080 -0.782301 0.018219 0.490931 0.2444959 -0.1454750 -0.2127608 0.9347682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4501 4281 0.019719 -1.035744 -0.289102 -0.2297830 -0.5612128 -0.2811018 0.7437888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4501 4538 -0.081106 -0.231685 0.905408 -0.7749357 -0.2504212 0.1607600 0.5576022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4501 5081 0.109273 0.980669 0.288466 -0.2642970 -0.5614692 -0.5675486 0.5410989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4502 4537 -0.665684 0.052940 -0.586594 -0.2896691 -0.6817772 0.0450344 0.6702563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4502 5082 -0.231838 0.841163 0.647221 -0.0619659 0.0801472 -0.8905879 0.4433846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4503 4536 -0.289251 0.742970 0.251360 -0.4695956 0.8384196 -0.1113547 0.2532443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4503 5083 0.811708 0.101237 0.612580 -0.5168954 -0.0241615 -0.8447958 0.1362186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4504 4535 0.633378 0.484116 -0.155586 -0.6898821 -0.4193704 -0.3868033 0.4456168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4504 5084 -0.278422 0.684130 0.541081 0.5750033 0.1763240 0.7879574 0.1319249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4505 4534 0.400852 -0.690373 0.553020 0.4888782 -0.5142550 -0.2808597 0.6462644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4505 5085 -0.732945 -0.293888 0.345499 0.2464610 -0.1127818 -0.9552206 0.1187046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4506 4533 -0.884781 0.154754 0.511972 -0.1740053 -0.3046602 0.7876472 0.5064744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4506 5086 0.266282 0.596393 0.767623 -0.4903651 -0.0559155 -0.3208072 0.8083924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4507 4287 0.803455 -0.335079 -0.484185 -0.1005303 -0.1528696 -0.2647996 0.9467870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4507 4492 -0.477986 -0.109169 -0.808902 -0.3996881 -0.7517153 0.3473270 0.3931126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4507 4532 0.654262 0.060867 0.908295 -0.2665186 -0.4426790 -0.7272044 0.4518594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4507 5087 -0.895776 0.018581 0.654376 0.0701047 -0.5618536 0.4757968 0.6730700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4508 4491 0.077443 0.371917 -0.885811 -0.3038380 -0.4213795 -0.2493418 0.8172824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4508 4531 -0.023677 -0.435907 0.877643 -0.1638969 0.9222751 0.2744661 0.2172899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4509 4289 0.239308 0.650697 -0.732560 0.2260639 0.3198199 0.1919731 0.8998648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4509 4530 0.814662 -0.445626 -0.091664 -0.1047637 -0.3379786 -0.2367796 0.9048373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4509 5089 -0.029484 -0.774984 0.692791 0.5326674 -0.4610255 0.5498223 0.4487943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4510 4529 -0.402967 -0.707134 -0.514276 0.1171051 -0.7587145 0.5111082 0.3865321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4510 5090 0.986310 -0.658572 0.338563 0.4846510 -0.2686119 0.4684063 0.6881545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4511 5091 -0.443186 -0.426896 0.719849 -0.0053065 -0.5973794 0.7223888 0.3482300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4512 4292 -0.515341 0.894938 -0.415877 0.0351208 -0.3141209 0.8108976 0.4924832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4512 4487 -0.229931 -0.526248 -1.055689 0.6088960 -0.1555983 -0.2714863 0.7289239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4512 4527 0.033608 0.624550 0.701269 -0.0904505 -0.8528134 0.5068368 0.0874331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4512 5092 0.486059 -0.882679 0.497015 -0.0256616 0.3900962 -0.8058333 0.4447461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4513 5093 0.486656 0.865927 0.180983 0.1302347 0.8877153 0.1450655 0.4170808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4514 4294 0.049555 0.164698 -0.887679 0.3681948 0.5073198 0.6921947 0.3576670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4514 4525 0.559130 0.840738 0.308319 0.5730146 0.0608287 -0.7790883 0.2469325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4514 5094 -0.065653 -0.211277 0.931970 -0.3813164 0.3202093 0.8101775 0.3093158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4515 4524 0.909881 -0.221945 0.310363 0.3834701 -0.0818629 0.4286771 0.8139319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4515 5095 -0.234880 0.090054 0.996595 -0.1740367 0.4502827 0.6069102 0.6313610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4516 5096 -0.675054 -0.617684 0.512964 0.5454490 0.1683421 -0.8007482 0.1815176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4517 5097 0.405625 0.835798 0.481216 -0.4749388 0.5049444 0.1066470 0.7128048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4519 4299 -0.015279 0.920615 -0.135615 0.2244153 -0.6575932 0.6886245 0.2073770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4519 4480 1.060136 -0.141474 0.194103 0.5607144 0.4211488 0.0525782 0.7109631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4519 5099 -0.036249 -1.004512 0.313927 -0.1212790 -0.5979610 0.4961261 0.6177321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4520 4260 -0.272930 0.735642 -0.494329 0.4914470 0.1122039 0.6338073 0.5866672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4520 4559 -1.111644 -0.178627 0.147535 0.3289122 0.5506564 -0.6863993 0.3427102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4520 5060 0.189023 -0.988785 0.330387 0.4510730 -0.5431582 -0.0631869 0.7053508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4521 4518 -0.403829 -0.186674 -0.810743 -0.5824602 -0.3650242 -0.2628965 0.6770398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4521 4558 0.624841 0.211846 1.068486 0.5540936 -0.3963168 -0.6337282 0.3664722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4521 5061 -0.449143 0.724361 0.082785 0.1557768 -0.3736283 -0.4753333 0.7811490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4522 4517 0.717460 0.164374 0.499566 0.3012660 -0.1214072 0.9334145 0.1524350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4522 4557 -0.856619 0.008894 -0.475089 -0.0404174 -0.7033452 0.2089499 0.6782418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4522 5062 -0.491561 -0.663856 0.703528 -0.0067599 0.4031910 -0.8864770 0.2270458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4523 4516 0.066750 0.648362 -0.698950 -0.6578085 -0.1678738 -0.0358586 0.7333625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4523 4556 0.010042 -0.637202 0.804578 -0.0105240 -0.4710191 -0.8397391 0.2699417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4523 5063 -0.834612 0.544608 0.230984 -0.1585508 -0.3073596 -0.0064218 0.9382699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4524 4555 0.587179 -0.589119 0.193879 -0.2727215 -0.0011249 -0.6478786 0.7112489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4524 5064 0.315330 0.654735 0.674779 0.0618290 -0.7705667 -0.5228108 0.3592673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4525 5065 -0.732638 0.440509 0.396161 -0.4311548 -0.2794835 0.7222652 0.4629551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4526 4553 -0.853365 -0.089937 -0.518437 -0.2550545 -0.6052499 -0.1180365 0.7447732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4527 4267 0.488221 0.783284 -0.301624 -0.1599367 -0.7076292 0.6833367 0.0820496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4527 4552 0.009358 -0.520511 -0.809318 0.0081570 -0.7969913 -0.0484072 0.6019925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4527 5067 -0.690163 -0.600223 0.277319 0.0373463 0.1915623 -0.8747765 0.4434809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4528 4511 -0.619457 0.157583 -0.767175 0.3925971 0.0189142 -0.8094241 0.4362824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4528 4551 0.514015 -0.091720 0.914548 0.0493773 -0.2319156 0.9544345 0.1811953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4528 5068 -0.759542 0.441535 0.458760 -0.3369279 -0.2379159 0.1209299 0.9029128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4529 4269 0.565114 0.936979 -0.048249 0.8220003 -0.0457040 -0.1999402 0.5312726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4529 4550 -0.239306 0.100489 1.085459 -0.3057793 -0.4878100 0.6240552 0.5282950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4530 4270 -0.578503 0.709329 -0.589963 0.2413111 0.3448393 0.2370994 0.8755791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4530 4549 0.790123 -0.112144 -0.826745 -0.2334915 0.2011141 -0.4002110 0.8630562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4530 5070 0.594908 -0.581867 0.631503 -0.0222567 -0.3492458 0.1933166 0.9166028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4531 5071 0.487036 1.052201 -0.065740 0.2936259 0.5643775 0.7701575 0.0460366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4532 4547 0.447876 0.908548 0.321634 0.8084508 0.2008754 0.2646046 0.4858403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4532 5072 0.851893 -0.471438 0.366388 0.0966579 0.5728254 0.1736794 0.7952130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4533 4273 -0.363570 0.799660 -0.159439 0.4083695 0.0577829 -0.9018666 0.1285770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4533 4546 0.340287 0.489654 0.866306 0.5740564 -0.1287520 0.6525568 0.4775477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4533 5073 0.312237 -0.879307 0.136795 0.9261341 0.0236389 -0.0019293 0.3764480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4534 5074 0.104771 0.435317 0.985527 0.1266883 0.5575241 0.0115358 0.8203559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4535 4544 0.061768 0.687047 0.672799 0.2439467 -0.7301636 0.6258736 0.1250329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4536 4543 -0.613216 0.666452 -0.347422 0.3234208 0.5191363 -0.7831256 0.1122975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4536 5076 -0.858211 -0.699428 0.063932 0.8220092 0.4815027 -0.1778937 0.2465964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4537 4542 -0.519628 0.152443 0.854856 -0.5891046 0.6990243 -0.3837644 0.1305594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4537 5077 0.647119 0.041832 0.640071 0.1837044 -0.0715169 -0.3094893 0.9302443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4538 4541 -0.057050 -1.012122 -0.371849 -0.4271612 -0.0053654 -0.7018440 0.5700171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4538 5078 0.589773 -0.362538 0.737852 0.6603952 -0.3846511 0.6387599 0.0889245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4539 5079 0.820012 -0.032736 0.639580 -0.0388627 0.3904415 -0.8905820 0.2300193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4540 5040 0.458195 0.573849 0.362384 0.1438246 -0.0335954 -0.9881234 0.0424037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4541 4241 -0.695569 -0.321767 -0.655930 -0.2238811 -0.6048436 -0.7594360 0.0854311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4541 4578 0.578761 0.438227 -0.707595 -0.0924603 0.5717837 -0.5682587 0.5844626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4541 5041 0.677802 0.304619 0.741020 -0.5719572 0.6032435 -0.5098092 0.2214879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4542 5042 -0.452781 -0.957093 0.002605 0.6807294 0.1230659 0.1265395 0.7109500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4543 4243 -0.353812 0.049285 -1.011894 0.4006665 -0.5172683 0.7400179 0.1557992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4543 4576 0.873618 -0.275465 -0.271657 0.2922396 -0.3516012 -0.4670339 0.7568698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4544 4575 0.203530 -0.667621 -0.799295 0.0096188 0.0520835 -0.0904835 0.9944886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4544 5044 -0.186443 -0.606292 0.520825 0.7054735 0.1564371 -0.6059658 0.3326259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4545 4534 0.838816 -0.693895 -0.127644 0.2945925 0.3869758 0.6863359 0.5407476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4545 4574 -0.542833 0.779232 0.384409 0.1606454 -0.0972760 -0.7448419 0.6402663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4545 5045 0.572429 0.354200 0.737705 -0.2521892 0.1711528 0.8986393 0.3155231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4546 4246 0.258798 -0.200992 -0.811967 0.6283731 -0.3588321 -0.6842352 0.0906041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4546 4573 0.802764 0.050215 0.189317 -0.4836867 -0.1442614 0.7702841 0.3897413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4546 5046 -0.309635 0.445077 0.993187 -0.1932418 -0.3838662 -0.8105717 0.3978416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4547 4572 0.780447 -0.035190 -0.572144 -0.5854770 0.1912246 0.7229254 0.3130954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4547 5047 0.300965 0.657627 0.624293 -0.0892738 0.6845552 0.1157653 0.7141518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4548 4531 0.940452 -0.173250 0.283295 0.2672321 0.3475618 0.2572781 0.8611596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4548 5048 0.006494 1.016913 0.486928 -0.5910426 -0.0581341 -0.5564614 0.5810678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4549 5049 0.659891 -0.284248 0.689915 0.1282904 0.3326287 0.6806853 0.6399744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4550 4569 0.365930 -1.026766 0.551373 -0.2237559 0.6111113 0.7328391 0.1985526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4550 5050 -0.628992 0.182673 0.629343 0.4556698 0.4722432 -0.6546418 0.3752272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4551 5051 0.935249 -0.345349 0.266983 0.2140161 0.6272527 0.1002443 0.7420932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4552 4567 -0.849666 -0.611840 0.135305 -0.4872923 0.2994215 -0.7402108 0.3535265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4552 5052 0.477624 -0.666515 0.393488 0.8805274 -0.1119612 -0.2057863 0.4120537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4553 4566 -0.833878 -0.279709 0.704311 0.2863753 0.8124891 -0.4999563 0.0888498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4553 5053 0.623683 -0.876405 0.428853 -0.1162516 0.0028292 0.0886022 0.9892559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4554 4525 -0.600082 -0.587836 -0.610256 0.4848353 0.3913596 -0.7781653 0.0789380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4554 4565 0.535938 0.545434 0.566392 -0.3133517 0.5034595 -0.5238140 0.6115211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4555 4564 0.860203 0.440384 0.201693 0.1165548 0.1674876 0.3785277 0.9028176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4555 5055 -0.423837 0.113277 0.896396 0.4998586 0.0123521 0.6265594 0.5978395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4556 4256 -0.572679 0.455101 -0.559397 0.4538631 0.2944110 -0.1296618 0.8309743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4556 4563 0.516017 0.806308 0.157434 0.8061816 0.0113238 0.4952963 0.3234572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4556 5056 0.438176 -0.245775 0.764455 0.4196497 0.7792426 0.1268052 0.4478788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4557 4257 -0.338984 0.862023 -0.452582 -0.7101650 0.0908873 -0.6824329 0.1472771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4557 4562 -0.791761 0.257872 0.676454 0.7398659 0.0055518 -0.5531343 0.3828970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4557 5057 0.312405 -0.738157 0.696984 0.5404411 -0.3174521 0.6349401 0.4516621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4558 4258 0.638752 0.257737 -0.709699 0.7781833 0.1285378 -0.5524250 0.2696952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4558 5058 -0.587483 -0.254164 0.847102 0.1392265 0.2528552 0.9108901 0.2948888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4559 4259 0.225040 -0.121341 -0.961383 0.5754694 -0.0814391 0.6189915 0.5282539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4560 4599 -0.943721 -0.292081 -0.181131 0.1254404 0.4177579 0.8426475 0.3157344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4560 5020 -0.165133 -0.248012 0.764821 0.1583798 -0.7619437 0.6188012 0.1069705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4561 4558 0.311905 0.476505 -0.871655 -0.2866665 0.6747015 0.6022633 0.3160366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4561 4598 -0.251274 -0.386243 0.844720 0.2961541 0.4185928 0.3241226 0.7949952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4561 5021 0.446895 0.717725 0.497366 0.0273603 0.8899197 0.2535979 0.3781302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4562 4597 -0.787192 0.094868 0.082653 -0.4401852 0.3868423 0.4336002 0.6845297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4562 5022 -0.063402 0.931947 0.070351 0.0804162 0.1886805 0.9209293 0.3313941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4563 5023 1.054439 0.563038 0.509623 0.1917136 0.1176416 0.6315140 0.7420219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4564 4595 0.955473 -0.164966 0.255707 -0.5305081 -0.2186845 0.3755571 0.7278016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4564 5024 -0.195905 0.517718 0.785730 0.2654369 -0.5962434 -0.5221925 0.5489554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4565 5025 0.612897 -0.345709 0.452466 0.4355565 0.3754297 -0.1149275 0.8100214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4566 4226 0.767701 0.180404 -0.459944 -0.2624624 -0.8155098 0.0123307 0.5156600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4566 5026 -0.951574 -0.281697 0.501332 0.7366104 -0.1802113 -0.0104315 0.6517823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4567 4592 0.857690 -0.082253 -0.563072 -0.3871364 0.0871337 -0.9083227 0.1322235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4568 4551 -0.744823 0.160827 -0.469121 -0.2814486 0.4871085 -0.8266406 0.0133129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4568 4591 0.907592 0.098329 0.507801 0.0273912 -0.1848815 0.5680243 0.8015092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4568 5028 -0.446395 -0.587813 0.592570 0.2092077 0.6636528 -0.5382563 0.4754758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4569 4590 -0.653543 0.373836 -0.662416 0.2270562 -0.5865474 -0.6786152 0.3793269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4570 4549 0.917367 -0.243109 -0.479797 0.3546918 -0.6271058 0.5154977 0.4638903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4570 4589 -0.742582 0.170592 0.477729 -0.1884604 0.5145436 -0.3724250 0.7490174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4570 5030 0.025753 -0.755520 0.776793 -0.2087514 0.1093612 0.9055785 0.3526906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4571 4548 -0.604902 -0.421459 0.352409 0.0144315 -0.1931274 -0.9119033 0.3618368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4571 4588 0.863250 0.151231 -0.265044 -0.3181572 0.4034090 0.3326426 0.7908135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4572 4587 0.488649 -0.672792 -0.763307 0.1590259 -0.8702669 0.3931476 0.2505619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4572 5032 -0.530890 -0.926607 0.432674 0.6962874 0.3970918 -0.5763983 0.1589561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4573 4233 0.379735 0.585930 -0.807588 -0.2908882 -0.1166276 0.6216261 0.7178879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4573 4586 -0.394365 -0.369889 -0.714982 0.2963673 -0.6616092 0.6609243 0.1939555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4573 5033 -0.407929 -0.629418 0.823760 0.1579018 -0.1333920 0.7655733 0.6092382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4574 4585 -0.573199 -0.616784 0.396226 -0.7678238 0.1888645 -0.0199393 0.6118653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4574 5034 -0.437453 0.909186 0.491472 -0.7911170 -0.0426379 0.4463605 0.4160268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4575 4584 0.339686 -0.500552 -0.817873 -0.1735075 0.1329256 0.9418516 0.2552285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4575 5035 0.009293 -0.866337 0.511907 -0.1873764 0.0178035 -0.8578120 0.4782590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4576 5036 0.365347 0.826892 0.372654 -0.3721130 -0.4963720 -0.4852266 0.6161995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4577 4542 0.668943 -0.716128 0.044185 0.4872385 -0.3306685 0.7929287 0.1565920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4577 4582 -0.643765 0.757568 0.017663 0.0476998 0.5718301 0.5842824 0.5738895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4578 5038 -0.739239 -0.101517 0.632262 0.2861847 -0.1402048 0.2139262 0.9234048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4579 4540 -0.983842 -0.057814 -0.621494 0.1965888 -0.0529961 -0.8979758 0.3901073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4579 5039 -0.203552 -0.995638 0.592810 0.3943662 -0.6110026 0.6703391 0.1476364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4580 4619 0.205239 0.973041 -0.507686 0.0318152 0.1714832 0.9832243 0.0533970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4581 4201 -0.591319 -0.778648 -0.147581 -0.7379589 -0.6463586 -0.1562515 0.1149899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4581 4618 -0.214894 0.357901 -0.954741 -0.0372528 0.3645003 -0.2386371 0.8993354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4581 5001 0.733265 0.621590 0.227925 0.0033271 0.4546663 -0.2918882 0.8414682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4582 4202 -0.029415 0.174073 -0.896744 -0.4660790 0.5249967 -0.3866391 0.5980460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4582 4617 0.938570 0.360844 -0.050119 0.3957366 -0.1318926 -0.2769603 0.8656153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4583 4616 -0.676096 -0.853946 -0.384258 -0.0306930 -0.3445212 0.1145670 0.9312559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4583 5003 -0.698778 0.465757 0.125731 0.2005757 -0.0895003 -0.9448478 0.2429438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4584 5004 -0.693660 0.618550 0.255287 -0.4861623 -0.7070572 -0.5009133 0.1131463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4585 4614 -0.562108 -0.043674 -0.820492 -0.4289966 0.0309560 0.6652902 0.6102397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4585 5005 -0.651368 -0.526276 0.483896 0.0615577 -0.1231467 -0.0478247 0.9893222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4586 4613 -0.276911 0.977778 0.549925 0.1979113 0.3560272 -0.7281575 0.5512372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4586 5006 1.024918 -0.181634 0.538802 0.5302176 0.5196737 -0.4439824 0.5016853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4587 4612 -0.448947 -0.073831 0.652295 0.2965227 0.2715985 -0.8941825 0.1968408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4587 5007 0.727430 -0.525013 0.516740 0.1825087 -0.1270795 0.6898926 0.6889046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4588 4208 0.551963 0.889654 -0.267802 0.2873730 0.2646910 -0.9200457 0.0295180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4588 4611 0.671801 -0.474432 0.589211 0.1685378 -0.0464392 -0.9724222 0.1543809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4588 5008 -0.582318 -0.823816 0.288725 0.4747601 -0.2665331 -0.8387087 0.0114290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4589 5009 0.223558 -0.944631 0.596149 0.3726424 0.3356759 0.5335464 0.6810195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4590 5010 -0.764305 0.300583 0.424222 -0.1093144 -0.3057205 -0.9199785 0.2196017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4591 4608 0.094655 -1.052242 0.020332 0.4919875 0.1546369 -0.1847016 0.8366129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4592 4607 -0.798973 0.305375 0.227665 -0.3472003 0.3656243 -0.2711166 0.8199186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4592 5012 -0.036744 -0.393071 0.853236 -0.3749620 -0.0448589 0.0229683 0.9256693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4593 4566 -0.881284 -0.193720 -0.288252 -0.5489088 0.1911460 0.5130675 0.6316044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4593 4606 0.770388 0.312798 0.249090 -0.3205302 -0.5956626 0.7364780 0.0068277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4593 5013 -0.310419 0.040775 1.028112 -0.3288170 0.1324805 -0.8721215 0.3372424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4594 4565 0.339926 -0.143098 -0.878114 0.1213473 0.2407318 -0.4055627 0.8734082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4594 4605 -0.340757 0.295075 0.843314 0.2598246 0.1606986 0.9079027 0.2870187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4594 5014 0.267195 -0.982821 0.306402 0.5181053 0.0962368 -0.3520613 0.7735362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4595 4604 0.476075 -0.609452 -0.622518 -0.0100053 -0.0389404 -0.8148181 0.5783208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4595 5015 0.316520 -0.401774 0.841476 -0.2431871 -0.1847066 0.8409017 0.4467973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4596 4216 0.406996 -0.359688 -0.973253 -0.4801412 0.4537974 0.4401507 0.6081115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4596 4563 1.046602 0.132068 0.307159 -0.1759942 -0.7683208 -0.5878084 0.1821825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4596 4603 -0.928823 -0.203339 -0.507953 -0.8258037 -0.0530258 0.3756735 0.4172599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4597 5017 0.075148 0.068655 0.976056 -0.6340845 0.0001191 -0.5520558 0.5414529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4598 4601 -0.801118 0.515148 0.295133 -0.6594120 0.2118785 -0.6399958 0.3326992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4598 5018 0.565157 0.750489 0.687613 -0.0593811 0.6075994 0.6966028 0.3768838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4599 4219 -0.074755 -1.073650 -0.201380 -0.0849772 0.2344278 0.8337132 0.4926913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4599 5019 -0.024193 1.019264 0.346944 -0.4396834 -0.7498607 -0.2118745 0.4466504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4600 4639 0.460420 0.819694 0.253464 -0.1072772 -0.3420493 0.8195598 0.4470075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4600 4980 -0.704046 0.071962 0.778265 0.0929051 -0.8028411 -0.5674421 0.1575572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4601 4638 -0.180775 -0.747383 -0.747546 0.0469016 0.6150444 -0.2791182 0.7359440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4601 4981 0.095483 -0.366750 0.753117 -0.0829357 -0.0071090 -0.1343249 0.9874350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4602 4597 -0.630885 0.802051 0.145241 -0.5398497 -0.2647700 -0.7721659 0.2054724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4602 4637 0.457092 -0.807354 -0.260486 -0.5003681 -0.3212703 -0.7658090 0.2448546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4602 4982 0.848368 0.480793 0.442294 -0.2691883 0.1454651 -0.2282231 0.9242791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4603 4636 -0.443063 0.529111 0.653309 -0.2113365 -0.5059642 -0.0631907 0.8338729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4603 4983 -0.614230 -0.778245 0.180652 0.5231129 -0.1381781 -0.0848195 0.8366991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4604 4635 0.431892 0.683129 -0.701305 0.2914645 0.4080962 0.0385564 0.8643028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4604 4984 0.388316 0.663114 0.962886 0.0840713 0.3915237 0.8197389 0.4094744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4605 4634 0.702230 0.434543 0.410720 -0.3579359 -0.2328151 0.5341230 0.7296517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4605 4985 -0.722159 0.632892 0.235398 -0.9122429 0.0093497 0.0532486 0.4060665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4606 4633 -0.606637 0.126216 -0.750582 0.7998883 -0.4902846 -0.3137294 0.1461968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4606 4986 -0.308493 -1.110080 0.050025 0.9110913 0.3720119 0.0865231 0.1550275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4607 4632 -1.050447 -0.054673 -0.491678 0.3978660 0.1589629 0.2213390 0.8760380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4607 4987 0.007385 -0.979349 0.391610 0.4864049 0.6205781 -0.0534095 0.6127320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4608 4631 0.246809 -0.117023 0.832196 -0.5409588 -0.1410535 -0.2438940 0.7924539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4608 4988 -0.618310 0.581951 0.527683 -0.3029927 -0.6349889 0.4380708 0.5595341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4609 4630 -0.364958 0.914584 -0.579165 0.2282729 0.1675972 0.9579363 0.0464831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4609 4989 0.307480 0.483057 0.912821 -0.3932263 -0.6803010 -0.4782820 0.3921862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4610 4589 0.629011 0.514065 0.783947 -0.5470258 -0.4768850 -0.5717722 0.3826487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4610 4629 -0.691757 -0.448881 -0.686864 -0.1444599 0.8489540 0.3549961 0.3638491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4610 4990 -0.672890 0.381257 -0.129683 0.7885532 0.3666756 -0.4934570 0.0152640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4611 4628 -0.644039 0.532836 0.225982 0.4946207 0.1597534 0.6006453 0.6074985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4612 4627 0.210708 -0.431007 0.705542 -0.1421521 -0.2922430 0.5533560 0.7669315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4613 4626 -0.895016 -0.224306 -0.298903 -0.6566915 0.1934579 -0.2739667 0.6754796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4613 4993 -0.361668 0.754485 0.698862 0.0164509 -0.0793362 -0.1843491 0.9795155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4614 4625 0.213869 0.956086 -0.350982 0.3550307 -0.3164910 -0.1996468 0.8566958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4614 4994 -0.678506 0.560980 0.350898 -0.0027077 0.4008061 0.8971419 0.1856975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4615 4195 0.104836 0.970975 -0.178180 0.6743531 0.4735264 -0.5041561 0.2585482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4615 4584 -0.560583 0.003859 -0.860263 -0.8747662 -0.2563191 0.4082452 0.0491978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4615 4624 0.476139 -0.073281 0.853089 -0.8090268 -0.3742894 0.4325844 0.1351063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4615 4995 0.008627 -1.064260 0.261504 -0.2562887 -0.9219253 0.1284733 0.2605081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4616 4623 -0.967223 -0.620984 0.256598 -0.7209513 -0.1077852 -0.5923539 0.3431157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4617 4622 0.240772 0.759106 -0.721452 -0.2334576 0.7677494 0.3722649 0.4663446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4617 4997 0.327419 0.735146 0.566125 -0.0872249 -0.2059993 0.7958272 0.5626856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4618 4998 -0.119875 0.717658 0.450357 -0.4473280 0.0768869 0.3218206 0.8309137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4619 4999 -0.734071 0.023090 0.680891 -0.0600041 0.0461252 0.6278602 0.7746377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4620 4160 -0.075363 0.993683 -0.270622 -0.0035672 -0.4900508 0.3138592 0.8132219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4620 4960 0.254801 -0.994432 0.155810 0.5466503 0.2303604 0.3032411 0.7457562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4621 4618 0.276038 -0.366173 -0.947762 0.6701524 0.5406957 0.3240573 0.3918300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4621 4658 -0.494324 0.443969 0.895593 0.2751662 0.3638617 -0.2756292 0.8461187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4622 4657 0.506033 -0.049872 0.806910 0.3439617 -0.9017621 -0.0115941 0.2614976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4622 4962 -0.900297 0.286393 0.526884 -0.0646608 0.6269148 0.7649197 0.1330214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4623 4656 0.241846 -0.146019 -1.061837 0.8282564 0.2915306 -0.2676913 0.3966644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4623 4963 0.234462 -0.970392 0.258188 0.5956373 0.3310688 0.1467448 0.7169906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4624 4655 -0.075198 -0.282331 -1.087419 -0.2298619 -0.1831315 -0.1647765 0.9415280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4624 4964 -1.023592 0.406877 0.143833 -0.5893314 -0.5304401 0.3188892 0.5192605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4625 4965 -0.575990 0.664892 0.451440 -0.0312127 0.0861211 -0.4766867 0.8742875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4626 4966 -0.583916 -0.723265 0.148410 -0.1784212 0.1282692 0.7948107 0.5656756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4627 4652 -0.028971 -0.567889 0.672983 -0.5305992 -0.1175032 0.2249712 0.8087308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4628 4651 0.659460 0.606392 -0.578032 0.5246892 0.2424103 0.7519889 0.3169403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4628 4968 0.830491 -0.242420 0.556181 0.0079445 0.5976966 0.1193093 0.7927553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4629 4969 0.464326 0.891496 0.290629 0.3584730 0.9179193 0.0478311 0.1631977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4630 4649 0.313681 -0.946439 -0.091283 -0.1922266 -0.6305258 0.3526612 0.6641658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4630 4970 0.293506 -0.308737 0.802475 0.7261062 0.1739631 0.4872159 0.4529097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4631 4648 0.528273 -0.506876 0.286614 -0.2842312 -0.3720340 0.6574009 0.5904468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4631 4971 -0.405371 -0.497041 0.756699 0.2697495 0.2625379 -0.8142815 0.4418762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4632 4647 -0.764968 -0.099836 -0.541689 0.2231688 0.2270597 -0.9082005 0.2716825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4632 4972 -0.630157 -0.280474 0.784830 0.2392756 0.1022001 -0.8874979 0.3803287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4633 4646 -0.012939 -0.000460 1.106693 -0.0852033 -0.4876870 -0.5530245 0.6701236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4634 4645 0.654809 -0.617626 -0.082981 0.1197988 0.1058580 -0.3915426 0.9061659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4635 4644 0.821760 0.204082 -0.592955 -0.3119701 0.1518064 0.9378846 0.0013853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4635 4975 0.037669 0.912624 0.402481 -0.7288359 0.4597306 -0.1085370 0.4956468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4636 4176 0.166739 0.868274 -0.413702 -0.3247137 -0.4968669 0.3883375 0.7048959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4636 4976 -0.283113 -0.688315 0.253878 0.8908151 -0.2531116 -0.3072703 0.2190159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4637 4642 -0.531024 0.825284 -0.183564 -0.5972335 -0.0400584 0.7391416 0.3088320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4637 4977 0.112154 0.328689 1.054135 -0.3186593 -0.1449373 -0.0987419 0.9315039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4638 4978 -0.560784 -0.521814 0.673227 0.3960663 0.7035889 -0.5576661 0.1926203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4640 4679 0.606236 -0.775641 0.311600 0.0414520 0.1042931 0.3059355 0.9454143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4640 4940 -0.523067 -0.219699 0.696570 0.3183425 -0.3557241 -0.8752112 0.0782547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4641 4638 0.029817 -0.997620 -0.395303 -0.4627793 -0.4708312 0.6526480 0.3717578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4641 4678 0.086815 1.024352 0.198366 0.3689936 0.0803167 0.5466377 0.7473822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4641 4941 -0.418021 -0.470838 0.973443 0.0977233 -0.2367295 -0.9162750 0.3079764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4642 4677 0.717425 -0.467572 0.351470 0.1268461 -0.3825845 0.5943833 0.6958791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4642 4942 -0.737799 -0.998773 0.209541 0.3049381 0.1803538 -0.9342507 0.0407548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4643 4636 -0.928789 -0.340262 0.564191 -0.6847053 0.3748988 -0.1507031 0.6065625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4643 4676 0.615607 0.475683 -0.562677 -0.3628089 -0.4791587 0.2964073 0.7422395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4643 4943 0.492294 0.248384 0.670496 -0.1162660 0.2877479 0.9343861 0.1749458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4644 4675 -0.447204 -0.362425 -0.760056 0.7345750 0.3159258 0.1540654 0.5803915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4644 4944 -0.310265 -0.811301 0.721731 0.0275794 0.5042436 0.1156182 0.8553422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4645 4945 -0.352344 0.547313 0.829106 0.1155024 -0.7140105 -0.0203424 0.6902422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4646 4146 0.494819 -0.776897 -0.055514 -0.0717136 -0.3070405 -0.3595490 0.8782413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4646 4673 0.792942 0.365526 0.492520 -0.6413133 -0.2547395 -0.6662742 0.2826725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4647 4672 0.970562 -0.203392 -0.171858 0.2244355 0.1534544 -0.3893265 0.8800598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4647 4947 -0.035976 -0.194979 0.974648 -0.5782457 -0.3043939 0.6673992 0.3571477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4648 4671 -0.919770 -0.546323 -0.430837 0.4576961 0.4087983 -0.7124156 0.3403853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4648 4948 -0.318676 -0.349644 0.803910 -0.0304114 -0.1544599 -0.6650940 0.7299776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4649 4670 -0.822178 -0.329322 -0.081604 -0.1823186 0.7429024 -0.6257052 0.1528036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4649 4949 0.341145 -0.825808 0.184604 0.2441457 -0.0911879 0.9647999 0.0351974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4650 4629 -0.939401 0.474305 0.223540 0.0976392 -0.2416429 -0.0841122 0.9617694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4650 4669 0.758713 -0.482579 0.023300 -0.2448096 -0.0571151 0.4892811 0.8351108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4650 4950 0.379742 0.760981 0.347029 -0.4265988 0.1765468 -0.4282997 0.7767909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4651 4951 -0.010614 0.382753 0.929235 -0.2533132 0.3184670 -0.7968343 0.4466165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4652 4667 -0.392615 -0.972781 -0.147185 0.7709418 -0.5412367 0.2698674 0.1997075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4652 4952 0.699124 -0.410901 0.582619 0.3427355 0.1290504 0.5307505 0.7643182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4654 4625 0.674935 0.856409 0.091910 -0.5148668 0.2824815 0.3687760 0.7205003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4654 4954 -0.839592 0.623026 0.242711 -0.1726037 -0.2425790 -0.5537470 0.7776424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4655 4664 -0.697175 0.155118 -0.759692 0.4828453 -0.1250875 -0.7865294 0.3641223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4655 4955 -0.615266 0.016774 0.609228 -0.8338768 -0.4049187 0.3300807 0.1781488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4656 4956 -0.337672 0.663822 0.556362 -0.0222867 0.3019624 -0.8911671 0.3378509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4657 4662 0.212814 -0.057455 -0.908177 -0.6061201 0.1159391 0.5950248 0.5149000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4658 4661 -0.960580 0.378581 0.078412 0.0385690 -0.3590553 0.9042248 0.2279677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4658 4958 0.113146 0.239872 0.853596 -0.1296154 0.1950146 -0.5500776 0.8016132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4659 4620 -0.844588 0.466589 0.072659 -0.0393777 -0.7331683 0.6735678 0.0849711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4660 4699 0.228594 0.710868 -0.364027 0.5084619 -0.0167190 -0.7358102 0.4469567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4660 4920 -1.043351 0.544790 0.199814 0.2018804 0.1805754 -0.9607889 0.0593420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4661 4698 1.089140 0.075775 -0.087680 -0.4098820 -0.2636070 0.8678900 0.0963066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4661 4921 0.176750 -0.985362 0.287839 0.3125624 -0.0669940 -0.2758532 0.9064886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4662 4122 -0.629611 0.710545 -0.455474 0.3321400 0.3880211 -0.4033437 0.7592342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4662 4922 0.569489 -0.730372 0.477772 0.0795696 -0.4051217 0.5724695 0.7083952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4663 4696 -0.713200 -0.533998 -0.021270 -0.7489110 0.4743737 0.3794089 0.2648598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4664 4695 0.641051 -0.686409 0.094742 0.0109801 -0.5915603 -0.1605441 0.7900389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4664 4924 -0.379972 0.100913 1.003339 0.3769928 -0.3794198 0.5669120 0.6265203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4665 4694 0.165247 0.353540 -0.986424 -0.0954819 0.5610615 0.8183328 0.0801534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4665 4925 0.007021 1.048815 0.223327 0.0108051 0.5183356 -0.0577240 0.8531585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4666 4653 0.120196 0.463600 0.838086 -0.2113182 0.6554504 -0.4536249 0.5656447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4666 4693 -0.128877 -0.518512 -0.721295 0.3672090 -0.4258658 0.2229559 0.7962955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4666 4926 0.607249 -0.535495 0.137732 0.0174696 0.4277841 -0.0290301 0.9032457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4667 4692 0.335877 0.763659 0.392290 0.4076483 -0.6849369 0.5604930 0.2247929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4667 4927 0.860864 -0.377810 0.199060 0.5589727 0.1246939 0.8033589 0.1631423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4668 4651 -0.732908 0.715654 0.018489 0.2517594 -0.3189344 0.4441994 0.7984892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4668 4691 0.740761 -0.743083 -0.094502 -0.4709291 0.1763064 0.8643194 0.0096816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4668 4928 -0.528427 -0.620077 0.595263 0.3854640 -0.1345418 0.9091129 0.0826422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4669 4129 -0.718134 0.203078 -0.515968 0.2357154 0.4764131 -0.1199693 0.8384964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4670 4689 0.988713 0.244145 0.164942 -0.0223883 -0.1777885 -0.9836933 0.0154098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4670 4930 -0.086690 -0.205486 0.959156 -0.0038615 0.0317896 -0.2839299 0.9583101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4671 4688 0.815359 -0.302071 0.709882 0.4603284 -0.3080727 -0.6081815 0.5685986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4671 4931 -0.708910 -0.418317 0.495412 -0.6116295 -0.5350542 0.0090497 0.5827045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4672 4687 0.864107 0.687740 0.262855 -0.3945697 -0.5247158 0.7234339 0.2136151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4673 4933 0.284080 -1.091943 0.458192 0.2882636 0.5161128 -0.8051881 0.0469439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4674 4645 0.706605 0.406659 -0.389551 -0.0465576 -0.5317423 -0.7951109 0.2878910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4674 4685 -0.756467 -0.320678 0.446821 0.1123347 0.0617576 0.8727923 0.4709570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4674 4934 0.477877 0.500872 0.942287 -0.6291932 0.5986735 0.0537888 0.4927603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4675 4684 -0.458076 -0.575300 0.160979 -0.2861608 -0.2859263 0.8954736 0.1857021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4675 4935 -0.682458 0.589366 0.271930 0.1090887 -0.4432010 -0.8841671 0.0996039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4677 4682 -0.029339 -0.946614 0.396684 -0.0368919 0.3891808 0.0980423 0.9151858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4678 4138 0.146418 -0.798281 -0.425736 0.1587104 -0.1203644 -0.9794911 0.0303406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4678 4681 0.954636 0.445306 -0.192486 -0.2549955 0.7018765 0.2922853 0.5974244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4678 4938 -0.248017 0.830959 0.632395 -0.4411161 0.6163626 0.0628856 0.6492759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4679 4939 -0.741580 0.383142 0.530354 0.0238189 -0.4434221 -0.8784673 0.1763649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4680 4100 -0.563065 0.872231 0.032977 0.6967639 -0.4476481 0.2022070 0.5227271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4681 4718 0.112462 -0.397210 1.024757 -0.4343737 0.3168200 0.5453881 0.6430369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4681 4901 -0.477152 0.812713 0.291665 -0.2676894 0.0355394 -0.3918972 0.8794862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4682 4717 -0.241620 -0.911480 0.323416 0.7332430 -0.2476657 -0.5207190 0.3603722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4682 4902 -0.909950 0.265711 0.485582 -0.6502104 -0.1107472 0.1198873 0.7420165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4683 4103 0.329199 -0.215249 -0.916432 0.2317926 0.1317353 0.9637955 0.0040327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4683 4676 -0.042763 -0.924259 0.493218 -0.0142506 -0.5981281 0.6199342 0.5076626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4683 4903 -0.154382 0.092257 0.953930 -0.5120774 -0.5027271 -0.1613906 0.6774919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4684 4715 -0.132316 0.385875 0.763255 0.6300376 -0.6440621 0.4221735 0.1000311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4684 4904 0.784829 -0.428883 0.193689 -0.1942622 0.1726901 0.6308879 0.7310409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4685 4905 0.439017 -0.308227 0.932351 -0.4833040 -0.0143753 -0.6011682 0.6362448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4686 4106 -0.011822 -0.975680 -0.267366 -0.1375983 -0.3532045 -0.9072060 0.1824571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4686 4673 0.968962 0.176795 0.622392 -0.7121111 -0.0660257 0.6813777 0.1557651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4686 4713 -0.616546 -0.160422 -0.606707 -0.1861405 0.7948001 0.3922492 0.4240107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4687 4712 -0.128576 -0.319680 -0.914462 0.2166330 -0.7701107 -0.0935435 0.5926629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4687 4907 -0.548775 -0.796197 0.292354 -0.5250415 -0.5936731 0.2333449 0.5634126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4688 4711 0.087970 0.887505 -0.386807 -0.1723259 0.3148055 -0.1372341 0.9232378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4688 4908 0.079079 0.140727 0.914066 -0.2881403 -0.4630245 -0.8351026 0.0720215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4689 4710 -1.095229 -0.106515 0.190435 -0.7398272 0.0103639 -0.0681081 0.6692605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4689 4909 0.170944 0.699572 0.793406 -0.4973214 0.0758616 -0.6677685 0.5486361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4690 4669 -0.769050 0.122657 0.173579 0.3688687 -0.5213207 0.2324636 0.7335675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4690 4709 0.950712 -0.085722 -0.222780 -0.2676909 -0.5136999 0.1857845 0.7936864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4690 4910 0.236094 -0.660448 0.661976 -0.2553339 0.4388746 0.2463553 0.8255318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4691 4708 -0.111574 0.523907 -0.739362 -0.2231611 0.6879642 0.4528777 0.5213504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4691 4911 -0.081768 0.868458 0.606521 0.6111799 -0.2405066 -0.7479986 0.0954664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4692 4707 -0.314848 -0.632487 -0.804952 0.4157139 0.2822684 0.5009831 0.7046435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4692 4912 -0.307367 -0.816072 0.472961 0.2282746 0.0669638 0.5239998 0.8178207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4693 4706 -0.943607 -0.697209 0.181948 0.4334950 -0.5910151 0.4213273 0.5341036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4693 4913 0.586825 -0.779720 0.264658 0.3882731 0.0361806 0.7822567 0.4858081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4694 4705 0.073969 -1.059043 0.006797 -0.0477303 -0.5024202 0.2439447 0.8281225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4694 4914 0.061135 -0.024084 0.966540 -0.3228697 -0.1465997 0.8466980 0.3966940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4695 4704 0.483058 -0.364713 -0.727252 -0.1754971 0.7458859 -0.3909007 0.5099526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4695 4915 0.721246 -0.059537 0.521096 0.6033722 -0.0038880 -0.0825222 0.7931689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4696 4703 0.234016 0.923746 0.018455 -0.7571425 -0.2952037 0.4317199 0.3914179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4696 4916 -0.720683 0.201587 0.838502 -0.2579484 0.0111787 0.9584181 0.1215421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4697 4662 0.653281 0.138685 -0.781206 0.6152315 0.2058046 0.7598285 0.0423716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4697 4917 0.273416 0.980240 0.123239 -0.8419585 0.1715624 -0.2213218 0.4611820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4698 4118 0.815567 -0.594704 -0.288098 -0.2448634 -0.7712224 -0.3089859 0.4997856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4698 4918 -0.921707 0.575686 0.293017 -0.0605613 -0.7684323 -0.6359455 0.0376485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4699 4919 -0.407641 -0.589847 0.699818 -0.0538767 -0.2536883 -0.6491889 0.7150477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4700 4080 0.743940 -0.064338 -0.742446 -0.5078169 0.0266718 -0.4781853 0.7160652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4700 4739 0.713722 0.146034 0.580788 0.1419059 0.2769787 0.9315145 0.1882186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4701 4081 -0.695152 0.004098 -0.705386 0.2073254 0.6482615 -0.5263758 0.5096095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4701 4698 -0.566044 0.121060 0.802749 0.0953872 -0.2512344 -0.9444642 0.1891294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4702 4697 0.102785 -0.628266 -0.628359 -0.4309206 0.2785576 0.8175025 0.2615392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4702 4882 -0.865649 -0.346393 -0.048868 0.3884004 0.3741962 -0.7348722 0.4111997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4703 4736 0.984835 -0.423129 0.259577 0.2945099 -0.8516222 0.3299815 0.2812753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4703 4883 -0.433435 -0.868665 0.473157 0.9249179 -0.0437386 0.1759861 0.3341297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4704 4884 -0.520815 -0.367664 0.669445 0.5170015 0.1185382 -0.8393844 0.1187098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4705 4085 -0.606905 0.356195 -0.433390 0.4682874 0.3327708 0.3966179 0.7160061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4705 4734 -0.261862 -0.876515 0.219815 -0.1114672 -0.3743162 0.8921186 0.2271273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4705 4885 0.780521 -0.424556 0.498277 0.3396897 0.5329843 -0.2610457 0.7296532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4706 4733 0.162142 0.343870 1.048650 0.2101680 -0.2516459 0.3904962 0.8602421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4708 4731 0.862295 0.221071 0.447622 0.5217461 -0.2243565 -0.8217232 0.0470758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4709 4730 0.128062 0.022570 -1.026923 0.5934912 0.6461686 0.0922012 0.4708857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4710 4729 -1.039036 -0.150494 -0.355940 -0.2872505 0.6212988 -0.6299432 0.3669420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4710 4890 0.000351 -0.981455 0.415033 0.0007939 -0.3185629 0.8781813 0.3568117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4711 4728 -0.030692 1.092133 0.060751 -0.2244756 0.2593203 -0.9272036 0.1505228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4711 4891 -0.380484 -0.106068 0.906189 -0.1128095 0.2380256 -0.5314605 0.8050886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4712 4892 0.490664 -0.463677 0.545994 0.2600835 0.4719841 0.7354704 0.4106956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4713 4893 0.048671 0.723720 0.368332 0.0702681 0.1763414 0.8255099 0.5315069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4714 4685 0.307220 0.414727 -0.814714 0.2309848 0.3046840 0.8980750 0.2174283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4714 4725 -0.151981 -0.497844 0.897794 0.1100812 -0.2079157 0.8854640 0.4007577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4715 4724 -0.127886 -0.409550 -0.930500 0.4568955 0.4237434 -0.4208407 0.6592277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4716 4683 -1.071839 -0.736325 -0.018523 0.4033175 0.6224618 -0.4670847 0.4813609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4716 4723 0.580595 0.591296 0.170192 -0.5133611 -0.6316502 0.5797720 0.0366439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4716 4896 0.679722 -0.658354 0.062766 0.6898447 -0.5038718 0.1366300 0.5015574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4717 4897 -0.809325 0.152264 0.595499 0.2777559 -0.7787582 -0.0063093 0.5624477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4718 4721 -0.919129 -0.409439 0.261358 0.4119839 0.2087717 0.6429724 0.6109584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4718 4898 -0.175894 0.274521 1.045251 -0.5781057 -0.3394209 0.4050932 0.6216806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4719 4680 0.193073 -0.741602 -0.778380 0.0495867 -0.3692780 0.2982425 0.8787641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4719 4899 0.662973 -0.647720 0.541362 0.6540116 -0.3446415 0.6046646 0.2964318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4721 4861 0.670089 0.780673 0.243518 0.5839103 0.1304002 0.7637063 0.2424815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4722 4757 -0.869146 -0.135555 0.513551 0.8376975 0.4390663 -0.2748989 0.1729574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4723 4756 0.102892 0.207723 -0.872344 -0.0471638 -0.2202331 0.5558492 0.8001904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4723 4863 -0.846621 0.597236 0.059188 -0.5183928 -0.3284652 -0.6514661 0.4460621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4724 4064 -0.132195 -0.542919 -0.958280 -0.4422978 0.2238738 -0.8569739 0.1408866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4724 4864 -0.018621 0.507250 1.135847 -0.6868969 -0.3244107 -0.4129615 0.5023874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4725 4865 0.400550 -0.934710 0.168447 0.9015476 -0.0410314 0.3975952 0.1656693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4726 4866 1.011279 0.461914 0.362214 -0.5469561 -0.3373474 -0.4243299 0.6379498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4727 4712 0.338992 0.939495 0.253906 -0.4141896 -0.7626672 -0.0356728 0.4954929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4727 4752 -0.526876 -0.739162 -0.334412 -0.3037925 0.6720068 0.6371194 0.2240443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4727 4867 -0.724467 0.440856 0.347947 0.2916790 -0.8849854 -0.0210393 0.3623279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4728 4751 -0.090540 -0.835165 -0.328490 -0.0689100 0.7325531 -0.3227668 0.5953477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4729 4869 0.701648 -0.567904 0.669824 0.5179510 -0.2430604 0.8114597 0.1190859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4730 4749 0.532842 -0.559504 0.379847 -0.1432865 -0.1173845 0.9792693 0.0819842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4730 4870 -0.844463 -0.110704 0.466323 0.1769146 -0.6157870 -0.3208476 0.6975417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4731 4071 0.359425 0.261169 -1.018616 -0.0216849 -0.0900127 0.1884031 0.9777176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4731 4871 -0.445141 -0.246482 0.914063 0.3723951 -0.2803993 0.2957516 0.8338040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4732 4707 0.423128 -0.762583 0.349140 0.9164682 -0.0690017 0.0634181 0.3889767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4732 4747 -0.351801 0.831010 -0.431312 0.5206020 -0.4957045 0.4139369 0.5584862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4732 4872 -0.958006 -0.550652 0.025121 0.4647642 0.0489486 -0.5743511 0.6721005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4733 4746 0.865937 0.340692 0.226937 -0.1074818 -0.0023983 0.7798471 0.6166688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4734 4874 -0.856914 -0.676392 0.177156 0.1514765 -0.1359701 -0.8060569 0.5557331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4735 4704 0.524945 0.807399 -0.468325 0.4956634 -0.2726370 -0.5664286 0.5992876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4735 4744 -0.280131 -0.807060 0.457439 0.0150406 -0.1022206 -0.7453330 0.6586375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4735 4875 -0.924087 0.484261 0.095025 -0.5228524 -0.6304094 0.5699101 0.0664224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4736 4743 -0.382035 -0.885775 -0.227543 -0.3711036 0.6500606 0.0299409 0.6624250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4736 4876 0.527958 -0.294516 0.354691 0.5299865 0.7587306 -0.2874600 0.2465948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4737 4077 0.782551 0.258882 -0.636544 -0.3954964 -0.8133664 0.3803976 0.1931719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4737 4742 -0.293221 1.076668 0.343309 -0.0191424 -0.0740951 -0.8619004 0.5012696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4737 4877 -0.602590 -0.394822 0.539846 0.4419170 0.5763228 -0.3513575 0.5908547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4738 4078 -0.069901 1.028480 -0.211928 0.0651232 -0.7162573 0.6214826 0.3106346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4738 4701 0.322773 -0.041098 0.861422 0.1259614 0.2282106 -0.6068911 0.7508241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4738 4741 -0.375257 -0.277977 -0.954490 -0.0045860 0.3593183 -0.1470428 0.9215464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4738 4878 0.021845 -1.171445 0.054615 -0.0758589 0.3459911 -0.9324111 0.0717295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4739 4879 0.881287 0.488877 0.532665 -0.6566984 0.0940150 0.4259858 0.6151783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4740 4779 0.708492 0.828997 -0.120512 -0.0275818 -0.3150954 -0.4293676 0.8459301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4740 4840 0.119218 0.206836 1.035234 0.1758888 0.0392023 -0.1458323 0.9727586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4741 4778 0.265613 -0.178977 -0.712015 -0.4927958 0.2829596 -0.8134420 0.1240897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4742 4777 -0.618100 -0.528719 0.418458 0.3179918 -0.0937373 -0.5448499 0.7702163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4742 4842 0.835086 -0.246567 0.403969 0.7322781 0.4894737 -0.1461029 0.4503756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4743 4843 0.193264 -1.051910 0.287132 0.8185633 0.1442665 0.1590058 0.5327836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4744 4775 0.837844 -0.267707 0.553669 0.2381400 -0.9323767 0.2474039 0.1129353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4745 4734 -0.692181 -0.293877 -0.673297 0.0387859 0.4235398 -0.1386821 0.8943584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4746 4773 0.176386 -0.974913 0.358180 -0.1694517 -0.2651162 0.9153265 0.2513503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4747 4047 0.010947 -0.915573 -0.577158 0.0680298 -0.4711221 0.0339948 0.8787834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4747 4847 -0.223263 0.777827 0.464140 -0.4998113 -0.0838910 -0.3652303 0.7808699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4748 4731 0.157439 -0.620998 0.540638 -0.3042049 0.0112770 -0.7353859 0.6054252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4748 4771 -0.273472 0.546736 -0.794238 0.2184828 0.1223656 -0.2422061 0.9373517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4748 4848 0.263957 0.773605 0.418937 -0.0559323 0.3540952 0.6028671 0.7127688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4749 4770 -0.835904 0.362536 0.348028 -0.3197801 0.4114190 0.4987988 0.6925856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4749 4849 0.475078 -0.145786 0.556229 0.7602595 0.4732133 0.3621372 0.2587109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4750 4729 -0.833240 -0.736687 0.051776 -0.2170603 -0.5155630 0.4167596 0.7165131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4750 4769 0.656877 0.967022 -0.250946 0.6256533 -0.3116081 -0.1841760 0.6910408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4750 4850 -0.337494 0.191761 0.926572 0.3511601 0.0631081 -0.4831001 0.7995738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4751 4768 0.674508 -0.762860 0.129721 -0.1510622 -0.1581944 -0.9149625 0.3391141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4751 4851 -0.469703 -0.396454 0.905588 0.5252372 -0.6454907 0.0031180 0.5544890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4752 4767 0.840241 -0.061305 -0.720631 0.1116207 -0.5645710 -0.7412442 0.3454814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4752 4852 0.201531 1.020765 0.348883 -0.8567426 -0.1937486 -0.1054607 0.4661884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4753 4726 1.165345 -0.145384 -0.078474 0.3747223 0.6250091 0.5557900 0.4000554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4753 4766 -1.032620 0.076972 -0.051802 -0.3227870 -0.7122591 0.0068909 0.6232560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4753 4853 0.049497 0.944579 0.448797 -0.6681687 0.0024270 0.4567094 0.5873340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4754 4765 -0.319204 0.024480 -0.928935 -0.7556332 -0.4604750 0.4588033 0.0805027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4754 4854 -0.721477 0.758221 0.246265 0.8057159 -0.3822523 -0.4524197 0.0046397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4755 4724 1.000785 0.276495 -0.118333 0.0607705 -0.6208453 -0.7529076 0.2097337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4755 4764 -1.088419 -0.518617 0.024551 -0.9048082 -0.2910219 0.0563101 0.3057083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4755 4855 -0.326100 0.763444 0.522643 -0.7079888 -0.4095397 -0.3204940 0.4778207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4756 4056 -0.369770 -0.835881 -0.396211 0.0536590 -0.8964227 -0.2682142 0.3487236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4756 4763 -0.153901 0.342659 -0.779304 -0.4672671 0.3549500 -0.6062450 0.5367858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4756 4856 0.124276 0.978244 0.363252 -0.3016633 0.3505465 -0.7569901 0.4616085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4757 4857 -0.732067 0.725900 0.257934 0.2828219 -0.4276798 0.0655347 0.8560415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4758 4721 -1.009698 0.143179 -0.261373 -0.2662532 -0.8487548 -0.3433814 0.3013531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4758 4761 0.890990 -0.252074 0.250898 -0.0766522 -0.3408118 0.2270286 0.9090819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4758 4858 0.205026 0.920187 0.704387 -0.4097435 -0.3457227 -0.2944595 0.7911256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4759 4720 0.714303 1.029249 0.088349 0.2355314 -0.7699724 -0.5437808 0.2365796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4759 4859 -0.515995 0.788013 -0.001233 0.4970359 0.1183823 -0.8295614 0.2253193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4760 4020 -0.710062 0.648094 -0.124125 -0.2191740 -0.3536096 0.9092793 0.0115828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4760 4799 0.581174 0.684204 -0.448568 0.0457846 0.3373002 -0.7336871 0.5880778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4760 4820 0.787918 -0.692647 0.117036 -0.0146030 -0.2100721 0.7676151 0.6053292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4761 4021 -0.812584 -0.445582 -0.148994 -0.4086176 0.4557485 0.1707089 0.7721292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4761 4798 0.453393 -0.537107 -0.651357 -0.3104565 -0.6321392 -0.5938315 0.3890769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4761 4821 0.861161 0.619891 0.133183 0.0618731 0.8953296 0.4124496 0.1563394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4762 4757 0.133501 0.973305 0.393416 0.3948397 0.7231409 0.4126617 0.3884316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4762 4822 0.558331 -0.353661 0.727491 -0.2960322 -0.0006336 0.7742405 0.5593891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4763 4796 -0.843590 0.678520 -0.510096 0.5297085 -0.2206804 -0.3847601 0.7229583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4763 4823 -0.745327 -0.516524 0.561616 0.3927457 0.2759334 -0.2302572 0.8465183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4765 4794 0.661224 0.277527 0.633467 -0.2108721 0.4007925 -0.7691644 0.4508708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4765 4825 0.435119 -0.920163 0.033431 0.7423484 0.3949428 -0.0947966 0.5328721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4766 4793 0.017734 -0.284315 1.043167 -0.1819867 0.6441489 -0.1922569 0.7176282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4766 4826 0.627964 0.757104 0.416112 -0.2718637 0.0544861 0.1365967 0.9510325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4767 4792 -0.849566 -0.324895 -0.541670 -0.3454466 -0.6132078 0.1709860 0.6894974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4768 4791 -0.211980 0.855778 0.008082 -0.4991234 -0.0506858 -0.3354159 0.7973726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4768 4828 0.909333 0.116173 0.673299 -0.3336432 0.5507981 0.3643118 0.6727411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4769 4790 -0.169001 0.157325 -1.138592 -0.7851592 -0.0532869 0.6128162 0.0717068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4769 4829 -0.356096 0.879464 0.086649 0.5238102 0.0235984 -0.8427732 0.1216521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4770 4789 -0.516231 0.842095 0.548406 -0.8111483 -0.1352239 0.5686429 0.0199530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4770 4830 -0.508676 -0.651911 0.615429 0.7415510 -0.5266548 0.1276652 0.3955231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4771 4788 -0.233577 0.169795 -0.976283 0.7442976 -0.3888494 -0.5308113 0.1142654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4771 4831 -0.145168 1.084225 0.192801 -0.9518756 0.0832462 0.0635016 0.2880459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4772 4747 0.535754 -0.247726 -0.689538 0.8945759 -0.1035629 0.0256118 0.4339962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4772 4832 -0.191064 -0.920078 0.199295 0.0282744 -0.1419493 -0.6478080 0.7479277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4773 4786 -0.704752 0.585852 0.521679 0.1740537 0.6173676 -0.7654464 0.0515207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4774 4745 -0.727632 -0.826795 -0.173692 -0.5412004 -0.1590592 -0.0851078 0.8213154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4774 4785 0.735536 0.592628 -0.067774 0.1182495 0.2870527 -0.8938958 0.3233699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4775 4784 -0.370195 -0.858568 -0.156062 -0.1866741 0.2244487 0.1976308 0.9357979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4775 4835 0.863593 -0.517394 0.166711 -0.0184640 0.2679113 -0.8017710 0.5338969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4776 4743 -0.839743 0.294223 -0.425140 -0.9382134 0.0405381 0.2390923 0.2468750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4776 4783 0.827509 -0.069490 0.453023 -0.1739843 0.5723199 0.1083777 0.7939985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4776 4836 0.114462 1.057330 0.270641 -0.3970692 -0.1818748 -0.8814225 0.1798665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4777 4782 0.240780 -0.359400 0.977907 -0.1230615 -0.7478983 -0.6519744 0.0208192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4777 4837 0.530233 0.945605 0.069578 -0.7873114 0.0108210 -0.0905879 0.6097683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4778 4038 -0.685428 -0.618179 -0.729272 -0.3635761 0.2025577 -0.3251341 0.8491588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4778 4781 -0.677742 0.750215 -0.001503 -0.3943183 -0.3533978 -0.7911430 0.3061303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4779 4839 0.586675 0.375705 0.703854 -0.2258269 -0.2221374 0.8450794 0.4306948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4780 4800 0.896649 0.180608 0.531742 -0.0015747 0.5157061 0.2039051 0.8321463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4781 4801 0.221118 0.260070 0.966489 0.4345528 0.1128022 -0.5576279 0.6982053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4782 4802 -0.641304 0.232836 1.003742 -0.6462567 0.0502960 -0.0197357 0.7612050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4783 4803 -0.092911 0.923009 0.359157 -0.3916686 0.3080809 0.6219214 0.6040659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4784 4804 0.405265 -0.800017 0.211121 0.0306070 0.2989672 0.6150699 0.7289519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4785 4805 0.005842 -0.857460 0.217671 0.3789061 -0.0021724 -0.3756335 0.8457688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4787 4772 0.683052 0.092336 0.751426 -0.5369450 -0.5509969 0.1920475 0.6092702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4787 4807 -0.447293 -0.415623 0.482756 -0.2362109 -0.5298953 0.5573829 0.5939189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4788 4808 -0.745491 -0.387339 0.273489 0.1605650 -0.7417199 0.3403161 0.5552075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4789 4009 0.759716 -0.250988 -0.356496 -0.2995563 -0.5097120 0.1273364 0.7963951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4789 4809 -0.847932 0.390072 0.422255 0.4967306 0.2351908 -0.8041797 0.2263604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4790 4810 0.038719 -0.879607 0.307951 0.1690499 0.8849063 -0.4221954 0.1005682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4791 4811 0.680091 0.186991 0.578179 -0.4860489 0.3904448 -0.1033173 0.7750063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4792 4812 0.425149 -0.615902 0.643241 -0.3434421 0.2060074 -0.7301009 0.5536796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4793 4813 -0.401412 0.536689 0.725714 -0.7806100 -0.1953168 -0.2266881 0.5487367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4794 4814 0.532481 0.338495 0.528603 0.2892779 0.6104504 -0.2137458 0.7056779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4795 4815 0.084292 0.341096 1.072322 0.4443190 -0.0614542 -0.2783676 0.8493029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4796 4816 -0.138276 0.125753 1.247370 0.4456120 -0.4997718 -0.7130255 0.2079730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4797 4762 -0.857904 0.313417 -0.813037 -0.5205774 -0.0308910 0.5219555 0.6749869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4797 4817 0.023080 0.907622 0.140457 -0.1930268 -0.6151493 -0.5254775 0.5551625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4799 4819 0.161040 0.565742 0.772260 -0.1740348 -0.4869773 -0.8523240 0.0781589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4800 4839 0.153150 0.920337 -0.036064 -0.4536718 0.4440923 -0.4923668 0.5954317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4800 5580 0.084603 -0.063346 1.113723 -0.7161717 -0.0917248 -0.2846846 0.6305865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4801 4838 -0.484343 -0.418055 -0.920870 -0.3152682 0.1650842 0.8829752 0.3061176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4801 5581 -0.962468 0.539309 0.365661 0.2234571 -0.6657171 0.2752487 0.6566017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4802 4837 0.254044 -0.526522 -0.768177 0.0049939 -0.6905493 0.7108151 0.1336360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4802 5582 -0.425562 -0.865525 0.544906 -0.1969615 -0.3603784 0.3309413 0.8495949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4803 4836 1.012296 -0.180947 -0.126270 -0.3575226 -0.1869306 0.5133427 0.7574390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4803 5583 -0.068636 -0.144814 1.055220 0.1954963 -0.4194481 -0.2204697 0.8586254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4804 4835 -0.028451 0.034818 0.754158 -0.6633496 0.0906429 0.7375471 0.0881778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4804 5584 -0.976865 -0.440337 -0.062444 0.6314967 -0.5040964 0.0930983 0.5817486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4805 4834 0.526916 0.582000 -0.019957 0.4501040 0.1450706 -0.8186198 0.3259180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4805 5585 0.595349 -0.253835 0.702141 0.2031322 0.3307476 -0.0154958 0.9214680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4806 4786 -0.101159 0.845136 -0.566345 -0.2501995 -0.5733375 0.5897689 0.5107417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4806 4833 -0.150536 -0.569268 -0.872877 0.3271452 0.6831621 -0.2518792 0.6023474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4806 5586 0.270598 -0.713370 0.477442 -0.0722314 0.2690473 -0.4153372 0.8659626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4807 4832 0.218970 -0.963240 -0.515391 -0.4088555 -0.1171249 -0.5629700 0.7086492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4807 5587 -0.043898 -0.242288 0.791204 -0.1943002 -0.0824594 -0.9689412 0.1288443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4808 5588 0.406955 -0.001749 0.963702 0.4171086 -0.1748316 -0.5459798 0.7052378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4809 4830 -0.290342 -0.479412 -0.860404 0.7281826 -0.3279211 -0.3077275 0.5172250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4810 4829 0.928496 -0.598464 0.098390 0.1604121 0.8899358 -0.3641516 0.2228807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4810 5590 -0.479370 -0.647643 0.641992 0.3343880 -0.6511480 0.6554686 0.1858814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4811 4828 0.629103 0.471347 0.102233 -0.1554672 -0.5249389 0.7418178 0.3872668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4811 5591 0.242028 -0.804793 0.781705 0.1548579 -0.0615173 -0.2367909 0.9571649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4812 4827 -0.206026 1.001448 0.088053 0.1211637 -0.1164845 0.2657757 0.9492702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4812 5592 0.408948 -0.253405 0.894096 -0.6044312 0.2868239 -0.1288001 0.7319874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4813 4826 0.538099 0.274762 0.724562 0.6125467 -0.2770502 -0.2605749 0.6929144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4813 5593 0.322877 -1.121574 0.244180 -0.2771793 0.9282041 -0.2163223 0.1217108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4814 4825 0.938064 0.526806 0.028265 -0.5450641 0.4605718 0.5381669 0.4485032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4814 5594 -0.652557 0.977066 0.246351 -0.6305209 -0.6195670 0.1260992 0.4501990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4815 4824 -0.950255 -0.360913 -0.274387 -0.2102052 -0.8124893 -0.3919257 0.3769206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4816 4823 -0.791584 -0.427079 -0.606881 0.7698837 -0.2535633 -0.5705162 0.1322723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4817 4822 -0.427133 -0.738545 0.180739 -0.0971234 0.3649036 -0.7547718 0.5364065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4817 5597 -0.209398 0.610041 0.871606 -0.4033787 0.2546679 0.8772833 0.0529514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4818 4821 0.090734 -0.736601 0.778892 0.3512797 -0.4854305 -0.6687902 0.4400902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4818 5598 -0.052567 0.531821 0.727381 -0.6263457 0.3712610 0.6284887 0.2736025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4819 5599 0.223479 0.263871 1.076350 -0.6788720 0.0356918 0.6951954 0.2335858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4820 4859 -0.285584 0.634049 0.902575 0.4349636 0.7234280 -0.4090633 0.3465916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4821 4858 0.600744 0.775919 0.005157 0.1582021 -0.5844833 -0.7944137 0.0475204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4821 5561 -0.649089 0.590105 0.570343 0.1526929 -0.2821206 -0.4457967 0.8356782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4822 5562 -0.719526 -0.751122 0.035610 -0.2071041 -0.4668717 -0.2522263 0.8219006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4823 4856 0.482617 0.059450 0.927512 -0.3105314 -0.0866999 0.1508122 0.9345101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4823 5563 -0.723112 -0.468591 0.418031 0.8832560 -0.1710774 -0.4345457 0.0419695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4824 4764 -0.432367 -0.389374 -0.794898 -0.8125678 0.2337469 -0.4468030 0.2923408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4824 5564 0.477909 0.410959 0.765895 -0.5817054 0.4569724 -0.5948188 0.3146198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4825 4854 0.046704 -0.983179 0.267096 -0.5762665 0.3230559 0.5845041 0.4710697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4825 5565 -0.070569 0.291450 1.020167 0.1417323 -0.1175799 -0.6962547 0.6937697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4826 4853 0.184080 0.796327 -0.574488 0.2264361 0.0060425 0.6532437 0.7224700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4826 5566 0.709846 0.162767 0.418728 0.2037272 0.5175212 0.4794559 0.6788145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4827 4767 -0.744787 0.132739 -0.675830 0.1800270 0.6148050 0.5052917 0.5781741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4827 5567 0.594223 -0.053019 0.653822 -0.2104023 -0.1902041 -0.8715159 0.4000166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4828 4851 -0.125643 -0.690115 -0.622361 0.5694614 -0.3261362 0.7191929 0.2282772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4828 5568 -0.425345 -0.763138 0.618981 0.8789566 0.0632384 0.1524953 0.4474164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4829 4850 -0.774479 0.182957 0.202711 -0.4893016 -0.6208319 0.6101619 0.0534250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4829 5569 -0.096513 -0.840265 -0.073301 0.1876708 -0.2344205 0.9431492 0.1424648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4830 4849 0.443005 -0.556860 0.845313 0.3440677 0.3809228 0.0003247 0.8582046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4830 5570 0.497730 0.747839 0.274891 0.9140575 -0.0481206 0.4024361 0.0151167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4831 4848 0.064465 -0.607505 -0.815876 0.4731373 -0.4542524 0.5018376 0.5638749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4831 5571 -0.271921 -0.777254 0.380361 0.2219858 0.0743331 -0.6931240 0.6817448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4832 4847 0.365631 0.201237 -0.862615 0.2254537 0.5090246 0.2303089 0.7981368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4832 5572 0.918352 -0.441475 0.274064 -0.2146297 0.4858244 0.4399785 0.7241047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4833 4773 0.528595 0.483626 -0.611309 0.1577045 -0.4930029 -0.0151593 0.8554809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4833 4846 0.842972 -0.374328 0.366024 0.2589760 -0.6867534 0.3085825 0.6050439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4834 4845 -0.726820 -0.478448 -0.879307 -0.4521832 0.7520984 0.4731805 0.0773218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4834 5574 -0.681477 0.793544 0.280583 -0.4679005 -0.0662197 0.8475815 0.2414325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4835 4844 -1.004665 -0.098470 0.170917 0.1896125 0.0043790 -0.2495057 0.9496183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4835 5575 -0.094383 0.504762 0.637455 0.2755193 0.3024630 0.3700616 0.8340621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4836 5576 -0.090001 -0.652053 0.597081 -0.3300511 0.4499758 -0.8216205 0.1163094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4837 4842 -0.352373 0.749143 0.643598 0.5015239 0.5544408 0.6430203 0.1661147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4837 5577 0.386586 -0.341881 0.761112 0.5541181 -0.5089049 0.6219597 0.2171063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4838 4841 0.640526 0.527083 -0.708954 0.0156821 0.3182116 -0.9001454 0.2970417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4838 5578 0.700610 0.116262 0.749356 0.3877583 0.4119909 -0.3256298 0.7575436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4839 5579 -0.060456 -0.850779 0.130464 0.7534662 -0.3584820 -0.4470246 0.3224102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4840 4879 -0.582654 -0.703589 0.478103 -0.4842700 0.1427588 -0.8313497 0.2322934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4840 5540 -0.085697 0.448382 0.889796 -0.5981501 -0.1770173 -0.5796262 0.5243232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4841 4878 -0.769848 0.450198 -0.610914 0.5633467 -0.4308053 -0.5640282 0.4229888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4842 4877 0.928743 0.312267 0.199337 -0.7639931 0.1567001 -0.4986300 0.3783222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4842 5542 0.085466 0.947156 0.177573 -0.6718041 0.1838896 -0.5579041 0.4512283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4843 4876 -0.311744 0.423892 -0.711228 -0.0004409 0.4653184 -0.1063044 0.8787366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4844 4744 0.309723 -0.959837 -0.244238 -0.9149552 0.0668795 -0.0928131 0.3870011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4844 4875 -1.060611 -0.448319 0.146874 0.3147631 0.1098280 0.9406892 0.0629745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4844 5544 -0.381775 0.927440 0.282194 -0.3624630 -0.2099543 -0.6552296 0.6286604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4845 4745 0.210372 -0.615691 -0.699892 -0.5445056 0.2166218 0.7750303 0.2364669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4845 4874 0.943585 -0.178048 0.374095 -0.5765724 -0.4818678 0.0613609 0.6569647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4846 4746 -0.747095 0.007550 -0.542082 -0.0221520 -0.0124202 -0.9969289 0.0740801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4846 4873 0.461329 -0.885477 -0.287917 0.1532607 0.0019300 -0.8345436 0.5291922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4847 4872 0.955742 -0.318493 0.103384 -0.1019902 0.2290781 -0.6148971 0.7476783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4847 5547 -0.176430 -0.256848 0.935679 0.3443923 -0.3977669 -0.8281573 0.1932120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4848 5548 0.330998 0.108727 0.883250 0.1158647 -0.1677747 0.6152715 0.7614906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4849 4870 -0.279860 0.075859 0.852989 -0.4779892 0.2916469 0.3244322 0.7623728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4849 5549 0.485316 0.805066 0.192143 -0.7422077 0.5653507 -0.1012315 0.3453382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4850 5550 -0.652596 0.114903 0.669143 -0.1699302 -0.5288154 0.0902597 0.8266385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4851 4868 -0.682977 0.784115 0.263496 -0.8420994 0.3615187 -0.3511147 0.1920714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4851 5551 0.657140 0.395726 0.391733 0.7151607 0.3810592 0.5132261 0.2827332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4852 4827 0.434498 0.769702 0.439201 -0.5444203 0.3731060 -0.7426149 0.1136733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4852 4867 -0.383238 -0.834180 -0.059750 -0.6356253 -0.1843818 -0.7103521 0.2395490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4852 5552 0.642685 -0.598468 0.557340 0.0640163 -0.1892984 0.9695654 0.1414601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4853 4866 0.618481 -0.239116 -0.723364 0.6681794 -0.1152237 -0.0610198 0.7324864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4853 5553 0.202814 -0.633535 0.797495 -0.4857209 0.0514166 -0.8464283 0.2121102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4854 4865 -0.545076 0.344433 -0.691453 0.4273433 -0.6953301 -0.0877849 0.5711283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4854 5554 -0.795668 -0.098465 0.756835 -0.7566921 0.3619371 0.4507732 0.3053231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4855 4824 -0.352299 -0.861421 -0.513019 0.6416770 -0.0487224 0.7608280 0.0837701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4855 4864 0.452937 0.799578 0.516405 -0.7301518 0.5121136 -0.4070587 0.1972845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4855 5555 0.665746 -0.495820 0.473649 -0.1897209 0.7562351 0.1221113 0.6141687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4857 4822 -0.298191 -0.279384 0.817039 -0.9500457 0.1905552 0.2403010 0.0579415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4857 4862 0.690797 0.178372 -0.777668 -0.3455140 0.3712365 -0.0908425 0.8570596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4857 5557 -0.298596 0.807721 0.180791 -0.9154137 -0.3757584 -0.0020056 0.1442888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4858 4861 -0.712282 -0.406500 0.510484 0.1004352 -0.2470254 0.8092438 0.5234651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4858 5558 0.224690 0.111785 0.972308 0.3410960 -0.4411864 -0.7008497 0.4447671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4860 4720 -0.618098 -0.266032 -0.600576 0.4120060 0.3547940 0.8222519 0.1681488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4860 4899 0.784861 -0.550136 -0.465302 0.5697235 0.0586805 0.8193779 0.0243220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4860 5520 0.588052 0.253734 0.760429 -0.1511341 -0.2791215 0.9460240 0.0654850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4861 4898 0.183087 0.683112 0.623488 0.2339982 -0.5745177 0.5098313 0.5960255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4861 5521 0.439880 -0.705099 0.454522 0.1933764 0.1324642 -0.5474473 0.8033432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4862 4897 0.708730 0.507465 0.291371 0.0642596 0.3692314 0.8037894 0.4620190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4862 5522 -0.592140 0.564467 0.303038 -0.3652695 0.5651054 0.2183718 0.7067870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4863 4856 -1.013049 0.057684 0.070562 0.2267493 0.2503654 0.3983132 0.8527887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4863 4896 1.024188 0.070570 -0.144248 -0.0824942 0.4671405 -0.5872520 0.6558274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4863 5523 -0.067035 -0.946855 0.166730 -0.4419206 -0.5091072 0.6870561 0.2710534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4864 5524 0.728559 -0.636661 0.263321 -0.1807181 0.0073584 -0.7123798 0.6780869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4865 5525 0.499690 0.682000 0.649835 -0.4866156 0.2739486 0.6589665 0.5039054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4866 4893 0.612818 -0.832510 0.161254 -0.7742774 -0.1667832 -0.5552098 0.2538107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4866 5526 0.591809 0.513947 0.487605 0.2395664 0.5667347 -0.3409252 0.7107670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4867 4892 -0.323478 0.374732 -0.886307 0.1698029 -0.8371350 -0.5190679 0.0306686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4867 5527 0.540973 0.728937 0.198046 0.7834957 0.5253260 0.3292246 0.0421683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4868 4728 -0.114500 0.999881 -0.484358 0.3863710 -0.7970761 0.4352901 0.1609646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4868 4891 -0.837940 -0.231880 -0.467279 0.1777308 0.8475952 -0.3145778 0.3886321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4868 5528 0.087276 -0.911479 0.374298 0.8966807 -0.2823111 -0.1806777 0.2891707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4869 4890 0.911777 0.258147 -0.345639 -0.1095340 0.1511473 0.9423713 0.2776565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4869 5529 0.042075 -0.122931 1.017903 -0.5260838 0.1895042 0.6093427 0.5621615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4870 4889 -1.089361 -0.131715 0.495420 -0.4319153 -0.2232118 0.8692421 0.0896879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4870 5530 0.337322 -0.112211 1.019516 -0.3117913 0.5672391 -0.2065621 0.7337289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4871 4848 -0.794309 0.419334 -0.082493 0.1945334 0.3746928 0.8469445 0.3231827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4871 4888 0.807006 -0.295996 0.143278 0.4142114 0.0779111 0.2853314 0.8607815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4871 5531 0.181330 0.651244 0.735961 -0.2768962 -0.7528475 -0.5571255 0.2148496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4872 5532 0.141626 -0.472738 0.660337 0.4397548 -0.4750927 -0.4074528 0.6441155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4873 4733 0.525582 -0.764351 -0.554656 0.1716788 -0.1749257 -0.9453799 0.2149051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4873 5533 -0.564936 0.645832 0.496743 -0.4149397 0.8270157 0.3642255 0.1058763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4875 4884 0.594542 0.552800 -0.730032 0.4939001 0.5266881 -0.0269998 0.6913273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4875 5535 0.576521 -0.761149 0.258319 0.3521226 -0.7220249 0.4100690 0.4318948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4876 4883 0.261888 0.605469 -0.611122 0.4174981 -0.6666885 0.1824669 0.5898539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4876 5536 -0.798774 0.484598 0.109561 0.3967034 -0.4788178 -0.4376001 0.6495122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4877 4882 0.334615 -0.033418 0.998514 0.2728992 -0.4546195 -0.2595364 0.8071481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4877 5537 -0.622599 -0.718649 -0.112602 0.0991047 -0.5882964 -0.2346792 0.7674707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4878 5538 0.150383 0.629720 0.750133 0.1719519 0.1998171 -0.1821807 0.9472676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4879 5539 0.516819 -0.894047 0.164029 0.0993716 0.1177369 0.5437241 0.8250015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4880 4700 -0.470710 -0.858413 -0.016573 -0.3296255 0.8305343 0.3548326 0.2750521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4880 4919 0.568385 -0.414553 0.844267 0.3163389 0.2712908 0.7152956 0.5609664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4880 5500 0.483300 0.880175 -0.032498 -0.5464354 0.0733941 -0.6403585 0.5347548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4881 4701 0.875379 -0.544936 -0.226902 -0.1861899 -0.0259428 0.9550350 0.2292782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4881 4878 -0.262135 0.311037 -1.017554 -0.1852135 -0.1635658 0.5179101 0.8189697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4881 5501 -0.888651 0.290083 0.447856 -0.4926673 -0.6790396 -0.5196579 0.1616779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4882 4917 0.668610 0.421086 0.066428 -0.0873419 0.4778125 -0.1012468 0.8682256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4882 5502 0.269230 -0.564603 0.695421 0.5647044 0.1454764 -0.0420395 0.8112818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4883 4916 -0.959033 -0.119103 -0.198020 -0.5513201 0.1297906 0.5255107 0.6348536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4883 5503 -0.158826 0.869621 0.229710 -0.2007988 -0.0935226 -0.6567020 0.7208855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4885 4874 -0.321861 -0.825106 0.300089 -0.0780206 -0.3767044 0.7386264 0.5535681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4885 5505 -0.293442 0.489720 0.798097 0.1141761 -0.2591012 -0.0700502 0.9565162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4886 4873 -0.617031 -0.575115 -0.529350 0.7755704 0.4439689 0.2538575 0.3700521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4886 5506 0.419897 -0.987525 0.176744 0.2319875 0.5469021 -0.7866234 0.1682363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4887 4707 0.164933 -0.254307 -1.142162 0.5441315 -0.2120147 -0.7346353 0.3453718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4887 4872 0.234498 0.857990 -0.130351 -0.0458090 0.2519545 -0.9648813 0.0585200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4887 4912 -0.349793 -1.000900 0.183668 0.3733637 0.0705296 -0.7800362 0.4971605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4887 5507 -0.044768 0.172715 0.966622 -0.3413427 -0.4737942 -0.7847232 0.2078790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4888 4708 -0.483758 -0.759154 -0.176923 -0.0220817 0.9212619 0.3308122 0.2033523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4888 4911 0.465076 -0.599396 0.646450 0.1197375 -0.3607114 -0.9180643 0.1127306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4888 5508 0.733596 0.811923 0.344781 -0.4354385 0.7089782 -0.0636391 0.5510838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4889 4709 0.909569 0.515473 -0.073500 -0.0094967 0.1516849 -0.5972016 0.7875606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4889 4910 0.162931 -0.031959 0.879803 0.6339936 0.5762660 -0.0995979 0.5060137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4890 4909 -0.487789 -0.785013 -0.186225 -0.3403990 -0.4026085 0.8317978 0.1736302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4890 5510 -0.673522 0.103670 0.775968 0.1945174 -0.6051684 -0.7599083 0.1359174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4891 4908 0.872934 -0.285507 0.017732 0.4268178 -0.1628548 -0.7607878 0.4609846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4892 4907 0.251274 -0.591907 0.818492 -0.5775613 -0.0104704 -0.2726017 0.7694164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4892 5512 -0.882634 0.287377 0.412935 -0.1047261 -0.1825899 0.3779458 0.9015821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4893 4906 0.200712 1.061081 -0.194238 0.5946219 -0.5006212 0.6238072 0.0816561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4893 5513 0.721580 -0.107564 0.704583 -0.6427742 -0.0364775 -0.5844602 0.4938796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4894 4714 -0.516003 0.127457 -0.946035 0.6683012 0.3567206 0.5589304 0.3372250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4894 4865 0.918183 -0.163474 -0.627032 0.3198353 -0.0055578 -0.3569452 0.8776472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4894 5514 0.648882 -0.404052 0.825981 0.3499965 0.6414484 0.5718979 0.3727991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4895 4715 0.380942 0.135662 -0.845371 -0.3042826 -0.7275426 0.2578306 0.5582268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4895 4864 1.046312 0.010378 0.504125 -0.3655093 -0.4021341 -0.6008888 0.5861944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4895 4904 -0.803556 0.134320 -0.416531 -0.1581509 0.4239960 -0.3511399 0.8197051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4895 5515 -0.510063 -0.343620 0.865931 0.0409048 -0.4626632 -0.8052257 0.3686207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4896 4903 -0.003489 0.600411 0.688181 0.7410051 -0.4888344 0.4560863 0.0627509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4897 4902 0.072125 -0.424736 0.750945 -0.2234268 0.1179802 -0.9484676 0.1912337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4897 5517 0.787412 0.487306 0.450493 -0.2657150 0.0283137 0.1099422 0.9573435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4898 4901 0.648769 -0.199830 -0.526935 -0.3198845 -0.5292378 0.7432059 0.2553943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4899 5519 0.419958 -0.342525 0.640722 0.0942665 -0.2026704 -0.5617463 0.7965423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4900 4680 0.125229 0.956237 -0.069726 0.1851016 -0.9566563 0.0881909 0.2068055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4900 4939 1.086367 -0.017714 -0.031361 0.3972871 -0.6768277 0.5947979 0.1740193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4900 5480 -0.157732 -1.076767 0.137064 -0.1217593 0.6290433 -0.7562052 0.1327890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4901 4938 -0.621892 0.510917 -0.718572 0.1742505 0.0264761 0.0145780 0.9842374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4902 4937 0.646244 0.310814 0.836362 0.0478113 -0.5163848 0.7083210 0.4788969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4902 5482 -0.960776 -0.393579 0.710118 0.4829189 0.1076912 -0.8681164 0.0395703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4903 4936 0.115431 -0.503940 -0.990568 0.0341425 -0.0144288 -0.8559296 0.5157621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4904 4935 0.080109 -0.150343 -1.195336 0.4628756 -0.6401172 -0.1128379 0.6027136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4904 5484 -0.499433 -0.805674 0.113464 0.2512906 -0.3778083 0.1807559 0.8726060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4905 4894 -0.251420 -0.290395 0.903015 -0.7552593 0.1430306 -0.6318910 0.0991935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4905 4934 0.686020 0.236815 -0.837671 -0.3833426 0.8188913 0.2136720 0.3698781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4905 5485 0.898775 -0.124976 0.401252 -0.4448179 -0.1541002 -0.7024906 0.5337576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4906 4686 -0.347757 0.937185 -0.207655 0.5454559 0.1580602 -0.7717112 0.2862807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4906 4933 -0.461833 -0.478220 -0.604143 0.0836301 0.4942548 -0.8624334 0.0701911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4906 5486 0.493262 -1.042132 0.393295 -0.4881214 0.0315546 -0.8617784 0.1344611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4907 4932 0.533226 -0.676368 0.015980 0.6934179 0.3264019 -0.2230535 0.6023957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4907 5487 -0.734503 -0.742537 0.171859 0.5688166 -0.5252810 -0.5736198 0.2673721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4908 4931 0.283520 0.713291 -0.506994 -0.8297927 0.3793637 -0.1467993 0.3820698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4908 5488 0.409403 0.703050 0.603574 -0.2710813 0.4577804 0.7397732 0.4119316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4909 5489 0.047471 -0.721096 0.635105 -0.5369963 0.0353926 -0.8128973 0.2226663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4910 4929 -0.590285 0.652628 -0.214769 0.7056393 -0.7083107 -0.0047743 0.0186080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4910 5490 -0.618151 -0.823450 0.148240 0.2592710 -0.0784773 0.6742043 0.6870724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4911 4928 -0.424024 0.743835 -0.063707 0.2574289 -0.1169126 0.9467435 0.1540731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4911 5491 -0.908633 -0.428292 0.486585 0.3503988 -0.2032794 -0.3335219 0.8512704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4912 4927 0.672776 0.230735 0.641046 0.5526440 -0.3228876 -0.6163149 0.4587856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4912 5492 -0.756199 0.110832 0.544020 -0.1226271 0.6160264 0.7770243 0.0413205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4913 4886 -0.152568 1.069800 -0.318554 -0.0627611 0.2340772 -0.8890008 0.3885183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4913 4926 0.273673 -1.055345 0.132590 -0.2068579 -0.3330256 0.9192788 0.0350746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4913 5493 -0.675341 0.099163 0.657192 -0.1386364 0.5182825 -0.8343693 0.1264560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4914 4885 -0.713519 0.662668 -0.263889 0.5084018 -0.0381383 -0.7648129 0.3938708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4914 4925 0.684918 -0.583017 -0.020099 0.1679776 0.3336599 0.7603709 0.5313103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4914 5494 -0.507406 -0.264556 1.069268 -0.0354245 -0.4406392 0.5782350 0.6857306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4915 4884 0.561947 -0.702008 0.252569 0.1284333 0.6735311 0.6147315 0.3898279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4915 4924 -0.477682 0.772825 -0.096426 0.2124875 0.3192365 0.2420937 0.8912507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4915 5495 0.653127 0.548754 0.154169 -0.2441621 0.6367192 0.4594846 0.5690759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4916 5496 0.156427 -0.124102 0.946851 0.4785372 0.2423148 0.7487568 0.3894213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4917 4922 0.190481 0.702428 0.828164 -0.0667429 0.0709253 -0.0427921 0.9943258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4917 5497 -0.107814 -0.629753 0.570412 0.6920314 -0.2862529 -0.1967416 0.6328069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4918 4881 0.295789 -1.036898 -0.233937 0.0374897 -0.5549578 -0.8275102 0.0764416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4918 5498 0.743614 0.155327 0.609776 0.0398197 0.7051114 0.0649991 0.7049875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4919 5499 0.978446 -0.454062 0.372976 -0.6507598 -0.0725009 -0.7557669 0.0084600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4920 4959 0.046511 0.387293 0.737055 0.4493164 0.3186791 -0.7945685 0.2553809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4920 5460 0.371218 -0.809004 0.260958 -0.0132599 0.1613170 0.7196776 0.6751778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4921 4918 0.761466 0.530447 -0.244528 0.6838973 -0.0539466 0.4494800 0.5721380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4921 4958 -0.541420 -0.571205 0.409362 0.1615592 -0.0654389 0.9726526 0.1535033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4921 5461 0.686683 -0.368212 0.777578 0.6905276 0.1590319 0.3814110 0.5936380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4922 4957 -0.091068 0.448039 0.930227 0.4000716 -0.4206832 0.0125375 0.8141322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4922 5462 -0.254603 -0.825816 0.453632 0.2093321 -0.4324200 -0.1492688 0.8642406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4923 4663 -0.839770 -0.633780 -0.154339 -0.1059469 -0.9883989 -0.1017170 0.0386840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4923 4916 0.826020 -0.758507 -0.151942 -0.2162842 0.5046610 0.3186305 0.7726662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4923 4956 -0.639766 0.762799 0.083852 0.4800063 -0.3906233 0.7734349 0.1371346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4923 5463 0.687466 0.818625 0.198488 0.6946325 0.6268082 0.2818944 0.2124446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4924 4955 0.158595 0.817025 -0.846897 0.1202776 -0.3064744 0.9292821 0.1674561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4924 5464 0.892462 0.508940 0.464579 0.2439092 -0.1125587 0.5662532 0.7792279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4925 4954 -0.774685 -0.498138 0.148514 -0.7981040 0.2323306 0.5402022 0.1312783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4926 4953 -0.730826 0.489413 0.608332 -0.7090998 0.4752175 -0.4958231 0.1597038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4927 4952 -0.521440 0.508885 -0.538665 -0.3879671 0.0140944 0.8720678 0.2979609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4927 5467 -0.482191 0.192696 0.810873 -0.0060332 -0.3176412 0.3003733 0.8993573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4928 4951 0.432994 -0.597318 -0.467362 0.2303755 0.0756275 0.9033568 0.3537711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4928 5468 0.847405 0.702541 0.190812 -0.2844972 -0.3707701 -0.3574739 0.8085811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4929 4950 -0.621646 0.718881 0.252772 -0.5316100 0.4221893 -0.4691934 0.5648049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4929 5469 0.678286 0.536384 -0.083439 0.7327422 0.5591747 0.2696558 0.2787441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4930 4909 0.724238 0.613479 0.306637 -0.0308668 -0.4377029 0.7832833 0.4403755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4930 4949 -0.810959 -0.562300 -0.207584 0.5909089 0.2210689 -0.0263099 0.7754115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4930 5470 -0.006312 -0.240688 0.930103 -0.0708356 -0.3080778 0.7390360 0.5948917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4931 4948 -0.299178 0.143730 0.951856 0.5134014 -0.2182628 -0.2557642 0.7895347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4931 5471 -0.275697 -0.933008 0.011447 0.4925220 -0.4369590 0.7172542 0.2281126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4932 4672 0.748090 0.463254 -0.585695 0.4322057 0.2672034 -0.8606251 0.0335423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4932 4947 0.383282 0.415554 0.912805 -0.1869726 0.1689030 0.0132396 0.9676455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4933 4946 0.653679 0.637130 0.371010 0.2648106 -0.1614799 -0.9503404 0.0255464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4934 4945 0.302951 -0.307546 0.644301 0.1413704 -0.1473702 0.9774197 0.0542876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4934 5474 -0.709754 -0.665459 0.036952 -0.0029181 -0.6367597 -0.2668297 0.7234158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4935 5475 0.360404 -0.070561 0.868139 0.2277327 -0.2693731 0.9211530 0.1644782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4936 4676 -0.015744 -0.915842 -0.288452 0.7403006 0.2862969 0.5721707 0.2064215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4936 4943 0.432116 0.223023 -0.734227 -0.5471368 0.0841032 -0.1447749 0.8201269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4936 5476 0.037219 0.964132 0.413439 0.0354339 -0.8521256 -0.5220139 0.0113088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4937 4942 0.425692 -0.962835 0.099647 -0.0149955 -0.0532504 -0.4111691 0.9098788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4938 4941 -0.472924 0.186622 -0.896115 -0.1430135 -0.1657600 0.8161216 0.5348050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4938 5478 -1.077888 0.199676 0.355465 0.6508368 -0.0501537 -0.5457390 0.5254189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4940 4979 0.273204 -0.955912 0.698508 -0.0642917 0.4863080 0.6954949 0.5250314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4940 5440 0.122472 0.634257 0.628271 -0.2865009 0.3056449 -0.7421257 0.5232093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4943 4976 0.241347 0.859008 0.120932 0.0569244 0.5529047 0.7702163 0.3127664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4943 5443 -0.513254 0.192147 0.922409 -0.3011501 -0.2272729 -0.7587230 0.5310321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4944 4935 0.207908 -0.497970 -0.717346 0.3842799 0.2635331 -0.8196241 0.3333100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4944 4975 -0.196708 0.556948 0.932739 0.8292798 0.3197259 -0.1349001 0.4380324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4944 5444 -0.900101 -0.514291 0.119638 -0.5508814 0.3707258 0.7476972 0.0064034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4945 4974 -0.025315 0.065052 0.908313 0.3129036 0.7478126 0.3426504 0.4748246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4945 5445 0.893248 0.660534 0.092680 -0.0368859 -0.9647617 -0.2594857 0.0232687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4946 4646 0.042728 0.015019 -0.989864 0.4295461 0.3993669 0.2326555 0.7758013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4946 4973 -0.864460 -0.557137 0.109327 -0.0439757 0.5459666 0.8366299 0.0060849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4946 5446 -0.095097 0.073193 1.015699 -0.4250862 -0.4368195 0.7202139 0.3313342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4947 5447 -0.839410 -0.552590 0.187893 0.4285784 0.7943128 -0.3830976 0.1965298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4949 4970 -0.714934 -0.596264 0.349324 0.0966451 0.9488262 0.2993585 0.0278022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4949 5449 -0.430209 0.736462 0.419155 -0.1035523 -0.2161669 0.8800907 0.4098648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4950 4969 -0.761824 -0.208209 -0.264090 0.0626216 0.7153445 0.6885510 0.1012834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4950 5450 -0.517189 0.099790 0.673185 0.0127986 0.4947374 -0.7389892 0.4571280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4951 4968 -0.941746 0.094022 -0.256732 0.4428734 0.0628349 0.0083207 0.8943409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4951 5451 -0.143600 -0.764094 0.701454 0.1829595 0.3361329 -0.5056955 0.7731834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4952 5452 -0.177159 -0.170008 1.038929 -0.2288441 0.5678257 0.6365212 0.4690897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4953 5453 0.730040 -0.593495 0.200660 0.1955312 -0.5614161 0.7058372 0.3851926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4954 4965 -0.519683 0.896336 0.469195 -0.4078262 -0.1033550 0.5574978 0.7156758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4955 4964 -0.193681 -0.088872 -0.983444 0.3772591 -0.0395487 -0.5281049 0.7597478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4955 5455 -0.419136 -0.661944 0.189460 -0.1769421 -0.7320304 0.3028324 0.5840509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4956 5456 -0.371746 -0.959589 0.060178 0.1161462 -0.3757302 0.9130081 0.1084122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4957 4962 0.471646 0.876528 0.034560 0.7160413 0.0760470 0.5457185 0.4285942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4957 5457 0.518211 -0.186318 0.854158 -0.0066261 0.4907133 -0.7048377 0.5122112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4958 4961 0.761941 0.684574 0.347286 0.1480929 -0.4787483 0.7696066 0.3956945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4958 5458 -0.336493 0.164955 0.968245 -0.4186180 -0.0834169 0.3179798 0.8465751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4959 4659 0.445315 -0.889802 -0.304542 -0.6785747 0.0437210 0.3620135 0.6376293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4960 4999 0.944624 -0.560128 0.421628 0.5371490 -0.1111868 0.0447756 0.8349273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4960 5420 -0.530218 -0.231852 0.974192 0.5279031 -0.5339399 -0.5418529 0.3776532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4961 4621 -0.760873 0.012267 -0.619568 -0.3029345 0.0117446 -0.0644612 0.9507563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4962 4997 0.612890 -0.668692 0.049230 0.5976177 -0.0218577 0.7064615 0.3785333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4963 4956 0.240815 -1.156515 0.050643 0.3589618 0.5946540 -0.6962371 0.1810718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4963 5423 -0.174478 -0.110151 0.715735 -0.3900911 -0.4123005 0.7943734 0.2163520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4964 4995 0.385691 -0.853421 -0.451145 -0.0655189 0.8135300 -0.4993051 0.2908103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4964 5424 0.477695 -0.351827 0.752335 0.7230430 0.1843028 0.4138275 0.5215248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4965 4994 0.415811 0.187691 1.004915 0.2103467 -0.6915767 -0.5548347 0.4118671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4966 4953 0.469395 0.648153 -0.421460 -0.6434734 -0.6789490 -0.3350586 0.1127209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4966 4993 -0.450892 -0.551790 0.313460 0.4193773 -0.7482620 -0.4317976 0.2788862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4967 4627 -0.850386 -0.269403 -0.497615 0.2906069 0.3835253 0.0085400 0.8765746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4967 4952 0.342290 -0.926216 0.118710 0.1781182 0.4225722 0.7357127 0.4984310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4967 4992 -0.326552 1.001577 -0.356263 -0.6968375 0.5271972 0.1650757 0.4574174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4967 5427 0.736674 0.105336 0.513755 0.1278698 0.9401340 0.2904705 0.1241942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4968 5428 -0.145733 -0.440355 0.916661 -0.0175358 -0.2687036 -0.4379103 0.8577444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4969 4990 0.624687 -0.150718 -0.570803 -0.3507876 0.0940452 0.8916208 0.2703995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4969 5429 0.070595 0.841053 -0.023687 -0.6334989 0.2698205 -0.5156325 0.5099011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4970 4989 0.638100 -0.330039 -0.483300 -0.3506574 -0.3402647 0.0600010 0.8704362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4971 4948 -0.032480 0.840081 0.388012 0.1823596 -0.3970574 0.8965832 0.0723121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4971 5431 -0.046740 -0.543863 0.916578 -0.3260518 -0.4445438 0.8258943 0.1181933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4972 4947 0.666188 -0.362429 -0.290974 -0.5681113 -0.0918715 0.6608539 0.4817482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4972 4987 -0.905080 0.352045 0.404634 -0.2984283 0.2427647 0.5160699 0.7652958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4972 5432 0.136241 -0.184727 0.973001 -0.0721695 0.0932040 0.7643629 0.6339194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4973 4633 -0.071454 -1.132806 -0.293945 -0.0888208 -0.5487729 0.1529459 0.8170476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4973 4986 0.983785 0.062302 -0.385439 0.1721704 0.0864682 -0.4945670 0.8475164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4973 5433 0.221046 0.883240 0.354568 0.6539003 0.3156115 0.6866167 0.0368958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4974 4634 -0.213046 -0.352151 -0.933850 -0.1760379 -0.1753625 -0.2260650 0.9418881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4974 5434 0.281720 0.465337 0.830448 0.0235819 0.5395790 0.6708886 0.5081407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4975 4984 -0.475991 -0.009038 -0.807220 -0.2021362 -0.5065486 0.5033790 0.6701933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4976 5436 0.139976 1.014912 0.284951 -0.8043677 -0.2861502 -0.4023045 0.3305477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4977 4982 0.303210 -0.785017 -0.558449 0.5014916 0.1184325 0.8254372 0.2305068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4977 5437 0.455571 -0.128122 0.945666 0.0513107 0.5702057 -0.2988872 0.7634783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4978 4941 -0.642484 0.915148 0.321226 0.3621622 -0.1280173 -0.8398426 0.3835551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4978 4981 0.670152 -0.538733 -0.258729 0.0992270 0.6595490 -0.6669867 0.3320810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4978 5438 -0.655960 -0.601609 0.572108 -0.2452889 -0.0962712 0.3447495 0.9009512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4979 5439 -0.227794 0.370681 0.936301 0.5952763 -0.0171426 -0.4535504 0.6630568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4980 5019 0.753494 -0.502369 -0.437756 -0.0753058 0.1900608 0.1862495 0.9609979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4981 5401 0.371806 -0.750195 0.690970 0.2189258 -0.5885692 0.3422529 0.6989426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4982 5017 -0.936648 0.368365 0.217151 0.3315807 -0.2237873 0.7928799 0.4596900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4982 5402 0.105152 0.466711 0.754164 0.6239884 0.2234228 0.4753118 0.5786185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4983 4976 -0.632993 0.884265 0.177533 0.6975885 -0.0585662 0.3543015 0.6200086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4983 5016 0.706145 -0.788419 -0.048911 0.2081081 -0.0399390 0.4430559 0.8710898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4983 5403 -0.357039 -0.432908 0.806338 -0.1360707 -0.5291712 -0.8342484 0.0741099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4984 5015 -0.405960 1.137893 -0.145074 -0.5182924 0.0844578 0.7191018 0.4551180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4984 5404 -0.109739 0.124271 1.241454 0.2331005 -0.3202207 0.9182149 0.0020436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4985 4974 0.674554 -0.634383 0.144034 0.4789642 -0.5395947 0.3140946 0.6170701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4985 5014 -0.822728 0.674244 -0.003843 -0.0754417 -0.3632323 0.9268413 0.0577593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4985 5405 -0.535849 -0.678661 0.392358 -0.1423493 -0.0221598 -0.7388334 0.6583091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4986 5013 0.352050 0.470070 -0.293914 -0.5246820 -0.3904314 0.7170848 0.2409595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4986 5406 -0.915041 0.604266 0.167042 -0.0901741 -0.8547524 -0.1877967 0.4753939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4987 5407 -0.686001 -0.513752 0.816039 0.3245429 -0.7807355 -0.2938685 0.4458310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4988 5011 -0.227065 0.923659 -0.046377 -0.3916350 0.3429163 0.6717843 0.5270070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4988 5408 0.960982 -0.151873 0.579227 -0.5137831 0.3373853 0.3466412 0.7085464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4989 5010 0.049811 -0.006160 -1.078057 0.7573135 0.1711924 0.5500303 0.3076297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4989 5409 0.910141 0.628205 0.219355 -0.5573120 0.6750089 -0.4533993 0.1679147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4990 5410 0.183262 -1.050326 0.095498 0.3115459 0.0409632 -0.7152679 0.6242219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4991 4611 -0.637332 0.832121 -0.475652 0.8757563 -0.2928548 0.1056176 0.3689606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4991 4968 -0.752509 -0.549702 -0.088045 0.0932817 -0.6704191 0.7291783 0.1006767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4991 5008 0.869036 0.612432 0.263101 0.8963078 0.0442054 0.4188978 0.1385742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4992 4612 0.418407 0.720612 -0.247307 0.7796459 0.2330598 0.2480186 0.5256636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4992 5007 -0.517765 0.264642 0.719804 0.2750986 0.7961170 -0.4764514 0.2520171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4992 5412 -0.257684 -0.899035 0.273192 0.4545719 0.1576185 -0.8563601 0.1875316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4993 5006 0.619105 0.620748 -0.066188 -0.1793626 0.5344953 0.3340406 0.7553547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4993 5413 -0.561954 0.504932 0.728341 -0.6331911 -0.5191977 0.3910325 0.4202338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4995 5004 0.196653 0.012587 0.870922 0.3067024 -0.7508335 -0.2186660 0.5425567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4995 5415 -0.484633 -0.896801 0.226258 0.2584910 0.0202780 0.6247396 0.7365268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4996 4616 -0.626779 0.725585 -0.241596 -0.3871119 -0.0393984 -0.9203888 0.0384256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4996 4963 0.778941 0.563286 -0.542734 0.5466522 -0.0347527 0.6827727 0.4835132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4996 5003 -0.652942 -0.404929 0.424841 0.0504463 0.1685144 0.2073833 0.9623150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4996 5416 0.751866 -0.628196 0.326333 -0.7383142 0.5556517 -0.3680389 0.1033959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4997 5417 0.723480 -0.514829 0.285881 0.6352023 0.0363397 0.6649496 0.3912026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4998 4961 0.902713 0.419110 0.094540 -0.4092389 -0.2914011 -0.5886879 0.6332894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4998 5418 0.038377 -0.081079 0.986006 0.1309547 0.2880808 -0.7223618 0.6148608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4999 5419 -0.095205 0.717256 0.578516 0.0786873 0.6373083 0.6093635 0.4651049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5000 4580 0.730989 0.071686 -0.853220 0.1085628 -0.4161354 0.8343522 0.3448215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5000 5039 0.577243 -0.218317 0.733954 -0.0522955 -0.4954657 -0.6639705 0.5576039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5000 5380 -0.718523 0.037667 0.542406 0.5412279 -0.7128216 -0.3698071 0.2494001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5001 4998 0.171298 0.267593 -0.772529 -0.4968545 0.0372110 0.2641806 0.8258084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5001 5038 -0.356265 -0.363172 0.817970 -0.1249607 0.0022857 -0.1971513 0.9723739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5001 5381 -0.149390 1.014928 0.387994 -0.5304934 -0.5286102 0.1288113 0.6500428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5002 4997 -0.254970 0.802692 0.630672 0.5044410 -0.5530609 0.6074791 0.2657669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5002 5037 0.351054 -0.805638 -0.592226 0.5702551 0.2950412 -0.5833585 0.4974461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5002 5382 0.451003 -0.344536 0.890790 -0.1290334 0.0235436 0.2013174 0.9707046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5003 5036 -1.032199 0.045754 0.081833 0.0272819 0.1493849 -0.9049735 0.3974453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5004 5035 0.448134 0.592480 -0.572674 -0.9107752 -0.0242718 -0.4058515 0.0719997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5004 5384 0.932384 -0.451895 0.409428 0.4839797 0.6089433 0.1834766 0.6010724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5005 4994 -0.649873 -0.359986 -0.695686 0.2066818 -0.6091340 -0.4571385 0.6142173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5005 5034 0.538615 0.286011 0.643569 -0.2918368 -0.4174646 0.2816795 0.8131490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5005 5385 -0.384114 -0.495814 0.676095 -0.1947927 -0.4682857 -0.5678808 0.6482867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5006 5033 0.424183 0.106180 1.025382 -0.3618685 -0.2480286 0.0951180 0.8935802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5006 5386 -0.510143 0.669656 0.441976 0.1205120 0.0731378 0.9890955 0.0426357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5007 5032 -0.235087 -0.698776 -0.761944 0.2967204 0.1900671 0.3072534 0.8839835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5008 5031 0.717607 -0.387379 0.357729 -0.7720181 0.4124362 0.1509901 0.4594414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5008 5388 0.558592 0.854687 0.183498 -0.8105352 -0.0439138 0.4246719 0.4009465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5009 5030 0.582212 0.279761 0.789314 -0.8165933 0.4192922 0.3966853 0.0032082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5010 5029 -0.441862 -0.878478 0.138096 0.0435796 0.2615323 0.6552648 0.7073398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5012 5027 0.917676 -0.139827 -0.505252 -0.0584467 -0.0131016 -0.0829244 0.9947542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5012 5392 0.214673 -0.885229 0.395142 0.0800610 0.1217603 0.8498581 0.5064641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5013 5026 0.598433 0.124515 -0.871871 0.0263031 -0.0430831 -0.9966948 0.0636504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5013 5393 0.648934 -0.471415 0.431966 0.6240484 -0.2965126 0.6753325 0.2580114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5014 5025 0.809595 -0.390517 -0.323726 0.0772205 0.1743371 -0.2859084 0.9390953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5015 5024 0.810360 -0.386355 0.893760 0.2019602 -0.0388176 0.6104577 0.7648835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5016 4596 0.239747 -0.409236 -0.757840 0.2701397 -0.2684131 -0.6710747 0.6361114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5016 5023 -0.029170 -0.811539 0.391393 -0.4417467 -0.1416363 -0.8237806 0.3258597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5016 5396 -0.251068 0.336374 0.968376 -0.1363383 0.6869438 0.2252741 0.6773268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5017 5022 0.661906 0.400136 -0.351482 0.6801518 -0.5934420 0.4226465 0.0811788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5017 5397 0.761484 -0.781923 0.300996 0.6827896 -0.1779357 0.2049700 0.6783248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5018 4981 0.725314 0.664149 0.285197 -0.3225701 -0.4460398 0.7913468 0.2660212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5018 5021 -0.705564 -0.687088 -0.175172 0.6263637 -0.2888936 -0.5365822 0.4860952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5018 5398 -0.537311 0.173896 0.735741 0.0716767 -0.0349115 -0.9837557 0.1608367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5019 5399 0.805063 0.346871 0.696689 0.1341894 0.1047601 0.7372848 0.6537811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5020 5059 -0.770076 -0.355007 -0.115108 0.8817424 -0.1377080 0.3403962 0.2961372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5020 5360 0.430164 -0.848605 0.119968 0.9821105 0.1026263 -0.1221160 0.1000725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5021 5058 0.412410 0.065639 0.693057 0.0695885 0.7346139 0.5670394 0.3660137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5021 5361 -0.508051 0.614261 0.424217 0.1077641 0.3865804 0.9156721 0.0220695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5022 5057 -0.641462 -0.626134 0.212676 0.4710165 0.1609106 -0.0372860 0.8665224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5022 5362 0.587020 -0.766240 0.528210 -0.0373515 0.1982870 -0.9787474 0.0366140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5023 5056 0.771995 0.480758 -0.279555 -0.1174835 0.1288988 0.9734329 0.1483613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5023 5363 0.515957 -0.649414 0.482064 0.2447093 0.2407724 0.9024805 0.2601440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5024 5055 0.024588 -0.559775 0.895323 0.2362537 0.7226882 0.4937900 0.4219922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5024 5364 -0.076531 0.815900 0.384278 0.2137641 -0.4254238 -0.0949480 0.8742450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5025 5054 1.045672 0.164199 -0.037338 0.1973450 0.4038035 -0.7420264 0.4973876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5026 5053 -0.594545 0.093476 -0.780310 0.0944775 0.3255196 -0.9301376 0.1412619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5026 5366 -0.610810 0.655094 0.445450 0.0453773 -0.8230864 -0.5471659 0.1451866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5027 4567 -0.393867 1.028603 -0.232159 -0.6088113 0.4686628 -0.6314657 0.1046666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5027 5052 0.814563 -0.060039 -0.531049 0.8082821 -0.1538143 -0.4061103 0.3976124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5028 5011 -0.901505 0.239922 0.426803 0.3392947 0.7290321 -0.0014429 0.5944655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5028 5051 0.651185 -0.328362 -0.464396 0.6908417 0.2612708 -0.2978239 0.6047944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5028 5368 -0.264892 -1.019113 0.174146 0.0544199 -0.8517487 0.5199211 0.0352809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5029 5050 -0.779514 0.492935 -0.326591 0.2831914 0.7166451 -0.4012712 0.4951806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5029 5369 -0.556265 -0.700422 0.667522 0.0040108 0.5388155 -0.7999787 0.2639998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5030 5049 -0.443465 -0.416381 -0.795605 -0.5777744 -0.1460278 -0.0431244 0.8018684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5030 5370 -0.787114 0.397613 0.202107 0.2537442 0.2044868 -0.8772300 0.3525145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5031 4571 0.523140 0.694879 -0.745232 0.1102900 -0.7212805 0.4052488 0.5507848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5031 5048 0.410731 -0.766961 -0.590493 0.2940982 0.5084530 -0.6015623 0.5413913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5031 5371 -0.293222 -0.565178 0.824577 0.8899423 0.0521078 -0.3745005 0.2550232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5032 5047 -0.508569 -0.810947 -0.262991 -0.2031892 0.2253289 0.6061588 0.7351956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5032 5372 -0.724335 -0.035193 0.904161 0.0498163 0.3180518 -0.9401635 0.1115976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5033 5046 0.503533 -0.589945 0.386411 -0.0163622 -0.3565979 0.2189027 0.9081034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5033 5373 -0.208183 0.365279 0.775591 0.4876361 0.6155167 0.5871897 0.1963629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5034 5045 0.860119 -0.449782 -0.024042 -0.4019820 -0.5150800 0.6821811 0.3282256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5034 5374 -0.073891 -0.773042 0.622317 -0.0125667 -0.5162862 -0.2813905 0.8087707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5035 5044 -0.009495 -0.690904 0.617615 0.2620851 0.8100614 0.1404861 0.5053470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5036 5043 0.771984 -0.350113 0.133014 0.0067751 -0.4042168 0.1330363 0.9049112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5036 5376 0.264125 0.752217 0.777149 0.1348904 0.3025401 0.7982161 0.5031155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5037 4577 0.476410 -0.757649 -0.303390 0.1521469 -0.2564538 0.5602691 0.7727751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5037 5042 0.971190 0.471837 0.436434 0.1235507 -0.3593134 -0.5752412 0.7243802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5038 5378 -0.472868 0.640944 0.428999 -0.1290447 -0.2218962 0.8968973 0.3601176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5039 5379 0.760391 0.021381 0.635723 0.1873909 -0.0334634 -0.1710488 0.9666991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5040 5079 -0.808162 0.627456 -0.370007 0.4255923 -0.0477279 0.0053975 0.9036393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5040 5340 -0.636716 -0.411884 0.237378 0.1792825 -0.0927161 0.0614905 0.9774868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5041 5038 -0.854546 0.549011 0.543044 0.6429579 0.0018596 0.4532266 0.6174037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5041 5078 0.721545 -0.491089 -0.709943 0.3707567 -0.6004535 -0.1268571 0.6970669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5041 5341 -0.257244 -0.721192 0.126038 0.4898204 0.1990161 -0.7568944 0.3841606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5042 5077 -0.202840 1.077858 -0.186797 0.4151623 -0.1958967 0.6483211 0.6074081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5042 5342 -0.589925 -0.010687 0.827427 0.0257740 0.3447218 0.5765044 0.7403684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5043 4543 -0.728649 -0.523186 -0.289805 0.5876128 0.3444318 0.7050520 0.1974324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5043 5076 0.621305 -0.812801 -0.127469 -0.1244967 0.1079837 -0.9783625 0.1250877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5043 5343 0.904730 0.623593 0.212275 -0.3977459 -0.6324047 -0.5081268 0.4285670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5044 5075 -0.928244 -0.199389 -0.347184 0.1715750 0.1232552 -0.8680246 0.4493367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5044 5344 -0.247397 0.697816 0.499453 0.1474244 0.2324503 -0.8009453 0.5317137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5045 5074 -0.486907 -0.050844 -0.734933 0.6213608 0.0608350 0.1716287 0.7620718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5046 5346 0.687567 0.232017 0.585257 -0.3800221 0.1430199 0.8545684 0.3237921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5047 5347 -0.541498 0.607335 0.620537 0.1357026 -0.5816388 -0.4446459 0.6675112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5048 5071 0.594392 0.475140 0.762575 0.2032835 0.0226550 -0.4256346 0.8814748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5048 5348 -0.170542 -0.670769 0.664026 -0.1786392 -0.5528888 0.5838083 0.5670714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5049 5070 -0.824121 0.627515 -0.504892 -0.3693048 -0.7635053 -0.0421883 0.5281039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5050 5069 0.642206 -0.523970 -0.747452 -0.0693453 -0.8278808 0.5562545 0.0196361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5050 5350 -0.306607 -0.835661 0.028221 0.9793779 0.0013606 -0.1977752 0.0412564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5051 5068 0.886718 0.267989 0.229015 0.2765145 -0.0166902 -0.8765602 0.3935776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5051 5351 -0.377880 0.070909 0.840105 -0.5680199 -0.3665652 0.5188138 0.5232739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5052 5067 0.601610 -0.431638 -0.668409 0.5231483 0.4244774 0.5421103 0.5022462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5052 5352 0.712520 0.735073 0.133636 -0.1855202 0.1476971 -0.0456937 0.9704019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5053 5066 0.727369 0.278059 -0.517236 0.3280583 0.0618959 -0.1343002 0.9330113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5054 5065 -0.573464 0.908054 0.065606 0.3693797 0.2168537 -0.8281121 0.3616123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5055 5064 -0.860167 0.663539 -0.334308 -0.0965779 -0.7917096 -0.3620643 0.4824708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5055 5355 0.498808 0.929072 0.283135 -0.0869780 0.4587899 -0.2168500 0.8572763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5056 5063 -0.479508 -0.733085 -0.336965 -0.6454201 0.0567126 0.4374060 0.6236125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5056 5356 -0.922962 0.479767 0.066335 -0.9109462 -0.3522564 0.1988703 0.0808894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5057 5062 -0.812848 -0.354318 0.361068 -0.0628450 -0.0421665 0.1747905 0.9816928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5058 5061 -0.806067 0.699091 0.310358 -0.3126190 0.1436859 -0.6771733 0.6504307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5058 5358 0.478190 0.785955 0.132954 -0.3870274 0.2061682 0.0028958 0.8987191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5059 4559 -0.403686 -0.589534 -0.765481 -0.2479137 0.3987112 0.1309546 0.8731661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5059 5359 0.632871 0.347026 0.842741 -0.3179827 0.2811330 -0.6707524 0.6082290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5060 5099 0.053994 -0.215188 -0.871812 0.0250542 0.2250605 0.7202200 0.6557463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5060 5320 0.700898 -0.410412 0.264254 0.5981881 0.0903821 0.7954559 0.0353833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5061 5098 -0.327282 -1.016139 -0.271055 -0.3203083 -0.2762506 0.0780135 0.9027746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5061 5321 -0.821508 0.169096 0.522705 0.2342966 -0.9063445 -0.1052669 0.3355051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5062 5097 -0.931432 -0.230117 0.678220 0.0448453 0.5181151 -0.2876451 0.8042425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5062 5322 0.521009 -0.139994 0.963102 0.5081620 0.5738503 0.0730696 0.6380658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5063 5096 -0.199235 0.671131 -0.564460 0.3021309 -0.2062176 -0.7548695 0.5443926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5064 5095 -0.160905 0.024460 0.842383 0.4693751 -0.6714412 -0.3626048 0.4442652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5064 5324 -0.263651 0.852892 -0.102198 -0.1562601 0.1759424 0.4337144 0.8697809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5065 5325 0.320791 -0.222858 0.869732 -0.2657558 -0.0284876 -0.0418208 0.9627114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5066 4526 -0.535871 0.461254 -0.681524 0.0254444 0.6231964 0.0234712 0.7812989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5066 5093 0.676532 0.093240 -0.794989 0.5367197 0.5132306 0.5996863 0.2981654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5066 5326 0.702383 -0.298907 0.602407 0.8591676 0.2696289 0.3523894 0.2548588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5067 5092 -0.489825 -0.460034 0.789764 0.5157607 0.0386087 0.8528755 0.0714394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5067 5327 0.725502 -0.419802 0.668934 0.1055726 0.5455222 -0.3628721 0.7480533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5068 5091 -0.983803 0.578710 -0.069323 -0.1148772 -0.1801216 -0.3499831 0.9120698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5068 5328 -0.200016 0.144828 1.139037 0.3564789 -0.1821506 -0.8854204 0.2361667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5069 4529 -0.167412 0.486236 -0.766386 -0.0098887 0.8513869 -0.4641747 0.2440992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5069 5090 -0.498880 0.560695 0.472858 0.2256556 -0.5421223 0.7547297 0.2925168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5069 5329 0.199068 -0.431455 0.772618 0.1362959 0.6001670 0.0491147 0.7866453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5070 5089 -0.031091 0.029877 0.954458 0.8694009 -0.2708000 0.0014102 0.4132886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5070 5330 0.579463 -0.869008 0.034123 0.9904910 0.0604198 -0.0585838 0.1088348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5071 5331 0.013894 -0.269001 0.817659 -0.1573165 0.1683059 0.8798657 0.4156452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5072 5047 -0.030671 0.931922 0.319416 -0.1101653 0.1816281 0.7638248 0.6094642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5072 5087 -0.110281 -0.671161 -0.490424 0.2870590 -0.2257316 0.8677639 0.3370879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5072 5332 -0.394828 -0.453282 0.669432 -0.0222492 0.6828931 -0.5304586 0.5017726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5073 5046 0.336913 0.414320 -0.937070 -0.4932953 -0.3010962 -0.2919596 0.7620764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5073 5086 -0.472969 -0.337576 0.827499 0.3494703 0.3573192 0.8553088 0.1365296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5073 5333 0.487103 0.770740 0.560559 -0.4953364 -0.2106403 0.0330972 0.8421266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5074 5085 -0.768267 -0.564964 -0.279527 -0.0033790 -0.7627916 -0.6234957 0.1714371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5074 5334 -0.623583 0.618524 0.213744 0.0438799 -0.8921840 -0.1727668 0.4150107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5075 4535 0.673447 0.712245 -0.372129 0.0679050 -0.7594895 -0.0384972 0.6458193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5075 5084 0.860472 -0.788013 0.017179 -0.1054610 -0.3733050 -0.6469644 0.6564743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5076 5083 -0.157591 0.982441 0.154159 0.2092591 -0.4900257 0.0081818 0.8461787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5076 5336 -0.968294 -0.329590 0.363341 -0.5955875 -0.2605243 0.0099117 0.7598055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5077 5082 0.652657 -0.152400 -0.938729 -0.7499415 0.3880623 -0.4828957 0.2319636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5077 5337 0.597558 0.841267 0.130174 -0.0598999 -0.1921492 -0.5812623 0.7884319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5078 5081 0.026157 -0.783320 -0.730141 0.4834982 0.2615916 0.6315777 0.5467256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5078 5338 0.540669 -0.480324 0.600481 0.1207766 0.8493853 -0.2956546 0.4201738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5079 5339 -0.764937 0.019965 0.605550 -0.5196407 -0.7760744 0.3571158 0.0122676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5080 5119 0.104367 0.926410 0.246775 0.2421036 -0.7485390 -0.5720904 0.2319219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5080 5300 -0.631418 0.126715 0.760349 0.0807470 0.4528968 -0.3784525 0.8032049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5081 5118 -0.805708 -0.167143 -0.063704 0.4103798 0.3418199 0.5289013 0.6595536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5081 5301 -0.230454 0.214750 0.869851 -0.3033274 0.3961033 0.4065660 0.7653749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5082 5117 -0.231958 0.416014 0.780364 0.5175912 -0.3362262 0.4867894 0.6181322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5082 5302 -0.504872 -0.784606 0.226079 0.6386194 0.1198226 0.4898541 0.5812493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5083 5116 -0.311250 1.151983 0.029061 0.0561270 0.2502919 -0.9652014 0.0508916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5083 5303 -0.181318 -0.022316 1.009693 0.4626170 0.4248231 -0.0589576 0.7759090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5084 5115 0.301489 0.358372 -0.756928 -0.3145902 0.8070563 0.0943609 0.4907028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5084 5304 0.800563 -0.534293 0.086890 0.4785841 0.7604225 0.3555038 0.2575500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5085 5305 0.708305 0.376197 0.636635 -0.2643882 0.2727968 -0.8493157 0.3665291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5086 5113 0.290471 0.747408 0.279224 -0.5228348 0.2160937 -0.5189839 0.6407831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5086 5306 0.375455 0.052622 1.001328 0.7590923 0.2072324 0.3774217 0.4882483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5087 5112 -0.695629 0.651738 0.158420 0.5389851 0.4047603 0.3878767 0.6286619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5087 5307 0.588010 0.551948 0.568529 -0.3479896 -0.7541581 -0.4183675 0.3675831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5088 4508 -0.407822 0.914404 -0.249336 0.7414301 0.5002894 0.3770269 0.2405051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5088 5308 0.490770 -0.821226 0.326287 0.1454686 0.9668012 -0.1746076 0.1168182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5089 5110 0.145774 0.713407 -0.801659 0.0851506 0.1016377 0.7049112 0.6967922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5089 5309 0.922319 0.444877 0.394198 0.4160582 0.2652486 0.4417750 0.7492487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5090 5109 0.858173 -0.163861 -0.405579 0.0580534 0.8182615 -0.2092506 0.5322518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5090 5310 0.347511 -0.676471 0.626329 -0.4806019 0.2788581 -0.5241690 0.6453734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5091 5108 -1.009643 -0.149151 0.350505 0.4058239 -0.0142498 0.9095614 0.0883292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5091 5311 0.156709 -0.478599 0.867532 0.0211632 -0.1636453 0.3181745 0.9335616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5092 5107 0.649640 0.440086 -0.277214 0.1879748 0.3724663 -0.1556490 0.8953813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5092 5312 0.086825 0.205557 1.127711 -0.2921280 0.4270403 0.4922500 0.6999912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5093 5106 -0.273751 -0.563331 0.723512 -0.9263749 0.1560651 0.3405538 0.0386827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5094 5065 -0.200088 -0.694687 0.622519 -0.3214158 0.2063667 0.9237934 0.0266518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5094 5105 0.256350 0.846839 -0.382234 0.7707308 -0.2129933 -0.6002022 0.0191106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5094 5314 -0.720220 0.685945 0.164850 -0.4389501 -0.3818601 -0.3793259 0.7194564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5095 5104 0.207478 0.896405 -0.282998 -0.1459650 0.1190464 0.7798928 0.5968998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5096 5103 -0.487093 -0.785340 -0.157281 -0.0608329 0.6145606 0.7669410 0.1744021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5096 5316 -0.243705 0.033732 0.928804 0.1712047 -0.4446049 0.4046976 0.7805352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5097 5317 -0.543215 0.000419 0.780020 0.4575823 0.2336139 0.6464575 0.5640352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5098 4518 0.148065 0.143260 -0.987937 -0.1240541 -0.2629825 0.2178410 0.9316631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5099 5319 -0.612510 -0.637630 0.330488 0.6344740 -0.1398011 0.6649688 0.3683951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5100 4480 0.905176 -0.387195 -0.402860 -0.2871077 -0.1015205 -0.0094634 0.9524564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5100 5139 0.579606 0.739361 0.432000 -0.4317144 0.4201683 0.2989496 0.7400746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5100 5280 -0.882518 0.349092 0.438361 -0.4985060 -0.8326121 0.0127499 0.2410109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5101 5138 0.792565 -0.412450 0.138105 0.6520418 -0.2133259 -0.7118833 0.1501852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5101 5281 -0.259874 0.053075 0.952988 0.6822962 -0.0008861 0.2290277 0.6942747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5102 5097 0.091596 0.854085 0.542585 0.1603390 0.4536124 0.5063290 0.7156523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5102 5137 -0.063769 -0.961411 -0.400340 0.3735070 0.3614108 0.6288874 0.5782521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5102 5282 0.729027 -0.059440 0.560850 -0.2282502 0.2970437 0.2014864 0.9050249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5103 5136 0.604496 0.116885 -0.728959 0.0304471 -0.1266839 -0.9819933 0.1367967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5104 5135 0.792219 -0.559231 -0.050186 0.5790547 -0.1583520 0.7990016 0.0348814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5104 5284 0.535001 0.625489 0.536272 -0.2394540 -0.2995447 0.8430569 0.3770807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5105 5134 0.219821 -1.003385 -0.200750 0.0103705 -0.4142412 0.4942781 0.7641897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5106 5133 -0.820512 0.698764 -0.368709 0.2997451 -0.7963067 -0.2111370 0.4811130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5106 5286 -0.595203 -0.578039 -0.014235 0.5071833 -0.6921803 0.5020078 0.1078872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5107 5132 0.654359 0.601812 -0.104199 0.6163797 -0.6350217 -0.3329403 0.3255370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5108 5131 0.739005 0.374728 -0.643860 -0.4192220 0.6431934 -0.2592710 0.5859468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5108 5288 0.367465 0.213979 0.746021 -0.4859579 -0.4823584 -0.7257548 0.0667479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5109 5130 -0.206166 0.286824 1.001839 0.5052468 -0.0974805 -0.5658527 0.6442313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5110 5129 0.630659 -0.378346 -0.492639 0.4882009 0.5217479 0.0349918 0.6987236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5110 5290 0.257281 -0.605447 0.638274 0.0509268 -0.2962496 -0.8472141 0.4380308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5111 5128 -0.687602 0.888082 0.121156 -0.2341726 -0.0126185 -0.7740981 0.5880273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5112 5127 0.200500 0.214860 -0.922357 0.2946241 0.4810831 0.7218826 0.4008007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5112 5292 0.714424 0.669246 0.350676 -0.2465709 0.2359948 0.8006226 0.4924558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5113 4493 -0.395126 0.664319 -0.478184 -0.2443691 0.3286965 0.1781440 0.8947106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5113 5126 -0.629382 0.049531 0.835760 0.6464781 0.0787605 0.0730003 0.7553369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5113 5293 0.374168 -0.943298 0.541595 0.2514526 0.1479913 -0.0967696 0.9515807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5114 5085 0.165784 0.422402 0.766739 0.3692747 0.2681757 -0.3773223 0.8058200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5114 5125 -0.319330 -0.536555 -1.100926 0.2445949 0.6727702 -0.4671063 0.5190042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5114 5294 0.784888 -0.698998 0.079808 0.2853232 0.6088734 -0.0914230 0.7345106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5115 5124 0.341670 0.381549 0.896438 0.4467895 0.6072476 -0.4655863 0.4635287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5116 5123 0.206854 -1.091939 -0.294356 0.6077559 0.2440151 0.1500219 0.7406637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5116 5296 0.055434 -0.323956 0.779649 0.1626844 0.5785515 -0.5822416 0.5475461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5117 4497 -0.053008 -0.398421 -0.941582 0.2402000 0.5636497 0.3889835 0.6879643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5117 5122 0.936148 0.442031 -0.181873 0.2358898 0.1118473 -0.7744544 0.5762521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5117 5297 0.069438 0.163756 0.986472 0.0035242 0.0972330 0.9913396 0.0881996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5118 5121 -0.545300 0.382844 -0.671268 -0.6441305 0.3993754 0.1985091 0.6214413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5118 5298 0.232277 0.919381 0.074441 -0.5113392 -0.3959227 -0.2326389 0.7263997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5119 4499 -0.500471 -0.849141 -0.079657 -0.3991667 0.7594632 0.1696963 0.4848553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5120 5260 -0.473541 -0.849127 0.558392 0.5036700 -0.6449299 -0.3181985 0.4786770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5121 4461 0.293792 0.191954 -0.852290 -0.1191632 -0.6551697 0.4174343 0.6183053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5121 5158 0.166128 0.869399 0.259718 0.3470919 -0.6217374 -0.5168231 0.4752512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5122 5157 -0.304270 0.598965 -0.796536 0.7415389 0.4207705 -0.4746953 0.2184871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5122 5262 -0.893177 -0.053891 0.527084 -0.1297396 -0.3178382 0.9310020 0.1240235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5123 5156 -0.048626 -0.191421 0.686834 -0.0746871 0.0638121 -0.1190251 0.9880197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5123 5263 -0.389794 1.004604 0.567575 -0.1581561 0.2866736 0.5219819 0.7876166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5124 5264 -0.324089 -0.287381 0.854152 0.6315905 -0.3276053 0.1605688 0.6840949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5125 5265 -0.474176 0.162568 0.769956 0.6265228 0.1223758 -0.7648570 0.0865282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5126 5153 -0.834676 0.487571 -0.111578 0.2085173 -0.1348150 0.9529949 0.1736265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5126 5266 0.337744 0.411453 0.806431 -0.7434780 0.3926159 0.0070500 0.5413350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5127 5152 -0.140421 -0.748647 0.151546 -0.0504853 -0.1606744 0.8877518 0.4284061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5128 5151 -0.505636 -0.852413 0.278301 0.7203038 -0.4168236 0.4752110 0.2856483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5129 4469 0.988916 -0.184706 -0.586737 0.1195837 -0.8018209 0.1797672 0.5571954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5129 5150 0.523501 -0.306960 0.806652 -0.1770384 -0.6229130 0.2171948 0.7303857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5130 4470 -0.249201 -0.031107 -0.848877 0.3259456 -0.3783178 -0.5828898 0.6409950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5130 5149 -0.775987 0.614223 0.264496 -0.3362814 0.0255250 -0.9385392 0.0735354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5131 5148 0.068467 0.372980 0.923351 0.2011887 0.7944416 -0.4083947 0.4019944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5131 5271 -0.906590 -0.576660 0.487439 0.8252020 -0.3408930 -0.2299454 0.3872450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5132 5147 -0.686738 -0.262338 -0.434240 0.3914754 0.0436304 -0.8215477 0.4121927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5132 5272 -0.499669 0.954452 0.101151 0.0190990 0.4865899 0.7789528 0.3950924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5133 5146 -0.380407 0.386988 0.822138 -0.1394602 0.0890217 0.5994896 0.7830953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5133 5273 0.783031 -0.318083 0.577253 0.2538047 0.3483893 0.2571190 0.8649265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5134 4474 -0.130430 -0.009332 -1.072214 -0.4040592 -0.3697640 0.0940604 0.8313624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5134 5145 -0.691498 -0.680354 0.307367 -0.1397501 0.3845932 -0.9115554 0.0403083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5134 5274 0.199278 -0.006012 0.783927 -0.5878272 -0.0291975 -0.5306486 0.6099334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5135 5275 0.252717 -0.952162 0.044882 0.3297429 -0.5196801 0.7669457 0.1816495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5136 5143 -0.583923 -0.180214 -0.782340 0.7072856 0.0020413 0.6688969 0.2287354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5136 5276 -0.038275 -0.886182 0.404189 -0.3260055 -0.1771567 0.9126538 0.1714613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5137 5142 -0.929828 -0.222301 -0.305025 -0.0363010 -0.2236780 0.9518171 0.2066267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5137 5277 -0.343371 0.288726 0.812540 0.0885431 -0.5697959 0.2894839 0.7639973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5140 4440 0.419516 -0.542011 -0.558930 0.2425426 0.0273023 0.0950085 0.9650912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5140 5179 0.416819 0.847670 -0.442909 -0.1766324 0.1375905 -0.2302149 0.9470327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5140 5240 -0.350264 0.412036 0.570493 0.1216804 -0.8561424 -0.3356701 0.3735500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5141 5138 0.337707 -1.010252 -0.022849 0.4206695 0.3482892 -0.4580171 0.7013930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5141 5178 -0.116338 1.062785 -0.109965 -0.1118475 -0.3820677 -0.8043723 0.4410210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5141 5241 -0.010185 0.269532 0.872545 -0.5389258 0.4495002 0.0267855 0.7118926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5142 5177 0.713772 0.655635 -0.112129 0.5202182 -0.5099287 0.6044501 0.3224682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5142 5242 0.476778 -0.519045 0.856177 -0.4579272 0.5633935 -0.6873304 0.0216190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5143 5176 -1.015614 0.090902 -0.276699 -0.8302061 -0.0918411 -0.0646105 0.5460297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5143 5243 0.280569 0.951001 0.028529 0.4281983 0.7396674 0.4675656 0.2256562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5144 4444 -0.855396 0.488304 -0.463094 0.0458431 0.0225875 0.2693030 0.9616986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5144 5135 -0.089032 -0.816415 -0.688951 -0.3239640 0.2427570 0.2204494 0.8874223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5145 5174 0.950598 0.396397 0.313860 -0.2539754 -0.1145551 0.7644079 0.5814242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5146 5173 0.207700 0.171073 1.004792 0.6252599 0.5497340 -0.2456271 0.4964976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5146 5246 -0.386415 -0.910557 0.252607 -0.1102761 -0.1903315 -0.2275625 0.9485929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5147 4447 0.453861 0.849923 0.076340 -0.0032186 0.9142081 -0.3068087 0.2647293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5147 5247 -0.682235 -0.994338 0.067570 -0.1119916 -0.7002018 -0.2976327 0.6392106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5148 5248 0.305775 -0.892068 0.096473 -0.0228690 -0.5288246 0.6943317 0.4875706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5149 5170 0.501419 -0.717420 -0.191436 -0.1841162 0.3685624 -0.2741378 0.8689715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5150 5169 0.655739 -0.975329 -0.168560 -0.0060312 0.1980901 0.9761588 0.0885318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5151 5251 0.221883 -0.247078 1.042472 0.4169228 0.0639354 0.8406242 0.3397627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5152 5167 -0.753317 0.626501 0.421332 0.3962613 0.0194821 0.3933176 0.8293966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5152 5252 -0.019851 -0.490261 0.870711 -0.1923451 0.1386923 0.0388261 0.9707010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5153 5253 0.103231 -0.667554 0.782298 -0.1834498 0.5404633 -0.6577806 0.4914980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5154 5125 -0.862729 0.054085 -0.422449 -0.3042367 -0.0909846 -0.2060717 0.9255789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5154 5165 0.733787 -0.013629 0.460552 -0.8515974 0.0610457 -0.3444642 0.3903840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5154 5254 -0.306978 0.963488 0.476861 0.2053158 0.3577901 0.5445260 0.7302897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5155 5124 0.026033 0.854625 0.571498 -0.3140158 -0.3908492 0.6193007 0.6042331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5155 5164 0.054720 -0.744956 -0.396196 0.3890508 -0.7322163 -0.3688700 0.4200400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5156 4456 0.571734 -0.449427 -0.636843 -0.4489708 0.5493541 0.3738914 0.5973613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5156 5163 -0.243799 -0.649680 0.685847 -0.5166577 -0.0216409 -0.6033186 0.6071270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5156 5256 -0.472506 0.696068 0.395232 -0.6373196 0.2085199 0.7413871 0.0262355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5157 5162 0.792868 -0.625254 0.100343 0.2439967 -0.1919736 -0.9032857 0.2961194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5157 5257 -0.575896 -0.882131 0.226061 -0.5782278 -0.3605881 0.6152972 0.3962804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5158 5161 -0.953018 0.468833 0.280705 0.2191278 0.8843227 0.3010103 0.2816899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5158 5258 0.412176 0.963435 0.341903 0.0519986 -0.0012009 0.7569320 0.6514205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5159 5259 0.043473 -0.590789 0.611492 0.0527779 0.1296494 0.1741094 0.9747263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5160 5199 -0.898296 0.593590 -0.222228 0.6172532 -0.1615337 -0.7586503 0.1317384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5161 4421 -0.112937 -0.709190 -0.711733 -0.1676322 -0.3526816 -0.6898387 0.6096210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5161 5198 0.979057 0.307260 -0.310324 -0.2035617 0.7198463 0.3972695 0.5315646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5161 5221 0.225327 0.870463 0.730344 -0.6274129 0.4017392 0.6601621 0.0956279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5162 5197 0.021101 0.833411 -0.425212 0.6234713 0.4979282 0.2474879 0.5496370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5162 5222 0.860102 0.546566 0.234367 0.5428289 0.2851930 0.7743395 0.1562053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5163 5196 0.788980 -0.404255 -0.230984 0.1863857 0.7768498 -0.4797922 0.3627179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5164 5224 0.794066 0.562646 0.265579 -0.2690172 -0.0982728 -0.8181292 0.4986349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5165 5194 0.932854 -0.309176 0.121237 -0.0875905 0.2500547 -0.6453791 0.7164401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5165 5225 -0.180774 -0.804101 0.231999 0.7743090 -0.4159017 -0.3711038 0.2995886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5166 5153 -0.794223 -0.169285 -0.638516 -0.7409200 -0.3382560 0.1293704 0.5655826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5166 5193 0.765368 0.262314 0.600966 -0.8401349 0.1441171 -0.2098766 0.4789106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5166 5226 -0.503076 0.664723 0.400138 -0.1035887 0.3585388 0.8070586 0.4575759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5167 5227 -0.002167 0.496637 1.060876 -0.0801059 0.2653649 0.7358421 0.6178195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5168 5151 -0.862655 -0.090790 -0.613794 -0.6814018 -0.4454780 -0.5308958 0.2353519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5168 5191 0.791762 -0.200434 0.487431 -0.7414612 0.2799636 -0.3289886 0.5134415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5168 5228 0.034971 0.851322 0.010621 0.0982690 -0.8428631 -0.2447423 0.4690694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5169 5190 -0.738832 0.563049 -0.546442 -0.1124088 -0.5407529 0.1103211 0.8263049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5169 5229 -0.531790 0.112924 0.856079 0.2119314 -0.0869195 -0.9733945 0.0057642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5170 5189 0.899953 -0.238391 0.153600 -0.0850191 0.2193344 0.0316708 0.9714222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5171 5148 -0.078628 -0.870018 -0.306586 -0.0474969 0.5849345 -0.7037981 0.4003299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5171 5188 0.296589 0.889917 0.425378 -0.3651520 -0.0864629 -0.3192863 0.8701979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5171 5231 -0.445292 -0.249585 0.780286 -0.1798908 0.0319996 0.9592054 0.2157323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5172 5147 0.262403 -1.058675 -0.310266 -0.7061557 -0.4015536 0.4042640 0.4203207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5172 5187 -0.378214 0.803891 0.053648 0.4050004 -0.4885526 0.1729158 0.7532537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5172 5232 -0.437081 -0.322297 0.744262 -0.2678469 -0.2087286 -0.7760263 0.5314824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5173 5186 -0.528395 0.306709 -0.944527 0.8855967 -0.1102143 -0.4159363 0.1748380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5173 5233 -0.878587 -0.348890 0.470709 -0.1741262 -0.6686908 -0.4839225 0.5369839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5174 5185 0.260347 -1.130551 -0.187714 0.7463995 -0.0181734 -0.5056252 0.4323202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5175 4435 0.231144 0.860534 -0.525910 0.5828272 0.4338291 -0.6185942 0.2990752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5175 5144 0.385995 0.173282 0.832831 0.2970873 -0.8308519 0.4553599 0.1186242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5175 5235 -0.484663 -0.930691 0.329578 -0.1042413 -0.0946723 0.8176344 0.5582517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5176 5183 -0.805233 0.176260 0.208473 -0.0576374 0.2335503 0.5984904 0.7641606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5176 5236 0.018748 -0.548863 0.998859 0.1795309 -0.3229465 -0.0588536 0.9273675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5177 5182 -0.335124 -0.751563 -0.365101 -0.2399675 0.5315695 -0.8123032 0.0036036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5177 5237 0.577452 -0.528952 0.481383 0.6978697 -0.4325349 0.5573554 0.1234765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5178 5181 -0.555718 -0.318246 0.570367 0.0567635 -0.4371425 0.1043203 0.8915165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5178 5238 0.218827 0.594455 0.830806 -0.2523799 0.6496870 0.6128793 0.3722770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5179 5239 -1.016506 -0.002124 0.544119 0.6369723 -0.2616763 0.0979875 0.7184638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5180 5200 0.164758 0.097572 0.925990 0.0364509 0.0578058 -0.7912358 0.6076806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5181 5201 0.788509 0.656572 0.039503 -0.5954113 0.5458092 0.1832492 0.5603547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5182 5202 -0.121430 -0.377676 0.866731 -0.3372585 0.2343169 -0.8947723 0.1753137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5183 5203 -0.551614 -0.074998 0.656328 0.6375262 -0.5484089 -0.5281203 0.1178850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5184 5204 0.057769 0.237808 0.820371 0.2249740 -0.1782491 0.6547152 0.6992582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5185 5205 -0.697159 0.216673 0.741313 -0.2855474 0.1828218 0.8649605 0.3699759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5186 5206 -0.872016 0.556391 0.527388 -0.4234050 -0.1652846 0.8900381 0.0352321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5187 5207 0.475295 0.529839 0.695833 0.2311202 0.3328188 0.3481369 0.8453495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5189 5209 -0.597676 -0.332260 0.628981 0.1685259 -0.6317885 -0.6811470 0.3293647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5191 5211 -0.650287 -0.250900 0.638242 0.1230169 -0.0534657 0.8635042 0.4861777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5192 4412 -0.821068 -0.455192 -0.210049 0.0926568 0.1411380 0.0750798 0.9827806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5192 5167 0.221678 -0.692792 0.714136 -0.1304930 0.3901744 -0.2470874 0.8773160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5192 5212 0.807894 0.551880 0.275742 -0.5087616 0.6850374 -0.4210168 0.3076203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5193 5213 -0.636039 -0.840837 0.174284 0.8088811 0.0227581 0.3887258 0.4405516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5194 5214 0.814147 -0.605495 -0.002729 0.4802489 -0.0019616 -0.4258980 0.7667907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5195 5164 0.629347 0.721892 0.454280 0.0764483 -0.0486643 -0.5918787 0.8009164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5195 5215 0.697530 -0.665915 0.289180 0.8517587 -0.2445860 0.2088009 0.4136267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5196 5216 -0.003062 -0.928081 0.440205 0.0002067 0.6225657 -0.7448507 0.2400196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5197 4417 -0.602088 -0.612287 -0.414472 -0.3136947 0.3066223 0.8957257 0.0724835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5197 5217 0.735682 0.509346 0.344768 0.4744094 -0.1914981 0.8146542 0.2731350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5198 5218 -0.481014 0.845922 0.613887 0.4634448 -0.4955476 -0.6647369 0.3126921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5199 5219 0.572775 0.853624 0.486452 -0.2338763 0.2544435 -0.9372299 0.0464817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5200 5239 -0.040179 -0.907977 -0.000235 0.6049454 0.1113810 -0.2122821 0.7593231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5200 5980 -0.144492 0.002321 0.989134 0.6044959 0.1107121 0.3520331 0.7059746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5201 5981 -0.042528 -0.593010 0.858183 -0.1668744 -0.2332916 -0.3174931 0.9038396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5202 5237 0.272448 0.860996 -0.364150 0.6494595 -0.1614899 0.6088227 0.4259792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5202 5982 0.919747 -0.182449 0.589295 0.1383623 0.7480998 -0.3536442 0.5441859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5203 5983 -0.074083 0.853490 0.352087 -0.8140892 -0.3059293 -0.2575565 0.4211066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5204 5235 0.655887 -0.394360 -0.485415 0.2139723 0.7329891 0.3253817 0.5577360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5204 5984 0.658963 0.037943 0.895582 0.1997339 0.5853395 -0.2589863 0.7418963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5205 5234 0.243969 0.944732 -0.444154 -0.3889680 -0.3550174 -0.3689617 0.7658550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5205 5985 -0.008582 0.499036 0.790721 -0.4874672 -0.4954270 -0.6922657 0.1941546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5206 5233 0.732205 -0.105359 -0.498869 -0.3242394 -0.0876087 -0.3333953 0.8809319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5206 5986 0.290954 -0.712482 0.820090 0.7044408 0.5178508 -0.1007013 0.4748188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5207 5232 -0.855875 -0.373711 0.719652 0.6551852 0.0909083 0.7380493 0.1332341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5208 5188 -0.609682 0.641128 -0.069839 -0.1647860 0.4891486 0.1754140 0.8383371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5208 5231 -0.522630 -0.801003 -0.469585 0.5667180 -0.1025842 0.8157823 0.0529753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5208 5988 0.549925 -0.776615 0.207142 -0.4009220 0.4789244 -0.7528642 0.2075778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5209 5230 0.153881 -0.414843 0.796729 -0.5666485 -0.5322000 -0.5501009 0.3050602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5209 5989 0.849412 0.457230 0.159435 -0.3904683 0.6261192 0.4903692 0.4637319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5210 5190 0.652544 0.265769 -0.660423 0.0302624 -0.2835418 0.9583057 0.0183981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5210 5229 -0.649800 0.919868 -0.075900 0.2025995 -0.3472610 -0.2180423 0.8892810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5211 5228 0.680115 0.151845 -0.576969 -0.0180137 0.8590089 0.2690232 0.4352077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5211 5991 0.274984 0.711872 0.624706 -0.4204253 0.0058416 0.9070681 0.0208764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5212 5227 0.507366 -0.926707 -0.179704 -0.2160276 -0.3811088 0.8497236 0.2933562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5212 5992 -0.722043 -0.568892 0.406714 0.8016143 -0.3211884 -0.2539469 0.4356185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5213 5226 -0.445642 -0.222016 -0.832635 -0.3427219 0.2786706 0.7005418 0.5604691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5214 5225 0.280289 -0.912585 0.439910 0.5610513 0.4349767 0.0592972 0.7017838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5215 5224 0.501292 -0.538114 -0.746814 0.2901370 0.7243769 0.4500574 0.4342200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5215 5995 0.692731 0.196249 0.473969 0.7677630 0.0194261 0.6403454 0.0109762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5216 5223 -0.003208 0.885680 0.217844 -0.0428865 -0.3562635 -0.1441575 0.9222015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5216 5996 0.093621 -0.202954 0.880320 0.0766665 -0.4886660 -0.7044405 0.5090101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5217 5222 0.887236 -0.103526 -0.584167 -0.0017804 0.5468940 -0.6791483 0.4895523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5217 5997 0.345034 -0.946007 0.434237 0.3269807 0.1918199 -0.5315004 0.7574933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5218 5221 -0.177632 -0.833871 0.407071 0.7111946 0.0334627 -0.6572978 0.2470669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5218 5998 -0.586456 0.435890 0.681529 -0.7637801 -0.4650851 0.4262175 0.1366548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5219 5999 -0.492830 -0.918365 0.252897 0.2715824 -0.2081399 0.4567400 0.8211634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5220 5259 -1.015734 -0.046811 0.078706 -0.2044123 -0.1134262 0.5717333 0.7864294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5220 5960 0.172800 -0.222593 0.954927 -0.3384512 -0.1425502 0.7269768 0.5802026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5221 5258 -0.065104 0.833272 0.509521 -0.0823617 0.2430884 -0.8633554 0.4344445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5221 5961 -0.723515 -0.307609 0.433821 0.2355334 -0.4650374 -0.5467979 0.6551919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5222 5257 -0.163510 1.007643 0.044296 -0.2384699 0.2621655 0.7856846 0.5070514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5223 5256 -0.177113 0.911069 0.373801 0.2146736 -0.1607235 0.9451455 0.1865026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5223 5963 0.821427 -0.014597 0.425890 0.4731763 0.2196316 0.7839529 0.3365768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5224 5964 -0.500308 0.407369 0.765332 -0.4058998 -0.4607519 0.6911220 0.3811868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5225 5254 -0.450917 0.175247 0.851409 0.6115405 0.7013778 0.1605359 0.3291133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5225 5965 0.626675 0.759354 0.219568 -0.2853512 0.5899184 0.6400639 0.4011099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5227 5252 -0.866909 0.388897 -0.051661 -0.0017531 0.3828534 -0.9024373 0.1975529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5228 5251 0.327813 -0.216072 0.944150 -0.2386034 0.6900750 0.6697543 0.1352555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5229 5250 -0.631751 0.518313 0.108998 0.0613454 -0.4519162 -0.3739047 0.8075913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5229 5969 0.191425 0.045319 0.947051 0.5441250 -0.0020470 -0.1218087 0.8301123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5230 5170 -0.018124 -0.807032 -0.751591 -0.2429622 -0.1119454 -0.8202094 0.5056621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5230 5249 0.396676 0.557147 -0.651206 -0.0558162 0.8108560 0.4927135 0.3108544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5231 5248 -0.304623 0.899001 -0.573712 0.3741299 -0.0672872 -0.8696158 0.3150676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5231 5971 0.025024 0.700691 1.008197 -0.3187840 -0.5992753 -0.6881783 0.2562354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5232 5247 0.339210 0.531631 -0.797222 -0.6458527 0.7162800 -0.0641793 0.2563166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5233 5973 0.958999 -0.723583 0.358701 -0.1430528 0.4745664 0.1083545 0.8617319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5234 5174 -0.488561 0.164629 -0.912661 -0.0801614 0.5889465 0.3381926 0.7296177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5234 5245 -0.515265 0.800647 0.461458 -0.0075712 0.7610622 -0.0029280 0.6486281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5235 5244 -0.065861 -0.713246 0.598560 0.1923032 0.3127950 0.6989533 0.6137125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5235 5975 -0.768037 0.490872 0.500671 -0.4344330 0.1357240 0.7053089 0.5434946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5236 5243 0.344700 -0.182182 -0.780752 -0.6786502 -0.1090133 -0.6355069 0.3516832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5237 5242 0.036215 -0.954439 -0.484387 -0.5086471 0.4153260 -0.5975040 0.4601862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5237 5977 0.665244 -0.242474 0.590514 -0.7528686 0.4755168 -0.3971761 0.2220897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5238 5201 -0.204563 0.667452 -0.422510 0.0455068 -0.0704578 -0.7911248 0.6058766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5238 5241 0.315226 -0.755431 0.614785 -0.6438660 -0.0065852 -0.0862962 0.7602277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5238 5978 -0.786797 0.130562 0.695611 -0.4124735 -0.6673231 -0.3054966 0.5396455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5239 5979 -0.504608 0.846046 0.208127 0.3922183 -0.3788596 -0.3274489 0.7716265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5240 5279 1.117700 -0.425003 -0.288714 -0.2523198 0.5493017 0.0545532 0.7947492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5240 5940 0.360656 0.899999 0.532810 -0.2514571 0.4446072 0.8221056 0.2514679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5241 5278 0.401614 -0.482610 -0.676167 0.6255330 -0.6797289 0.0228291 0.3823034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5241 5941 -0.448737 -0.726609 0.041591 0.4198573 -0.0935528 0.7523882 0.4988784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5242 5277 0.803814 0.560719 0.197538 0.6173339 -0.3900264 0.1866864 0.6572111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5242 5942 0.529337 -0.581471 0.782999 0.2880264 -0.1503643 0.3021252 0.8961873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5243 5276 -0.571376 0.681757 0.240500 -0.0185573 0.0933954 -0.7585392 0.6446326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5244 5144 -0.487480 -0.966854 0.070708 -0.9187574 -0.2986790 -0.2514430 0.0587547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5244 5275 -0.789387 0.448127 0.207296 -0.5312318 0.5376255 0.1820312 0.6289803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5244 5944 0.546632 0.994770 0.023558 -0.1603070 0.4220214 -0.3278252 0.8298977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5245 5145 0.839623 0.272687 -0.567255 0.0339960 -0.0843227 -0.6727348 0.7342764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5245 5274 -0.448393 0.622094 -0.567935 -0.2072690 -0.7495896 -0.1951033 0.5975698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5245 5945 -0.834657 -0.379134 0.360331 0.5165210 -0.1666725 0.3492174 0.7638544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5246 5233 0.344959 0.177118 0.908129 -0.3087780 0.4579819 -0.4160562 0.7223614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5246 5273 -0.077664 -0.127935 -1.155169 0.5885750 0.3159778 -0.1473824 0.7293942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5246 5946 0.101281 -0.944310 0.098346 -0.0978118 0.4553769 -0.7249727 0.5074242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5247 5272 -0.507013 0.016904 1.048847 0.2667204 0.1645809 -0.6831704 0.6595844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5248 5271 0.188974 -0.888255 -0.616674 0.6656389 -0.3497413 -0.0421695 0.6578964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5248 5948 -0.604973 -0.338517 0.644011 -0.6826998 -0.1492105 0.6581343 0.2802079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5249 5270 0.017123 -0.457859 0.897908 0.1027591 -0.7437469 -0.1037570 0.6523155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5249 5949 -0.397909 0.785923 0.254128 -0.4264960 -0.6529582 -0.4393966 0.4457323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5250 5150 -0.828433 -0.413955 -0.292644 0.1385979 0.3000504 0.4385847 0.8357056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5250 5269 -0.861047 -0.056796 0.891499 -0.2248725 0.4487916 0.5460144 0.6707359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5251 5268 -0.642998 0.762550 -0.157545 -0.0888206 -0.1085547 0.6994807 0.7007521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5251 5951 0.113473 0.462381 0.834876 -0.4998477 -0.4956194 -0.6717481 0.2307991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5252 5952 -0.188612 -0.905182 0.550070 0.1819003 -0.7713024 0.5777630 0.1954349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5253 5226 0.058587 0.911185 0.665347 -0.1612781 -0.0206254 -0.9042370 0.3948663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5253 5266 -0.232799 -0.953779 -0.515188 -0.1945008 0.6923189 -0.1114799 0.6858835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5254 5265 0.049772 0.349058 -1.108168 -0.5431718 0.7285668 0.3450956 0.2346567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5255 5155 -0.662365 0.552424 -0.701288 0.0046203 -0.3417635 0.8511031 0.3984970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5255 5224 0.429014 0.526278 0.215913 0.5494732 0.5121252 -0.2069677 0.6268743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5255 5264 -0.613220 -0.647948 -0.045134 0.1752586 -0.1049286 -0.8114574 0.5475503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5255 5955 0.502623 -0.679112 0.628344 -0.4837940 0.4645419 -0.6347488 0.3837162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5256 5263 0.606162 -0.846255 -0.085896 0.4643179 -0.3658893 -0.4744142 0.6522769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5256 5956 -0.543395 -0.198524 0.857700 -0.1489441 0.4291763 0.7613224 0.4626138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5257 5262 0.622440 -0.257368 0.711862 -0.0758200 -0.0483064 0.9958088 0.0168106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5257 5957 -0.780034 0.142142 0.537050 0.2724574 0.0573994 -0.6300101 0.7249548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5258 5958 0.567993 -0.345555 0.327041 -0.5941549 0.5433537 -0.3433276 0.4836040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5259 5959 -0.586081 -0.343622 0.671015 0.8105720 -0.0283442 -0.1766069 0.5576554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5260 5299 0.363561 -0.936350 0.249143 -0.0120000 0.8233800 -0.0349651 0.5662851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5260 5920 0.884105 0.361692 0.499477 0.4758585 0.6607593 0.1764832 0.5530004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5261 5121 -0.478829 0.800119 0.072431 0.5808151 0.1913667 0.4112288 0.6759611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5261 5258 0.086617 0.059510 1.036829 0.4945322 -0.4507100 -0.1219330 0.7330967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5261 5298 -0.112574 0.128774 -0.783927 0.4297930 0.3620564 -0.5311598 0.6340839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5261 5921 0.370431 -0.849000 -0.082807 -0.0041016 0.2723607 -0.9616648 0.0316800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5262 5297 -0.751419 0.178805 0.693880 0.2839795 -0.0479799 0.8499041 0.4412671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5262 5922 0.819240 -0.141834 0.631236 -0.2589538 -0.1029319 0.4342296 0.8566169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5263 5296 0.947195 -0.094209 -0.299984 -0.2784679 0.1740315 0.9443777 0.0178707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5263 5923 0.453989 0.555096 0.697200 -0.8212752 0.1078945 0.4298375 0.3593125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5264 5924 0.303383 0.790112 0.339375 0.0478657 -0.7055545 -0.6831127 0.1823701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5266 5293 0.692449 -0.297769 -0.043521 0.5064609 -0.3133122 -0.2311150 0.7693625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5266 5926 -0.597512 -0.779482 0.133117 0.7325679 -0.0379520 0.3519009 0.5814376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5267 5252 -0.344817 -0.752860 0.413837 0.8197792 0.1816808 -0.5425247 0.0249211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5267 5292 0.519127 0.869597 -0.489572 -0.3284802 -0.4647201 -0.5172842 0.6391816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5267 5927 -0.845546 0.521998 0.000519 0.1441531 -0.0261660 -0.9775962 0.1511319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5268 5128 -0.424889 0.086405 -0.863223 -0.2680374 -0.3374129 -0.0144368 0.9022749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5268 5291 0.858691 0.544843 -0.254358 -0.1294335 0.3883007 0.9108571 0.0529994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5268 5928 0.441349 -0.314202 0.678191 0.5703906 -0.0754184 -0.3206743 0.7524192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5269 5129 0.097773 0.610505 -0.737927 0.5061639 0.3719431 0.0199193 0.7778559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5269 5290 -0.838365 0.722220 0.329118 0.1700262 -0.3899824 -0.8564675 0.2923496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5269 5929 -0.104991 -0.712211 0.665350 0.1385651 0.3316461 -0.9064693 0.2216393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5270 5130 -0.209437 -0.885514 -0.258476 -0.5413521 0.2345446 0.3719915 0.7166234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5270 5930 0.318373 0.750779 0.253027 -0.6953663 -0.3182313 -0.6037642 0.2250854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5272 5932 0.875014 0.363497 0.564327 -0.7315685 -0.2833828 -0.5292035 0.3231800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5273 5286 0.464944 -0.953890 -0.145314 0.5150087 -0.4210414 0.1348796 0.7343689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5273 5933 -0.104329 -0.145910 0.927979 0.0073084 -0.3348039 0.9368711 0.1006254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5275 5284 -0.914686 0.724678 0.046743 -0.2915218 -0.7261156 0.4880456 0.3867593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5276 5283 -0.618326 -0.561899 0.327422 -0.4893536 -0.3206928 -0.3243073 0.7433128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5277 5937 0.863260 0.251134 0.453632 -0.7370412 0.1601969 -0.2938907 0.5871418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5278 5138 -0.747566 -0.622817 -0.471076 0.0943688 0.4157018 -0.7117041 0.5583581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5279 5139 0.384568 -0.304954 -0.829962 0.6493062 -0.5421277 -0.4897242 0.2113509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5279 5939 -0.379362 0.213888 0.897556 -0.2926187 0.2689650 0.4221634 0.8147455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5280 5319 -0.613254 -0.899380 0.468379 -0.2626992 -0.1283780 -0.8300057 0.4749723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5280 5900 0.543157 -0.660298 0.158236 -0.4330719 0.8306002 0.0944300 0.3370979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5281 5278 0.613746 -0.188424 0.622177 -0.5622074 -0.7876526 -0.1724327 0.1838292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5281 5901 0.240697 0.858948 -0.010918 -0.6069054 0.0937835 0.7516681 0.2405525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5282 5277 0.162032 -0.537681 -0.790612 0.6780460 -0.4737985 0.4966112 0.2629562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5282 5317 0.035092 0.527008 0.688702 0.4723131 0.2769481 0.8320192 0.0892424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5282 5902 0.138133 -0.685260 0.437104 0.1065502 0.7073914 -0.6945416 0.0765271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5283 5103 -0.151257 0.442267 -0.705353 0.7929925 0.1327813 0.1987763 0.5603749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5283 5316 -0.235304 -1.034770 -0.568965 -0.1476014 -0.1330351 -0.7103705 0.6751957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5284 5315 0.949520 0.131590 0.254745 0.1408743 0.8785392 -0.4564187 0.0022845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5284 5904 0.117151 -1.065342 -0.050265 0.5523590 -0.6759209 0.1214735 0.4725195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5285 5274 0.075981 0.581277 0.708123 0.7069497 -0.4676146 0.4660940 0.2536042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5285 5314 -0.202601 -0.767691 -0.734422 -0.0612334 0.4828255 0.2338080 0.8417030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5285 5905 0.740084 -0.538388 0.442087 -0.0877962 -0.8097569 0.5619764 0.1441119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5286 5313 0.415265 -0.740566 0.507092 -0.0427574 0.3545066 0.2568536 0.8980663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5286 5906 0.690658 0.547081 0.238848 -0.8258217 -0.3144309 -0.3045372 0.3555403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5287 5107 -0.576364 0.000667 -0.723855 0.1079779 -0.2310157 -0.9417808 0.2191380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5287 5272 -0.311245 -0.808949 0.208509 -0.5577150 -0.2117756 -0.6594809 0.4573730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5287 5312 0.222797 0.960426 -0.259351 -0.0189456 0.4921601 -0.6560138 0.5718963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5287 5907 0.635368 -0.140995 0.741748 -0.1245594 -0.2661731 -0.3464966 0.8908294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5288 5311 0.648952 0.027222 -0.719059 -0.2829236 0.1859968 0.5662048 0.7515128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5289 5109 -0.769851 0.720313 -0.336979 -0.0595140 0.9524487 -0.0270334 0.2976050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5289 5270 0.526638 0.243499 -0.710165 -0.4179787 -0.2128413 -0.8126208 0.3458899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5289 5909 0.779375 -0.790867 0.444230 0.5092176 -0.0882712 0.5698898 0.6388515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5290 5309 0.291670 -0.295859 0.748475 0.1403311 0.4987941 0.5648059 0.6422663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5290 5910 0.365157 0.862920 0.255971 -0.0093261 -0.5053980 -0.6154418 0.6047456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5291 5111 0.642847 -0.630781 -0.164033 -0.1051420 -0.2424450 -0.5954708 0.7586699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5291 5308 -0.606183 -0.640502 0.181470 0.8006692 0.0612976 -0.4966643 0.3293872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5291 5911 -0.636269 0.690358 0.255885 0.3157209 -0.4680354 -0.1768156 0.8062254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5292 5307 -0.424175 0.603184 0.594218 0.8635897 -0.2704136 -0.0013055 0.4255438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5292 5912 0.030207 -0.696227 0.974610 0.5674764 0.3436827 -0.2866586 0.6911437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5293 5306 0.853589 -0.341293 -0.501280 -0.4798692 -0.4443148 -0.7414158 0.1503744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5293 5913 0.202279 -0.245651 0.979209 0.0908956 0.4364382 -0.8449210 0.2955813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5294 5265 0.609708 -0.760215 0.135840 -0.5053435 -0.0237153 0.7777857 0.3729812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5294 5305 -0.799517 0.821044 0.105758 0.1835298 0.2722583 -0.8352630 0.4410532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5294 5914 0.128512 -0.031090 0.956572 0.4875450 0.4473629 -0.1137941 0.7410919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5295 5115 0.206167 0.335291 -0.841815 -0.1940080 -0.6810551 0.6734739 0.2120324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5295 5304 0.894326 0.383119 0.228081 0.6442586 0.2073007 -0.6624889 0.3210383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5295 5915 -0.217878 -0.263600 1.139866 0.4646691 -0.2874393 0.5227500 0.6543651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5296 5303 -0.824096 -0.008863 -0.951690 0.8740457 0.0317593 -0.3604895 0.3241647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5297 5302 0.898624 0.352859 0.099661 -0.2572089 0.3747934 0.8823926 0.1214776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5298 5301 0.858641 -0.285264 -0.214918 -0.0874470 0.6991726 0.2441230 0.6662692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5298 5918 0.523219 0.288735 0.889501 -0.5967487 -0.3963098 -0.6779990 0.1647628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5299 5919 -0.638146 0.384235 0.626959 0.5458397 -0.1765407 -0.3666041 0.7324574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5300 5339 0.658609 -0.729287 0.440126 -0.3941424 -0.8616274 -0.0015572 0.3197618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5300 5880 -0.856607 -0.566756 0.085526 0.4521067 0.1821480 -0.7495163 0.4479363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5301 5338 0.116454 -0.556509 0.631034 -0.8665831 -0.0462723 0.4515626 0.2073252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5301 5881 -0.655725 0.231053 0.549143 0.2848619 -0.5528055 -0.3594676 0.6957319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5302 5337 -0.765360 -0.674944 0.261902 0.3234954 -0.3724735 -0.2053701 0.8452440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5302 5882 -0.612452 0.818921 0.371043 -0.5532911 0.5233386 0.3341593 0.5552686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5303 5336 0.001774 -0.536262 0.884824 -0.9494033 0.0396778 -0.0878568 0.2988983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5303 5883 -0.735716 0.573966 0.356095 -0.9477516 0.0156041 0.0057915 0.3185747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5304 5335 -0.628925 0.268256 -0.890930 -0.5296234 -0.1194099 0.0151156 0.8396498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5304 5884 -0.907875 0.304117 0.450674 -0.2867649 -0.7379931 0.4171822 0.4461963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5305 5334 -0.107399 -1.004936 -0.342251 0.1262744 0.2463840 0.9521877 0.1291835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5306 5333 -0.981241 0.441693 0.145796 0.0602240 0.4278091 0.5394038 0.7227696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5307 5332 -0.574639 0.281743 -0.831488 0.7494735 -0.1554075 0.6395090 0.0718761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5307 5887 0.424655 1.101004 -0.210223 -0.3358776 0.1134535 0.4095152 0.8406021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5308 5331 -0.248478 0.453758 0.923883 0.8624235 0.0609556 -0.0954802 0.4933495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5308 5888 -0.809022 -0.886650 0.117882 -0.7207647 0.2624551 0.6333720 0.1022521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5309 5330 -0.886998 0.475182 0.507660 -0.0492528 -0.4566979 -0.5998237 0.6551433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5310 5329 -0.410372 -0.839033 -0.567378 0.2038393 0.9051286 -0.1649963 0.3346163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5311 5328 0.804894 -0.257947 -0.525781 0.1179007 0.0473394 -0.9713349 0.2009151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5312 5327 -0.772750 0.451447 -0.716434 -0.3147093 -0.0900078 0.6527484 0.6832102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5313 5093 -0.245295 -0.135869 -0.849299 -0.0864202 -0.6624873 -0.7397244 0.0803109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5313 5326 -0.317762 -0.774164 0.278715 -0.5302318 -0.6326396 -0.5612333 0.0603206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5313 5893 0.385034 0.221472 0.871068 -0.7739227 0.1924211 0.1189225 0.5915024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5314 5325 0.437771 -0.734356 -0.648679 -0.2169160 0.5994227 -0.7346830 0.2321222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5314 5894 -0.216332 -0.858386 0.617019 -0.1753186 0.0888895 0.8721253 0.4480620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5315 5095 0.310788 0.532229 -0.863027 0.7702022 0.2184345 -0.4186892 0.4286890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5315 5324 -0.897123 -0.054134 -0.476596 0.3645697 0.0561493 0.9152800 0.1618600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5315 5895 -0.264312 -0.630695 0.758763 0.7381029 0.0843366 -0.2075176 0.6364181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5316 5323 0.637196 -0.099692 -0.876388 -0.1682402 0.2130412 -0.6346801 0.7235260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5316 5896 0.718000 0.094719 0.619605 0.4934254 -0.3666236 0.6412735 0.4592241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5317 5897 -0.006900 0.930304 0.194806 -0.3448702 -0.8349768 -0.2274143 0.3635397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5318 5098 1.050448 -0.034416 -0.471046 -0.4580021 -0.3571522 0.3960316 0.7112210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5318 5281 0.128719 -0.931503 0.278374 0.6212901 -0.6056028 0.1237896 0.4815808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5318 5321 -0.088848 1.065989 -0.285806 0.3720823 -0.8031829 0.2462157 0.3947529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5319 5899 0.309099 1.112018 0.089729 -0.3445124 -0.2436751 -0.7435265 0.5187504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5320 5860 0.032545 0.514989 0.745775 0.4194200 -0.2843485 -0.8489975 0.1497869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5321 5358 -0.543728 0.668855 -0.564010 0.4424316 0.6827951 0.4268668 0.3947528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5322 5317 -0.751495 -0.175260 -0.804632 0.1784600 -0.0378580 0.3274870 0.9270766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5323 5063 0.109260 -0.410030 -1.040525 -0.2435607 0.3908484 0.8491921 0.2584348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5323 5356 0.161445 0.769517 -0.263420 -0.5137858 -0.3529443 0.7623905 0.1738255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5323 5863 0.040002 0.276675 1.003646 0.1179446 -0.0796914 0.5497814 0.8230910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5324 5355 0.373258 0.257722 -0.818542 0.0659310 0.8391552 0.2974633 0.4505411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5324 5864 0.590449 0.634880 0.145266 -0.2346951 -0.6969157 -0.4441879 0.5117850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5325 5354 0.096595 0.720852 0.574159 0.1629183 0.3681422 -0.2574085 0.8784474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5325 5865 0.641408 -0.568410 0.599246 -0.0437737 -0.1452269 -0.8581241 0.4905262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5326 5353 -0.011224 0.317837 -1.199765 0.4125599 0.4310310 0.8015530 0.0389801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5327 5352 0.613087 0.778291 -0.210897 0.0908396 -0.6638509 -0.6129958 0.4186720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5327 5867 -0.299750 0.149967 0.876248 -0.3564306 0.2613667 -0.8140418 0.3768032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5328 5351 -0.107667 0.851039 -0.688692 -0.7515018 -0.0331044 0.0159646 0.6587065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5328 5868 -0.371005 0.654516 0.923538 0.3746730 -0.2821283 -0.6692009 0.5763626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5329 5869 -0.698118 -0.328435 0.578691 -0.3395521 -0.1432025 0.3495716 0.8613925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5330 5349 0.014004 -0.157179 0.924755 -0.1721638 -0.6978472 -0.5784407 0.3857139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5330 5870 0.250516 0.839161 0.007135 -0.2847302 0.2314512 -0.8578278 0.3598480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5331 5348 -0.537383 0.670137 -0.557096 -0.5698857 -0.2886003 0.1053749 0.7621261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5331 5871 -0.616573 0.203452 0.880447 -0.0943827 -0.1261360 0.9096676 0.3843000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5332 5872 -0.131936 -0.919626 -0.007396 -0.3702158 0.7334691 -0.5025229 0.2691358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5333 5346 0.332415 0.814000 -0.219204 -0.3209382 0.4562419 0.6847935 0.4689347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5334 5345 -0.083716 0.539889 -0.689430 -0.2305933 -0.5536180 -0.6376120 0.4835129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5334 5874 0.666939 0.672573 0.431615 0.3150296 -0.1716236 0.8574287 0.3689414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5335 5075 0.787137 0.323861 -0.645941 -0.1775942 0.0968546 -0.1341905 0.9700889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5335 5344 -0.449395 0.839969 -0.244823 -0.2562786 0.1673164 -0.0899429 0.9477536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5335 5875 -0.789514 -0.339679 0.500441 0.6161388 0.1184165 -0.1701399 0.7598704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5336 5343 0.136506 0.001214 -0.860878 0.8892395 -0.3118837 -0.3302362 0.0540894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5336 5876 -0.548412 -0.495853 -0.127689 -0.2207483 -0.6489765 0.7212445 0.0995294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5337 5877 -0.755403 0.839024 0.344789 -0.1367167 0.0534228 0.3835116 0.9117968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5338 5341 -0.570847 0.374451 -0.639609 0.4953451 -0.4153324 -0.4617557 0.6073828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5340 5379 0.598082 -0.519959 0.650476 0.2459224 -0.5572696 0.6505536 0.4535998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5341 5378 -0.786037 -0.878066 0.358409 -0.5899909 -0.2556438 -0.5514257 0.5314948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5341 5841 0.112258 0.500117 0.890879 -0.6752517 0.1266466 0.6847223 0.2432101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5342 5337 0.891663 0.284095 0.343426 0.3500526 -0.6337524 -0.2776005 0.6314737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5342 5842 -0.435346 0.852984 0.237768 -0.5634925 -0.4846360 -0.1075148 0.6603368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5343 5376 0.493118 -0.277976 0.769697 -0.5331823 -0.4705919 -0.3593534 0.6042557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5344 5375 -0.661296 0.622282 0.125631 -0.0656303 -0.5351464 0.7829434 0.3103395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5344 5844 -0.776843 -0.752964 0.143452 0.2528677 0.2240865 -0.5272972 0.7796158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5345 5045 0.139233 -0.821152 -0.570044 0.1608191 -0.0213190 -0.9085516 0.3849893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5345 5374 -0.568642 -0.584458 0.619056 -0.2969942 -0.4093002 0.6510816 0.5660040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5345 5845 -0.083885 0.910502 0.618037 -0.3502566 -0.1809817 -0.4194320 0.8177058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5346 5373 0.450452 -0.568153 0.839088 0.6476796 -0.6695830 0.3545773 0.0802796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5347 5332 -0.607271 -0.468573 0.518250 -0.0973713 0.4879860 -0.8618772 0.0977556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5347 5372 0.482396 0.646482 -0.436506 0.2683681 -0.1336696 0.9482350 0.1046963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5347 5847 -0.080380 0.221040 0.695107 0.4626247 -0.2611957 -0.0842247 0.8430073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5348 5371 -0.524616 0.789422 0.748705 0.8571818 0.1977657 -0.3390701 0.3334059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5348 5848 -0.120246 -0.766546 0.667814 0.3911757 0.1930913 0.1212564 0.8916245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5349 5049 0.403144 -0.630484 -0.714869 -0.6080840 0.1530306 0.3671445 0.6870374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5349 5370 0.618913 0.671450 -0.097471 -0.2902037 0.2307596 -0.8640509 0.3405111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5349 5849 -0.400443 0.581681 0.642878 -0.0088635 0.6456016 0.6654820 0.3745046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5350 5329 0.867530 0.226695 0.610223 0.3522568 -0.3835278 -0.6985261 0.4907982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5350 5369 -0.960243 -0.283634 -0.385939 -0.7783278 -0.3857029 0.1878723 0.4584137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5350 5850 -0.359587 0.884681 -0.113125 -0.3331586 -0.2004314 0.8415109 0.3750893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5351 5368 -0.170202 0.329231 1.001613 0.1884555 -0.7689930 0.4955144 0.3572111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5351 5851 -0.377773 -1.015800 0.266165 0.0261564 -0.3119225 0.9094987 0.2735551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5352 5367 -0.665396 0.480047 0.498398 -0.1964643 0.6810150 0.2000648 0.6764573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5352 5852 0.597577 0.683908 0.346675 0.1380041 -0.0148266 0.7380366 0.6603310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5353 5053 -0.012746 0.176605 -1.012105 -0.2148407 -0.5914025 0.3607200 0.6884531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5353 5366 -0.516712 -0.681040 -0.295725 0.5294805 0.0966798 0.8068801 0.2434090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5353 5853 0.210802 -0.227685 1.008138 0.0485938 0.2641035 -0.3398950 0.9013098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5354 5054 -0.160234 -0.078836 -1.003436 0.4088931 0.4465202 -0.7896778 0.0991721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5354 5365 -0.630982 0.859274 0.019071 -0.0161521 0.4492360 -0.6132138 0.6495344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5355 5364 0.473712 -0.372223 0.808054 -0.0077087 0.8596036 0.4003874 0.3173519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5355 5855 -0.080274 0.923668 0.648804 -0.5003764 -0.4435644 0.5890426 0.4537653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5356 5856 -0.583198 -0.817097 0.070895 -0.8637317 0.1181522 0.4877234 0.0461909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5357 5322 -0.818195 0.224457 -0.621040 0.0082160 0.0648777 -0.2180546 0.9737431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5357 5362 0.626740 -0.349863 0.645418 -0.3818818 0.7475000 0.4433045 0.3144695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5357 5857 -0.186436 0.949887 0.278452 -0.4201615 -0.3649785 0.3030752 0.7735635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5358 5361 0.861135 -0.273342 -0.200496 -0.0878245 -0.1876650 0.3762139 0.9030680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5358 5858 0.296649 0.323592 0.743208 -0.6290270 -0.2061180 0.1287690 0.7384165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5359 5320 -0.667630 -0.586469 -0.476098 0.2349948 -0.2092819 0.5255336 0.7904384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5359 5859 -0.291220 -0.373301 0.921455 0.0773490 0.3447738 -0.1339923 0.9258478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5360 5399 0.801194 -0.259041 -0.332944 -0.8880085 0.0570320 0.0059045 0.4562383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5360 5820 0.417570 0.821495 -0.037883 0.6796940 0.2487744 0.6111194 0.3204067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5361 5398 0.170230 -0.578032 -0.645932 0.4576214 -0.0091737 0.5848665 0.6696489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5361 5821 0.805513 -0.197392 0.598448 0.4933239 0.2149583 -0.7128045 0.4498158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5362 5397 -0.796879 -0.622886 -0.174757 -0.1230335 -0.4256125 0.6994787 0.5607552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5362 5822 -0.553211 0.366891 0.566992 0.3000323 -0.4730901 -0.6025259 0.5684443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5363 5356 -0.438611 -0.742951 0.542896 0.7298258 0.3304602 -0.5975381 0.0331443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5363 5396 0.232511 0.757330 -0.184104 -0.2776283 0.4499449 0.1423152 0.8367906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5363 5823 -0.657480 0.552596 0.763344 0.0615918 -0.9275541 0.0332963 0.3670711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5364 5395 -0.969828 0.107456 -0.618464 -0.1325733 0.4656600 -0.1505666 0.8619250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5365 5025 0.501350 0.584661 -0.647815 0.3483757 -0.2614981 0.3136995 0.8437095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5365 5394 -0.475115 -0.470845 -0.741469 -0.1872656 -0.1210195 -0.6615242 0.7160109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5365 5825 -0.518329 -0.535706 0.834464 -0.1968628 -0.0258561 -0.9780783 0.0627635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5366 5393 -0.439691 0.811782 -0.292563 0.0637470 0.1905432 0.6336094 0.7471069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5366 5826 0.713299 0.768999 0.594327 -0.2025141 0.1133407 0.7601315 0.6069119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5367 5027 0.526018 -0.494600 -0.966546 -0.6933343 -0.1820357 -0.3800224 0.5845798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5367 5392 -0.438525 0.814423 -0.612559 -0.3321767 0.5482691 0.3874568 0.6625231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5367 5827 -0.378213 0.399776 0.992124 -0.1772103 0.1150462 0.9751065 0.0672923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5368 5391 0.740243 -0.234800 -0.524745 0.5419071 0.2580747 -0.2703221 0.7527683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5368 5828 0.379048 -0.492369 0.847268 0.7818526 0.0465432 0.4853205 0.3885928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5369 5829 0.618598 -0.689368 0.687779 -0.3316409 0.1135144 0.0201862 0.9363340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5370 5830 0.193036 -0.991518 0.218017 0.4973728 -0.1044012 -0.7883678 0.3466942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5371 5388 -0.735040 -0.476856 -0.507364 -0.5861849 -0.5448273 0.5831867 0.1394411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5371 5831 -0.475420 0.776354 0.395761 -0.4086638 -0.2549609 0.5000537 0.7196771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5372 5387 -0.545071 -0.674497 -0.194068 -0.0232169 0.4494576 -0.8011801 0.3944101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5372 5832 0.565823 -0.763958 0.578192 -0.4272060 0.0121522 -0.7256525 0.5392363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5373 5386 0.639809 -0.756092 0.043455 -0.6971405 0.1092334 0.3980480 0.5861919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5373 5833 0.803255 0.690538 0.102829 -0.2891032 0.9107536 0.1195788 0.2695331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5374 5385 -0.266559 0.176472 0.857723 -0.6677746 0.3047658 -0.1475899 0.6628816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5375 5035 -0.245924 -0.357289 -0.861652 -0.1718120 -0.5253825 -0.2466806 0.7959916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5375 5384 1.028012 -0.067325 -0.089921 0.0574295 -0.4030310 -0.9127704 0.0334388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5376 5383 0.752906 0.401310 -0.516454 0.1518391 0.4627696 0.3262134 0.8101691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5377 5037 -0.531662 -0.147232 -0.832230 0.1384315 0.8317876 0.4264341 0.3272921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5377 5342 -0.256432 0.724369 -0.195285 0.2264443 0.8091818 0.3684892 0.3976977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5377 5382 0.343419 -1.035517 0.401109 0.3828230 -0.2218102 0.8895202 0.1140202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5377 5837 0.579965 0.432838 0.709056 0.1649267 0.0838805 0.5287576 0.8283590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5378 5381 0.445612 -0.390684 -0.737277 -0.6242690 0.2166320 -0.5006721 0.5591835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5379 5839 0.736343 0.492121 0.666659 -0.8769488 0.3126087 -0.3468472 0.1137260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5380 5419 0.185280 0.082179 1.039303 -0.3416867 -0.7569868 -0.2434216 0.5009662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5380 5800 0.207810 0.906773 0.007597 0.1326021 0.8518116 0.4097551 0.2982188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5381 5801 0.832595 -0.012899 0.532736 0.6170597 0.0884370 0.6195655 0.4770270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5382 5417 -0.129162 0.601753 0.860507 0.1767274 0.2882367 -0.8397390 0.4248827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5382 5802 0.236038 -0.692414 0.666334 0.5812402 0.1172797 0.7417145 0.3134723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5383 5003 0.484293 -0.450393 -1.003019 -0.6035129 -0.2308075 -0.3400127 0.6832945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5383 5416 0.872160 -0.526739 0.606724 0.0681014 -0.2402258 0.8680169 0.4291858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5384 5415 -0.920346 -0.152713 -0.238182 0.0110027 0.3465889 -0.0387595 0.9371514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5384 5804 -0.437636 0.433762 0.733427 -0.2777569 -0.4399440 -0.7821907 0.3427509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5385 5414 -0.504650 -0.870022 -0.416302 -0.3655053 -0.2797402 -0.7903710 0.4043081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5385 5805 1.003566 -0.435381 0.018999 -0.3101026 0.9301889 0.0045211 0.1963785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5387 5007 0.141714 0.038725 -0.853357 -0.1959273 0.2462537 -0.6247966 0.7145634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5387 5412 1.004888 0.053462 0.090896 0.3303403 -0.3098735 -0.4508764 0.7691321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5387 5807 -0.141366 0.259246 1.111753 -0.6169830 0.3602659 0.1250276 0.6884102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5388 5411 0.207823 0.397750 0.970074 0.0741686 0.4168461 -0.6468882 0.6342508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5389 5370 0.282063 -0.941257 -0.014952 -0.1869988 -0.0383663 -0.6003246 0.7766401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5389 5410 -0.322158 1.035255 -0.093179 0.3939450 -0.7599998 -0.3634867 0.3675393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5389 5809 -0.681972 -0.412963 0.625077 -0.0742987 -0.0558672 -0.6510187 0.7533480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5390 5369 -0.939617 0.011114 -0.500536 -0.0858020 0.4684609 -0.7682143 0.4278191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5390 5409 0.876478 0.028067 0.460063 -0.4657705 -0.2761423 0.4447874 0.7134195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5390 5810 -0.240283 -0.723434 0.783536 0.2270912 0.3063519 -0.7125020 0.5889983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5391 5011 0.067362 -0.820523 -0.729736 0.6661290 0.1238599 -0.7346105 0.0357525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5391 5408 1.009587 -0.006129 0.218470 -0.6715548 -0.1445867 0.6628286 0.2979381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5391 5811 -0.009652 0.585701 0.722590 0.0374083 -0.3437945 0.0856758 0.9343798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5392 5407 0.546406 0.984964 0.352224 -0.1327002 -0.1197420 0.8581560 0.4812700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5392 5812 -0.847257 0.397703 0.299891 -0.7918040 -0.5286353 0.2411942 0.1881926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5393 5813 0.640801 -0.189688 0.869037 0.2327009 -0.4218090 0.2875467 0.8277949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5394 5405 0.122533 -0.399221 -0.841252 -0.5913131 0.4882616 -0.1587682 0.6218859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5394 5814 0.786314 -0.757242 0.471081 0.7618035 -0.2596620 0.3818386 0.4543462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5395 5015 0.452539 -0.984031 -0.141936 -0.2850654 -0.1112981 -0.5235968 0.7951081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5395 5404 0.151672 0.191131 -1.071299 -0.7813530 -0.4768765 0.0937245 0.3915253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5395 5815 -0.426066 0.851212 0.094506 0.1416775 0.0101252 -0.9692241 0.2010712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5396 5816 -0.832619 0.539551 0.152826 0.6889267 -0.6424361 -0.0442735 0.3327095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5397 5817 0.846547 -0.202605 0.668457 -0.0533072 0.5515514 -0.7494059 0.3624089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5398 5818 0.279570 -0.313881 0.970472 -0.2038935 -0.0837128 -0.0776454 0.9723121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5399 5819 0.261505 -0.753651 0.878870 0.0789847 -0.2431077 -0.1577652 0.9538188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5400 4980 -0.529019 -0.728829 -0.403873 -0.0885772 -0.2897740 -0.0792365 0.9496877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5400 5439 -0.775892 0.545512 -0.005906 -0.0484615 0.9606247 -0.0301188 0.2719275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5400 5780 0.662481 0.540693 0.296419 -0.7037084 -0.0708182 -0.2568879 0.6586258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5401 5438 -0.919664 -0.338982 0.380288 -0.1872741 -0.2677646 0.7814104 0.5316280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5402 5437 0.126000 -0.281890 0.866187 -0.2200193 0.8057146 0.4656340 0.2925756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5402 5782 0.956331 0.791770 0.108195 -0.0987371 -0.1197620 -0.1961184 0.9682178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5403 5396 -0.694548 0.500771 -0.596887 -0.0332301 0.0629569 -0.7202652 0.6900364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5403 5436 0.472677 -0.628944 0.720504 0.1439020 0.4132888 0.7444041 0.5043284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5403 5783 0.637870 0.845168 0.099559 -0.1910359 -0.2764474 -0.4870059 0.8061683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5404 5435 -0.092246 0.722261 0.779504 -0.1002695 0.1435394 0.9833750 0.0481264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5404 5784 0.572893 -0.682081 0.457167 -0.5658083 0.3649757 -0.6095966 0.4183847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5405 5434 0.672609 0.816116 0.093204 -0.0510546 0.4283027 -0.8724955 0.2295687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5406 5433 0.513469 -0.780541 -0.192199 -0.4999768 -0.1597614 -0.0960193 0.8457422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5406 5786 0.525878 0.285073 0.801945 0.2910835 -0.3336568 -0.3444904 0.8278103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5407 5432 0.265963 -0.849291 -0.014923 -0.0366089 0.6765383 0.4712152 0.5647229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5407 5787 0.839129 0.314044 0.357989 0.2890696 0.1255046 0.6517905 0.6898236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5408 5431 -0.150557 -0.210524 -0.905043 0.3396644 0.1777487 0.1791150 0.9060636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5408 5788 -0.124627 -1.099258 0.374759 0.3087704 -0.8327001 0.0216237 0.4591338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5409 5789 -0.822341 -0.655732 0.333225 0.3370690 0.0991648 -0.9118741 0.2122178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5410 5429 -0.704170 0.478685 0.479450 -0.3521054 0.4539616 -0.6350399 0.5163962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5410 5790 0.484331 0.658466 0.447446 0.4828735 0.7292265 0.4124683 0.2548171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5411 4991 -0.462305 -0.124037 -0.836492 -0.6368532 0.0560686 0.0432825 0.7677245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5411 5428 -0.709088 -0.177433 0.433518 0.3127834 -0.0179701 0.8429444 0.4373653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5411 5791 0.455567 0.176202 0.739541 -0.5705049 -0.3676302 -0.5333093 0.5049291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5412 5427 0.453918 0.661215 -0.616666 0.4519751 -0.4202157 -0.5524008 0.5603487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5412 5792 -0.169274 0.520239 0.395749 -0.2776362 0.5074329 0.0216348 0.8154520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5413 5426 -0.765438 -0.171013 0.675975 0.2681360 -0.2307058 0.9229419 0.1518425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5413 5793 0.474591 -0.845975 0.427838 0.5519854 0.2476723 0.7754925 0.1805047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5414 5425 0.283834 0.079845 -0.964538 -0.6917307 0.6446537 0.2198941 0.2399517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5414 5794 0.256532 0.757118 -0.011628 -0.8812422 0.0685499 -0.4226931 0.2001092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5415 5424 -0.308087 -0.166635 -0.712944 -0.2538846 0.3618149 0.6955649 0.5664116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5415 5795 -0.822486 0.428670 0.336779 -0.1383614 0.1237165 0.5570563 0.8094681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5416 5423 -0.623681 -0.526282 0.683082 -0.0453603 0.0936301 0.5899884 0.8006807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5416 5796 0.760500 -0.319576 0.563590 -0.0519387 -0.2837507 -0.8942107 0.3423085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5417 5422 -0.751737 -0.837808 0.357366 -0.5423589 0.0616082 -0.5394737 0.6411079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5417 5797 0.021545 0.271015 0.936898 0.0869034 0.6294314 -0.6908757 0.3448981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5418 5381 0.560513 -0.796342 0.268458 0.0796642 -0.7486164 0.2567550 0.6060561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5418 5421 -0.429359 0.809201 -0.243395 0.7826372 -0.3052829 -0.4954104 0.2210201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5418 5798 -0.548500 -0.226914 0.830163 0.5206238 -0.4716101 -0.0958622 0.7052271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5419 5799 0.258088 0.794300 0.424746 0.0512165 0.0566839 -0.6031996 0.7939232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5420 5459 -0.085030 -0.468998 0.937227 0.1030427 -0.2254996 0.0562526 0.9671441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5420 5760 0.180993 1.152845 0.303262 0.4677946 -0.2240016 -0.8548430 0.0153283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5421 4961 0.669390 -0.727337 -0.564830 -0.0568700 0.0067044 0.9248100 0.3760948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5421 5458 -0.577383 -0.685574 0.479280 -0.8070358 0.0845483 0.3302055 0.4821920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5421 5761 -0.412492 0.686565 0.459761 -0.3956323 -0.2316295 0.8877709 0.0410562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5422 4962 -0.402196 0.731241 -0.738868 -0.5934055 0.0378879 -0.7916867 0.1402377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5422 5457 0.317850 -0.472985 -0.745339 0.2533880 0.5901709 -0.2066066 0.7381101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5422 5762 0.295752 -0.582413 0.730157 -0.4381103 -0.0971240 -0.8780325 0.1663889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5423 5456 -0.856679 0.238592 0.229279 -0.0380367 -0.0499038 -0.9817819 0.1793521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5424 5455 0.434208 0.303267 -0.827981 -0.5547832 0.2327903 0.7094334 0.3670538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5424 5764 0.162168 0.628469 0.414732 -0.0131226 0.0869687 0.7800547 0.6194989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5425 4965 0.788975 0.123014 -0.505978 -0.8194966 -0.1791760 0.5282518 0.1314201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5425 5454 0.634642 -0.105717 0.813939 0.1968654 -0.4772448 -0.1656289 0.8402669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5425 5765 -0.663480 -0.025007 0.575656 0.1962466 0.0680634 -0.6046967 0.7688930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5426 5766 -0.165415 0.486864 0.882258 -0.3700272 0.1752133 -0.1654595 0.8972198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5428 5451 0.345041 0.917151 0.018448 -0.2252633 0.2257289 -0.2197280 0.9219667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5428 5768 0.457055 -0.337232 0.820727 0.4033526 -0.3974668 0.4040879 0.7183590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5429 5450 -0.252429 -0.778593 -0.650789 -0.6285794 -0.5891055 0.2093167 0.4626329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5429 5769 -0.902101 -0.227496 0.514113 0.0835867 0.2112833 0.4150489 0.8809694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5430 4970 -0.343595 -1.116295 0.078002 -0.4713314 -0.8629381 -0.0671476 0.1693391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5430 5409 -0.413806 0.103083 0.804946 0.5019378 -0.4509948 -0.7379457 0.0099128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5430 5449 0.398166 -0.183566 -0.772308 0.0763448 0.1478579 0.6740506 0.7196981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5430 5770 0.603567 0.881554 0.297092 -0.9231579 -0.1048976 -0.0657192 0.3639463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5431 5448 0.108969 -0.945458 -0.308400 -0.2311857 0.1158541 0.9638552 0.0641417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5431 5771 -0.424794 -0.333629 0.799492 0.7735020 -0.3813483 0.0007860 0.5062288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5432 5447 -0.514365 -0.742589 -0.462421 0.0996625 0.5623658 -0.8066775 0.1519326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5432 5772 -0.487551 -0.112325 0.870116 -0.5288699 -0.5127149 0.6735695 0.0610253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5433 5773 0.813410 -0.599959 0.467726 0.6991204 -0.0717014 -0.2232935 0.6754477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5434 5774 -0.276414 0.396467 0.841008 -0.1209023 -0.2297511 0.1557091 0.9530749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5435 4975 0.611863 -0.901752 -0.158644 -0.0185168 -0.0539911 -0.6100949 0.7902698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5435 5444 0.172260 -0.443483 0.835438 0.0489640 -0.9128253 -0.0714287 0.3990619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5435 5775 -0.729626 0.775819 0.354205 -0.0548311 -0.1479127 -0.3391412 0.9274150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5436 5443 -0.885270 -0.077861 0.615088 -0.5766909 0.4114086 -0.7053659 0.0250905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5436 5776 0.121175 -0.426606 0.528844 0.1306650 0.1717829 -0.1134820 0.9698140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5437 5442 -0.628236 0.380105 -0.686619 0.7805382 -0.2382828 0.0101414 0.5778223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5437 5777 -0.653466 -0.161753 0.683973 -0.4440924 -0.4650119 0.5309964 0.5518956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5438 5441 0.028778 0.533995 0.763542 0.4139086 -0.7358323 0.4876056 0.2224213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5438 5778 -0.842574 -0.481298 0.447770 -0.0153427 -0.4445161 0.0228507 0.8953479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5440 5479 -0.817612 0.042984 -0.769040 0.7091174 -0.2472073 -0.6310664 0.1944124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5440 5740 -0.496904 -0.326937 0.467933 -0.3740076 -0.8330424 0.3827232 0.1402914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5441 5478 0.418040 -0.244064 -0.848369 -0.3469470 0.3717766 -0.7890148 0.3447689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5441 5741 0.722424 0.563972 0.237240 -0.2747396 -0.1490420 -0.8646335 0.3933365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5442 4942 0.519388 -1.078161 -0.211573 -0.4404418 -0.0279836 0.4249448 0.7903479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5442 5477 -0.978621 -0.367192 -0.041418 0.0194900 -0.0256745 -0.9482894 0.3157659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5442 5742 -0.374049 0.987116 0.173286 0.5865231 -0.7715345 -0.2088307 0.1308240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5443 5476 0.859024 0.067904 -0.839159 0.2343221 0.2116181 -0.6585740 0.6830749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5444 5475 0.817787 -0.484816 -0.610308 0.0452064 0.4292828 0.8692252 0.2410814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5444 5744 0.500559 0.830633 0.328026 -0.4994588 0.5153379 0.3265923 0.6150653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5445 5434 0.177094 0.470913 -1.002654 -0.5688948 0.3442939 0.4701545 0.5803233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5445 5474 -0.070610 -0.415368 0.906873 -0.6029008 -0.2950292 0.7260889 0.1492089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5445 5745 -0.636932 0.602081 0.216874 -0.9465356 0.0536700 -0.1308869 0.2899284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5446 5433 -0.029254 0.534951 0.859701 0.0733099 0.0323977 -0.5622562 0.8230698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5446 5473 0.064956 -0.362854 -1.118175 0.7544112 -0.4812473 0.4406673 0.0712530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5446 5746 -0.103463 -0.905114 0.256057 0.2357578 0.4361537 0.1830233 0.8489350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5447 5472 0.732107 0.171416 0.515294 0.0338660 -0.9147003 0.3042115 0.2638786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5447 5747 0.302316 -0.975586 0.365439 0.0817474 -0.3554692 -0.1544208 0.9182120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5448 4948 0.043351 -0.619670 -0.738871 0.1175121 0.1765527 0.9419073 0.2604432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5448 5471 -0.064353 0.770301 -0.617563 -0.0453651 -0.4672326 -0.5164045 0.7162137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5448 5748 0.157080 0.524339 0.867193 -0.6863088 0.2031541 0.2530213 0.6509139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5449 5749 0.997819 -0.315949 0.293902 0.6873840 -0.0150972 0.7255656 0.0288082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5450 5469 -0.958924 0.136664 0.363091 0.6540356 -0.4278287 -0.4167031 0.4642828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5450 5750 -0.214334 -1.101363 0.266159 0.7050290 0.3970971 -0.3675781 0.4584041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5451 5751 0.188426 -0.267649 0.689604 -0.1325600 0.2773008 0.0346644 0.9509629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5452 5752 -0.725247 0.661939 0.170416 -0.7745407 -0.5399051 0.3266225 0.0436688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5453 5426 -0.685612 0.573866 0.086611 0.7528954 -0.0490427 -0.2795596 0.5937928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5453 5466 0.781043 -0.654179 -0.251845 0.1081943 0.2430777 0.0962832 0.9591334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5453 5753 -0.732430 -0.752040 0.398536 0.9140512 0.0110897 -0.2983772 0.2745148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5454 5465 0.886779 0.044812 0.018948 0.0696606 0.4508871 -0.0541971 0.8882066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5454 5754 -0.024902 0.107574 1.045844 -0.2589374 -0.0115092 -0.2336692 0.9371327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5455 5464 0.821796 -0.533649 -0.371107 -0.3553815 0.6781090 -0.6307045 0.1268229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5455 5755 -0.287221 -0.711972 0.636188 0.0991418 -0.3574510 -0.9234581 0.0981058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5456 5463 0.556461 -0.582761 0.234771 0.5279042 0.5316528 0.4500049 0.4859609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5456 5756 0.640975 0.599418 0.514330 -0.4929958 -0.5837053 -0.4481278 0.4641386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5457 5757 -0.580653 -0.232855 0.830405 -0.3925978 -0.6081361 0.6600530 0.2009166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5458 5461 -0.821872 0.304253 -0.563602 0.1747241 -0.2495965 -0.9100765 0.2809517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5459 4959 -0.308844 -0.883367 0.176530 -0.0125387 -0.6127972 -0.3667262 0.6998816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5459 5759 0.198495 0.887722 0.005565 -0.4058367 0.6685812 0.3201986 0.5345733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5460 5499 -0.060839 -0.068660 -0.944320 0.3192101 -0.5988044 0.4976343 0.5402761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5460 5720 -0.713829 -0.433033 0.411322 -0.7269630 0.0522635 0.5912407 0.3452937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5461 5721 0.434010 0.632348 0.537920 0.2667899 0.1996913 0.6321654 0.6995094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5462 5457 0.259183 0.966587 0.411277 0.0710410 0.6760918 -0.5191461 0.5180158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5462 5722 0.620171 -0.587102 0.497988 0.0228826 -0.3196878 0.1795701 0.9300702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5463 5496 -0.768471 0.307224 0.592952 0.0946013 0.2772399 -0.0561412 0.9544825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5463 5723 0.800208 0.671513 0.582695 -0.1499564 -0.1214632 0.8785673 0.4368972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5464 5495 -0.407896 0.145054 1.125435 -0.1289853 0.7204258 -0.4797745 0.4839069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5464 5724 0.791264 -0.610589 0.117300 0.0856407 0.9014075 0.1573159 0.3941852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5465 4925 0.773728 -0.021777 -0.646316 0.6040021 -0.2348644 0.1237027 0.7514771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5465 5494 0.434553 0.292678 0.877501 -0.0731046 -0.4565266 -0.3643615 0.8083810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5465 5725 -0.966745 -0.028390 0.474162 0.5203377 -0.3442733 -0.2187008 0.7502630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5466 5493 0.493906 -0.756955 0.339900 -0.1325455 -0.8557404 -0.3184050 0.3856920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5466 5726 -0.822160 -0.535465 0.041551 -0.1325815 -0.8838880 0.4478456 0.0244640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5467 5452 -0.201021 0.824812 -0.219289 0.5064629 -0.2394837 -0.6979879 0.4460445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5467 5492 0.139322 -0.970606 0.403830 0.0332552 -0.4867380 -0.3518930 0.7988438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5467 5727 0.307051 0.335371 0.952861 0.2590191 0.0802907 -0.9622719 0.0222572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5468 5451 -0.013967 0.261184 -0.906480 0.1712681 0.3982462 0.8738721 0.2200334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5468 5491 0.095040 -0.079685 0.990657 -0.5042410 -0.1307432 -0.7203992 0.4578998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5468 5728 0.347210 0.792806 0.200287 0.3216340 0.5599655 0.5611411 0.5177943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5469 5490 -0.373916 0.200828 0.889607 0.1669592 0.0959553 -0.7438289 0.6400280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5469 5729 0.918573 0.406779 0.630999 -0.4836620 -0.7216917 -0.4629420 0.1758316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5470 5449 -0.452529 0.692442 0.412428 -0.0114602 -0.4790977 -0.1268155 0.8684767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5470 5489 0.467879 -0.766638 -0.510702 -0.5131233 -0.1197994 -0.8283306 0.1903181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5470 5730 -0.037621 -0.558283 0.855124 -0.2095624 -0.2837121 0.1884534 0.9165568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5471 5488 -1.169102 -0.029812 0.198652 -0.4783388 0.4049251 0.2433040 0.7402910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5471 5731 0.208675 0.700403 0.801130 -0.5048299 0.2631122 0.5077968 0.6465765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5472 4932 -0.037030 0.967636 -0.355880 0.2533827 0.0867777 0.3714561 0.8889810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5473 4933 -0.870291 -0.480983 -0.201377 -0.3498368 0.5258047 -0.3480123 0.6928427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5473 5733 0.851577 0.246285 0.311681 0.6163203 0.5595165 0.0736179 0.5492458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5474 5485 -0.954566 -0.021678 0.323481 -0.0977451 0.1050306 -0.9377244 0.3163660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5474 5734 0.339377 -0.909900 0.619494 0.0460004 0.9103438 -0.3746350 0.1697257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5475 5484 -0.723400 -0.606254 -0.080017 0.2133629 0.4202275 -0.8722390 0.1307070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5475 5735 -0.150154 -0.356113 1.084209 0.2634848 0.2507419 -0.0681700 0.9290087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5476 5483 0.341140 0.687346 -0.739157 0.1220054 0.1096788 -0.8978383 0.4086216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5477 4937 0.342780 0.838294 -0.127066 0.2914670 0.2389056 -0.7689848 0.5163657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5477 5482 1.052349 -0.193775 0.019297 0.6706393 0.0450358 -0.0764548 0.7364573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5477 5737 -0.214396 -0.763981 0.431241 -0.5187837 -0.4154704 0.7098998 0.2330021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5478 5481 -0.273633 1.064129 0.015014 0.2041815 -0.2791534 -0.8771655 0.3331126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5478 5738 -0.675840 -0.197567 0.632216 0.1138294 -0.1150983 0.3643982 0.9170655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5479 4939 0.036607 -0.741808 -0.403959 -0.4405501 -0.5352154 -0.6217944 0.3644610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5479 5739 -0.067645 0.828586 0.551731 0.3525519 -0.2082597 -0.8932853 0.1854087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5480 5700 0.565335 -0.077680 0.882803 -0.0762323 -0.4469073 -0.8858358 0.0987794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5481 4901 -0.578382 -0.300639 -0.977275 0.0176862 0.3941635 -0.7810180 0.4840798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5481 5518 -0.717321 -0.644922 0.351151 0.4936576 0.4512722 -0.2093279 0.7133284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5481 5701 0.585556 0.221222 0.979404 -0.4163772 0.1555874 0.7561992 0.4801930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5482 5517 0.860297 0.339339 0.198464 -0.1318211 -0.5449309 -0.3526012 0.7492302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5482 5702 -0.321991 0.323113 0.880057 0.3590442 -0.4778049 -0.4224365 0.6814229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5483 4903 0.564598 0.562508 -0.371251 0.0141439 -0.9175058 0.2396933 0.3170649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5483 5516 -0.567423 0.075338 -0.978719 -0.0953828 -0.0447386 0.1774508 0.9784742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5483 5703 -0.851819 -0.834111 0.368792 0.2309701 0.6141327 -0.6955581 0.2927333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5484 5515 0.656857 0.371225 0.500929 0.2343676 -0.5190734 -0.6120770 0.5486314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5484 5704 -0.390615 -0.540503 0.738621 0.4685074 -0.4385636 0.6747633 0.3644959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5485 5514 0.911335 -0.540025 0.056716 0.0746083 0.7920520 0.0910987 0.5989894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5485 5705 0.411565 0.662096 0.560445 -0.1315534 -0.3227306 0.0131897 0.9372111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5486 5513 0.129158 -0.475168 0.777127 -0.6909658 -0.5332342 -0.4063339 0.2704078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5487 5472 0.660048 -0.173067 -0.751887 -0.8263055 0.3944237 -0.2254701 0.3328850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5487 5512 -0.665759 0.090796 0.688602 0.2096223 0.7024005 0.5102171 0.4498562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5487 5707 0.684794 0.413037 0.566963 0.2894157 0.5484788 0.4580752 0.6368490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5488 5511 -0.768080 0.824143 -0.225218 -0.0865753 -0.0294791 -0.5566996 0.8256641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5488 5708 -0.620344 -0.108580 0.724777 0.0664438 0.1839557 -0.6137671 0.7648761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5489 5510 -0.531267 0.872719 -0.021135 -0.4098123 -0.2549624 -0.4800153 0.7325526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5490 5509 -0.605651 -0.581233 0.547376 -0.2183309 -0.5605801 -0.1481980 0.7849324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5490 5710 -0.661701 0.751839 0.263962 0.2131275 -0.8587090 -0.1566835 0.4389143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5491 5508 0.885471 -0.155440 0.205094 0.5169939 0.2131085 -0.5524564 0.6181374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5491 5711 -0.342051 -0.171342 0.862467 -0.2368863 0.0465521 0.1938186 0.9508691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5492 5507 0.880050 -0.523808 -0.378031 0.5048772 0.5303024 0.4446331 0.5159261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5492 5712 0.473185 0.794353 0.344281 -0.3098728 0.4713713 0.7699213 0.2983441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5493 5506 -0.220295 -0.093482 -0.995364 0.3039896 0.7750352 -0.4364840 0.3411634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5493 5713 0.747475 -0.788095 0.043638 0.7201571 0.1778525 0.6460287 0.1799699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5494 5505 0.519865 0.579747 0.203203 0.3366420 0.1686106 0.8795951 0.2907837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5494 5714 -0.040449 -0.258937 1.171697 0.7210816 -0.1334090 0.3233295 0.5980815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5495 5504 -0.520039 -0.908045 -0.140834 0.3904009 0.1938696 -0.0237120 0.8996886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5495 5715 -0.188665 -0.055139 1.103482 0.3905493 -0.1667744 0.2569673 0.8681160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5496 5503 -0.898622 0.374585 -0.015267 -0.5112216 0.5560112 0.4775821 0.4487977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5496 5716 0.245864 0.729503 0.745369 -0.3691122 0.2546494 0.8723264 0.1948242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5497 5502 0.299970 -0.640742 0.594275 -0.0233842 0.4029185 0.3038213 0.8630194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5497 5717 0.534714 0.673415 0.558115 -0.2500819 -0.5502236 -0.1091500 0.7891763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5498 5461 0.106366 0.944636 -0.346222 0.1011109 -0.6192321 -0.2535641 0.7362292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5498 5718 -0.418745 0.162202 1.027696 -0.1732488 -0.3474437 0.8230640 0.4145278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5500 5539 -0.970238 0.028152 -0.591682 -0.5324952 -0.1229705 0.1662783 0.8207793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5501 5498 0.660502 0.563294 -0.914025 0.2081640 0.7445251 -0.4538740 0.4431124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5501 5538 -0.479725 -0.479257 0.757183 0.6038555 0.3431863 0.7190567 0.0232196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5502 5537 -0.768104 -0.432970 0.299846 -0.5338481 -0.1885779 0.2705180 0.7786299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5502 5682 0.271353 0.531892 0.782060 -0.5979325 0.4499660 0.4004486 0.5288179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5504 4884 0.484779 -0.314425 -1.068443 -0.3141468 -0.0492203 0.4182666 0.8508479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5504 5535 -0.637101 -0.848797 0.291624 -0.0173818 0.2944554 -0.9089010 0.2947758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5504 5684 -0.393832 0.290456 0.934524 -0.7271241 -0.0446251 0.4409543 0.5242694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5505 5534 0.084773 -0.799151 0.587698 -0.3640713 -0.5841369 -0.2422667 0.6837712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5505 5685 -0.125539 0.718392 0.787666 -0.5156434 -0.1910500 -0.0040198 0.8352219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5506 5533 0.916600 0.178526 0.277510 0.5925673 -0.2120786 -0.0625854 0.7745771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5507 5532 -0.032613 -0.416463 1.028933 -0.2918666 -0.3253849 -0.2032603 0.8761414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5507 5687 0.812681 0.462966 0.535066 -0.2698154 -0.0209366 0.1722110 0.9471561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5508 5531 -0.018763 0.970895 0.001624 0.0952412 0.2191320 0.8686954 0.4339107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5508 5688 -0.648693 -0.010511 0.682107 0.0754823 0.2411407 -0.4504186 0.8563158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5509 5530 0.567330 -0.875685 0.135867 -0.0236489 0.3504746 -0.6929599 0.6296148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5509 5689 0.099718 0.078234 1.002488 -0.6868787 0.1008932 0.1192212 0.7097919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5510 5529 -0.778951 -0.134432 0.572698 -0.6865641 0.5013005 0.4956331 0.1779756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5510 5690 0.194108 0.796415 0.586486 0.2287734 -0.4101409 -0.8757351 0.1119611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5511 4891 0.014456 0.579058 -0.712350 -0.1307740 -0.0957243 0.3229006 0.9324539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5511 5528 -1.000033 -0.522307 -0.010307 -0.3875750 -0.2712822 -0.8735562 0.1144164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5511 5691 0.067099 -0.621440 0.762661 0.4147708 0.0340479 -0.8854739 0.2067411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5512 5527 0.123227 0.970179 -0.494276 0.0558173 -0.4459505 0.2997387 0.8415279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5512 5692 -0.205840 0.381564 0.775994 -0.0053955 -0.3494276 0.7976072 0.4916239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5513 5526 0.565756 0.185361 -0.839056 0.1940829 -0.1325105 -0.7707198 0.5922531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5513 5693 1.012694 0.304946 0.434306 -0.2021380 0.7107614 0.0500057 0.6719061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5514 5525 -0.483866 -0.545418 0.658777 -0.5356808 -0.2151061 -0.4919797 0.6517142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5514 5694 -0.383147 0.796712 0.293434 0.4591423 -0.5613817 -0.6361920 0.2632464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5515 5524 -0.423445 0.654143 -0.247720 -0.1709555 -0.3691210 -0.2980459 0.8635349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5515 5695 0.662500 0.471318 0.505152 -0.8434720 -0.1092895 -0.4476863 0.2760213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5516 4896 0.696538 0.330495 -0.441145 0.0586768 0.0189882 -0.8614897 0.5040159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5516 5523 -0.677838 0.199239 -0.783268 -0.8585842 -0.0884475 0.4799521 0.1570227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5516 5696 -0.858939 -0.503720 0.318252 -0.1441094 0.0358083 0.9799941 0.1325208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5517 5522 0.132266 0.980585 -0.470138 0.3813554 0.3778080 -0.6533161 0.5338607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5517 5697 0.830388 0.053922 0.681928 -0.0403661 0.1752987 0.9832498 0.0293378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5518 4898 0.487275 -0.682717 -0.101738 -0.7738894 -0.1650051 0.5921093 0.1525615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5518 5698 -0.268186 0.885513 0.110280 0.7881280 -0.1653474 -0.5821278 0.1124353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5519 5480 -0.360692 -0.371200 0.749954 -0.1721665 0.2803133 0.3506714 0.8768196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5519 5699 0.672562 0.627708 0.359497 -0.4171193 0.4142567 0.3484597 0.7300540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5521 5518 -0.732374 0.445798 0.373740 0.2449849 0.8734267 0.2995381 0.2956098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5521 5558 0.892202 -0.531080 -0.161735 0.0395765 -0.7313864 -0.6659186 0.1416335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5521 5661 0.763306 0.440770 0.727496 -0.5457759 0.6773403 -0.4021376 0.2856995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5522 5557 0.182751 0.363393 -1.178043 -0.2341117 -0.0654600 -0.9574430 0.1555943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5522 5662 -0.599419 0.827137 0.130633 -0.1541583 -0.0009669 -0.9681497 0.1972829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5523 5556 0.445023 -0.125160 0.980388 0.5070432 -0.5469906 -0.1757716 0.6425051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5523 5663 -1.017190 0.141834 0.424809 -0.1381261 -0.0542682 0.9779784 0.1467460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5524 5555 -0.760254 0.215029 0.500480 -0.3619701 0.2704422 -0.8762051 0.1676404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5525 5554 0.706485 -0.684387 -0.457556 -0.2543801 0.3190389 0.7853191 0.4655952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5525 5665 -0.282413 -0.603737 0.604265 0.0697496 -0.1453674 0.9161028 0.3670953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5526 5666 -0.410739 0.849997 0.097633 -0.1083181 -0.2114201 -0.6787036 0.6949318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5527 5552 -0.050694 0.884269 -0.745286 -0.2459380 -0.3594090 -0.8996654 0.0306896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5528 5551 0.574359 -0.238213 -0.758372 -0.8092981 -0.4822643 -0.3050683 0.1392516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5528 5668 0.656387 0.731194 0.055559 -0.3096393 0.3442580 -0.5164210 0.7203605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5529 5550 -0.643887 0.876809 0.192997 0.2798181 -0.6431291 -0.0111569 0.7127148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5530 5670 -0.571127 -0.731586 0.567655 0.5751055 -0.1578500 -0.1419285 0.7900591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5531 5671 0.578155 0.880992 0.367885 -0.7504595 0.0829900 0.4669208 0.4603347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5532 5547 0.570530 -0.968535 0.376386 0.0267520 0.2886908 -0.3380070 0.8953732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5532 5672 0.768319 0.566649 0.112006 -0.2308562 -0.3756321 -0.3271136 0.8358245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5533 5546 0.838389 0.418475 -0.429077 -0.7293027 -0.0125634 0.1714258 0.6622484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5533 5673 -0.589021 0.884251 0.292094 -0.3841292 -0.4931719 -0.7036271 0.3378389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5534 4874 -0.652048 -0.485835 -0.456047 0.7618055 -0.0484802 0.6062593 0.2230509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5534 5545 0.600658 -0.460475 -0.775631 -0.1933299 -0.1289414 0.8093116 0.5394556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5534 5674 0.715084 0.445833 0.539635 -0.3894068 -0.0553967 0.2494930 0.8848993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5535 5544 0.761005 0.299487 0.426498 0.2962806 0.6133590 -0.2590844 0.6847509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5535 5675 0.320412 -1.067116 0.403390 0.1652435 0.1199733 0.2612511 0.9434240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5536 5503 -0.744240 -0.557395 -0.531923 0.1229682 0.1464220 -0.2788633 0.9411029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5536 5543 0.515742 0.681518 0.439476 -0.3623537 -0.6955032 -0.0570764 0.6178328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5536 5676 -0.696512 0.212881 0.820256 0.4818506 -0.6785899 -0.0189613 0.5540544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5537 5542 -0.904650 -0.261020 0.130589 0.1106153 0.6888621 0.1743849 0.6948548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5537 5677 0.357606 -0.781417 0.486223 0.3395583 -0.0765665 0.9221775 0.1686014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5538 5541 0.330713 0.534379 -0.562924 -0.1673097 -0.7735436 -0.0190671 0.6109618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5538 5678 -0.470429 0.871668 0.647405 -0.6689737 0.3764007 0.4483494 0.4580170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5539 5679 -0.676506 -0.639970 0.309528 -0.2316535 -0.7884183 0.5672282 0.0546388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5540 5579 -0.560373 0.570461 0.893557 0.8743654 0.0781775 0.4785415 0.0192752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5540 5640 0.331350 -0.717640 0.675597 0.3527973 -0.1730429 0.5350443 0.7478756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5541 5641 0.657226 0.371221 0.541417 -0.0425414 0.0173316 -0.9974505 0.0546106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5542 5577 -0.206313 -0.037899 -1.104496 0.0153143 -0.9050920 0.2047695 0.3723485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5542 5642 -1.005719 -0.697261 0.290884 -0.6604033 -0.2817254 0.5364729 0.4435032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5543 4843 -0.681448 0.502614 -0.287570 0.5306254 0.3902668 0.6626072 0.3564831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5543 5643 0.706560 -0.616670 0.273418 0.0947248 -0.1439493 -0.9649354 0.1980038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5544 5644 -0.490644 -0.425650 0.836206 -0.2841358 -0.8064507 0.2877070 0.4314264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5545 5645 -0.008056 -0.978641 0.127699 0.6591826 0.1097329 0.2109104 0.7134100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5546 5646 -0.192614 -0.332872 1.036328 0.3195470 -0.0479331 0.7353534 0.5956907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5547 5572 0.449356 -0.389583 0.775310 0.5717091 -0.0382858 -0.8195475 0.0049745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5547 5647 0.168440 1.043507 0.420771 0.4883983 0.6483711 0.4814857 0.3305352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5548 5531 -0.130937 0.934657 0.631976 0.5250348 -0.0662400 -0.3150601 0.7878375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5548 5571 0.076408 -0.948832 -0.492042 0.5357500 -0.2096691 0.6907023 0.4381109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5548 5648 0.523385 -0.380878 0.746881 -0.2846478 0.7948269 -0.4535581 0.2855011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5549 5530 -0.502176 -0.223667 -0.945703 -0.0241741 -0.0673189 -0.1679575 0.9831958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5549 5570 0.308288 0.369668 0.821559 -0.0151862 0.5951899 -0.6943820 0.4041683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5550 5569 -0.250668 1.150991 0.223871 0.3985035 -0.1205642 -0.5583107 0.7175990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5550 5650 0.167797 -0.028368 0.697453 -0.1195429 0.5738964 0.7935010 0.1634275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5551 5568 -0.592824 0.291554 0.813009 0.4991678 0.7993075 0.2233926 0.2490678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5552 5567 -0.204636 -0.869695 0.160577 0.2458429 -0.5725645 -0.7383983 0.2578740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5552 5652 -0.413110 0.124015 0.764007 0.1276557 -0.6158243 -0.5739520 0.5244459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5553 5526 -0.794629 0.710644 0.182949 -0.0030898 -0.6743816 -0.6374606 0.3726177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5553 5566 0.450774 -0.572259 -0.179892 0.2498883 0.3884103 0.8517287 0.2474906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5554 5565 -0.497389 -0.487121 -0.851701 -0.2817922 -0.3813266 -0.1013674 0.8745901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5554 5654 -0.742356 0.587351 0.071072 0.4650315 -0.7371982 -0.2391494 0.4278927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5555 5564 0.506482 -0.486426 -0.666047 -0.3008802 -0.7352779 -0.0182011 0.6070472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5555 5655 -0.511810 -0.681898 0.234217 -0.5908482 -0.5167049 0.5638738 0.2568283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5556 4856 0.407241 -0.631095 -0.507486 0.1140641 0.1264222 -0.7681767 0.6171802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5556 5563 0.820976 0.464407 -0.354475 -0.2250733 0.6687230 0.2307161 0.6700161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5556 5656 -0.402813 0.784244 0.521489 -0.0412752 -0.3184081 0.2233306 0.9203456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5557 5562 -0.426980 -0.471351 -0.775379 0.1732419 -0.6063764 0.1936849 0.7515192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5557 5657 0.318197 -0.837911 0.055479 -0.1524520 0.5502240 -0.7076295 0.4162600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5558 5561 -0.701879 -0.407168 -0.788041 0.3627067 -0.5542619 -0.5807232 0.4732845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5558 5658 -0.556126 0.774139 0.341130 0.0952053 -0.1560811 -0.8276033 0.5307046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5559 4859 -0.181896 -0.993225 -0.287695 -0.7626092 -0.0363734 -0.6402909 0.0844491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5559 5659 0.341939 1.241801 0.198500 -0.7725649 -0.3450096 -0.4487820 0.2875876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5560 4820 -0.467804 0.900508 -0.078543 -0.0894909 -0.4282871 0.5806554 0.6865864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5560 5620 0.543738 -0.972022 0.016200 0.8830239 0.2079082 0.4049413 0.1143048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5561 5598 0.532082 -0.792591 0.520127 -0.0234318 0.1302694 -0.3121475 0.9407682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5562 5597 -1.000227 -0.141345 0.526597 0.4728166 0.7170888 -0.4815657 0.1741339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5562 5622 -0.030885 -1.116773 0.366314 0.2424889 -0.5480302 0.2502348 0.7604239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5563 5596 0.582384 0.017914 0.733532 0.1079329 0.6387307 0.6007086 0.4685326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5563 5623 -0.459826 0.906910 0.256888 -0.7240428 0.5821748 0.2166869 0.2998020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5564 5595 -0.821933 0.167044 -0.528678 0.5732296 -0.1506996 -0.3436160 0.7284405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5564 5624 -0.105093 -1.000989 0.278956 0.5901911 -0.7450644 0.2017311 0.2363433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5565 5594 -1.031544 -0.119649 -0.572783 -0.2285587 -0.5370793 -0.2477050 0.7732716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5565 5625 -0.502269 0.171379 1.025991 0.1734000 0.3096170 0.4032837 0.8434643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5566 5593 -0.932406 0.217522 -0.019382 -0.2286624 -0.5985636 0.6615373 0.3896197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5566 5626 -0.043447 0.093642 0.997211 -0.3206674 -0.2815820 0.9039859 0.0263348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5567 5627 -0.037181 0.640189 0.515105 -0.1115909 -0.7303732 -0.3150642 0.5956820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5568 5591 0.376278 0.027808 -1.049106 0.0578623 0.6529021 0.7550462 0.0166158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5569 5590 -1.064257 0.089193 -0.082225 0.1007326 0.2835433 0.8466890 0.4388325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5569 5629 -0.202164 1.050045 0.441291 -0.1203205 0.7236922 0.4828253 0.4781969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5570 5630 0.316114 -0.658232 0.034183 0.6457770 -0.0420681 0.5475096 0.5305050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5571 5588 -0.759115 0.181342 0.656812 -0.2168404 -0.6351117 -0.7259897 0.1501741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5571 5631 0.370250 -0.137163 0.578372 0.0732316 -0.2619531 0.5576403 0.7842544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5572 5632 -0.439026 -1.001029 0.429678 0.1994477 0.1387434 -0.3401092 0.9084584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5573 4833 -0.506125 -0.651495 -0.250657 -0.6135235 0.5621771 0.3293742 0.4461596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5573 5586 -0.459084 0.093734 0.871856 -0.4759214 0.0938619 0.5259452 0.6986204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5573 5633 0.617750 0.928595 0.434213 -0.0280307 0.2198364 -0.1883601 0.9567689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5574 5545 0.677784 0.740540 0.050666 -0.4240908 0.3683856 0.0905911 0.8223334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5574 5585 -0.799505 -0.756856 0.149560 0.2178928 0.3530261 -0.0684467 0.9073094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5574 5634 0.312911 -0.482855 0.552642 0.2860694 0.6508751 0.2575315 0.6543725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5575 5544 -0.426148 0.480751 -0.647665 -0.0632931 -0.2961365 -0.9487208 0.0906969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5575 5584 0.547423 -0.488068 0.601445 -0.1964349 0.6652552 0.1762320 0.6984205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5575 5635 0.429323 0.737129 0.199875 0.3406415 0.6731084 0.3049770 0.5812723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5576 5543 -0.216053 0.774521 0.252526 -0.6597401 0.2829829 -0.4080760 0.5640369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5576 5583 0.173070 -0.945368 -0.319883 0.7629689 0.1696704 0.3861083 0.4899090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5577 5582 -0.614505 0.239296 0.705308 -0.0110071 -0.2382259 0.8102481 0.5353739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5578 5541 0.907777 0.539671 -0.208608 -0.0209550 0.1426470 0.7282845 0.6699361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5578 5581 -0.699449 -0.701354 0.335385 0.1060705 -0.9100323 -0.3994028 0.0326755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5578 5638 -0.536719 0.884143 0.347227 -0.7654436 0.0569751 -0.4280268 0.4771195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5579 5639 0.807269 0.893867 -0.119185 -0.4676151 -0.2070656 -0.2088733 0.8335658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5580 5600 0.509226 -0.914687 0.035539 0.6836523 0.1051893 0.3011577 0.6563984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5582 5602 -0.714252 -0.518492 0.657275 0.4310893 -0.5173113 -0.6245447 0.3955944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5583 5603 0.681047 0.544718 0.623513 0.3333582 0.7094956 0.4699435 0.4057603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5584 5604 -0.201881 0.492410 0.771918 0.3087978 -0.1800118 -0.8486319 0.3899534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5585 5605 0.087368 -0.015946 0.883474 -0.0769154 -0.5942447 -0.7210856 0.3478403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5586 5606 0.596964 -0.665625 0.633452 0.0865011 0.2854069 0.8943688 0.3334140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5587 5607 0.312612 0.484335 0.749111 -0.0810809 0.0315513 0.9531693 0.2896527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5588 5608 -0.140742 1.004888 0.071779 0.0223003 -0.8964748 -0.3558598 0.2630579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5589 5570 0.052580 -0.845482 0.284415 -0.5249712 -0.0028382 -0.7016610 0.4817353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5589 5609 -0.746880 0.021678 0.645542 -0.1762145 -0.1369571 0.6864224 0.6921094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5590 5610 0.893240 -0.148260 0.602060 -0.4259306 0.7439429 -0.0572656 0.5117155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5592 5567 -0.768626 -0.055014 0.453241 0.6522706 0.1408362 -0.5705585 0.4787183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5592 5612 0.292172 -0.987910 0.076201 -0.0574211 0.7468810 -0.4292597 0.5045867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5593 5613 0.359374 -0.833881 0.085092 -0.6157873 0.3761593 -0.6728617 0.1629949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5594 5614 0.662835 -0.289925 0.763862 0.0825103 0.4670035 -0.7619646 0.4410327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5595 4815 -0.547199 -0.173166 -0.812575 0.2157130 -0.3794562 -0.7914800 0.4278321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5595 5615 0.716631 0.056292 0.672939 0.3335025 -0.3334092 0.4460421 0.7606976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5596 4816 -0.749340 -0.621525 -0.239395 -0.1520926 -0.8201429 -0.4707533 0.2874452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5597 5617 -0.474638 -0.094648 0.908924 -0.0372003 -0.5842809 -0.7439631 0.3221040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5598 5618 -0.971691 -0.337646 0.406382 0.4328374 0.0414433 -0.2084179 0.8760686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5599 5560 0.471178 -0.430384 0.861054 0.2233139 0.8936304 -0.3369608 0.1949693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5599 5619 -0.694261 -0.447058 0.445904 -0.4556721 -0.6528076 -0.0427863 0.6036344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5600 5639 -0.140174 0.842822 -0.010606 -0.2859348 -0.4086011 -0.8647721 0.0587856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5600 6380 -0.167908 -0.093392 1.065811 -0.6173279 0.0483481 -0.1752776 0.7654061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5601 5581 -0.615114 0.071260 -0.753027 0.6549287 0.4911998 0.4844775 0.3083385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5601 5638 0.659104 -0.547285 -0.427932 -0.1969957 0.7709239 -0.5692169 0.2070292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5601 6381 0.685618 0.206091 0.833097 -0.0351649 -0.5152817 0.7664683 0.3818043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5602 5637 0.012338 -0.845305 0.502761 -0.0757750 0.2904687 0.3080036 0.9027845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5602 6382 0.555584 0.345810 0.764418 0.2230196 0.1490583 0.7292376 0.6294890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5603 5636 0.039041 -0.722472 0.673927 -0.6962362 0.4766091 0.2455830 0.4772714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5603 6383 -0.164143 0.726730 0.878852 -0.8549637 -0.3195020 -0.3638138 0.1859978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5605 6385 0.275679 0.977792 0.348653 -0.3844025 0.5447143 0.6241373 0.4073988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5606 5633 -0.458030 -0.830421 -0.431904 -0.4467013 0.6660550 0.5613266 0.2043063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5606 6386 -1.025494 0.547731 0.262003 -0.0856002 0.4684415 0.7726057 0.4198995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5607 5632 0.595805 -0.726237 -0.507681 -0.0911045 0.4674427 -0.5575573 0.6799464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5608 5631 0.814152 -0.226656 0.481513 -0.6272260 -0.1906742 0.5320487 0.5358685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5608 6388 -0.109172 0.904630 0.322485 0.2550824 0.7069022 0.5625290 0.3446497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5609 5630 -0.900250 -0.379146 0.190672 0.0842733 -0.0216635 -0.7847364 0.6136916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5610 5629 0.041080 -0.456658 -0.813353 0.7226089 -0.2048166 0.3079355 0.5840053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5610 6390 -0.535069 -0.865337 0.315771 -0.2352319 -0.7659065 0.0869751 0.5920208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5611 5628 -0.723432 0.369823 0.004791 0.3615666 0.0686331 0.0557802 0.9281420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5613 6393 0.743794 0.384610 0.650997 0.0977457 -0.0890458 -0.1417707 0.9810289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5614 6394 -0.569729 0.290279 0.805601 -0.2446078 -0.1452882 0.6768574 0.6789127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5615 6395 0.784343 -0.520967 0.502797 0.7160880 0.3358580 0.4053044 0.4584166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5616 5596 -0.948654 -0.492976 -0.370481 -0.0304717 -0.1289158 -0.1180144 0.9841366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5616 5623 0.610214 -0.927123 -0.236655 -0.0659208 0.4480640 -0.7231569 0.5214760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5617 5622 -0.406269 0.043308 0.914346 -0.7216912 0.4690300 -0.2685301 0.4325092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5617 6397 0.894225 0.408595 0.294086 -0.4098316 -0.3562608 -0.6751854 0.4992404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5619 6399 -0.413709 -0.658901 0.147626 -0.4935308 -0.5105379 0.3716385 0.5980495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5620 5659 -0.843606 -0.021181 -0.546670 -0.5944344 -0.4817213 -0.5889408 0.2602712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5620 6360 -0.172301 0.869968 0.332082 -0.1971368 0.7012544 0.0740619 0.6810978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5621 5561 0.696460 -0.800263 -0.310910 -0.3304876 -0.1477584 -0.0144502 0.9320604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5621 5618 0.066097 -0.122494 0.841141 0.1882836 -0.2403468 -0.4866182 0.8185264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5621 5658 -0.260602 0.243900 -1.003382 -0.7785671 -0.1920771 -0.1596849 0.5757086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5621 6361 -1.025626 0.543772 0.161384 0.2283227 0.0796028 -0.9279868 0.2835006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5622 5657 -0.059934 -0.610441 -1.096234 0.4644660 -0.3370191 0.3152430 0.7558514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5622 6362 -0.007601 -0.609426 0.604092 0.0311226 0.3664188 -0.2253672 0.9022074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5624 5615 -0.094276 0.763900 0.537242 -0.4310999 -0.0203678 -0.0704846 0.8993164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5624 5655 0.268761 -0.862498 -0.549915 0.0086633 0.7827624 0.0863153 0.6162448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5624 6364 0.938144 -0.220697 0.645960 0.8002699 0.4565390 0.0123244 0.3885723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5625 5614 -0.458651 0.293889 -0.837115 0.5355698 -0.5120871 -0.6709158 0.0283521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5625 5654 0.329536 -0.351196 0.858848 0.4113889 -0.7606272 -0.4830106 0.1374998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5625 6365 -0.511047 0.720607 0.390510 -0.7894290 0.3289155 0.1721414 0.4888596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5626 5653 -0.941068 0.293862 -0.400783 0.7306310 0.0026404 -0.1076306 0.6742307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5627 5612 -0.799451 0.602634 -0.213929 -0.6104845 0.2268910 0.5214877 0.5512529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5627 6367 0.353045 0.867183 0.193732 -0.0858820 -0.0965706 -0.5112295 0.8496722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5628 5568 0.400578 0.119374 -0.853910 0.7009000 -0.4995625 -0.3858693 0.3320863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5628 5651 -0.751152 0.352470 -0.570900 0.0192575 0.2350143 0.8798162 0.4126996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5629 5650 -0.386348 -0.522030 0.676125 -0.2421196 0.8004824 0.2105302 0.5062441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5629 6369 -0.231747 0.910586 0.580529 -0.6042877 0.1101313 0.7263915 0.3083227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5630 5649 0.447718 -0.822521 0.262691 0.6846232 0.0429088 -0.4025862 0.6061141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5631 5648 -0.115168 -0.645592 -0.836691 -0.1155628 -0.0156835 0.3726957 0.9205961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5631 6371 0.337262 -0.723820 0.583088 0.6116580 0.5510761 -0.3341199 0.4588611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5632 5647 0.681228 0.587974 0.448208 0.8718972 -0.3068689 0.3686645 0.0985561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5632 6372 0.436836 -0.894112 0.605221 0.5083393 0.6669047 -0.3518033 0.4160093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5633 6373 -0.147958 0.835012 0.352838 0.0148714 0.1571213 -0.4070744 0.8996567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5634 6374 -0.610890 0.233004 0.584020 0.0647274 0.3491826 0.9347983 0.0058250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5635 5604 -0.949638 0.475416 0.338048 0.0240887 -0.6121854 -0.7902994 0.0086921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5635 6375 0.522071 0.829676 0.242377 -0.1262692 -0.3390469 -0.8667997 0.3431641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5636 5576 0.982731 0.424946 -0.106993 -0.0159818 -0.7557492 0.6023835 0.2563626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5636 5643 -0.203728 -0.272932 -1.034041 -0.7616979 0.3570066 0.4841370 0.2407779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5636 6376 -0.841369 -0.194974 0.335022 0.8546808 -0.1561406 0.1205956 0.4802058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5637 6377 0.610113 -0.017248 0.890650 -0.3442450 -0.4340837 -0.5985701 0.5786022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5638 5641 -0.087897 0.203109 0.911257 0.5445591 0.2777632 -0.0244601 0.7910150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5638 6378 -0.489102 -0.878288 0.108158 -0.5613914 -0.0819069 0.6396653 0.5186128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5639 6379 0.401125 0.630651 0.476225 0.1345090 -0.0142079 0.0176462 0.9906534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5640 5679 -0.678471 -0.982923 -0.172615 -0.0746704 -0.3684132 0.4638723 0.8021961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5641 5678 -0.450169 0.974816 0.073456 0.5078180 -0.0563327 -0.2121473 0.8330312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5642 5677 -0.414588 -0.973250 -0.295502 0.1042809 -0.4630773 0.3054694 0.8254534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5642 6342 -0.730579 0.220394 0.817229 -0.6293371 0.0133947 -0.2067072 0.7490177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5643 5676 0.818840 0.534446 0.466421 -0.0039506 0.5676647 0.4122945 0.7125689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5643 6343 -0.440600 0.867247 0.329764 -0.6879017 -0.2869189 -0.0210747 0.6663517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5644 5635 0.983587 0.033047 -0.224167 -0.1909255 0.2165574 -0.9095384 0.2989821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5644 5675 -0.971804 -0.106537 -0.056887 0.3444737 0.3670465 0.2125642 0.8375149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5644 6344 0.169416 -1.061145 0.144591 -0.1190992 -0.3825732 0.8936468 0.2021099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5645 6345 -0.528755 0.149929 0.841673 -0.1683443 0.0830959 0.9819808 0.0216565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5646 5633 0.421308 -0.777137 0.491997 0.2606210 0.5319273 0.2865738 0.7529976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5646 5673 -0.268374 0.782049 -0.174811 0.0323079 0.0768651 0.8972390 0.4336014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5646 6346 0.280202 0.616891 0.668147 -0.4041512 0.4699238 -0.5041265 0.6014066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5647 5672 0.433990 -0.814825 -0.116390 0.5748351 0.7848513 0.0439219 0.2272530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5647 6347 0.795753 0.550805 0.139723 0.2243739 0.3121783 0.9079645 0.1667380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5648 6348 -0.185938 -0.859848 0.345212 0.5330594 -0.3158055 0.7019858 0.3511844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5649 6349 -0.643964 0.580696 0.098007 0.6093285 -0.4473441 -0.4459941 0.4792613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5650 5669 -0.176061 0.102466 -0.840180 -0.4878805 -0.0317475 0.2720959 0.8288115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5650 6350 -0.668785 0.879849 0.395172 -0.1633757 -0.2921504 0.3135900 0.8886044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5651 5551 -0.018864 -0.716852 -0.724595 -0.0495439 -0.1863421 0.4039057 0.8942495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5651 6351 0.123837 0.782267 0.638419 0.1513544 0.1034569 0.6473275 0.7398349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5652 5627 0.893333 -0.230966 -0.340718 -0.3355939 -0.6674922 -0.5548670 0.3659965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5652 5667 -1.029143 0.182523 0.497888 -0.5238561 0.2683340 -0.2259919 0.7762083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5653 5553 0.542946 -0.731402 -0.435159 -0.0525893 -0.1352643 0.6303050 0.7626622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5653 5666 -1.019016 -0.409700 -0.036665 0.5487835 -0.1857595 -0.7957265 0.1764920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5654 6354 -0.434578 0.716243 0.662032 0.2257719 -0.4545781 0.0509516 0.8601103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5655 5664 0.248826 -0.945571 0.127529 -0.3235190 -0.7967496 0.4969750 0.1163673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5655 6355 -0.702011 -0.347330 0.513840 0.5208588 0.3931088 -0.6287582 0.4228885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5656 5663 -0.697730 -0.233296 0.572520 -0.6827943 -0.3285717 -0.6469953 0.0850274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5656 6356 0.306952 0.648433 0.364258 0.1627591 0.4095898 0.0259844 0.8972572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5659 6359 0.345888 -0.426648 0.749286 -0.1938680 0.5154039 -0.2201582 0.8051735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5660 5699 0.985505 -0.613897 0.340506 -0.2734202 0.0247115 0.9101610 0.3102220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5661 5658 0.339535 -0.239345 0.860388 -0.2963221 -0.7203715 0.1727351 0.6028438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5661 5698 -0.437298 0.119321 -0.930780 0.4102166 0.4354988 -0.0454366 0.7999991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5662 5657 -0.520015 -0.322390 -0.931939 -0.0122082 0.5738633 -0.6515429 0.4960079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5662 5697 0.412200 0.149417 0.984159 0.6191312 0.4748596 0.3722820 0.5025843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5662 6322 0.318758 -0.863684 -0.034090 0.7534220 -0.5384554 0.3407314 0.1622442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5663 5696 0.632947 0.154776 -0.609416 -0.6431303 -0.2606746 -0.7047471 0.1475254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5663 6323 0.883265 -0.112808 0.785781 -0.2329253 0.2293383 0.7777100 0.5369515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5664 5524 -0.330513 0.838777 -0.212957 -0.3641453 0.1309506 -0.8440503 0.3712536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5664 5695 -0.828232 -0.294157 0.323511 0.6428438 -0.6562230 0.3555538 0.1723502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5664 6324 0.665352 -0.961895 0.281901 0.0709209 -0.3694201 0.9142625 0.1504096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5665 5654 -0.913437 0.278390 -0.049835 0.2743157 -0.4592700 -0.6724560 0.5114929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5665 5694 0.975005 -0.271172 0.183783 -0.3364464 0.4141861 0.6471334 0.5444925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5665 6325 -0.058388 0.546677 0.952450 -0.2505111 0.6546370 0.3330207 0.6307074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5666 5693 0.556617 0.480366 0.685155 0.6218976 0.4025777 -0.6648951 0.0953368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5666 6326 -0.638415 -0.473533 0.696967 0.3752283 0.2561748 -0.8857770 0.0947484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5667 5527 0.086953 0.282096 -0.791594 0.1450881 -0.4287391 -0.4097870 0.7919639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5667 5692 -0.854042 -0.213841 -0.203222 0.0343538 -0.6115443 0.1434963 0.7773301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5667 6327 0.005302 -0.316155 0.935640 0.5267078 -0.0088159 0.8213645 0.2187726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5668 5651 0.266320 0.787775 -0.339442 0.2087004 -0.6494523 -0.7039950 0.1976027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5668 5691 -0.406141 -0.795756 0.164254 -0.2706751 0.3206889 0.4908477 0.7635196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5668 6328 -0.554195 0.506321 0.830028 -0.8184172 -0.0350958 0.2414789 0.5202399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5669 5690 0.076096 0.925603 -0.405681 0.2878044 0.0227593 -0.7886659 0.5428229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5669 6329 -0.286959 0.242519 1.033677 0.1490325 -0.3995849 0.3194242 0.8462206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5670 5649 0.462838 0.884518 -0.319517 0.6643185 -0.2232801 -0.5809856 0.4138630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5670 5689 -0.328978 -0.823212 0.085971 -0.4413829 -0.3990291 0.8033101 0.0254918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5670 6330 -0.132617 0.423754 0.796396 0.2884952 0.3627822 -0.7238716 0.5110475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5671 5648 -0.059524 -0.179802 -0.832451 -0.0584375 0.9438290 -0.1774499 0.2725499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5671 5688 0.009163 0.403009 1.054709 -0.1141828 -0.4921416 0.6257907 0.5942601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5671 6331 0.509199 -1.101551 0.202638 0.7614887 0.4251532 -0.2442248 0.4239504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5672 5687 -0.696697 0.430221 0.211993 0.3537357 0.4304885 0.6443484 0.5237995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5672 6332 0.133455 0.840672 -0.012944 0.2561385 0.0875930 0.9619994 0.0357452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5673 5686 1.039327 -0.067186 -0.508126 0.0249045 0.3771780 -0.4450728 0.8118046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5673 6333 0.119512 -0.270523 0.803969 0.2000564 -0.2953121 0.8652180 0.3523720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5674 5645 0.287379 0.026089 -0.929320 0.4115468 0.1767683 0.7829366 0.4317319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5674 5685 -0.331896 -0.076261 0.844924 0.4164618 0.0569146 0.2015722 0.8846971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5674 6334 0.796123 -0.467643 0.276606 -0.7080326 0.0968461 -0.6452594 0.2700944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5675 5684 -0.712090 0.101202 -0.650863 0.5441430 0.5979336 -0.5400902 0.2338511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5675 6335 -0.538855 -0.576667 0.502521 -0.1890046 0.0756890 0.8933667 0.4005550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5676 5683 -0.106197 -0.025510 1.091069 -0.5958508 -0.2449480 -0.0882346 0.7597216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5677 5682 -0.932341 -0.534600 0.314947 0.1072681 0.2734920 -0.7779085 0.5554765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5677 6337 -0.063184 0.507646 0.906836 0.1295516 0.1535581 0.7919402 0.5765995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5678 5681 -0.676287 0.486211 -0.606760 -0.0075017 0.6047098 0.7688857 0.2075684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5678 6338 -0.585660 0.124352 0.739086 -0.6092586 -0.1409984 0.2982371 0.7210950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5680 5500 0.684840 0.244123 -0.474111 0.4671198 0.0903561 -0.5689385 0.6707786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5680 5719 -0.115392 -0.810671 -0.389434 0.3293181 0.6612711 -0.6466141 0.1901585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5680 6300 -0.747738 -0.204472 0.660299 0.1536261 -0.0620684 0.3471883 0.9230422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5681 5501 -0.293668 -0.781945 -0.144633 -0.9051458 -0.2708027 0.1571113 0.2875638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5681 6301 0.504132 0.822306 0.248772 -0.5471820 -0.2594384 -0.7887225 0.1058319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5682 5717 0.672354 -0.685655 0.468828 0.0484381 0.2528553 0.9631532 0.0778069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5683 5503 -0.509634 -0.120528 -0.616293 -0.2739561 0.7165603 0.2777164 0.5782413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5683 5716 0.383716 -0.706342 0.004663 -0.2803313 0.3323188 0.7563684 0.4887590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5683 6303 0.479990 0.342893 0.676717 -0.7554332 0.2714148 -0.2512840 0.5408428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5684 5715 0.603248 -0.411386 0.370535 0.6065307 -0.3452225 -0.3193187 0.6410753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5684 6304 -0.546266 -0.564440 0.515550 0.2705369 0.7673005 -0.5618967 0.1494383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5685 5714 -0.130472 0.689581 0.603008 0.1553983 -0.2948714 -0.5480752 0.7671478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5685 6305 0.547420 -0.240441 0.769012 -0.2049567 0.0730364 0.4261391 0.8781024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5686 5506 0.152514 0.365863 -0.722942 0.3653922 0.0943825 -0.9100709 0.1713228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5686 6306 -0.123523 -0.298355 0.773283 0.1121967 -0.3741532 0.8509336 0.3511882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5687 5712 0.547597 0.541461 -0.539523 -0.1854900 0.7774926 -0.0462747 0.5991305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5687 6307 0.794686 -0.125653 0.469108 0.5156503 0.0145434 0.8420568 0.1575865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5688 5711 0.649241 -0.635860 0.451242 0.6533615 0.5642801 -0.5022532 0.0494813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5689 5710 -0.451401 0.507620 0.861249 0.7995336 -0.1682907 -0.5118878 0.2653209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5689 6309 -0.504009 -0.844024 0.363437 -0.1232611 -0.4578367 -0.1857127 0.8606411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5690 6310 -0.705565 -0.155279 0.875391 0.6585789 0.0327043 -0.2491100 0.7093295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5691 5708 -0.803675 0.134002 -0.551089 -0.5622451 0.0176042 0.7875101 0.2517904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5691 6311 -0.390308 0.643865 0.613602 0.7012954 -0.0770862 -0.7005388 0.1071818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5692 5707 -0.449096 0.020863 0.850208 -0.2316898 0.2803722 -0.7786607 0.5112717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5693 5706 -0.679552 -0.144271 -0.896573 0.6975170 0.0038914 -0.7153707 0.0412269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5693 6313 -0.394544 -0.315551 0.675258 -0.1152748 -0.1440093 0.8009188 0.5696509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5694 5705 -0.382085 -0.957914 0.013050 0.2463609 -0.2935862 0.7128695 0.5873078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5694 6314 -0.581944 0.272123 0.872321 0.4007742 0.3483229 -0.8446911 0.0674401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5695 6315 0.597782 -0.373729 0.517857 0.0290679 0.3948478 -0.0872910 0.9141283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5696 6316 0.594315 0.754437 0.520456 -0.1163300 -0.2451226 0.9064926 0.3235018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5697 5702 0.399021 1.013201 0.036427 -0.2396544 0.4611304 0.7871269 0.3321983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5697 6317 -0.762636 0.108420 0.534441 0.1527966 -0.0311327 -0.8410907 0.5179289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5698 6318 -0.759182 -0.685535 0.449955 0.0322612 -0.2842921 -0.1880638 0.9395580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5699 6319 0.119260 -0.385424 0.881555 0.0091020 0.1245989 0.8149982 0.5658359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5700 6280 -0.417091 0.835892 0.431463 -0.3734692 -0.8481441 -0.2290966 0.2978038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5701 5698 -0.780994 0.623954 0.147781 -0.1758234 -0.2548810 0.1109463 0.9443584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5701 5738 0.640910 -0.635260 -0.069497 0.2091063 -0.2505361 0.6188071 0.7145516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5702 5737 0.043654 -0.557944 0.809523 -0.0951683 -0.0236604 -0.6036770 0.7911746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5702 6282 0.173878 0.890242 0.355367 -0.7450979 0.4024977 -0.1787091 0.5008870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5703 5696 0.925959 0.125852 -0.175707 0.7361484 -0.1566423 -0.0820505 0.6533119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5703 5736 -0.800981 -0.183241 0.095152 0.0885594 0.0703540 -0.8795413 0.4621847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5703 6283 0.432423 -0.588827 0.622590 -0.2180790 -0.1809864 0.9271158 0.2452381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5704 5695 0.481928 -0.925145 -0.213412 0.1450310 0.0797576 0.5505863 0.8182050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5704 5735 -0.282428 0.870807 -0.100235 -0.0260836 0.7659890 0.3187332 0.5576644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5704 6284 0.824061 0.397081 0.508749 -0.5124987 0.7771816 -0.3043097 0.2018154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5705 5734 -0.860873 0.534609 0.575988 -0.6325048 0.5250141 0.4027306 0.4026238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5705 6285 0.947981 0.709037 0.393645 0.3705235 0.7467691 0.1037282 0.5424839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5706 6286 -0.719936 0.283394 0.631337 0.0018971 -0.1329727 -0.9902624 0.0411711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5707 6287 0.207710 0.327631 0.855242 0.3624804 0.2248352 -0.2803891 0.8599064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5708 6288 -0.262367 -0.366186 0.756236 0.7755572 -0.3185124 0.2879234 0.4627753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5709 5690 -0.756277 0.498533 0.088703 -0.3117448 0.3850633 0.8192662 0.2886942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5709 6289 0.389502 0.492823 0.747040 -0.4064615 -0.3086183 -0.4838407 0.7109444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5710 5729 -0.992330 0.079276 0.129406 0.1246469 -0.1376527 -0.0908214 0.9783999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5710 6290 0.195200 0.700300 0.527498 0.0972172 -0.1125997 -0.9811383 0.1234416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5711 5728 -0.897784 0.402695 -0.161190 -0.0772923 -0.0372502 -0.9619537 0.2593905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5712 5727 0.278558 0.621014 0.776913 -0.5306445 -0.3803931 0.5792981 0.4879869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5712 6292 -0.477777 -0.285456 0.645771 0.0024710 -0.1456196 -0.1967117 0.9695841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5713 5686 -1.024175 -0.252975 -0.082969 -0.5074728 -0.1274790 -0.2565000 0.8126674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5713 5726 1.008343 0.461795 -0.088839 -0.7170672 -0.4057045 0.0847335 0.5603916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5713 6293 -0.454668 0.653709 0.588585 -0.3587151 -0.2953525 0.5150836 0.7202633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5714 5725 -0.710342 0.420685 0.483634 -0.2686778 -0.0860412 -0.6176233 0.7341326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5714 6294 0.476357 0.565351 0.281426 -0.5676259 -0.0936855 -0.7838172 0.2337832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5715 5724 0.880925 0.381956 -0.371804 -0.5756574 0.5627365 0.1895507 0.5621536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5715 6295 0.215825 0.366844 0.867603 -0.2700274 0.6153529 0.4175314 0.6116318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5716 5723 -0.630849 -0.111497 -0.702607 -0.2852233 -0.0931771 -0.2822899 0.9111960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5716 6296 -0.485435 -0.559702 0.598509 0.5634977 -0.5000033 -0.1053936 0.6491219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5717 5722 -0.541981 0.754284 0.378657 0.1396819 -0.0158897 0.7345582 0.6638228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5717 6297 0.881554 0.639872 0.226153 0.3977320 0.5216382 0.6948162 0.2948444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5718 5681 -0.574763 0.172538 0.822883 0.7446327 -0.1101028 -0.2179848 0.6211941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5718 5721 0.648624 -0.296647 -0.759297 -0.0017100 0.0260028 -0.4180716 0.9080403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5718 6298 0.418344 -0.502746 0.755241 -0.3881980 0.6175497 -0.2779558 0.6250402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5719 5499 0.049312 0.910853 -0.436960 0.5119358 -0.3946096 0.7093818 0.2810382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5720 5759 -0.904239 -0.625605 -0.107012 0.4694689 -0.5677104 -0.6717673 0.0776694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5720 6260 -0.666267 0.564699 0.323469 -0.0006450 -0.4114917 0.4925650 0.7668467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5721 5758 0.464113 0.473739 -0.682687 -0.6262249 -0.2649617 -0.6447081 0.3492695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5721 6261 0.500876 -0.045561 0.729720 0.4415187 -0.3843043 0.7095757 0.3922674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5722 5757 0.948572 0.556329 0.005413 0.0751090 0.3307428 0.2383799 0.9100235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5722 6262 0.689884 -0.740975 0.131981 0.1476189 -0.5111396 0.6553755 0.5361230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5723 5756 -0.808283 -0.131558 -0.746860 0.7488244 -0.2325111 -0.3986733 0.4756682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5724 5755 0.512194 -0.434478 0.701624 0.5371143 -0.3209249 0.7116992 0.3193740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5724 6264 -0.829959 -0.457116 0.254201 0.5594135 0.6551213 -0.3923624 0.3223729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5725 6265 -0.439422 0.574405 0.714543 -0.0385483 0.2230465 -0.7144035 0.6621117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5726 5753 0.858113 0.494190 -0.303524 0.0954908 0.0956792 0.9906290 0.0195244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5727 5752 0.604062 -0.897817 -0.310570 0.2092699 0.8827710 -0.4206158 0.0019529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5727 6267 -0.608188 -0.394701 0.561912 0.1777526 0.6089979 -0.5952989 0.4930971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5728 5751 0.287479 -0.912405 -0.052706 -0.4484842 0.4386795 0.2638107 0.7326842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5729 5750 -0.992389 -0.099573 0.216451 -0.3039879 0.6669219 0.6638999 0.1484703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5729 6269 0.131292 0.779425 0.221972 0.0626096 -0.3021978 -0.2871995 0.9067927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5730 5749 0.069182 0.716045 0.954387 0.5020384 -0.3943284 0.7296750 0.2450242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5730 6270 -0.000232 -0.713254 0.622735 0.7325842 0.4218161 -0.5313842 0.0549763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5731 5708 -0.433040 0.676699 0.317811 0.1497729 0.3729726 -0.6593960 0.6353397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5731 5748 0.403121 -0.820577 -0.262208 -0.2752458 -0.3141848 0.3487960 0.8389690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5732 5472 -0.932699 0.562747 -0.148677 -0.4032814 0.8866299 -0.1405471 0.1774766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5732 5707 0.028360 0.043082 0.822676 0.7071077 0.3920505 0.0556898 0.5858275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5732 5747 -0.019062 0.050139 -1.016408 0.5354093 -0.5061039 0.1869581 0.6498018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5732 6272 0.776483 -0.617763 -0.048622 0.3294681 0.0339858 -0.0453542 0.9424642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5733 5706 -0.250988 0.370184 -1.013088 -0.2507368 0.0487084 -0.7398501 0.6223989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5733 5746 0.337701 -0.545357 0.904775 0.1908966 -0.2071905 -0.9561859 0.0796185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5734 5745 -0.653448 0.474595 0.406811 -0.3205530 -0.2238214 0.2291983 0.8914134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5734 6274 -0.443043 -0.757363 0.297135 -0.3213075 -0.6842788 0.6482566 0.0910350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5735 5744 0.395789 1.048561 0.203588 0.1068199 -0.0083575 -0.6048823 0.7890736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5735 6275 -0.824078 0.219883 0.683598 -0.1003110 -0.4072996 0.8858217 0.1984053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5736 5476 -0.229083 -0.397152 -0.869870 0.0828491 0.4960738 0.3124754 0.8058572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5737 5742 0.516304 -0.299985 0.855079 -0.6398232 0.4419788 0.3839219 0.4978805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5737 6277 -0.709732 0.143914 0.605021 0.5372335 -0.2545096 -0.0949817 0.7984883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5739 5700 -0.404657 0.962452 -0.047921 0.7374309 -0.3440652 -0.2663088 0.5166183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5739 6279 -0.554699 -0.325688 0.624459 0.0770316 -0.2737377 0.2172616 0.9337726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5740 5779 -0.427265 -0.125852 -0.774955 0.4678296 -0.7153257 0.4026567 0.3275853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5740 6240 0.007576 -0.911388 0.091122 0.4654698 0.0335070 0.5298736 0.7081307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5741 6241 -0.697563 0.251194 0.851106 0.4411248 -0.5808888 0.1454354 0.6684501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5742 5777 -0.565370 -0.744122 -0.100720 -0.4298790 -0.4289250 -0.3505209 0.7129954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5743 5443 0.337860 -0.109735 -0.868205 0.0730814 -0.4003735 0.8371925 0.3653339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5743 5736 -0.524730 0.762313 -0.278760 0.3063413 -0.3274062 -0.0626326 0.8916487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5743 5776 0.393922 -1.039739 0.220958 -0.0623829 -0.2049202 -0.5866162 0.7810234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5743 6243 -0.391792 0.194968 0.687549 -0.2193438 0.1014175 -0.9513973 0.1909083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5744 5775 -0.883870 0.713010 -0.046756 0.3229566 0.3190353 0.0871065 0.8867514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5744 6244 -0.576483 -0.462624 0.914462 0.0973617 -0.0837934 0.4117352 0.9022048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5745 6245 -0.684295 -0.720643 -0.009499 0.7211220 0.0019869 0.4458819 0.5302532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5746 5773 -0.431050 0.720116 0.482667 0.6127187 -0.7196861 -0.3023345 0.1233756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5746 6246 -0.701950 -0.567207 0.468657 0.5689165 0.5217761 -0.3728292 0.5148612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5747 5772 -1.004025 -0.738812 0.169155 -0.0551349 0.7589197 0.1168247 0.6382421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5747 6247 0.597468 -0.869910 0.225271 0.0761460 -0.2716358 0.9013483 0.3286139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5748 5771 -0.490825 -0.222665 -0.777608 0.3652753 0.1534757 0.8811721 0.2579825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5749 5770 0.664110 -0.723061 0.049592 -0.2400257 -0.2855542 0.4451126 0.8140769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5749 6249 0.342005 0.091708 0.887005 -0.6044397 0.4279048 -0.1967511 0.6425256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5750 6250 -0.284613 0.024763 1.062978 0.5859756 -0.3880698 -0.0943014 0.7050828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5751 5768 0.443183 -0.650447 -0.602365 0.4459350 -0.6602330 0.5755040 0.1844711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5751 6251 -0.144431 -0.891635 0.648180 -0.5865868 -0.1811708 0.7776013 0.1357546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5752 5767 -0.764881 -0.401224 0.588898 0.4607544 -0.6117588 -0.1301435 0.6296977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5752 6252 0.564277 -1.070066 0.257842 0.3266019 0.7844503 -0.5148668 0.1134946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5753 5766 -0.733293 -0.849846 0.162482 -0.6789977 -0.0589027 -0.0414599 0.7305982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5753 6253 -0.692865 0.679550 0.286521 0.0921988 -0.2823389 0.0675499 0.9524816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5754 5725 0.934577 0.634399 0.170246 0.5141747 0.1912328 -0.2927425 0.7831706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5754 5765 -0.813167 -0.545237 0.141295 -0.0947990 0.4428299 -0.3001545 0.8395368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5755 5764 0.606421 -0.186819 0.771972 0.4484964 0.4076277 0.6557959 0.4501360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5755 6255 0.482578 0.904225 0.045114 0.0225353 0.7742115 0.4984773 0.3893702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5756 5763 -0.131630 -0.563603 0.869642 -0.6270088 0.6092795 0.3453039 0.3411798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5756 6256 0.589523 0.667563 0.338213 -0.5002660 -0.3899664 -0.6547297 0.4110829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5757 5762 0.714535 0.158157 0.414241 0.7622184 -0.2092867 0.5576917 0.2533814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5757 6257 0.065958 -0.937445 0.543320 0.5960535 -0.4963755 0.0699370 0.6272483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5758 5458 -0.811257 -0.655013 -0.577417 0.1899079 0.0213760 0.9812399 0.0254212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5758 5761 -0.763462 0.178572 0.625027 -0.7464080 0.2905523 -0.5730400 0.1734346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5758 6258 0.615929 0.435645 0.551790 -0.7768914 0.1505293 -0.5954227 0.1387534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5759 6259 -0.195016 0.435966 0.990547 -0.1400149 0.3941325 0.0672517 0.9058326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5760 6220 -0.440251 -0.752744 0.506414 -0.0911217 0.7697798 -0.6281402 0.0676444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5761 5798 0.293778 -0.567060 -0.746267 0.7283861 0.0590393 -0.4398873 0.5219840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5761 6221 0.249226 -0.946236 0.481420 0.2225242 -0.9217557 0.2193347 0.2296557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5762 5797 0.837305 -0.675241 0.361298 -0.4762777 0.0467186 0.8780521 0.0012455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5762 6222 0.378998 0.789263 0.372135 -0.0339398 -0.1707167 0.8586862 0.4820394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5763 5423 0.780937 0.565236 -0.438251 0.3740894 0.4460156 -0.5828408 0.5669425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5763 5796 -0.510316 -0.140272 -1.069035 0.7159737 -0.1635629 0.3818051 0.5611183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5764 5795 -0.354515 0.642096 0.701964 -0.1296116 -0.2341363 -0.9048716 0.3310415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5764 6224 0.908940 -0.353187 0.684010 0.0483134 0.3042961 -0.0748367 0.9484035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5765 5794 -0.107989 -0.789911 -0.540722 -0.1319443 0.3282891 -0.1907037 0.9156687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5765 6225 -0.225289 -0.616150 0.666728 0.5355614 -0.3181153 -0.7680748 0.1484515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5766 5793 -0.694285 -0.272853 -0.817808 0.7919255 -0.1390207 -0.0502817 0.5924517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5766 6226 -0.801209 -0.471154 0.851002 0.8377723 0.0151060 -0.0807911 0.5397983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5767 5427 -0.864888 0.481818 -0.093222 -0.4857750 -0.6064970 -0.6279756 0.0427859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5767 6227 0.809321 -0.742134 0.075436 0.5155777 0.3430244 0.7362840 0.2727632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5768 5791 -0.506427 0.135187 0.812677 0.4813247 0.0042147 0.0171532 0.8763644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5768 6228 0.771865 -0.219787 0.580796 0.7930782 0.1062728 0.4387903 0.4088962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5769 5790 0.632659 0.635201 0.508406 -0.2891490 0.5767893 0.6550352 0.3932377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5769 6229 -0.917294 0.506535 0.506141 0.1071245 -0.4808124 -0.2284508 0.8397345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5770 5789 -0.181614 -0.742913 -0.455604 0.5295971 0.0345172 -0.0416748 0.8465215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5770 6230 0.649665 -0.624887 0.621763 0.2660084 0.6930142 -0.6184890 0.2577639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5771 5788 -0.372633 -0.055960 -0.709998 -0.3134668 -0.0925121 0.8059934 0.4935126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5771 6231 0.001892 0.886290 0.116882 -0.0093609 0.3287380 0.2319934 0.9154358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5772 6232 -0.284949 -0.769219 0.377407 0.1796101 0.4355617 -0.8521173 0.2278649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5773 5786 -0.803142 0.721038 0.116716 -0.0780334 -0.1256954 -0.2001622 0.9685280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5773 6233 0.886286 0.556284 0.035670 -0.2213425 -0.9125068 -0.3334067 0.0847278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5774 5785 0.951608 0.030184 -0.033926 -0.2473114 0.3838947 -0.0631359 0.8873983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5775 5784 -0.405217 0.328203 -0.860229 -0.1920741 -0.6123907 0.6582064 0.3935093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5775 6235 -0.845047 0.164966 0.652913 -0.0323467 -0.0671318 -0.0658629 0.9950423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5776 5783 1.110485 -0.043531 -0.071779 -0.0192956 0.5185126 0.8488709 0.1009489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5776 6236 0.237984 -0.247794 0.899842 0.1528424 -0.4034687 -0.3564189 0.8287447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5777 5782 -0.367198 -0.773739 -0.509449 0.4024153 0.2105920 0.8819328 0.1261248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5777 6237 -0.058594 -0.524846 0.819647 -0.0343703 0.1954230 -0.7064478 0.6793821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5778 5741 0.692934 0.585677 0.605223 0.6289466 0.1423780 -0.6464838 0.4076928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5778 5781 -0.561338 -0.454200 -0.632023 -0.2879571 0.5407199 -0.4491149 0.6503833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5778 6238 -0.226389 -0.386739 0.814327 -0.2912214 -0.2636920 0.2176493 0.8934682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5779 5439 -0.563788 0.252984 -0.787656 0.4896631 0.0540046 -0.8531173 0.1717688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5779 6239 0.400624 -0.278514 0.915796 -0.1626038 -0.0336468 0.8366378 0.5219819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5780 6200 0.412872 -0.025073 0.871129 0.6223332 0.3602578 -0.3100987 0.6218959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5781 5401 -0.217911 0.942433 -0.105608 0.1471667 0.2810095 -0.2499454 0.9148240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5781 5818 0.694554 -0.063024 -0.672794 0.1972286 0.4018926 -0.4572218 0.7684604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5781 6201 0.111571 -0.935236 0.162730 0.0513240 -0.6145188 0.7759667 0.1326960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5782 5817 -0.426565 0.443629 -0.768226 -0.4778483 0.7230628 0.1226374 0.4835299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5782 6202 0.636875 0.904730 0.113478 -0.5563669 -0.1703766 -0.7447169 0.3268400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5783 5816 -0.901402 -0.208716 -0.051460 0.4033899 -0.6161121 -0.3185071 0.5968548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5783 6203 -0.282162 0.987617 0.247959 -0.0714541 -0.3536499 -0.3525679 0.8634361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5784 5815 0.339206 0.908559 0.022952 -0.5005408 0.5036330 0.1037070 0.6964607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5784 6204 0.886487 -0.362995 0.563340 0.7608920 0.0556559 -0.0385363 0.6453377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5785 5405 0.640897 0.148435 -0.670963 -0.0279064 -0.7944106 0.6016898 0.0781179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5785 5814 0.691063 -0.306828 0.864934 0.0682482 -0.6605549 -0.2787417 0.6937669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5785 6205 -0.560347 -0.240160 0.911572 -0.1354736 -0.2674702 -0.6803809 0.6687215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5786 5813 -0.860674 0.407740 0.197419 -0.4571771 -0.0742920 0.5384402 0.7039546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5786 6206 0.501554 0.906269 -0.010516 -0.1398134 0.0013917 -0.5970057 0.7899585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5787 5772 -0.710946 -0.364011 0.579344 -0.1595352 -0.3079914 0.7401322 0.5761026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5787 5812 0.783537 0.220170 -0.391416 -0.3395859 0.7282426 -0.5637586 0.1911030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5788 5811 0.483311 0.719803 -0.385039 -0.5937468 0.0124717 -0.7215855 0.3558419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5788 6208 0.623612 -0.571271 0.015332 -0.8277592 0.4575917 -0.3020361 0.1191587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5789 5810 -0.135321 -1.015751 0.586518 -0.4305366 0.2349752 -0.3249658 0.8085927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5789 6209 0.426408 0.137368 0.667641 -0.5701594 0.6557423 -0.4482271 0.2097921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5790 5809 -0.469340 -0.265305 0.577511 -0.3634069 0.0260292 -0.9312405 0.0070095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5790 6210 0.120229 1.043249 0.483703 -0.6823740 -0.3614272 -0.6335094 0.0490086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5791 5808 -0.366185 0.607724 0.292392 0.2411616 0.8016756 0.4680215 0.2830425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5791 6211 0.761475 0.189255 0.502969 0.0383681 -0.3333776 -0.4488736 0.8281907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5792 5767 0.441501 0.615983 0.404457 -0.0980072 -0.6064986 0.7788546 0.1262518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5792 5807 -0.573414 -0.708238 -0.456194 -0.8735341 -0.0475635 0.0349171 0.4831736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5792 6212 -0.701773 0.208148 0.632989 -0.0242027 -0.8288566 0.0984212 0.5502038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5793 5806 -0.722629 -0.383188 0.185206 0.5404727 -0.5007007 -0.6416720 0.2131786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5793 6213 -0.409165 0.649794 0.098447 -0.2631680 0.4766196 0.4442828 0.7114697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5794 5805 0.597872 -0.403569 -0.895987 -0.3013727 -0.8603361 0.1526657 0.3816930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5794 6214 -0.524186 -0.740716 0.220801 0.2564288 -0.3331550 0.8992468 0.1208603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5795 6215 -0.126708 0.795756 0.175733 0.3890045 0.8493078 0.3533852 0.0497064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5796 6216 -0.221076 0.814870 0.287801 0.0851696 -0.4084527 -0.6724544 0.6113245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5797 5802 -0.657928 0.569048 -0.351116 0.8449825 -0.4149049 0.1095055 0.3191662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5798 5801 0.928979 -0.351788 0.102587 0.4287236 0.4719992 0.7680753 0.0589329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5799 5760 0.160047 0.847815 -0.438730 -0.5376837 -0.2197129 -0.3678913 0.7261395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5799 6219 -0.979929 0.443514 0.226580 -0.6985017 -0.6122918 0.3372335 0.1531918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5800 5839 0.377007 -0.671085 0.513201 -0.2295262 -0.3546048 0.8170328 0.3924674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5800 6180 0.350017 0.610017 0.967764 -0.4737629 -0.4586301 -0.3284658 0.6762524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5801 5838 -0.500489 0.636345 0.423258 0.2922816 -0.2779343 0.8803855 0.2494902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5801 6181 0.856514 -0.105709 0.778820 0.4081270 -0.3863784 0.7460058 0.3572387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5802 5837 -1.051227 0.043829 0.026183 0.1304161 0.4135143 0.7988184 0.4169974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5802 6182 0.083678 0.871681 0.666316 -0.4047227 0.2992832 -0.6092416 0.6127428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5803 5383 0.246512 0.936291 -0.327863 -0.2227987 -0.3622385 0.8842345 0.1930633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5803 5836 0.951003 -0.262220 -0.556329 0.7345234 -0.4289533 0.5173754 0.0937924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5804 5795 0.353035 -0.783106 -0.506738 -0.0687562 -0.3397543 -0.8944730 0.2824139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5804 6184 0.441921 -0.302127 0.845349 -0.6498995 -0.3628206 -0.6672489 0.0277633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5805 6185 -0.505695 -0.819916 -0.038777 0.4405583 0.8755205 -0.1953520 0.0347819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5806 5386 0.673923 0.001668 -0.784714 -0.4052158 -0.2719865 -0.7212736 0.4915160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5806 6186 -0.639563 -0.132021 0.684030 0.4884981 -0.7363256 -0.3504577 0.3104409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5807 5832 -0.635063 0.385866 -0.368548 0.5685688 -0.6677613 -0.4112591 0.2483755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5807 6187 -0.812602 -0.595109 0.020063 0.5474669 -0.1872280 -0.7622364 0.2902090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5808 5831 0.706584 0.632259 0.080459 -0.2774515 -0.1339331 0.6493130 0.6953239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5808 6188 -0.512164 0.563069 0.433124 -0.2547020 -0.1187051 0.4987164 0.8199500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5809 5830 1.038194 -0.018830 -0.039349 0.4827089 -0.1878615 -0.7353533 0.4369848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5809 6189 0.167140 -0.862054 0.492893 -0.2582907 0.0048577 0.4437781 0.8580928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5810 6190 -0.065829 -0.430430 0.892313 0.4330274 0.1774335 0.0563701 0.8819450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5811 5828 -0.832669 0.006723 0.497331 0.4827359 0.5971995 0.3810608 0.5148898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5811 6191 0.565688 0.628741 0.485599 0.0509696 -0.1451720 -0.7147021 0.6822962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5812 5827 -0.723366 0.099007 0.519572 0.5398793 -0.0914425 -0.0064898 0.8367356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5812 6192 0.112402 -1.176679 0.276149 0.5526212 0.0352812 0.5604532 0.6158387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5813 5826 -0.112173 0.308084 0.981014 -0.3420107 0.5682453 -0.1036727 0.7412003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5814 5825 0.757943 0.393461 -0.771374 0.7764553 0.2301778 0.5816959 0.0759293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5814 6194 0.847689 0.031724 0.689772 -0.5923451 0.0869385 0.1284757 0.7906092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5815 5824 -0.110070 0.178681 0.934261 0.3643420 -0.0009516 -0.6674742 0.6494091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5815 6195 0.047126 -0.848501 0.247753 0.0055244 -0.4389721 0.6202704 0.6500290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5816 5823 0.140575 0.012983 1.022801 -0.0666981 -0.5850647 0.5198994 0.6188338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5816 6196 -0.654929 0.811792 -0.016285 -0.5685701 0.6823268 0.0855844 0.4514793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5817 5822 0.359160 0.639724 0.528951 0.5059489 -0.3001462 -0.4578184 0.6665810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5817 6197 -0.721198 -0.178914 0.833013 0.6610371 0.2461581 -0.5186845 0.4831176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5818 6198 0.578466 -0.465470 0.571695 -0.0120222 -0.1668218 0.6200113 0.7665585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5819 5780 0.480315 0.771578 -0.425259 -0.5980646 0.2602369 -0.7111708 0.2623577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5819 6199 0.796255 -0.493954 0.666933 -0.6880195 0.3231832 -0.3160482 0.5677106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5820 5859 0.332351 0.253366 -0.809948 0.0793980 0.1105484 0.8010594 0.5829055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5821 5818 1.005692 0.592265 0.101839 -0.1680130 0.2844808 0.9394569 0.0909013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5821 5858 -0.886784 -0.344400 0.002962 -0.7843033 -0.4460349 0.3707007 0.2202320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5821 6161 -0.473686 0.846300 0.378690 0.4851891 -0.6598707 -0.4432214 0.3643035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5822 6162 -0.265706 0.553696 0.897989 -0.3891190 0.6548640 0.5606427 0.3246833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5823 5856 0.508068 -0.740249 -0.059239 0.4076422 0.8926600 -0.0397991 0.1881544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5823 6163 0.839303 0.443356 0.006736 0.3125125 0.0588731 0.6007796 0.7334397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5824 5855 -0.652403 0.159016 0.727927 0.2758282 -0.2699159 0.6806826 0.6226840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5824 6164 0.836820 0.262187 0.599797 -0.1446312 0.3345582 -0.8478548 0.3850908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5825 5854 -0.305922 -0.362540 0.758495 -0.3944922 0.4983527 -0.2681188 0.7239702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5825 6165 0.850360 0.315119 0.316375 0.1808938 0.9284175 0.2866429 0.1521654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5826 5853 -1.123951 -0.183815 0.039603 0.2227798 -0.2109018 0.6955423 0.6497004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5826 6166 0.276699 -0.679430 0.527272 0.3982382 -0.3409753 0.5895181 0.6145002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5827 5852 -0.814332 0.641991 0.252179 -0.5975665 0.1318118 -0.5975764 0.5181142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5828 5851 -0.116485 0.609072 -1.017759 -0.2770680 0.0169307 -0.4726935 0.8363657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5828 6168 0.479804 0.610964 0.460110 0.0456524 0.1880225 0.1343363 0.9718627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5829 5810 -0.839333 -0.117025 0.517956 0.5332087 -0.1411883 0.2635884 0.7913757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5829 5850 0.734647 0.244431 -0.245917 0.5667138 -0.6831255 0.0655507 0.4559365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5829 6169 0.430035 -0.980366 0.112918 0.5730245 0.6700110 0.0379670 0.4704111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5830 6170 0.536820 0.989824 0.493384 0.1806068 -0.0045648 0.8509926 0.4931247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5831 5848 0.694668 -0.755433 -0.233177 -0.1128441 0.4679225 0.1091589 0.8697121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5831 6171 0.465620 0.188069 0.945732 0.3360245 0.1010627 -0.5074897 0.7869740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5833 5806 -0.184452 -0.874941 -0.012283 -0.2695308 -0.0367772 0.1595224 0.9489748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5833 6173 -0.766237 0.150852 0.637503 -0.4189878 -0.0458240 -0.7819640 0.4592186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5834 5374 0.385426 -1.035144 0.020953 -0.8057976 -0.5424956 -0.0534995 0.2313580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5834 5805 -0.265578 0.033667 -1.085269 0.5867227 -0.0182201 -0.7962079 0.1465521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5834 5845 0.371548 -0.192393 0.855544 0.0101114 -0.5938535 -0.7814123 0.1913912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5835 5844 0.598079 -0.529521 -0.477058 -0.7013517 0.4063191 -0.3127381 0.4951822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5836 5376 -0.677353 -0.549471 -0.374233 -0.1225911 0.4637444 0.2958125 0.8260796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5837 5842 0.703920 0.551898 -0.626180 -0.0468293 0.1100788 0.1039733 0.9873597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5837 6177 0.549837 -0.060486 0.641062 -0.0976047 0.4104919 0.8000502 0.4264849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5838 5378 -0.053877 0.656943 -0.823699 -0.4374160 0.4732011 -0.7226586 0.2500249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5839 6179 0.401594 -0.975338 0.049084 -0.5857269 -0.0423443 -0.7978798 0.1360836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5840 5340 -0.352581 -0.644102 -0.455360 0.1184958 -0.2055102 -0.9616770 0.1374834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5840 6140 0.506874 0.752855 0.538040 -0.2089526 -0.0379914 -0.2875783 0.9339134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5841 5838 -0.506209 0.708927 -0.038935 0.2644191 -0.3033707 -0.4040047 0.8214797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5842 5877 0.763064 0.522969 -0.044543 0.4447209 -0.0231260 -0.3457687 0.8259132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5842 6142 0.269627 -0.209208 1.024245 0.2846723 0.5403253 0.1909321 0.7684759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5843 5343 -0.104358 -0.251784 -0.950866 0.4482085 -0.1307618 -0.3205491 0.8241715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5843 5836 0.005804 -0.939628 0.210624 -0.4099892 -0.5480492 -0.6811011 0.2601002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5843 5876 -0.061074 0.951569 -0.262263 -0.3082186 -0.1111252 -0.9408736 0.0860772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5843 6143 0.151293 0.061785 0.827484 0.3575007 0.3996895 0.2731781 0.7986334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5844 5875 0.924628 0.267149 0.235419 0.4331027 0.3916644 0.5014419 0.6384176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5844 6144 0.450101 -0.803672 0.412855 -0.2728250 -0.4189809 0.8024494 0.3257244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5846 5346 -0.543089 0.946706 -0.499947 -0.2872097 -0.7924323 0.5348948 0.0587303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5846 5873 0.910783 0.510354 0.025963 0.2008220 0.1881948 0.4369644 0.8563383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5847 5832 -0.106474 0.072491 -0.894525 -0.0528535 0.2027456 0.5251721 0.8248000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5847 6147 0.085128 1.088404 0.084599 0.3010631 -0.7498682 -0.5855897 0.0643687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5849 5830 0.065617 -0.408491 0.991880 0.0382033 -0.1498694 0.1015081 0.9827389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5849 5870 -0.113896 0.369325 -1.085840 -0.1226770 0.2355011 -0.8360579 0.4801008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5849 6149 0.225909 0.952499 0.411054 -0.2012996 -0.0856797 -0.6023732 0.7676483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5850 5869 -0.390391 -0.971850 -0.309220 0.1391351 -0.2348028 0.9395129 0.2069412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5850 6150 0.804804 -0.560176 0.298274 0.6442246 -0.0306544 -0.2922449 0.7061359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5851 5868 -0.568459 0.706941 -0.564922 -0.2678564 0.5102518 0.5048845 0.6426412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5852 5867 -0.577421 -0.679435 -0.327687 -0.5390416 0.7320125 -0.3016590 0.2873913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5852 6152 0.636263 -0.686614 0.328999 -0.4509701 0.5189352 -0.1207685 0.7160637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5853 6153 -0.139123 -0.284919 0.874859 -0.4536226 -0.2855907 0.3121321 0.7843711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5854 5354 0.286067 0.386134 -1.058615 0.0468420 -0.0677951 -0.5394513 0.8379749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5854 5865 -0.138335 -1.043483 -0.113261 0.0741219 -0.5469405 -0.8172033 0.1659543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5855 5864 0.526255 0.636277 0.362471 0.8493845 0.2970900 0.3127909 0.3040484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5855 6155 0.634570 -0.789496 0.217108 0.0137528 0.9800335 -0.0863013 0.1785979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5856 6156 -0.157789 1.104585 0.074845 -0.0597183 -0.9641039 -0.1224347 0.2279190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5857 5822 0.599036 -0.774342 -0.494482 0.1915114 0.5637930 -0.0278340 0.8029235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5857 5862 -0.571467 0.754380 0.347729 -0.1389229 0.1447708 -0.7871195 0.5832536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5857 6157 0.890624 0.260840 0.491248 -0.3980563 0.0546539 -0.7869624 0.4682459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5858 5861 -0.625539 -0.311410 0.998683 0.5025151 0.0660680 0.0025133 0.8620367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5858 6158 0.583349 -0.791521 0.470383 -0.4467060 0.5117369 -0.5849170 0.4432281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5859 6159 -0.823797 -0.303553 0.410148 -0.7304894 -0.3087848 0.1928549 0.5777925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5860 5899 0.600399 -0.197882 0.751947 -0.4689566 -0.1113317 0.2113639 0.8503001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5860 6120 -0.862216 0.078784 0.572293 -0.0814056 0.4741262 -0.8766226 0.0105062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5861 5321 -0.269568 0.230232 -0.787816 -0.4274929 -0.5077047 -0.5957359 0.4523101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5861 5898 -0.797408 0.341977 0.601047 0.3883953 0.3681255 0.6301298 0.5626448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5861 6121 0.433187 0.029681 1.108682 -0.0951528 -0.4929758 -0.8104092 0.3019235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5862 5897 -0.480366 -0.993801 0.273655 0.1963291 -0.4236514 0.1573062 0.8701891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5862 6122 -0.312382 0.290666 0.994713 -0.6513171 -0.0596983 0.5912121 0.4719009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5863 5856 0.848148 0.012542 -0.529545 0.4883515 0.1474119 -0.3310730 0.7938345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5863 5896 -0.788527 0.130014 0.492252 0.3259791 -0.3537820 0.7896702 0.3807846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5863 6123 0.477207 0.386550 0.826572 -0.4875771 -0.6854611 -0.5325584 0.0937722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5864 5895 0.851587 -0.012769 0.141377 -0.0721042 -0.0516460 -0.3139774 0.9452787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5864 6124 -0.148395 0.835076 0.381761 -0.9461553 0.1372022 0.1558263 0.2483623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5865 5894 0.367519 0.029067 -0.910586 -0.2513819 0.8373485 0.1433627 0.4637907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5865 6125 0.289709 0.943944 0.379100 -0.4168787 0.4082231 -0.7486866 0.3146973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5866 5326 -0.096933 -0.803478 -0.156465 0.2779516 0.9275065 0.2157551 0.1261917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5866 5853 -0.210191 -0.260935 0.821466 -0.6695236 0.0210184 -0.2429156 0.7016327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5866 5893 0.229809 0.220647 -1.121247 -0.9739586 0.0153332 0.1421619 0.1759532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5866 6126 0.236184 0.999535 0.171015 -0.7345213 0.0209075 -0.5739391 0.3614350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5867 5892 1.212650 0.399989 -0.046784 -0.2000508 0.0150028 -0.3012886 0.9321908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5867 6127 0.257785 -0.896720 0.504165 0.2373834 0.6492671 -0.6477309 0.3202282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5868 5891 0.685537 0.682089 0.189687 0.2969838 0.0135806 -0.6322475 0.7154574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5868 6128 -0.486110 0.398712 0.636720 0.4958517 -0.4760841 0.0634604 0.7234969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5869 5890 0.027092 0.856974 0.145801 0.3346327 0.0773088 -0.4879157 0.8024853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5869 6129 -0.702204 0.005133 0.624137 0.2284682 0.0277811 -0.3809316 0.8955008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5870 5889 -0.237288 0.347963 -1.084764 0.8226899 -0.3235123 0.0111686 0.4673290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5870 6130 -1.000944 -0.529662 0.017075 -0.3271425 -0.9074141 -0.0806581 0.2511407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5871 5848 0.704379 -0.033635 -0.355140 0.0222031 0.3228471 -0.8435462 0.4286100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5872 5847 0.458352 0.808518 -0.589897 0.5591950 0.1319093 -0.5444322 0.6111420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5873 5333 0.370027 0.454593 -0.734582 0.2261946 -0.6005071 0.6669635 0.3786647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5873 5886 0.825718 -0.384841 0.558312 0.7790755 -0.1991698 0.1901555 0.5632172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5873 6133 -0.668775 -0.260474 0.779201 -0.4723454 -0.7436160 0.4589885 0.1151290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5874 5845 0.045767 -0.160632 -0.915585 0.6160160 0.2348077 0.1144613 0.7431610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5874 5885 -0.020845 0.005938 0.963915 0.0640111 0.0616984 0.9677248 0.2358063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5875 6135 -0.922229 0.378490 0.399998 0.4584577 0.3160401 -0.7913043 0.2525328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5876 5883 -0.191326 -0.947958 0.094324 0.1601089 0.5714968 -0.7925181 0.1402554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5876 6136 0.329192 -0.126346 0.895190 -0.6901097 0.1759486 -0.3365178 0.6160734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5877 5882 0.304387 0.594779 -0.975724 -0.3184648 0.7529823 0.4600409 0.3463527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5877 6137 0.014842 0.675631 0.586605 0.1868759 -0.6900336 -0.2338245 0.6589819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5878 5338 0.806864 0.675266 -0.356708 -0.6420899 -0.3591400 0.4589664 0.4980852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5878 5841 0.588042 -0.777214 -0.194910 -0.8147075 -0.4996686 0.2633746 0.1312126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5878 5881 -0.523496 0.706724 0.172384 0.6549889 -0.2414423 -0.4797625 0.5315290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5878 6138 -0.763821 -0.628158 0.347268 -0.2844468 -0.8183782 0.4593463 0.1958267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5879 5339 -0.085993 -1.006703 -0.163191 0.1782467 -0.1576346 0.9711379 0.0164494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5879 5840 0.347556 0.490543 -0.728089 -0.3291672 -0.7494760 -0.2363672 0.5235124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5879 6139 0.165029 0.993602 0.469285 -0.8603102 -0.1087388 -0.0684543 0.4933116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5880 5919 -0.086561 -1.033860 -0.179729 -0.0985960 0.4626324 0.7584335 0.4483623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5880 6100 0.414960 -0.321968 0.850837 -0.2932097 -0.3261885 -0.8361338 0.3294076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5881 5918 -0.996517 -0.218665 0.153764 -0.3888717 -0.5560221 -0.6665407 0.3087746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5881 6101 0.068371 0.348515 0.830769 -0.4394530 -0.0532825 -0.1557268 0.8830579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5882 6102 -0.636615 0.656997 0.708112 -0.5748816 0.1933022 0.5529004 0.5713550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5883 5916 0.195686 0.224094 0.991205 -0.3291540 -0.0463113 0.7369600 0.5885600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5883 6103 -0.706689 -0.510955 0.226310 0.5646569 0.5708930 -0.3403415 0.4892969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5884 5875 -0.021341 1.006710 0.481781 0.2372253 0.6910891 -0.5687770 0.3776411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5884 6104 0.891018 -0.028715 0.426694 0.7827168 0.2950502 -0.0177364 0.5477091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5885 5305 0.687261 -0.658935 -0.196373 0.2048403 -0.4077973 -0.6941027 0.5567435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5885 6105 -1.056661 0.652213 0.140124 -0.2557552 -0.2273120 -0.6539107 0.6747736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5886 5913 1.155410 -0.159299 0.152756 -0.7758099 0.4437897 0.2279230 0.3862913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5887 5872 0.187163 0.946581 -0.208918 0.0473038 -0.1238399 0.1821172 0.9742994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5887 6107 0.807672 0.018573 0.627721 -0.1902055 0.3902906 -0.7132406 0.5502572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5888 5871 -1.031228 0.117584 -0.003913 0.2968846 0.5794297 0.7466090 0.1367322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5888 6108 0.179615 0.878649 0.109283 0.3697442 -0.0984713 -0.9056478 0.1827424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5889 5309 0.365265 -0.731504 -0.596508 -0.2312410 -0.6460124 -0.6213306 0.3783436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5889 5910 -0.700687 -0.694539 0.425263 -0.0573410 0.2527218 0.0198192 0.9656350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5889 6109 -0.229980 0.694878 0.584205 -0.0691441 -0.4818808 -0.0536909 0.8718528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5890 5310 0.283674 0.264687 -0.654463 0.0083181 -0.8601735 0.3097141 0.4051043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5890 5909 -0.835470 0.491191 -0.634889 0.1886163 0.0726690 -0.7361945 0.6458799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5891 5311 0.646733 0.350675 -0.484798 -0.0868255 -0.5771275 -0.1249816 0.8023496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5891 5908 -0.511454 0.439538 -0.314357 0.4857962 -0.2453987 0.1561765 0.8242515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5891 6111 -0.829668 -0.280817 0.596577 0.7175623 0.5288697 -0.4436024 0.0928340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5892 5312 -0.892049 0.512974 0.015995 0.4105659 0.2954547 0.7054262 0.4965039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5892 5907 0.533058 0.672031 -0.050247 0.9740803 -0.0117662 0.1587651 0.1606946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5892 6112 0.827802 -0.672654 0.190055 -0.0168107 0.2894254 0.3066766 0.9065869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5893 5906 0.716187 0.172232 0.879822 -0.1677680 0.5028924 -0.7193413 0.4488888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5893 6113 -0.112979 -0.934883 0.069724 0.3828124 0.0890393 -0.2302790 0.8902237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5894 6114 -0.749038 0.524267 0.289759 0.7206064 -0.1477255 -0.6148926 0.2842722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5895 5904 0.793981 0.667055 -0.155998 -0.4598853 -0.5630506 -0.5575021 0.4008379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5895 6115 -0.475210 0.581506 0.513622 0.4558289 -0.5536253 -0.6137269 0.3302398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5896 5903 0.869853 0.591083 -0.065697 0.6209835 -0.5925538 0.3847940 0.3394010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5896 6116 0.545027 -1.045682 0.123786 -0.1568961 0.4902238 -0.4332235 0.7398525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5897 6117 0.572356 0.860517 0.553140 -0.6097866 -0.5259523 -0.2570174 0.5343001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5898 5318 -0.029388 -0.665004 -0.615475 -0.5537772 0.4619274 0.6639063 0.1979453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5898 5901 0.680199 0.744506 -0.351974 0.0685119 -0.3026482 0.9476943 0.0747380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5898 6118 0.168610 0.685699 0.773719 0.1779109 0.1935666 0.9407977 0.2139612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5899 6119 -0.671624 -0.265417 0.737428 0.2330584 -0.6342861 -0.3551251 0.6459497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5900 5939 -0.329328 -0.051146 0.974712 0.6125948 0.0331322 0.5322440 0.5833920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5900 6080 0.086361 -0.858071 0.008053 -0.0233969 -0.2594701 0.3449708 0.9017333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5901 5938 -0.800856 -0.489370 -0.658763 0.2174122 0.3067222 -0.0242422 0.9263184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5901 6081 0.398586 -0.834777 0.369754 0.0314815 0.0915038 -0.8778467 0.4690641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5902 5897 -0.064856 -0.770807 -0.636524 0.1246121 0.1590427 0.9791891 0.0191306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5902 5937 0.285749 0.783884 0.609664 -0.1707580 0.3783450 -0.8866168 0.2039791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5902 6082 -0.259155 -0.563579 0.853738 0.0615395 0.6641698 -0.5119179 0.5413238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5903 5936 -0.312348 -0.696503 -0.440534 0.4075591 0.0629074 -0.6965330 0.5871797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5903 6083 0.703305 -0.242149 0.487611 0.0442393 0.4642160 -0.2468810 0.8494681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5904 5935 -0.141217 0.687351 0.554194 0.2771480 0.4429903 -0.4682074 0.7125521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5904 6084 0.615022 -0.463699 0.534549 -0.6946602 0.4805971 -0.4755667 0.2455809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5905 5894 -0.034907 0.296047 0.887482 0.9736204 -0.0510933 -0.1207015 0.1867726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5905 5934 0.323827 -0.379994 -0.923856 0.3898300 -0.6249711 0.1490346 0.6597215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5905 6085 -0.743832 -0.524267 0.062876 0.5850326 0.5225755 -0.6186607 0.0437102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5906 5933 -0.497708 -0.591043 0.851894 -0.5924325 0.3582344 -0.5484672 0.4689088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5906 6086 0.930286 0.197060 0.579684 -0.3856763 -0.0788692 0.3295788 0.8581441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5907 5932 0.483636 -0.737694 -0.300997 0.7853117 0.3948016 0.3645330 0.3074621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5908 5288 0.296704 -0.438757 -0.641173 0.0228850 -0.6287070 -0.2233794 0.7445169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5908 5931 -0.873011 0.302325 -0.524683 0.1905335 0.2535369 -0.1840785 0.9303392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5909 6089 0.132860 -0.411501 1.033297 0.0720609 -0.3900994 0.3122096 0.8632235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5910 5929 -0.747989 -0.661331 -0.028154 -0.5991425 0.1224807 0.6481745 0.4537583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5911 5888 0.139438 -0.722711 0.877429 -0.0177635 0.4745856 0.5663648 0.6735606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5911 5928 -0.207667 0.470079 -0.952888 0.2013365 -0.9039382 -0.2973356 0.2322734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5911 6091 -0.619970 0.559223 0.324896 -0.4829036 -0.7232835 -0.2033799 0.4497796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5912 5887 -0.886377 0.107875 -0.604193 0.0563688 -0.3210703 0.8216001 0.4676640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5912 6092 -0.759574 0.200421 0.993618 0.3564671 0.1620127 -0.0322413 0.9195888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5913 5926 0.431926 -0.791999 -0.167421 -0.4615389 0.1629491 0.7993308 0.3485680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5914 5925 0.255749 0.022974 0.811779 -0.0429926 0.1095797 0.1744608 0.9776029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5915 5884 0.694687 -0.586801 -0.182508 -0.7731682 -0.1585319 -0.5937213 0.1567596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5915 5924 -0.753371 0.619618 0.226272 -0.0358734 -0.4387076 -0.8931191 0.0926663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5915 6095 0.597049 0.438947 0.807651 -0.1160427 0.3095787 -0.8313385 0.4467341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5916 5296 0.557571 -0.632183 -0.461532 0.1591318 -0.2120934 -0.7280058 0.6322191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5916 6096 -0.586396 0.841192 0.439854 0.4632125 -0.7593601 -0.3445377 0.3001670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5917 5297 -0.893496 0.698492 -0.079951 0.6442699 -0.3455368 0.6477419 0.2143619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5917 5882 -0.407320 -0.662744 0.494072 0.6358566 0.5545935 0.5094915 0.1689106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5917 5922 0.550282 0.518086 -0.800026 0.2611131 -0.1902952 0.3604513 0.8750329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5917 6097 0.760346 -0.710855 0.044198 0.1971397 0.1676123 -0.7604768 0.5955813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5918 5921 0.659624 -0.728167 -0.470482 0.1982767 0.7762617 -0.0058441 0.5983895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5918 6098 0.879319 0.271749 0.636391 0.4685741 0.5044491 -0.1186919 0.7154590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5919 6099 -0.925199 0.442781 0.312752 0.4157341 -0.3129109 -0.2260071 0.8235124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5920 5959 0.972709 -0.045126 -0.349045 -0.0874044 0.6205494 0.0317518 0.7786339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5920 6060 0.201834 0.729250 0.617321 -0.7953891 0.3811461 -0.1040179 0.4596348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5921 5958 -0.179982 -0.480596 0.912190 -0.3136312 -0.1514611 0.8872565 0.3024414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5921 6061 -0.484219 0.808040 0.504165 0.0688194 -0.5972912 0.2232024 0.7672599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5922 6062 0.186947 -1.105756 0.226221 -0.3243556 0.7620558 -0.1931224 0.5260877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5923 5916 0.893610 -0.230433 -0.513375 -0.7461971 -0.2147953 0.6023269 0.1850818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5924 5955 0.634124 -0.293410 0.670713 -0.1073887 -0.2856725 0.9253456 0.2249320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5924 6064 -0.518129 0.365975 0.792524 -0.2588741 -0.4645623 0.4443729 0.7209014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5925 5954 0.271186 -0.015493 1.282402 0.0776701 -0.4788074 -0.3835512 0.7858749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5925 6065 -0.523035 0.871479 0.234129 -0.7768283 -0.4810785 -0.0464270 0.4036654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5926 6066 -0.653410 0.723839 0.510711 0.3328935 -0.1566492 -0.2080910 0.9062787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5927 5912 -0.673730 -0.666302 -0.568005 0.3869288 0.2722739 0.6622238 0.5810445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5927 6067 0.697567 -0.773134 0.371161 -0.0108019 0.1867547 -0.2845765 0.9402246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5928 5951 -0.294410 -0.036496 0.871340 0.4559912 0.5747650 0.5408608 0.4113232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5928 6068 0.242268 0.999456 0.318692 0.3754298 0.8041945 0.4473536 0.1104465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5929 5950 -0.049266 0.926262 0.119906 -0.4583177 0.1499798 0.7603674 0.4350774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5929 6069 -0.140028 -0.090676 1.049593 -0.4439437 -0.4859235 0.1579238 0.7361062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5930 5909 0.029002 0.889343 0.652389 0.1625276 0.1372463 0.1572140 0.9643817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5930 5949 0.066593 -0.877460 -0.622245 0.5366168 -0.2262239 0.5643521 0.5851256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5930 6070 0.349011 -0.464271 0.741890 -0.0215071 0.2332869 0.8863936 0.3992758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5931 5271 0.844070 -0.485173 -0.086839 -0.2008546 -0.1068821 0.4293952 0.8739870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5931 5948 -0.304186 -0.051276 -0.989929 0.5427500 -0.3732624 -0.5251431 0.5388157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5931 6071 -1.050258 0.514061 0.130808 -0.0178797 -0.7573138 -0.0205562 0.6524827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5932 5947 -0.552454 0.629660 0.622722 -0.2769675 0.7711109 0.0051605 0.5732803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5932 6072 0.836590 0.400010 0.440175 -0.1341641 0.7191568 -0.6380410 0.2402439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5933 5946 0.513612 -0.703753 -0.463952 0.5328416 -0.3788715 0.5069965 0.5616857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5933 6073 0.032651 -0.398287 0.734275 -0.2624084 0.3933387 -0.8426137 0.2577374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5934 5274 0.031329 -0.094383 -1.092167 -0.6022947 -0.0796289 -0.5615381 0.5617609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5934 5945 -0.783016 -0.640946 0.198887 0.4711319 -0.2360626 -0.5242789 0.6689102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5934 6074 0.098200 0.207572 0.987631 -0.1410388 -0.5889111 -0.7520687 0.2601625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5935 5275 0.268497 -0.443198 -0.990886 0.1539368 -0.1625394 -0.9419059 0.2503950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5935 6075 -0.210046 0.353852 1.115905 -0.4083310 0.1513332 0.8714014 0.2258840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5936 5276 0.069011 -0.886455 -0.188184 -0.0372845 -0.3837844 -0.4655610 0.7966005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5936 5943 0.898129 -0.070064 0.359631 -0.6279220 -0.0662749 -0.3689834 0.6820358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5936 6076 0.028425 0.989256 0.365579 -0.6258500 0.3255765 0.5998097 0.3775447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5937 5942 -0.682310 -0.693537 -0.211381 0.3381035 -0.0382748 0.4711084 0.8138046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5937 6077 0.535505 -0.367471 0.548904 0.3012072 -0.1255773 -0.8127070 0.4827131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5938 5278 0.146745 0.560133 -0.788682 -0.4246901 0.0826016 -0.8902676 0.1422635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5938 5941 -0.396008 -0.627122 -0.654600 0.5219137 -0.2237136 -0.8040816 0.1760995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5938 6078 0.085943 -0.761077 0.737185 -0.1159334 0.3857205 -0.6952865 0.5952779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5939 6079 -0.505084 0.223046 0.863945 0.0031378 0.2635061 0.8597124 0.4375492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5940 5979 0.634467 0.568634 0.681776 -0.7484803 0.2685388 0.5788909 0.1804149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5941 6041 -0.051956 0.764406 0.230616 -0.5604889 -0.1197705 0.5028897 0.6470001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5942 5977 -1.071588 0.114841 0.416750 -0.5981453 0.0116218 -0.3616224 0.7150639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5942 6042 0.361658 -0.365366 1.044747 0.3942905 0.4270814 -0.5853510 0.5652439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5943 5243 0.305905 0.305309 -0.790541 0.5007291 -0.4566643 0.3605790 0.6408673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5943 5976 0.872368 0.472246 0.330935 -0.0241193 -0.3172731 -0.9208180 0.2255002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5944 5975 0.806980 0.177060 0.536058 -0.3290004 -0.1580465 0.0294147 0.9305454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5944 6044 -0.367722 0.878695 0.513100 0.5600696 0.2748290 0.7749077 0.1015338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5945 5974 0.284098 -0.242315 1.032149 0.1750529 0.7133941 0.6170285 0.2823140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5945 6045 -0.410932 0.895949 0.219198 0.3286958 0.3253033 0.8665269 0.1877975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5946 5973 -0.649394 -0.536107 0.410212 -0.4675632 0.2461777 0.1281960 0.8392538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5947 5247 0.724827 0.097668 -0.858460 -0.0801576 0.5609425 -0.7093363 0.4192377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5947 5972 -0.577403 0.338327 -0.528532 -0.2925398 0.0337390 -0.5405525 0.7880896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5947 6047 -0.725434 -0.159494 0.706745 -0.4184970 -0.1964321 0.0080954 0.8866844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5948 5971 0.234235 -0.992069 0.060136 0.0973854 -0.4793769 -0.8343250 0.2541961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5948 6048 -0.739685 0.180505 0.820847 0.3247678 0.1449668 -0.7653824 0.5363771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5949 6049 0.536974 0.035598 0.761437 -0.2305955 -0.0221352 -0.9708732 0.0611628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5950 5250 1.166975 -0.104815 -0.646796 0.2231248 -0.8255679 -0.1164395 0.5050692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5950 5969 0.658224 -0.186354 0.634628 0.4455136 -0.4054222 0.2965178 0.7410990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5950 6050 -0.862267 -0.069669 0.469614 0.2187528 -0.5415439 -0.6537453 0.4811388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5951 5968 0.021193 1.038874 -0.331484 -0.2552845 0.0861775 -0.8546061 0.4439050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5951 6051 0.849070 0.163963 0.501212 -0.1427334 0.2987610 -0.8227020 0.4620936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5952 5967 0.726325 0.285303 -0.692235 0.0588036 -0.1937367 0.9211093 0.3325146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5952 6052 0.650420 -0.488428 0.756921 0.6153864 -0.5283878 0.4746513 0.3417778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5953 5253 -0.517752 -0.996244 -0.062744 -0.6110282 -0.2131303 -0.7592217 0.0692992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5953 5926 -0.799869 0.527238 -0.526786 0.0000423 -0.8366708 -0.4789201 0.2657393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5953 5966 0.691589 -0.415537 0.520726 -0.5739354 0.4104717 -0.3869930 0.5935887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5954 5254 0.606604 -0.423437 -0.761518 0.2639439 0.3604725 0.8217707 0.3536752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5954 5965 0.898233 0.454802 0.490578 -0.5780315 -0.1524776 0.5295846 0.6018059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5954 6054 -0.685205 0.367333 0.576056 -0.6217076 -0.4882464 -0.1515864 0.5933942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5956 5923 -0.727058 -0.256909 -0.675080 0.1197928 0.0625238 -0.9019701 0.4101102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5956 5963 0.801762 0.541963 0.796611 -0.3046290 0.7050180 0.6388103 0.0455222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5956 6056 -0.303579 0.836051 0.149597 -0.4580093 -0.2173571 -0.3522235 0.7867160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5957 5922 -0.004499 0.699013 0.539538 -0.2703677 -0.0486408 -0.3866305 0.8803705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5957 5962 -0.094644 -0.768372 -0.518854 0.5194743 -0.3769430 -0.4523211 0.6192463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5957 6057 -0.513391 -0.455527 0.541482 0.5741749 -0.1686428 0.0581011 0.7990663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5958 5961 -0.529678 -0.056795 0.805813 -0.5708911 0.3300852 -0.6933388 0.2905312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5958 6058 0.785433 -0.476669 0.682261 0.8069623 0.2114190 0.4948840 0.2433181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5959 6059 -0.488291 0.813369 0.422268 -0.1493487 -0.1689913 -0.8713442 0.4357708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5960 5999 -0.019085 -0.648269 -0.859324 0.7298341 0.2007749 -0.4608829 0.4632695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5960 6020 -0.770658 -0.609950 0.631945 -0.2905861 -0.3977313 0.6550108 0.5730012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5961 5998 0.570200 -0.651641 -0.600012 -0.6254717 0.4163375 0.0824303 0.6547163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5961 6021 0.640510 -0.286553 0.849891 0.2153465 -0.3641482 0.6937328 0.5828865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5962 5222 -0.386079 -0.610833 -0.881476 -0.2482311 0.1884400 0.3548506 0.8814492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5962 5997 0.950275 -0.788533 0.185007 0.1723623 0.3301517 0.6181306 0.6922468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5962 6022 0.409945 0.497883 0.762716 -0.6069352 0.3707655 0.6052688 0.3575085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5963 6023 0.168127 0.428134 0.686618 -0.5442656 0.3252822 0.3251220 0.7016139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5964 5955 -0.590003 -0.118153 0.521619 0.5282056 -0.6185421 0.5572342 0.1670163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5964 6024 0.582119 -0.660107 0.492777 0.2585505 0.2737197 -0.1349406 0.9165261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5965 5994 0.764171 -0.753893 -0.150978 0.6642501 -0.0462566 -0.5250880 0.5300138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5966 5226 0.616061 0.053014 -0.750900 0.0268954 -0.1595224 0.8694675 0.4667500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5966 6026 -0.817470 -0.087779 0.829153 0.4429793 0.2947009 -0.7570783 0.3791480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5967 5227 0.402517 0.162356 -0.687769 0.3079490 -0.0925413 -0.8799703 0.3496510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5967 5992 -0.765639 -0.529487 -0.645124 0.5255965 -0.1423363 0.2868765 0.7881564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5968 5228 0.532776 -0.391459 -1.034179 -0.0211316 0.5413078 0.5176693 0.6622369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5968 5991 -1.001658 -0.442528 -0.157153 -0.7370569 -0.2775348 0.6097478 0.0890455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5968 6028 -0.285071 0.427041 0.827468 0.3201549 -0.2184275 0.3239688 0.8630379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5969 6029 -0.141290 0.928813 0.534117 -0.5217152 0.6592425 0.4784786 0.2535168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5970 5230 -0.086717 -0.497638 -0.899700 0.0356586 -0.2270976 -0.2243475 0.9470076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5970 5949 1.031979 0.178091 -0.255507 -0.3221023 -0.2072623 0.1897204 0.9040457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5970 5989 -0.906227 -0.094224 0.289549 0.2036001 0.0635483 -0.9746168 0.0680491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5971 5988 0.346370 0.560925 -0.932038 -0.4108697 -0.2969534 -0.8619401 0.0080041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5971 6031 0.643745 0.239339 0.658313 -0.4265957 0.1857165 0.4965491 0.7327786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5972 5232 -0.180952 0.993107 -0.068383 0.4263873 -0.4941640 -0.2699875 0.7078859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5973 5986 -0.869037 -0.456916 -0.465951 0.5016669 0.4718490 0.5460692 0.4769668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5974 5234 -0.665104 -0.483024 -0.490096 0.6255814 0.2093586 0.7473912 0.0788877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5974 6034 0.705365 0.400762 0.479972 -0.1674358 -0.6823633 -0.4609991 0.5420566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5975 5984 1.042404 0.036145 0.093540 0.4388952 -0.3655397 -0.8202397 0.0309601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5976 5236 -0.636596 -0.670502 -0.534378 -0.4025483 -0.0852184 0.1751520 0.8944353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5976 5983 -0.901599 0.524168 0.379036 -0.8259947 0.0821250 -0.5010384 0.2448441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5976 6036 0.400870 0.700509 0.455548 0.4125001 -0.0450371 0.8957723 0.1593968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5977 5982 -0.422253 -0.856597 -0.142262 0.4927972 0.7683853 -0.0849101 0.3994060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5977 6037 0.705396 -0.727488 -0.012102 -0.4053812 0.3456842 -0.4532380 0.7146634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5978 5941 0.469135 -0.307682 -0.986446 0.5754809 0.5078237 0.6402993 0.0308809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5978 5981 -0.443152 0.183533 0.921633 -0.6924795 0.4525438 -0.2838416 0.4848816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5978 6038 0.935252 -0.392170 0.462897 0.3937988 0.3572357 -0.1927833 0.8247058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5979 6039 -0.819631 0.619786 0.184804 0.0726729 -0.0012331 -0.9326829 0.3532982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5980 6000 0.177808 1.005708 0.111029 -0.5824149 -0.1600588 -0.3194410 0.7301585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5981 6001 0.608743 -0.492019 0.490084 0.4387791 -0.4187412 0.7448488 0.2780807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5982 6002 -0.850795 0.249272 0.604175 -0.5626296 0.1622557 -0.2169523 0.7810587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5983 6003 0.498805 -0.851707 0.377425 0.6596385 -0.1948655 -0.2387677 0.6854885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5984 6004 -0.713660 0.374024 0.716317 -0.1970943 0.4576205 0.8613937 0.0986825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5985 5974 -0.569540 -0.274670 0.801913 -0.5488803 -0.1570296 -0.5174507 0.6374299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5985 6005 0.998544 0.255452 0.493173 0.1523074 -0.1096003 0.8632444 0.4686143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5986 6006 -0.593200 0.666987 0.332022 -0.6995173 -0.2282659 0.2894461 0.6122019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5987 5207 0.695020 -0.805437 -0.403827 -0.0813096 -0.7682381 -0.1640825 0.6134133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5987 5972 -0.512984 -0.050993 -0.839898 0.7034637 0.2945709 -0.6413293 0.0840448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5987 6007 -0.830108 0.699332 0.444000 -0.6865476 0.0054696 -0.1852243 0.7030750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5990 5210 0.170343 -1.065226 -0.125140 -0.6414767 0.5084867 0.5648780 0.1042194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5990 5969 -0.498599 -0.142706 0.768676 -0.1552180 0.6379484 0.1498939 0.7392300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5990 6010 -0.015732 0.924709 -0.005061 0.0130295 -0.6915574 -0.4563606 0.5597442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5991 6011 -0.665090 -0.749591 0.175574 -0.1151876 0.8752287 -0.4344092 0.1788723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5992 6012 -0.132891 0.637053 0.512587 -0.4154923 -0.4049548 0.3416674 0.7393518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5993 5213 -0.835127 0.621939 -0.360106 0.5213234 0.6500599 0.5386814 0.1243641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5993 5966 -0.520261 -0.605706 -0.059233 0.2848357 0.3379005 0.6824502 0.5821972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5994 5214 0.384242 -0.609588 -0.536765 -0.1877046 -0.8617683 -0.1963260 0.4284605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5994 6014 -0.260281 0.649936 0.669374 0.0468342 -0.0901214 -0.4525176 0.8859529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5995 6015 0.629578 -0.000534 0.658762 -0.5744023 -0.4142972 -0.5302261 0.4661331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5996 5963 -0.837234 0.177298 0.557716 -0.4580738 -0.5765129 -0.6300013 0.2467784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5996 6016 0.584939 0.841617 0.016221 -0.5735053 -0.4315785 -0.3099875 0.6234897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5997 6017 0.490904 0.481935 0.735869 0.2373625 -0.5986389 -0.7606935 0.0814606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5998 6018 -0.160974 -1.009411 -0.192148 -0.2521755 0.5630871 -0.4325603 0.6574435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5999 6019 -0.761076 -0.126420 0.596188 -0.3006476 0.4280119 0.8303854 0.1920336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6000 6039 0.078932 -0.849451 -0.068099 -0.2821741 -0.5409365 0.5783914 0.5415061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6002 6037 -0.511909 0.662420 0.716102 0.3350753 -0.3538181 -0.7539476 0.4405682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6002 6782 -0.695514 -0.693563 0.098725 0.7268128 0.2268430 -0.5009918 0.4114518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6003 6036 -0.388062 0.918602 -0.697838 -0.8250785 0.2778014 -0.2979274 0.3915496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6004 6035 -1.115204 0.186546 0.202005 -0.3066304 0.3358594 -0.1482906 0.8781720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6004 6784 0.512341 0.490828 0.693453 -0.1412867 0.7793418 0.4537737 0.4083550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6005 6034 0.385450 0.399981 0.899777 0.9376978 -0.1325995 -0.1272583 0.2948654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6005 6785 -0.007634 -0.712528 0.501990 -0.2002098 -0.5488392 0.3466900 0.7338240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6007 6032 -0.541695 0.825683 -0.235560 -0.5563132 -0.6999615 0.1127182 0.4334331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6007 6787 -0.660496 -0.348224 0.524088 -0.3828043 -0.2937591 -0.1360722 0.8652461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6008 5988 -0.203181 -0.283113 -0.743328 0.0516720 0.2653131 0.6397456 0.7194891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6008 6031 -0.675779 0.786905 -0.072730 -0.6080068 0.2318093 -0.3354813 0.6812081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6008 6788 0.195643 0.289091 0.920793 -0.3528061 0.1692593 -0.6179124 0.6819556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6009 5989 -0.369054 0.015238 -0.951339 -0.1874561 0.0002927 0.7385678 0.6475938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6009 6789 0.508344 0.124736 0.845314 -0.0462520 0.2966702 -0.0841058 0.9501441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6010 6029 0.877993 0.062284 0.581400 0.1058929 0.0070744 -0.3027521 0.9471419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6011 6028 0.130200 0.619236 0.776040 0.8951880 0.1258892 0.4238077 0.0563678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6011 6791 0.511172 -0.835664 0.288599 0.1543791 0.4870858 0.6052603 0.6103888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6012 6027 0.330709 -0.097653 -0.721415 -0.2837533 -0.0291697 -0.9414006 0.1799946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6012 6792 0.800073 -0.001225 0.673074 -0.6181509 0.1795462 -0.1773981 0.7444343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6013 5993 -0.708237 0.603732 -0.632318 -0.5002654 0.3222285 -0.3210958 0.7367502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6014 6794 -0.426948 0.218317 0.685702 0.5420355 -0.0647462 -0.3917177 0.7406501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6015 6795 0.795305 0.704738 0.349650 0.5980434 0.6940917 0.2521782 0.3114272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6016 6023 0.521534 -0.890616 0.574598 -0.4968543 0.6209602 -0.1510103 0.5871458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6016 6796 0.432533 0.539275 0.637854 0.6067798 0.5039551 0.5596858 0.2541640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6017 6022 -0.768006 -0.779194 0.220558 0.6923413 -0.0623254 -0.5668706 0.4420823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6017 6797 -0.764375 0.619920 0.154917 -0.1113812 -0.9338747 -0.0852309 0.3289499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6018 6021 -0.035509 -0.331918 -0.851515 -0.3998053 0.6847410 -0.1723655 0.5844447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6019 6799 -0.091735 0.960964 0.655422 0.6839628 -0.2194260 -0.6941954 0.0462586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6020 6059 0.745039 -0.655625 0.214548 -0.4734849 -0.2470416 0.3842050 0.7531062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6020 6760 -0.333581 0.197174 1.050728 -0.3559696 -0.3698201 0.4347873 0.7399180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6021 6058 0.763798 0.664247 0.051570 -0.5862653 -0.1027264 -0.8028391 0.0344916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6021 6761 0.503498 -0.511290 0.719504 0.0471511 -0.9240385 0.3608044 0.1172592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6022 6057 0.103882 0.407580 0.966094 0.6352122 -0.3596038 -0.1738981 0.6610220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6023 6056 0.460611 -0.881775 -0.247745 -0.3949533 -0.3373515 0.5529795 0.6514749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6023 6763 -0.777732 -0.310478 0.553363 -0.3696534 0.3322232 0.7054182 0.5053407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6024 6015 0.937193 -0.019967 -0.064186 -0.1952266 -0.4492537 -0.6712453 0.5563159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6024 6055 -1.021813 -0.027407 0.240330 -0.2889747 -0.1148937 0.9284077 0.2033522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6024 6764 0.287986 -0.386597 1.051521 0.3785620 -0.2907161 0.0074044 0.8787037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6025 6014 0.449642 0.928643 -0.020150 0.1431741 0.7197716 -0.2748827 0.6211840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6025 6054 -0.357881 -0.779795 0.093126 -0.1878876 0.0319098 0.2965678 0.9358032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6025 6765 0.889761 -0.314142 0.389162 0.8007640 -0.3813754 0.3791222 0.2638107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6026 6013 -0.646334 0.596517 0.261723 0.1311768 -0.7313413 0.6690361 0.0179785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6026 6053 0.466363 -0.855267 -0.288292 0.1268893 -0.5752598 0.6642464 0.4601652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6026 6766 -0.227180 -0.551702 0.580484 0.5210685 -0.5306956 -0.4655508 0.4797001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6027 5967 0.180989 -0.354540 -0.961912 -0.4778191 0.1006275 0.7904044 0.3698971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6027 6767 -0.210243 0.342562 0.843808 -0.1385588 -0.5185089 -0.8042228 0.2552954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6028 6051 1.108216 -0.232743 -0.171269 -0.3829239 0.4136014 -0.3595103 0.7436770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6028 6768 0.334203 0.841345 0.405066 -0.5384699 0.4916060 -0.6090816 0.3120790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6029 6050 0.631649 0.744269 0.471646 -0.1721771 -0.0544225 0.9260341 0.3314424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6029 6769 -0.956728 0.186372 0.528083 0.2970986 -0.1218387 0.7655549 0.5575065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6030 5970 0.242708 -0.010193 -0.993648 0.2911880 -0.2291943 -0.8259773 0.4247835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6030 6009 0.108092 0.791392 0.326106 0.0597572 -0.3305019 -0.3001647 0.8928039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6030 6049 -0.334253 -0.828695 -0.345015 -0.0282569 -0.0848708 0.6656680 0.7408675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6030 6770 -0.071259 -0.123908 0.937155 0.1927592 -0.0963034 -0.7585451 0.6149626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6031 6771 -0.147094 -0.928728 0.525567 0.6078971 0.3316284 -0.5873298 0.4189599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6032 5972 0.383397 1.082113 -0.098750 0.0064777 -0.1408164 -0.0612957 0.9881152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6032 6047 0.597693 -0.123430 0.661513 0.0220697 -0.5488626 0.2387675 0.8007827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6032 6772 -0.096569 -0.960076 0.249101 0.0568461 -0.9844469 0.0879507 0.1410582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6033 5973 0.682246 0.522909 -0.883790 -0.0723586 -0.0427715 -0.4744115 0.8762811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6033 6006 -0.924580 0.251927 -0.402144 -0.0336179 -0.4069567 0.3455598 0.8448932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6033 6773 -0.447422 -0.583314 0.806047 0.1358313 -0.6846532 -0.0189843 0.7158488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6034 6045 0.284458 0.070669 -1.116385 0.2847676 0.2933132 0.7995839 0.4399322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6035 5975 0.281257 -0.219967 -0.842075 0.0964210 -0.0743017 0.0859863 0.9888319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6035 6044 -0.880054 0.187892 -0.297544 -0.5749713 0.0055734 -0.7606578 0.3012917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6035 6775 -0.216241 0.142527 0.930625 -0.0696888 -0.5869911 -0.6418372 0.4884977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6036 6043 -0.812536 0.000408 0.349983 0.7937601 -0.1463511 0.0172484 0.5901090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6036 6776 0.293340 -0.732086 0.520549 0.0602654 -0.4000566 0.8848371 0.2310542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6037 6042 -0.412968 0.194157 1.082399 0.1819466 0.6437034 0.6646754 0.3327882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6037 6777 0.869552 -0.042499 0.640472 0.6182359 0.2513155 0.1090560 0.7367033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6038 6001 -0.833238 0.339217 0.150851 -0.2935900 0.1156326 0.4320990 0.8448222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6038 6041 0.903015 -0.517610 -0.164277 0.3684698 0.0639947 0.9261420 0.0489453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6038 6778 0.177106 0.604218 0.892339 -0.3649325 -0.1139783 -0.7965506 0.4683379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6039 6779 0.261644 -0.936648 0.227186 0.6033588 -0.2037277 0.7135272 0.2921165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6040 5940 -0.184611 0.880707 -0.106799 0.4148952 -0.0297734 0.5294065 0.7393946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6040 6079 -0.072618 -0.190272 -1.075841 -0.4192513 0.3568073 -0.8291747 0.0968823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6040 6740 0.239106 -1.101137 0.147225 0.3657682 0.1031990 -0.5350256 0.7545271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6041 6078 -0.789064 0.578521 0.679726 -0.2072977 0.2130526 -0.2129817 0.9307390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6041 6741 0.480495 -0.008276 0.803846 -0.0425298 0.1810285 0.1540352 0.9704087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6042 6077 0.311385 1.057626 -0.051183 0.5818763 -0.6743914 -0.2552577 0.3761115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6042 6742 -0.754079 0.284917 0.590001 -0.2920255 -0.2527026 0.1598146 0.9084722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6043 5943 -0.485526 -0.585172 -0.588788 -0.5446093 0.2557437 -0.5351279 0.5929874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6043 6076 -0.553950 0.649460 -0.071902 -0.3296665 0.4098609 0.6116067 0.5909918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6043 6743 0.449468 0.583669 0.543258 -0.1067818 0.9259676 0.1418690 0.3332490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6044 6075 -0.136726 -0.212624 -1.126921 0.5054810 -0.0467846 0.7547950 0.4154331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6044 6744 0.695635 -0.620982 -0.036772 -0.3761804 -0.3279521 -0.8608794 0.0991080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6045 6074 -0.352246 -0.688568 -0.672944 0.8809338 0.1985295 0.2929143 0.3142339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6045 6745 0.783789 -0.528859 0.275544 0.4887032 0.6307699 0.1221585 0.5902336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6046 5946 -0.211887 -0.637322 -0.762674 0.2290960 0.1189307 0.6339778 0.7290012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6046 6073 -0.841362 0.795170 -0.223707 -0.3976497 -0.1337359 -0.8927981 0.1640152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6046 6746 0.523970 0.506538 0.719681 -0.1373131 0.1141399 -0.9509276 0.2526931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6047 6747 -0.337279 -0.650967 0.626644 0.5115630 0.1085361 -0.3317678 0.7851455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6048 6031 0.664713 0.652424 0.743594 -0.2014001 -0.4277218 0.2714314 0.8383418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6048 6071 -0.659411 -0.596950 -0.609690 0.2414287 -0.1291203 -0.9311886 0.2406824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6048 6748 -0.427475 -0.593338 0.657300 -0.0258659 0.0567031 0.1773595 0.9821707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6049 6749 0.009505 0.094030 0.937499 -0.3049398 0.2235349 0.0438902 0.9247256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6050 6069 -0.040038 -1.084510 0.374279 -0.5985572 -0.1203130 0.2445230 0.7533011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6050 6750 0.442457 0.219942 0.849542 -0.1555790 -0.3205648 0.9074961 0.2224504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6051 6068 0.663065 0.193890 0.592758 0.0082487 0.1483154 0.8803706 0.4504244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6052 6027 -0.628510 -0.703934 -0.048232 -0.0722296 0.5090517 -0.7254561 0.4575616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6052 6067 0.405529 0.700957 -0.259525 0.7459932 -0.2629212 0.3655623 0.4906433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6052 6752 0.754490 -0.609460 0.057810 0.4058574 0.1966562 -0.8532987 0.2617009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6053 5953 -0.372150 0.144569 -0.656274 0.7791404 0.0829365 0.2682870 0.5604319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6053 6066 -0.826239 -0.160389 0.384640 0.2692312 -0.2877791 -0.9188907 0.0183728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6053 6753 0.231556 -0.132012 0.874220 -0.6186518 0.2910080 -0.5350196 0.4963249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6054 6065 -1.082788 -0.413749 -0.078423 0.2164353 -0.5164227 0.3485661 0.7516415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6055 5955 0.857109 0.148580 -0.711840 -0.0981308 -0.7028228 -0.0081710 0.7045166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6055 6064 0.449559 0.146623 0.782379 0.0800734 -0.4508271 -0.6557134 0.6003192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6055 6755 -0.660855 -0.588614 0.865235 0.7269722 -0.2959649 -0.2486747 0.5675184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6056 6063 -0.905574 -0.036790 -0.526496 -0.0247207 0.4454220 0.4695461 0.7619151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6057 6062 0.204375 0.652099 -0.491332 -0.3118243 0.3580489 -0.8785341 0.0523871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6057 6757 -0.173684 0.466768 0.940522 -0.6239661 -0.2707576 -0.1957809 0.7064181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6058 6061 -0.154794 -0.352468 0.792252 0.4118669 0.6463974 0.3637914 0.5293315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6058 6758 0.194200 0.924565 0.255780 0.1442530 0.9411080 0.2291791 0.2024444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6059 6759 -0.006862 -0.632204 0.708874 0.5087114 0.7283176 -0.4438094 0.1174705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6060 6099 -0.486807 0.211270 -0.631660 -0.4229236 -0.2743141 0.7454942 0.4360342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6060 6720 -0.498580 -0.655151 0.248018 -0.0174512 -0.1368334 0.2810655 0.9497233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6061 6721 0.298782 0.749737 0.294358 -0.7193007 -0.1238100 -0.3262221 0.6007135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6062 6722 0.400458 -0.932956 0.009712 -0.1881123 0.7791278 -0.1767311 0.5712615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6063 5923 0.791275 -0.495882 -0.165216 0.5653655 0.2034393 -0.6828953 0.4154857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6063 6096 0.099386 0.418558 -0.791903 0.4449208 -0.7472955 -0.1796417 0.4596997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6064 6095 -0.112154 1.040844 0.288682 -0.0399465 0.6007783 0.3591940 0.7130563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6065 6094 -0.269229 0.523214 0.810888 0.2086004 0.4932218 -0.2180150 0.8158968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6065 6725 0.269420 -0.801436 0.510764 0.4747390 0.2416543 -0.8195588 0.2110675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6066 6093 0.605239 0.680314 0.527097 0.0875066 0.1229247 0.8090127 0.5680938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6066 6726 -0.659069 0.545605 0.221113 -0.7050149 -0.2536461 0.5813546 0.3172450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6067 6727 0.614027 -0.449635 0.618522 -0.0678237 -0.4101408 0.7562683 0.5052155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6068 6091 -0.307240 -0.517014 0.859822 -0.8697497 -0.1887466 -0.3259079 0.3188953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6068 6728 0.354757 0.771985 0.608359 -0.0351786 0.7783672 0.3309435 0.5323376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6069 6090 -0.593993 -0.254711 -0.706077 0.2949338 0.9297421 -0.1848150 0.1201546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6069 6729 0.371639 -1.012182 0.280183 0.4622455 0.6500395 -0.5989032 0.0713630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6070 6049 -0.320775 0.302930 -1.056314 -0.5641991 0.1638241 0.7970651 0.1397436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6070 6089 0.459608 -0.358518 1.035731 -0.1848963 -0.5779940 -0.5408566 0.5824178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6070 6730 -0.766079 0.386365 0.423193 0.2903078 0.1228432 -0.9308813 0.1846371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6071 6088 0.863212 0.206148 -0.466122 0.0891750 0.2694403 0.8804699 0.3797663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6071 6731 0.208891 0.495523 0.520842 -0.4302713 -0.3284375 -0.4193971 0.7287671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6072 6732 -0.955715 -0.438711 0.143851 -0.8306541 -0.5300744 0.1645825 0.0441294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6073 6733 0.302346 -0.001059 1.001623 0.0542082 -0.1696736 0.5714739 0.8010555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6074 6085 -0.846916 0.172670 0.250146 -0.5408871 0.0925568 -0.4418802 0.7096592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6074 6734 0.371272 0.489549 0.408729 -0.9150682 0.2320024 -0.0652842 0.3233621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6075 6084 -0.826437 -0.214720 -0.499564 0.0487596 -0.7110552 0.6012696 0.3612449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6075 6735 -0.394833 -0.200749 0.913794 0.3676599 -0.0160824 0.1516074 0.9173782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6076 6083 0.427921 0.749898 0.576687 0.2082025 0.0188983 -0.4982702 0.8414400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6076 6736 -0.276742 -0.482725 0.867222 0.6558970 -0.2896610 0.3372141 0.6100675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6077 6082 -0.947687 0.078870 -0.311937 0.3484006 -0.0631697 -0.9294969 0.1032572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6077 6737 -0.102035 1.019060 0.257477 -0.4054307 -0.4589874 -0.7886344 0.0548841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6078 6081 -0.909803 -0.208851 0.373379 0.6479880 -0.1412010 -0.1911833 0.7236179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6078 6738 0.520601 -0.404804 0.897844 0.4405000 -0.0654221 -0.3781586 0.8115884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6079 6739 0.397281 0.398403 0.541555 -0.5741774 -0.5975510 -0.4646557 0.3120067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6080 6119 0.063932 -0.096322 -1.085395 0.4788733 -0.6478413 0.5620565 0.1872820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6080 6700 -0.387841 -0.954449 0.084916 -0.7495805 -0.2784277 0.5983304 0.0510669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6081 6118 -0.703221 0.195144 0.525292 0.2094616 0.2730976 0.6672329 0.6605632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6081 6701 0.691333 0.751125 0.509420 -0.5579319 0.2985347 0.5702500 0.5238358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6082 6117 0.856268 -0.302538 0.462055 -0.1476187 0.2649142 -0.8971280 0.3212328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6082 6702 -0.170884 -0.839758 0.173108 -0.0757784 -0.8810099 0.2073427 0.4184355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6083 6116 -0.785214 0.690783 -0.052400 -0.3002422 0.3431805 -0.8882018 0.0563861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6083 6703 0.036995 -0.263031 1.042009 0.1224026 -0.6095177 -0.5086222 0.5956586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6084 6115 0.439944 0.957221 0.486639 0.5371679 0.3721737 0.6542456 0.3806573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6084 6704 0.755305 -0.593928 0.180383 0.1331055 -0.5883993 0.7883631 0.1206351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6085 6114 -0.381545 -0.956130 -0.199462 0.2736820 0.4885165 -0.4673951 0.6840991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6085 6705 -0.158749 -0.159785 0.894700 -0.3172178 -0.1697597 0.8125537 0.4585967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6086 6113 0.881337 0.392757 -0.406330 0.5353221 -0.4144412 0.4022225 0.6163487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6086 6706 0.571038 -0.719772 0.184032 0.0872876 -0.1728950 0.0293127 0.9806268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6087 5907 -0.913803 0.024391 -0.525253 0.8741538 0.2250489 0.4279642 0.0453291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6087 6072 -0.059969 1.005648 0.176371 -0.0310922 -0.5509303 0.8327622 0.0449015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6087 6112 0.235646 -0.844349 -0.132815 -0.1807195 0.0251348 0.5590647 0.8087987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6088 6111 -0.639737 -0.920185 0.253731 -0.4223515 0.0547688 0.7011974 0.5717883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6088 6708 0.206462 -0.114200 1.010182 0.3747276 -0.0763422 -0.0099070 0.9239334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6089 6110 0.750064 0.722044 -0.243574 0.1726505 0.2180449 0.9513957 0.1322667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6089 6709 0.383700 -0.496093 0.719960 0.6556331 0.4730425 -0.3773075 0.4516803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6090 5910 0.776490 0.382390 -0.327995 0.7963302 -0.1304651 0.0318382 0.5897656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6090 6109 0.572526 -0.345393 0.563944 0.5924274 -0.4679665 -0.5505154 0.3563285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6091 6711 0.657291 -0.431670 0.463890 0.6504633 0.0940295 -0.0662881 0.7507741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6092 6067 0.408938 0.560587 0.679141 -0.1492532 -0.6163494 -0.7079804 0.3108064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6092 6107 -0.526379 -0.572756 -0.730733 -0.4622928 -0.2604313 0.1135428 0.8399815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6092 6712 -0.807403 0.570582 0.142239 0.0591436 -0.5823887 -0.6588106 0.4725400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6093 5913 -0.584337 -0.591977 -0.027454 0.1283352 0.4528530 0.8806056 0.0546634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6093 6106 0.348898 -0.654192 0.635289 0.7019486 0.6455322 0.1999564 0.2248863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6094 6714 -0.466546 -0.408779 0.880194 0.5935078 -0.2238294 -0.7667562 0.0986604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6095 6104 -0.037065 0.846263 0.453609 0.6515263 -0.5091074 0.2675347 0.4947204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6095 6715 -0.671007 -0.257838 0.500058 0.4016940 -0.4229063 0.6461254 0.4922541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6096 6103 -0.825081 -0.405377 0.220797 0.0494367 0.0743606 -0.9284878 0.3604677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6097 6062 -0.250060 0.438826 -0.705395 -0.7946949 -0.0926714 0.5551198 0.2274071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6097 6102 0.505906 -0.322127 0.966248 -0.3274585 -0.3780780 -0.6493313 0.5728846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6097 6717 0.311225 1.146639 0.056830 -0.3586278 0.9222319 0.1200044 0.0804572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6098 6061 0.503765 -0.167546 0.920551 -0.2149545 -0.2342243 0.1436990 0.9371682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6098 6101 -0.248434 0.219565 -0.908093 -0.5475367 0.3021369 0.6194509 0.4745496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6098 6718 -0.031996 0.895957 0.297014 -0.6107953 0.1213477 0.6286451 0.4658425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6101 6681 0.135245 -0.134790 0.999957 0.3399045 0.2129818 0.8249077 0.3982849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6102 6137 0.831824 0.561449 0.330244 0.4652549 0.1093977 0.4558454 0.7508495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6102 6682 -0.409769 0.228127 0.910733 0.5780883 0.3386347 -0.7361971 0.0956780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6103 6136 0.969687 -0.271253 0.404497 -0.0921952 0.6176199 -0.5776444 0.5257116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6103 6683 -0.510165 -0.583720 0.447331 0.7271274 0.0582613 0.3364197 0.5955780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6104 6684 0.471243 0.877992 0.154445 -0.5803266 0.2715453 -0.7204768 0.2653250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6105 6094 0.562540 0.272061 0.771070 0.0273450 -0.3671323 0.2928815 0.8824322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6105 6134 -0.525422 -0.224926 -0.725141 0.1589783 -0.5816738 0.1112798 0.7899356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6105 6685 -0.359388 -0.810210 0.475406 -0.0452672 -0.1178481 -0.9914214 0.0338576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6106 5886 -0.573759 -0.620313 -0.209926 0.0099513 -0.0943445 -0.4827854 0.8705851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6106 6133 -0.480076 0.769987 -0.357301 -0.4705190 0.1913140 0.7719374 0.3822610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6106 6686 0.625792 0.522454 0.349824 -0.4376214 0.2912386 -0.4689052 0.7097855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6107 6132 -0.844748 0.107958 -0.349936 0.0612949 -0.4009739 -0.5511659 0.7291632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6107 6687 -0.490566 -0.041725 0.899123 -0.1013636 -0.5049777 0.3651456 0.7754944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6108 6091 -0.434474 0.375224 -0.775433 0.2501375 -0.8944969 -0.0227342 0.3698509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6108 6131 0.492582 -0.315201 0.630323 -0.0200823 -0.9350369 0.1205851 0.3328092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6108 6688 -0.592485 -0.760522 0.151137 0.3682994 0.5485964 -0.7450371 0.0911996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6109 6130 0.116120 0.906162 -0.642132 -0.0182836 -0.3859102 0.8827573 0.2673549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6109 6689 0.156396 0.268935 0.877699 -0.0518512 0.2801043 -0.6643097 0.6910468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6110 5890 0.563171 -0.526859 -0.582739 0.1203573 -0.0642112 -0.7469354 0.6507523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6110 6690 -0.509244 0.564760 0.793339 -0.1282374 0.0332824 0.6965346 0.7051857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6111 6128 -1.001790 0.646609 -0.067825 -0.6823568 0.3874982 0.6044652 0.1373174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6111 6691 -0.784687 -0.645627 0.187534 -0.9023087 0.2424642 0.3535129 0.0455927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6112 6692 0.303182 -0.864616 0.256128 0.4330900 0.6637698 -0.5145228 0.3272751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6113 6126 0.018859 -0.730989 -0.731892 -0.1605914 0.4889323 -0.1757044 0.8392160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6113 6693 0.202196 -0.540042 0.544074 0.2692285 0.7549818 -0.5545022 0.2237094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6114 6125 0.334346 -0.723243 0.485324 -0.4064879 -0.0078871 -0.0892389 0.9092534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6114 6694 -0.861941 -0.261936 0.575009 0.4497909 -0.7417381 -0.3995414 0.2964446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6115 6124 0.972689 0.329919 0.544772 0.0719131 0.3466131 -0.8583514 0.3713767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6115 6695 -0.644543 0.701005 0.769405 -0.4340370 -0.6862991 -0.2813162 0.5113380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6116 6123 0.315373 -0.788834 -0.608700 0.7973330 0.3162232 0.4743803 0.1980564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6116 6696 0.708580 -0.329349 0.688904 0.2868569 -0.2764986 -0.5904997 0.7018346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6117 6122 -0.427885 0.340497 0.712920 0.3936995 -0.2072728 0.8954932 0.0114284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6117 6697 0.836309 0.140720 0.404175 0.3224518 -0.0226713 -0.0881804 0.9421969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6118 6121 0.346269 0.851759 -0.036540 0.4092386 0.0088899 -0.4948771 0.7665125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6118 6698 0.620529 -0.145889 0.717964 -0.3287900 0.5067196 -0.4987487 0.6215964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6119 6699 0.709212 0.443322 0.548913 0.0290488 -0.1556572 -0.6340730 0.7568874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6120 6159 0.561959 0.639544 -0.640323 0.0005154 0.5939103 0.6431643 0.4833322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6122 6662 -0.392822 -0.573626 0.567559 0.5432764 -0.0596842 -0.7654912 0.3395759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6123 6156 -0.518990 0.345474 0.586062 0.0027982 0.3722297 0.0051963 0.9281219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6124 6155 -1.020822 0.240855 0.361875 -0.4130790 -0.8809158 0.0948445 0.2106127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6124 6664 -0.242539 -1.008581 -0.024052 -0.1654569 0.5837943 -0.7811346 0.1470949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6125 6154 0.481129 -0.787412 -0.263912 0.4507749 -0.0300821 -0.5084252 0.7330763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6125 6665 -0.819442 -0.568421 0.265472 -0.1178660 -0.1321317 -0.1359138 0.9747699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6126 6153 0.800130 -0.349991 -0.344048 -0.1745100 -0.5829737 0.3128548 0.7292529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6126 6666 -0.210428 -0.898551 0.589955 0.0392448 -0.2284903 -0.9724969 0.0224014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6127 6667 -0.365962 0.092187 0.973992 -0.0417811 0.4216798 0.8458111 0.3241050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6128 6668 -0.151785 0.886845 0.123037 0.1484672 0.6666532 0.6775647 0.2728316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6129 6150 0.666489 -0.574023 0.374461 0.0977063 -0.6208657 -0.7152244 0.3056686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6129 6669 -0.682140 -0.430566 0.680473 0.6213449 -0.1606762 -0.7607512 0.0968049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6130 6149 0.087774 0.129764 -1.070326 0.6809720 0.5525256 -0.1782428 0.4463430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6130 6670 0.112840 -0.920413 0.094624 0.8967472 0.1168396 0.4098086 0.1193730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6131 5871 -0.343583 0.597851 -0.403343 0.0721434 0.2736797 -0.5383503 0.7937718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6131 6148 0.071963 -0.366272 -0.882561 -0.5533042 -0.1981745 -0.8008374 0.1150686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6131 6671 0.556309 -0.814680 0.224843 -0.4906612 0.5874317 -0.6325012 0.1188183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6132 5872 -0.384453 -0.091936 -0.835890 -0.6910455 -0.0167830 -0.7224398 0.0159733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6132 6147 -0.355119 -0.676805 0.250948 -0.0509265 0.3951895 -0.4721011 0.7863538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6132 6672 0.434505 0.331208 0.905284 0.4019927 0.1683040 0.6073966 0.6641875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6133 6146 0.770712 -0.234009 0.521477 -0.1811681 -0.6173016 0.6105129 0.4619425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6133 6673 -0.112403 -0.974694 -0.081289 -0.2050239 -0.1477468 0.9671635 0.0270343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6134 5874 -0.545893 0.493530 -0.904792 -0.5407037 0.5541115 -0.4321614 0.4624246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6134 6145 -0.936520 -0.051712 0.320700 0.1141604 0.0918415 0.7999350 0.5819248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6135 6104 -1.055113 0.091254 -0.130430 0.6789692 -0.2318337 -0.5944949 0.3630838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6135 6144 1.035401 0.124753 -0.012156 0.5956315 0.5338392 -0.0737504 0.5956506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6135 6675 -0.023724 -0.839675 0.384130 0.1911725 0.0837930 0.8341929 0.5104450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6136 6143 -0.493774 -0.005929 0.781026 0.5631862 0.3349873 -0.6376946 0.4049079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6136 6676 0.622815 -0.862025 0.451708 0.7685980 0.5748523 0.2231047 0.1703708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6137 6142 0.947856 -0.148250 0.315199 -0.3480301 0.8602975 0.3725023 0.0022867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6137 6677 0.224237 0.897473 0.332191 -0.1467705 -0.7250982 -0.6656715 0.0978396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6138 6101 1.014752 0.090326 -0.260559 0.2367204 -0.5387120 0.7401389 0.3254953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6138 6141 -0.785995 0.012633 0.469366 0.3681230 -0.3649449 0.7507806 0.4094253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6138 6678 0.303163 -0.818798 0.677414 0.5932044 0.3883196 -0.7022107 0.0649353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6139 6100 -0.251540 -0.730501 -0.865475 -0.2760994 0.0293881 -0.8920202 0.3566587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6139 6679 0.388339 -0.696253 0.403334 0.1033782 -0.4063768 0.8429959 0.3369403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6140 6179 -0.802312 -0.242403 0.319508 0.2605421 -0.2040028 -0.0685594 0.9411696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6140 6640 -0.009750 0.634365 0.832898 0.1717824 0.0092070 0.9613655 0.2149008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6141 5841 -0.041164 0.054894 -0.969402 0.0423283 0.7170652 -0.3960942 0.5719574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6141 6178 0.730037 0.870077 0.047104 0.1906381 -0.0288384 -0.9807786 0.0299784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6141 6641 0.120151 0.127337 0.993020 -0.1451490 0.6547827 -0.7237576 0.1623770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6142 6177 -0.756470 -0.411408 -0.630739 -0.6511006 0.1521865 0.4147838 0.6171399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6142 6642 -0.871135 0.479668 0.559374 -0.5648264 0.0845249 0.8118541 0.1213247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6143 6176 -0.829887 -0.304265 0.477367 -0.1744674 -0.1984715 -0.4214696 0.8674869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6143 6643 -0.315169 0.871635 0.655950 -0.5112855 0.4025733 0.0109004 0.7592122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6144 6175 0.378216 0.893552 0.494023 -0.0703497 0.1955729 0.9724197 0.1058402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6144 6644 -0.797877 -0.077161 0.507637 0.4044902 0.1195525 -0.9053420 0.0495057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6145 5845 0.621511 0.028658 -0.703996 -0.3235424 -0.0423155 0.9253067 0.1932283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6145 6174 0.337821 0.947733 0.260933 -0.1714647 -0.4468944 0.8437286 0.2429142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6146 5846 0.512652 0.031638 -0.865831 -0.3241289 -0.5848431 0.0569222 0.7413898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6146 6173 -0.295785 -0.977024 -0.468040 -0.2900943 0.3437629 -0.7408645 0.4987908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6146 6646 -0.401268 -0.128887 0.846160 -0.2668103 -0.0894666 -0.7297024 0.6231713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6147 6172 0.144500 -0.831649 0.248243 0.0122908 -0.6706298 -0.0492578 0.7400529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6148 5848 -0.171850 -0.990515 0.034850 -0.6211976 0.4824342 -0.0712209 0.6134316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6148 6171 -0.929150 0.373817 -0.332495 -0.1945544 -0.1180883 -0.3762386 0.8981360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6148 6648 0.256616 0.986569 0.036591 -0.4246833 0.2019426 -0.3263356 0.8199807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6149 6170 0.481998 -0.326312 0.830513 -0.2194529 0.2311260 -0.9363290 0.1473402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6149 6649 -0.652000 0.215513 0.688085 -0.1227574 -0.3399576 0.7484859 0.5559931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6150 6169 -0.028410 0.634051 -0.997206 -0.2114439 -0.1592238 -0.9142701 0.3066747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6150 6650 0.647649 0.395619 0.405883 0.4821399 0.5189546 0.3484299 0.6138598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6151 5851 0.428557 -0.911542 -0.336941 -0.3531048 0.4188055 0.5606705 0.6209408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6151 6128 -0.562346 -0.646185 0.384624 -0.0428897 0.8609716 0.3237641 0.3899552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6151 6168 0.684672 0.421154 -0.328809 0.1089635 0.7792756 0.5948454 0.1643638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6151 6651 -0.502926 0.856635 0.342061 0.5043209 -0.7262907 -0.4306042 0.1809481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6152 6127 0.326323 -0.008539 -1.047053 -0.0623584 0.5487899 -0.8325738 0.0419758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6152 6167 -0.407007 0.064135 0.998710 -0.3124985 0.1407415 -0.7599439 0.5522878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6152 6652 0.472806 -0.791695 0.344084 0.5158742 0.7090062 0.0594147 0.4771309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6154 6165 1.059091 0.207316 -0.039329 0.3100507 0.4947869 0.5255034 0.6187897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6154 6654 -0.084906 -0.438689 0.763625 0.4439811 -0.4807792 0.6898838 0.3095037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6156 6163 -1.010530 0.320333 0.023787 0.2198276 0.0199607 0.8457612 0.4857627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6156 6656 0.211365 1.040390 0.265509 0.4443223 0.3230764 0.7399504 0.3881659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6157 6122 -0.124526 -0.906352 0.131707 -0.4013975 -0.0236516 0.8008061 0.4438808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6157 6162 0.000004 1.063048 -0.356680 0.5202600 -0.1386630 -0.5924947 0.5992096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6157 6657 -0.070622 0.166209 0.923614 0.1162488 -0.2665582 -0.2762993 0.9160195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6158 6121 0.384850 -0.894266 -0.482774 0.5360078 0.2749054 -0.1659320 0.7807620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6158 6658 0.775616 -0.179062 0.570126 0.1581009 0.1448444 -0.7069402 0.6739880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6159 6659 -0.943468 -0.444559 0.118742 0.2787332 0.3243937 -0.7312631 0.5313481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6160 5820 0.618208 0.542165 -0.477749 -0.0746779 0.8074384 -0.5736702 0.1156244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6160 6199 0.627629 -0.885745 -0.026821 -0.0276762 0.6831090 -0.7160080 0.1411693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6160 6620 -0.709778 -0.430569 0.513109 0.3082978 -0.6090505 0.0030905 0.7307533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6161 6158 0.583074 -0.036357 0.721404 -0.2745777 -0.5111377 0.5212898 0.6257814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6161 6621 -0.739825 0.410124 0.778900 -0.6615562 -0.2887348 -0.4477840 0.5276979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6162 6197 -0.685390 -0.217224 -0.867575 0.7811075 -0.2467500 -0.5117188 0.2590934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6162 6622 -0.482514 0.716920 0.336638 -0.1883359 -0.7155464 -0.2165519 0.6368894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6163 6196 0.640540 0.513193 -0.486230 0.6435039 0.7310615 -0.1314582 0.1848529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6163 6623 0.926711 -0.583080 0.249292 0.0866326 0.8771712 -0.3986133 0.2533238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6164 6155 0.224637 -1.092333 0.121574 -0.7723336 -0.5051611 0.3577947 0.1424642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6164 6195 -0.272900 0.929071 -0.145019 0.2966706 0.0650699 -0.3214415 0.8968990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6164 6624 -0.761483 0.114749 0.768834 -0.4861192 -0.4059620 0.3263331 0.7017048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6165 6194 0.013344 -0.014315 1.250193 -0.6118518 -0.4318044 0.6591554 0.0685307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6165 6625 -0.745692 0.929743 0.215923 -0.5753736 -0.6482642 -0.4700956 0.1664598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6166 6153 -0.112227 0.891018 0.319094 -0.3788289 -0.0766137 0.4504539 0.8048045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6166 6193 0.163090 -0.885866 -0.125640 -0.3337642 -0.3172935 -0.0130474 0.8875562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6166 6626 0.388952 -0.075054 0.941564 -0.4030220 -0.1558064 -0.6504739 0.6246450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6167 5827 -0.597500 -0.419077 -0.319148 -0.5368839 0.2085302 -0.2400011 0.7814540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6167 6192 0.414496 -0.669309 0.342563 -0.1174323 0.6466161 -0.1456377 0.7395181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6167 6627 0.845283 0.599172 0.419247 0.0602394 -0.0278705 0.8196393 0.5690219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6169 6190 -0.498554 -0.686693 -0.737944 -0.1534892 -0.0635472 0.6770888 0.7169055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6169 6629 -0.769977 0.039957 0.597070 0.2967475 -0.5969695 -0.4160362 0.6184515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6170 6189 -0.141271 0.117236 1.060044 -0.0414236 0.5937140 0.4914552 0.6358141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6170 6630 0.621601 -0.781659 0.056832 0.5220947 -0.1361301 -0.0935730 0.8367376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6171 6188 -0.851821 -0.169218 -0.212802 -0.2256256 -0.1670174 0.3861825 0.8786702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6171 6631 -0.478253 0.815704 0.472561 -0.1895730 0.3607668 0.7148357 0.5682599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6172 5832 -0.768035 -0.126250 -0.785659 -0.3291335 -0.2639417 -0.3526056 0.8352695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6172 6187 0.241987 -0.801039 0.170135 -0.5781783 -0.2347966 -0.6834345 0.3788110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6172 6632 0.634387 -0.076737 0.489202 -0.1643916 0.2340598 -0.9174812 0.2764411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6173 6186 0.631264 0.392527 -0.560684 0.9950537 0.0476450 0.0169273 0.0855076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6173 6633 0.412094 -0.935209 0.142748 -0.3375846 0.8335929 -0.3495825 0.2625862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6174 5834 -0.487966 0.622507 -0.598113 -0.0622001 -0.3484546 -0.9276048 0.1194146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6174 6185 0.265307 -0.708488 -0.734791 -0.0576145 -0.5224171 0.7251458 0.4448871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6174 6634 0.680034 -0.451576 0.822320 0.2359883 -0.3427325 0.7397327 0.5288095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6175 5835 -0.727636 -0.405296 -0.739798 0.2771033 0.2125141 0.5170836 0.7814577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6175 6184 -0.543878 -0.583477 0.897575 0.5572000 0.4891753 0.2096756 0.6373946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6175 6635 0.569370 0.359719 0.562592 -0.6524389 0.0707755 -0.5062156 0.5595177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6176 5836 0.479723 -0.102251 -0.984711 -0.2091809 -0.6623843 -0.7106566 0.1116134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6176 6183 0.075388 -0.827321 0.343814 -0.1153268 -0.3973989 -0.7775299 0.4735199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6177 6182 -0.119050 0.882126 -0.178800 -0.5762550 0.0064787 0.1580975 0.8018063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6177 6637 -0.663074 -0.019185 0.807027 -0.1603975 -0.6712868 0.7127471 0.1250526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6178 5838 0.498142 -0.131808 -0.775209 -0.4747451 -0.3598209 0.4607282 0.6579328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6178 6181 -0.488808 -0.741933 -0.139124 -0.4661607 -0.5859873 0.3747711 0.5466806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6178 6638 -0.469302 0.198494 0.821453 -0.4425209 -0.3819750 0.7395993 0.3335613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6179 6639 0.326760 1.032468 0.058189 -0.3049049 -0.5055311 0.2187857 0.7769197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6180 6600 0.594975 0.210405 0.507368 -0.2960233 0.3341778 0.7648917 0.4643663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6181 6218 -0.738168 -0.101214 0.629423 0.6886865 0.0256483 0.7109977 0.1397688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6181 6601 0.394807 -0.782672 0.646806 -0.1296089 0.9129814 -0.1095113 0.3710441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6182 6217 -0.068756 0.367071 0.966396 0.2934982 0.0906034 -0.4985735 0.8106012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6182 6602 -0.692170 -0.463826 0.293285 0.1591578 0.2919715 -0.3501940 0.8756629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6183 6216 0.752324 0.314225 -0.380993 0.1259349 0.3498308 -0.7405292 0.5597994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6183 6603 0.329764 0.034591 0.836825 -0.2284114 0.1096620 0.0604686 0.9654771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6184 6215 -0.771483 0.644249 -0.096719 -0.5169501 -0.6815551 -0.0720719 0.5128848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6184 6604 0.169835 0.827827 0.122033 0.2097335 0.2041952 0.1286248 0.9475082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6186 6213 0.948711 -0.416063 0.370833 -0.2321741 0.1664995 -0.1003202 0.9530525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6186 6606 0.305560 0.974142 0.051466 0.0792775 -0.4612843 -0.8263416 0.3131954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6187 6212 0.326115 0.827918 -0.306241 0.1800552 -0.0902558 0.2661396 0.9426578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6187 6607 0.669390 0.313198 0.784938 0.0635768 0.2507253 0.4600966 0.8493562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6188 6211 -0.856247 0.408865 0.232216 0.5971669 0.5650519 0.4678899 0.3243257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6188 6608 0.421190 0.304264 0.918729 -0.1659295 0.0037627 0.9849985 0.0472351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6189 6210 -0.787203 0.555916 0.137443 0.2887577 -0.4738329 -0.5752201 0.6010185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6189 6609 -0.597627 -0.720398 0.125052 0.6593160 0.5834979 -0.0808634 0.4672191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6190 6610 -0.153645 0.491400 0.958533 0.3118363 0.0164328 0.0569161 0.9482872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6191 6168 0.304656 -0.606811 0.992701 0.0598504 -0.8750427 -0.4292548 0.2155421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6191 6208 -0.091746 0.620544 -0.609256 -0.1778044 -0.3840399 0.8201092 0.3851230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6192 6207 0.014177 -0.866404 0.564359 0.0496896 -0.7746281 -0.6188243 0.1205767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6192 6612 -0.549092 0.563329 0.693469 -0.4756171 -0.4289568 0.7100529 0.2925908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6193 5813 -0.723018 0.427517 -0.231210 -0.1936109 0.0738414 -0.1196023 0.9709570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6193 6613 0.764936 -0.805727 0.119813 -0.2898140 0.7564248 -0.5246138 0.2619346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6194 6205 -0.602894 -0.457603 0.150385 0.1253883 0.2027830 -0.2224118 0.9453517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6195 6204 -0.825172 0.128452 -0.465993 0.4895830 -0.7562726 -0.1878411 0.3912492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6195 6615 -0.774655 -0.297290 0.555613 0.3410764 -0.3963444 -0.2558194 0.8131017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6196 6203 0.740487 0.570412 0.230005 0.0506093 -0.5236955 -0.1529342 0.8365362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6196 6616 -0.536285 0.793374 -0.047283 -0.6419101 -0.5647863 -0.4058213 0.3229194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6197 6202 0.696796 -0.189799 0.996469 0.2331994 -0.3177917 -0.3124593 0.8642891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6198 6161 0.677289 -0.623847 -0.543544 0.7357339 0.2907550 -0.1373281 0.5960690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6198 6201 -0.679072 0.585981 0.359683 -0.1376889 -0.3880832 0.8975318 0.1577018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6198 6618 -0.220665 -0.951542 0.594471 0.8978250 0.2141819 -0.3315056 0.1952957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6199 6619 0.675711 -0.544976 0.327057 0.3656340 0.1838369 -0.5163816 0.7522405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6200 6239 -0.746031 -0.431326 0.480459 -0.9019852 0.1067110 -0.0953146 0.4073704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6201 6238 0.739618 -0.538073 0.138296 -0.4649638 0.0792523 -0.3399611 0.8136057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6201 6581 -0.385830 0.014272 1.031016 -0.3314536 -0.3697868 0.8143426 0.3004037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6202 6237 0.706626 0.486784 0.286830 -0.1769950 0.2862306 -0.8331440 0.4388803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6202 6582 -0.146868 -0.102265 1.119641 -0.4489461 -0.4818501 0.0728242 0.7489756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6203 6583 -0.496673 0.502389 0.783796 -0.3950687 -0.2609894 -0.8157692 0.3321534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6204 6235 -0.138012 0.242168 0.740548 -0.2580622 -0.1170310 -0.8969024 0.3395198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6204 6584 0.829604 0.821781 0.274662 0.1963785 0.7455941 -0.0051498 0.6367875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6205 6234 -0.208665 -0.898244 -0.400177 0.0024328 -0.1709007 0.8383574 0.5176329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6205 6585 0.720971 -0.252288 0.813520 -0.4459795 -0.3533910 -0.7901416 0.2278014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6206 6193 -0.562910 -0.923826 0.371057 -0.2002206 -0.2734174 0.9343421 0.1102704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6206 6233 0.690643 0.789436 -0.330746 0.5662821 -0.7106552 -0.2342585 0.3455673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6206 6586 -0.821684 0.541851 0.356869 0.4861683 -0.5483035 -0.6312849 0.2539352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6207 5787 -0.429717 -0.907093 -0.313495 -0.7070289 -0.2970359 -0.6369009 0.0789750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6207 6232 0.257001 0.169836 -0.958929 0.3941703 0.5391245 0.7378468 0.0977578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6207 6587 0.488432 0.912258 0.549103 0.1199448 -0.9278373 -0.3422616 0.0871102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6208 6231 0.477696 0.573405 -0.579378 -0.7977754 -0.3090434 -0.5089652 0.0948737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6208 6588 0.880584 -0.411053 0.325941 -0.4977017 -0.2217520 -0.8132906 0.2041504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6209 6190 1.068579 -0.090027 0.028857 0.7132737 -0.2286624 0.4465758 0.4894120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6209 6230 -1.063242 0.110631 0.046704 0.6496426 0.3526306 0.2001809 0.6430737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6209 6589 0.019011 -0.840697 0.132000 0.4284820 -0.7683430 0.2873846 0.3787641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6210 6229 -0.596776 -0.056829 0.896735 0.0441511 0.5045738 -0.6403636 0.5773997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6211 6228 0.698907 -0.330534 -0.622653 0.4003538 0.7211574 0.4589822 0.3301275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6211 6591 0.318540 0.988991 0.111247 -0.4381314 0.2346537 0.7438336 0.4468670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6212 6592 0.893909 0.145310 0.459509 -0.2275524 0.7885864 -0.0465003 0.5693761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6214 6185 -0.886560 0.234258 0.120638 0.0120333 0.1062061 -0.9933140 0.0436218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6214 6594 0.181060 0.814365 0.617821 -0.3920994 -0.0692815 -0.8500166 0.3448621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6215 6224 -0.022676 -0.373811 0.717099 -0.7485100 0.0533906 -0.3662178 0.5502425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6216 6223 -0.499692 1.014357 -0.409018 0.5756426 -0.0090637 -0.7539228 0.3164711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6217 6222 -0.803849 0.572749 0.221815 0.1600900 -0.8941930 0.4009268 0.1185233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6218 5798 -0.145455 -0.742733 -0.553012 -0.1317617 -0.5904455 -0.5516916 0.5741510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6218 6598 0.242191 0.694422 0.583120 -0.2925039 -0.5000415 -0.6367066 0.5089250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6219 6180 -1.009493 -0.315638 -0.206432 -0.3338993 0.4814613 -0.7484840 0.3106089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6219 6599 0.283497 -0.822488 0.328773 -0.3165136 -0.4752763 0.8205364 0.0255276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6220 6259 0.424877 -0.447473 -0.820671 0.0276049 0.0464890 0.9601095 0.2743475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6221 6218 -0.578595 -0.218585 0.807960 0.4899013 0.2537419 -0.7094907 0.4384458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6221 6258 0.612896 0.094271 -0.773757 -0.3370682 0.8278098 -0.3723296 0.2499732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6221 6561 0.344975 -1.216575 0.064466 0.9122049 -0.3409001 0.2166676 0.0687355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6222 6257 0.893850 0.434986 -0.527812 -0.5871087 0.4709295 -0.5356987 0.3828259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6222 6562 0.469034 -0.913023 -0.053936 0.9469132 -0.2352410 -0.0362071 0.2161159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6223 5763 0.410785 -0.043783 -0.857692 0.3819778 0.4168381 -0.6319124 0.5301185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6223 6256 -0.361460 -0.949692 0.053962 0.1199039 -0.2485793 0.4898184 0.8269881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6223 6563 -0.551089 0.069215 0.910441 -0.6699846 -0.2808021 -0.1254375 0.6756747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6224 6255 0.745759 -0.694124 -0.271007 0.2421824 0.1659516 -0.2295704 0.9279575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6224 6564 0.240438 -0.001022 0.939387 -0.3236090 -0.5019268 -0.7425988 0.3031398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6225 6254 -0.911910 0.105772 0.313394 0.0908463 0.9854784 0.1431708 0.0090241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6225 6565 0.119768 0.866460 0.273477 -0.0931693 0.0644538 -0.4928676 0.8626974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6226 6213 -0.504703 -0.717141 0.492868 -0.3922603 0.4386089 0.4924689 0.6412710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6226 6253 0.536804 0.505778 -0.524735 -0.1187741 -0.1114406 0.2627908 0.9510072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6226 6566 -0.831943 0.849660 -0.017451 -0.6335671 0.3606082 0.0061751 0.6844825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6227 6212 0.828164 0.304825 0.480692 0.1587478 -0.0192790 0.9377257 0.3083796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6227 6252 -0.664513 -0.316616 -0.766202 -0.6243757 0.0838123 0.3370535 0.6996609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6227 6567 -0.737143 0.343312 0.754541 -0.6410898 0.3825634 0.4693156 0.4715845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6228 6568 0.696176 0.376391 0.744790 0.1924625 0.2178734 0.6515811 0.7006650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6229 6250 -0.425259 -0.739510 0.017631 0.5709356 -0.3327745 0.0386918 0.7495309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6229 6569 -0.400589 0.339992 0.867855 0.3482244 0.1524972 0.4367491 0.8153126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6230 6249 -0.627327 -0.268442 -0.883088 -0.5274470 -0.3190218 -0.1279219 0.7769561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6230 6570 -1.022018 -0.020146 0.425989 -0.0320759 0.3055383 -0.9139618 0.2651252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6231 6248 -0.378181 -0.162292 0.982349 0.0946376 0.4374351 -0.0752098 0.8910879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6231 6571 0.521391 0.850976 0.395957 -0.6419602 -0.0904246 -0.6581404 0.3828337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6232 6247 -0.528905 -0.861162 0.107765 0.0058486 0.5324166 -0.0148203 0.8463325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6232 6572 0.381890 -0.146871 0.842862 -0.0540531 -0.4602230 0.8714737 0.1606444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6233 6246 -0.866153 -0.411331 -0.354302 0.7379153 -0.0887452 -0.6651468 0.0720072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6233 6573 -0.607461 0.886709 0.223011 0.4986941 -0.2095868 -0.8392453 0.0551805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6234 6245 -0.694459 0.875792 0.012823 0.9008009 -0.0774277 -0.4132614 0.1085249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6234 6574 -0.643826 -0.442946 0.655965 -0.0782806 -0.2369797 0.7243721 0.6426490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6235 6244 0.626298 -0.380277 0.787443 -0.2939098 -0.1789335 0.4499068 0.8241260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6235 6575 -0.887166 0.042039 0.738649 -0.7034150 0.3490454 0.4780281 0.3935274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6236 6203 0.403844 0.624493 -0.776537 0.1828520 0.6272989 0.7564878 0.0280603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6236 6243 -0.320863 -0.568373 0.921186 -0.7336119 0.0512959 -0.0893329 0.6717157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6236 6576 0.713693 0.748268 0.721384 -0.0631663 0.2493291 -0.8210119 0.5096906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6237 6242 -0.927915 0.167897 0.573002 0.1913937 0.6491326 -0.6206811 0.3959170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6237 6577 0.453093 -0.498598 0.613630 -0.2575523 -0.6453611 0.6982943 0.1719332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6238 6241 1.146930 -0.087820 0.222989 -0.0791136 -0.1950343 -0.9748179 0.0737065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6238 6578 -0.134744 -0.843384 0.691443 0.5458046 0.4448021 -0.6846808 0.1883098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6239 6579 -0.741604 -0.532645 0.507154 -0.2746932 -0.4215574 0.2322825 0.8323928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6240 6279 0.769941 0.166632 0.649280 0.2293714 -0.2930300 -0.6344220 0.6775182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6240 6540 -0.616189 0.289071 0.763043 0.1623716 -0.7569889 -0.1558726 0.6134386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6241 6278 -0.879457 0.184590 0.128734 -0.2282121 -0.8388291 -0.4929135 0.0363496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6242 5742 0.631239 0.409903 -0.546201 0.8945977 -0.0417940 -0.4243332 0.1337517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6242 6277 0.296273 -0.709567 -0.351294 0.1455457 0.0821247 0.5631145 0.8093046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6242 6542 -0.950993 -0.387041 0.517121 0.5733432 -0.1739627 0.4637819 0.6526262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6243 6276 -0.252268 -0.855571 -0.537852 0.2521245 0.5522470 -0.7804483 0.1495223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6243 6543 0.541172 -0.675911 0.403981 0.5105155 -0.0309004 0.7102271 0.4837320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6244 6275 0.064118 -0.924368 0.159679 0.1978077 -0.2982593 0.9320817 0.0560117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6244 6544 -0.257611 0.287826 0.774176 -0.0584936 0.4079270 0.8912708 0.1892366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6245 6274 -0.671830 -0.508761 0.320513 -0.8366894 0.0434452 0.4814861 0.2573605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6245 6545 -0.668056 0.845904 0.222797 -0.4901059 0.4352910 0.1578166 0.7385201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6246 6273 0.249880 0.304815 1.186063 0.7322866 0.4340485 -0.5144101 0.1036366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6246 6546 -0.637206 -0.685610 0.310925 0.2880141 -0.0554298 -0.0037261 0.9560134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6247 6272 -0.515140 -0.739151 -0.344360 0.0173892 -0.5706017 0.7622787 0.3050288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6247 6547 -0.835465 0.153505 0.689908 0.1633187 -0.0729804 -0.9346832 0.3071939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6248 5748 0.114899 -0.753003 -0.306458 0.3718515 -0.1601365 -0.9143756 0.0002364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6248 6271 -0.946121 -0.231344 0.287115 0.3706247 -0.6826954 -0.5266143 0.3453140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6248 6548 -0.152410 0.916678 0.396848 0.3404764 0.0064230 -0.8577966 0.3849928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6249 6549 -0.237147 -0.906192 0.422276 -0.0239690 -0.5337852 -0.1506949 0.8317391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6250 6269 0.057954 -0.143435 0.946075 0.1538395 -0.9221518 -0.1988440 0.2939908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6250 6550 0.175533 1.068841 0.202543 -0.4655553 0.3243962 0.2411221 0.7873281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6251 6551 -0.737240 0.359394 0.545353 0.0051530 -0.7800778 -0.6249263 0.0303174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6252 6267 -0.179966 0.970562 0.081628 0.1522989 0.5204184 -0.7444364 0.3895948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6252 6552 -0.845327 -0.091284 0.664169 0.3693621 -0.2936904 -0.6262865 0.6205504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6253 6266 0.624172 0.437149 -0.752671 0.1832940 -0.1816538 -0.8763516 0.4067100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6253 6553 -0.085321 0.817828 0.297685 -0.5336425 -0.2751971 -0.7872420 0.1405071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6254 5754 -0.163332 -1.051368 -0.266418 -0.7905594 -0.0576649 -0.0061778 0.6096331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6255 6264 0.916979 -0.316681 0.085500 -0.6932532 0.1827017 -0.0195347 0.6968777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6256 6263 -0.996540 -0.253756 0.459223 -0.0550807 -0.3294178 -0.1521652 0.9302128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6256 6556 0.272333 0.108611 0.997180 -0.4154279 -0.2295175 -0.8081559 0.3487484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6257 6262 -0.560628 0.233634 0.786291 -0.1382044 0.2375412 0.7893053 0.5490637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6258 6261 -0.410363 0.424777 1.032387 0.2367439 -0.4545745 0.2302645 0.8272198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6258 6558 0.421037 -0.719882 0.471156 0.5165527 -0.5419072 0.5178976 0.4138743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6259 6559 -0.827625 0.115481 0.441851 0.7441155 -0.3606276 -0.4330692 0.3587352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6260 6299 0.916596 -0.242975 -0.746965 -0.9210291 0.1609115 -0.3115137 0.1696231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6261 6298 0.629046 0.820435 0.471589 0.2214631 -0.8693045 0.4322477 0.0917916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6261 6521 0.723874 -0.747093 0.387370 0.1987444 0.5125570 -0.8352448 0.0123369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6262 6297 0.131790 0.981071 0.789886 0.3339280 0.0684604 -0.7227780 0.6011633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6263 5723 -0.579044 -0.393525 -0.738676 0.2407262 -0.3126894 0.8887504 0.2332358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6263 6296 -0.399384 -0.385649 0.769837 -0.5810908 -0.4664084 -0.6520538 0.1400805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6263 6523 0.601952 0.199796 0.457262 -0.6312518 0.5988417 0.2890160 0.3992236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6265 6254 0.937675 -0.537685 0.276314 0.0231515 0.2088845 0.9063367 0.3665858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6265 6525 -0.762045 -0.551748 0.393751 0.0466840 0.1518436 0.9558269 0.2473037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6266 5726 0.702631 0.624363 -0.565969 -0.0682440 -0.5954888 -0.3163999 0.7352733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6266 6293 -0.691624 0.087254 -0.820342 0.0872106 -0.7687676 0.2043989 0.5996764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6267 6527 -0.076403 -0.898155 0.182591 0.3516200 -0.0491186 -0.5245505 0.7738201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6268 6251 -0.919220 0.286747 -0.232368 0.0406496 0.2713938 0.5629050 0.7796351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6268 6528 -0.173856 -0.539947 0.975168 0.5263544 0.6016530 -0.6007673 0.0065792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6269 6290 0.633714 0.472832 -0.553578 -0.2880887 -0.1998235 -0.7101482 0.6105448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6270 6289 0.568935 0.489601 0.799857 -0.3244234 0.0502348 0.9012918 0.2826642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6270 6530 -0.950104 0.436534 0.303687 0.8529438 0.2888120 -0.3979969 0.1751371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6271 5731 0.673941 -0.291173 -0.394789 0.1457531 -0.1650667 -0.7497822 0.6239677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6271 6531 -0.922037 0.343029 0.564326 -0.3404034 -0.4088702 0.8417276 0.0918982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6272 6287 -0.211436 0.654435 0.716329 0.4255203 0.7111160 -0.3108874 0.4653983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6272 6532 0.860839 -0.075979 0.237049 0.2239519 0.6899362 0.6153001 0.3086089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6273 5733 0.698993 0.040480 -0.503693 0.3033809 -0.0808197 0.8369505 0.4482657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6273 6286 -0.580986 -0.136130 -0.743283 0.0313119 -0.0607734 -0.9716627 0.2262691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6273 6533 -0.668133 -0.121004 0.703635 0.5340883 0.2534264 -0.5104512 0.6244712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6274 6534 -0.289993 -0.243683 0.932437 0.4293207 -0.0242188 0.7117100 0.5554872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6275 6284 -0.129674 0.687805 0.615408 -0.2154764 -0.2636521 0.6804963 0.6488314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6275 6535 0.708305 -0.483148 0.634081 -0.0801227 -0.0637982 0.9543778 0.2804872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6276 5736 0.876309 0.053759 -0.387928 0.4626727 -0.6012202 -0.5191667 0.3936168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6276 6283 0.515602 0.536435 0.507306 0.8074843 -0.1241950 -0.5668030 0.1062029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6276 6536 -0.910871 0.005785 0.531253 -0.1683054 -0.1664689 -0.8468105 0.4763123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6277 6537 -0.631636 0.599580 0.531690 -0.4682528 0.6894224 0.5414000 0.1110052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6278 6281 0.790817 -0.348828 0.074773 0.1943013 -0.1993234 0.1275609 0.9519692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6278 6538 0.029826 0.500257 0.907495 0.1457571 -0.4385999 0.1542581 0.8732637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6280 6319 0.353868 -0.998755 0.167566 -0.0555755 0.7227373 0.0057218 0.6888610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6280 6500 1.020766 0.516525 0.348288 0.9554929 -0.1318013 0.2557693 0.0651448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6281 5701 -0.661385 -0.647270 -0.364444 0.0086084 0.0935347 -0.9954710 0.0146541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6281 6318 0.709597 -0.529021 -0.267043 -0.5170287 0.1560962 -0.8364492 0.0931020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6281 6501 0.607851 0.619761 0.201040 -0.8140123 -0.0906488 0.0169073 0.5734814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6282 6277 0.348560 -0.492011 -0.633606 0.8589843 -0.0022027 -0.5052438 0.0828847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6282 6502 -0.623191 -0.945810 0.521835 0.5553433 -0.3760195 -0.7348472 0.1010090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6283 6316 -0.569022 -0.586705 -0.543616 -0.6341806 -0.2073272 -0.4353147 0.6044266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6283 6503 -0.772209 0.363869 0.520951 -0.4441425 0.6055423 0.6499423 0.1167515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6284 6315 0.639035 -0.460168 0.578215 -0.0110502 -0.7808588 0.4894352 0.3880602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6284 6504 -0.494279 -1.010428 -0.096379 -0.1244754 0.9766672 -0.1742298 0.0164651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6285 6274 0.108875 0.380145 -1.028568 -0.4739624 0.3998618 0.7393707 0.2622998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6285 6314 -0.273080 -0.459857 0.805516 -0.8554050 0.0998153 -0.0184034 0.5079179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6285 6505 -0.001701 0.798529 0.390117 -0.4575906 -0.6989049 -0.5488919 0.0293314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6286 6506 0.712247 -0.054901 0.816464 -0.0160178 -0.2026012 0.4238766 0.8826238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6287 6312 -0.363111 0.305729 -0.796327 -0.7820838 0.2607477 0.5490090 0.1376398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6287 6507 -0.725274 0.790601 0.363246 -0.9400331 -0.1664692 0.2859536 0.0828032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6288 6271 0.793988 -0.411552 -0.438805 0.0300384 -0.7302088 -0.6186209 0.2884458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6288 6311 -0.778329 0.387680 0.601789 -0.6904190 0.5774974 -0.2502242 0.3566598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6288 6508 0.555448 0.885077 0.115900 -0.9653708 -0.0863303 -0.1411360 0.2017098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6289 6509 0.806332 -0.127879 0.902682 0.0051208 -0.2807833 0.8336200 0.4756177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6290 6309 -0.936584 0.396381 -0.273930 -0.1182883 0.4175604 -0.5241029 0.7327806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6290 6510 -0.580745 -0.555011 0.653451 0.0678906 -0.4200955 -0.7963540 0.4298033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6291 6268 -0.090411 -0.457035 -0.833656 -0.3087693 -0.6383155 0.3714022 0.5993958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6291 6511 -0.731130 -0.519461 0.529917 -0.1183520 0.0952416 0.7489784 0.6449443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6292 6267 0.075156 0.748104 0.709361 -0.3720362 -0.0975102 -0.0025761 0.9230786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6293 6513 0.618892 -0.443943 0.848165 -0.5640949 0.0802848 -0.4216961 0.7053536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6294 6265 0.481206 -0.817250 -0.455504 -0.0752138 0.5087397 -0.2060679 0.8325039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6294 6305 -0.472896 0.668823 0.206930 -0.0403267 0.4883043 -0.6991876 0.5206432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6294 6514 -0.234081 -0.164669 1.050799 0.2158521 -0.4222772 -0.4699108 0.7444956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6295 6264 0.528319 -0.507621 0.776519 0.6497969 0.4284863 -0.6245891 0.0636554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6295 6304 -0.290600 0.619634 -0.369015 -0.5154534 -0.4852297 0.7062849 0.0046456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6295 6515 -0.858199 0.323793 0.624131 -0.3386392 -0.2021551 0.9040297 0.1648851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6296 6303 0.548929 0.213679 -0.798350 -0.5901328 0.2066898 -0.7788432 0.0492533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6296 6516 0.558948 0.532466 0.601421 0.1965560 -0.1289051 -0.6625134 0.7112139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6297 6517 0.153470 -0.024844 0.935033 -0.4026512 -0.0352906 0.2562922 0.8780324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6298 6301 -0.614509 -0.256444 -0.715126 0.2367201 0.3982559 -0.3999673 0.7908110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6298 6518 0.066384 -1.140661 0.127291 0.7586040 0.3988945 0.3491368 0.3788227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6299 5719 -0.275512 0.876605 -0.391441 0.2143717 -0.8595345 0.3924994 0.2473651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6299 6519 0.308990 -0.847107 0.248853 -0.0124130 -0.0366465 -0.0893030 0.9952527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6300 6339 0.654332 0.744594 -0.062937 0.4278069 -0.1428474 -0.8659482 0.2161237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6300 6480 -0.485592 0.468261 0.758662 0.1219654 -0.2898479 -0.5456714 0.7767596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6301 6338 0.468180 -0.616254 -0.386365 -0.1703645 0.2737107 0.2304785 0.9181166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6302 5682 -0.874035 0.258677 -0.463424 -0.0097355 0.8591010 -0.2255027 0.4593466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6302 6297 -0.053800 -0.696885 -0.404914 -0.2653188 0.3687372 -0.5250058 0.7197276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6302 6337 0.071283 0.757134 0.147637 0.6511953 -0.1317557 0.7470155 0.0235160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6302 6482 0.938497 -0.206525 0.589705 -0.0828872 -0.2115704 0.8981371 0.3764536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6303 6336 -0.916468 -0.200368 0.453453 0.6278321 -0.1398755 -0.0684254 0.7626137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6303 6483 0.229419 -0.879411 0.461598 -0.1018780 0.0770318 0.9901060 0.0581121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6304 6484 -0.234566 -0.817638 0.551740 -0.0781011 0.0335807 0.9219976 0.3777472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6305 6334 -0.274895 -0.356579 -0.773739 0.6265601 -0.3537706 0.5733154 0.3918906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6305 6485 0.111901 -0.672049 0.564325 0.4393622 0.1254572 0.7080287 0.5384391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6306 6333 -0.101614 1.074236 0.204503 0.0145855 -0.0681397 0.4859930 0.8711802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6306 6486 0.305154 -0.334078 0.787755 -0.3397763 -0.0781774 0.9169170 0.1941740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6307 6332 0.301220 0.837925 -0.078699 -0.3419080 0.5282623 -0.6160307 0.4738607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6307 6487 0.164323 -0.077033 0.806290 0.0903428 0.3135197 -0.9231911 0.2031298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6308 5688 0.062961 0.932959 -0.334150 0.1550094 0.0524373 0.4005503 0.9015442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6308 6291 0.983072 0.180695 0.330273 -0.2054830 -0.5453061 0.4145397 0.6989813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6308 6331 -0.994293 0.014936 -0.292850 0.5682770 0.3470451 -0.7448132 0.0432930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6308 6488 -0.088606 -0.993276 0.024050 -0.5641133 -0.5504862 0.6154137 0.0026669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6309 6330 -0.186041 -0.134158 -0.873283 0.1405926 -0.0022827 0.5685269 0.8105589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6309 6489 0.335730 -0.923319 0.304427 0.3333849 -0.4284496 0.2528698 0.8008385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6310 6329 0.065642 0.826959 -0.569254 -0.1041184 0.6336757 0.7665033 0.0093311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6310 6490 -0.777972 0.514180 0.397181 -0.2712814 0.5464829 0.7757581 0.1611283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6311 6328 -0.519623 0.402222 -0.965751 0.6719276 0.5363941 -0.4801698 0.1738726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6311 6491 -0.558072 -0.542431 0.507761 0.6998158 0.5168916 -0.2889993 0.3994501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6312 6327 0.685555 -0.012022 0.583536 0.2291579 -0.2541664 0.8948911 0.2864544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6312 6492 -0.774423 -0.231058 0.682819 -0.0216249 -0.1847179 0.9795476 0.0768001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6313 6286 0.078740 0.918104 -0.067222 -0.3891465 -0.3902540 -0.5469847 0.6301385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6313 6493 -0.175467 0.300420 1.182857 -0.2237641 -0.5764813 -0.3757261 0.6902382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6314 6325 -0.137902 -0.759923 -0.672598 -0.4455804 -0.0992100 0.8440907 0.2812942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6315 6324 -0.275480 -0.909736 -0.108861 0.2134742 0.3272501 0.4798066 0.7855710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6315 6495 0.057911 -0.497386 1.002653 -0.1025006 0.5234443 -0.4373607 0.7240271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6316 6323 -0.609638 -0.015021 -0.651712 -0.2355525 -0.5789401 0.4303892 0.6512361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6316 6496 -0.001093 -0.875575 0.076646 0.3765717 -0.8084078 -0.0230345 0.4518185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6317 6497 -0.022062 -0.770974 0.651451 0.6477698 0.3723939 -0.1763127 0.6408049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6318 6321 -0.314970 0.579059 0.614305 -0.2425817 -0.1985075 0.4040596 0.8593513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6318 6498 -0.071850 -0.800965 0.679852 -0.1938123 0.5164709 -0.6974112 0.4575064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6319 6499 -0.456993 0.319886 0.760412 0.3140814 0.5327458 0.7844571 0.0464951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6320 5660 0.225151 -0.755562 -0.120450 -0.2014224 0.7793031 0.5631933 0.1868930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6320 6460 -0.021142 1.084908 0.139137 -0.7840115 -0.0642757 -0.3086614 0.5347175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6321 5661 0.686184 0.647825 -0.343277 -0.1907514 -0.0112453 -0.0639962 0.9794856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6321 6358 0.061341 0.185464 1.110516 0.6194530 0.1336546 0.0041547 0.7735614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6321 6461 -0.572542 -0.592237 0.382077 0.6617161 0.3589117 -0.5926282 0.2865415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6322 6317 0.555152 -0.699473 -0.646390 0.2276656 -0.1934388 0.8305414 0.4700539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6322 6357 -0.565990 0.330920 0.600727 -0.6142824 0.5447172 -0.1383311 0.5538996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6322 6462 0.841493 -0.023730 0.593627 0.1409621 0.6537010 0.0380562 0.7425338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6323 6356 -0.388822 0.728178 0.473186 0.1925557 -0.2510003 0.7810364 0.5384267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6323 6463 -0.865446 -0.647558 0.471765 -0.7055593 -0.1625070 0.6141430 0.3140159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6324 6355 -0.815156 -0.112832 -0.249693 -0.1174078 0.1489565 -0.6581041 0.7286470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6324 6464 -0.411819 0.541488 0.807449 0.6383077 -0.4263900 -0.4647026 0.4413687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6325 6354 0.103284 0.891398 -0.447171 -0.1446071 0.4595658 0.6268881 0.6122902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6325 6465 -1.097557 0.495212 0.443516 -0.4087709 0.5064026 0.4905841 0.5794739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6326 6313 -0.989808 -0.371880 0.213064 0.0153211 0.1955714 0.8255733 0.5290991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6326 6353 0.993774 0.545966 0.051521 -0.0419980 0.2875573 -0.8517953 0.4358804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6326 6466 0.073708 -0.077056 1.090305 -0.3680060 0.5775236 -0.5238097 0.5066177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6327 6352 0.005725 -0.567123 0.910526 -0.5618711 0.2962117 -0.3077504 0.7084131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6328 6351 0.605212 -0.185623 0.612467 0.2724860 -0.1886654 -0.8650644 0.3765905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6329 6350 -0.018544 -0.584943 0.749752 -0.1678707 0.0044397 -0.4195469 0.8920651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6329 6469 0.686872 0.509040 0.580162 -0.0568183 -0.2661151 -0.9449705 0.1816181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6330 6349 -0.484182 0.010133 -0.974551 0.8583546 0.1220478 -0.4843485 0.1172101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6331 6471 -0.452167 0.630119 0.591704 -0.2829269 -0.1652152 0.9250109 0.1923828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6332 6347 -0.887543 0.229077 0.066438 -0.3129282 -0.7908399 0.5243851 0.0408469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6332 6472 -0.155889 -0.972472 0.349410 0.4410894 -0.4077782 0.6691855 0.4374333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6333 6346 1.056169 0.520275 0.193275 -0.3218856 0.1897670 0.3607207 0.8545517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6333 6473 -0.022837 -0.442286 0.792764 0.7321372 0.0608587 -0.6117270 0.2933624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6334 6345 -0.989463 0.618696 0.357137 0.2150079 0.3619617 0.6839810 0.5957561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6334 6474 0.585393 0.382619 0.630966 -0.8623477 -0.1358528 -0.0931770 0.4787677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6335 6344 -0.720192 -0.632123 0.181728 -0.3157595 0.3593212 0.1138998 0.8707532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6335 6475 -0.377364 0.610437 0.641564 -0.6034239 0.3618744 0.4676898 0.5349699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6336 5676 -0.411296 -0.142298 -0.784708 0.7208273 0.4554048 0.2811061 0.4404474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6336 6476 0.839145 0.177321 0.743480 0.2136314 0.3485240 0.6368688 0.6536749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6337 6342 0.572340 -1.018852 0.064796 -0.0522497 0.7274151 -0.6448237 0.2287787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6337 6477 0.563207 0.029266 0.716173 0.0435771 0.5630731 0.8216430 0.0771526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6338 6341 0.203473 -0.995852 -0.407840 0.7462266 0.1347587 -0.6274778 0.1767982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6338 6478 -0.538512 -0.575916 0.590369 0.2531832 -0.0795707 -0.6351780 0.7253383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6339 5679 0.417146 0.444414 -0.861270 -0.0417230 0.3129328 -0.8019637 0.5071356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6340 5640 -1.134304 -0.310023 -0.181438 0.2249404 0.3679389 0.7183494 0.5458908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6340 6379 -0.592751 0.535908 0.715392 0.5699885 0.5372135 0.0614300 0.6186608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6340 6440 0.913209 0.350780 0.240890 0.2071778 0.5184409 -0.5199572 0.6464835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6341 5641 0.529069 -0.453487 -0.685225 -0.7732459 -0.0457505 0.5463885 0.3185236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6341 6378 0.519681 0.781058 0.172588 0.3997260 0.1775172 -0.1410340 0.8881532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6341 6441 -0.567832 0.368721 0.728329 0.4183765 0.4820741 -0.7178092 0.2780569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6342 6377 0.099147 -0.201433 1.017876 0.3908118 -0.2007820 -0.8903126 0.1195671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6342 6442 -0.659954 -0.788017 -0.222418 0.1746112 -0.2928066 -0.6035226 0.7207883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6344 6375 -0.957985 -0.290898 -0.430032 0.5136893 -0.2641494 -0.7040095 0.4131817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6344 6444 -0.661183 0.642558 0.557388 0.1300899 0.4643988 0.8735876 0.0652305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6346 6446 -0.650400 -0.609854 0.515547 0.1958198 -0.6893136 0.5517123 0.4267492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6347 6372 0.740931 -0.540107 0.154387 0.0799795 0.0262989 0.3438597 0.9352391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6347 6447 -0.606173 -0.502247 0.648687 0.0390493 0.8177086 -0.5368878 0.2039101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6348 6331 -0.662035 0.528175 -0.431140 0.0744347 0.3069890 -0.1566035 0.9357845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6349 6370 0.722961 -0.315370 0.759432 0.2925196 0.0556077 -0.9540423 0.0338149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6349 6449 -0.759832 0.127571 0.539510 0.4615881 0.4721598 -0.7099460 0.2449044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6350 6450 0.082021 0.659725 0.700645 -0.4725639 0.5661117 -0.0562974 0.6730762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6351 6451 0.627888 0.208634 0.603053 -0.9047810 0.1283603 -0.3782472 0.1477292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6352 5652 -0.099626 0.211239 -0.957407 0.1649504 -0.2586715 -0.5896087 0.7471560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6352 6367 0.292009 -0.932901 -0.065551 0.2895157 0.4963417 0.5433511 0.6120418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6352 6452 0.123055 -0.409114 0.963570 0.2122598 0.3605402 -0.6307833 0.6535052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6353 5653 0.318544 0.307697 -1.009342 0.0658025 0.1567921 0.8651374 0.4718300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6353 6366 -0.765269 0.577074 0.213835 0.2212704 0.7630048 -0.2757675 0.5411242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6353 6453 -0.334980 -0.539541 0.746806 0.3974356 -0.5361628 0.6293202 0.3981590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6354 6365 0.969576 -0.184799 0.445467 -0.2053544 -0.0296136 -0.7644639 0.6103667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6354 6454 0.051281 0.912583 0.241447 -0.9243193 -0.0470439 0.0080566 0.3786235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6355 6364 0.175141 -0.588230 -0.649694 -0.2565372 0.3511541 0.8918160 0.1246744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6356 6363 1.028399 0.068937 -0.042474 -0.1536133 0.6370539 -0.0593818 0.7530199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6356 6456 -0.188790 0.896827 0.491422 -0.0181171 0.6699407 0.1574042 0.7253104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6358 5658 0.817954 -0.166508 -0.611451 -0.7683956 -0.3668258 0.5243240 0.0095634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6358 6361 0.313499 0.963264 0.145104 -0.3253670 -0.3330083 -0.5396810 0.7014173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6358 6458 -0.867806 0.101343 0.621303 0.4826853 -0.4083685 -0.5879214 0.5045776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6359 6320 0.592443 -0.784465 -0.372636 -0.0617848 0.3718923 0.9152815 0.1419101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6359 6459 -0.139553 -0.662088 0.613112 0.6710578 0.2726877 0.3493520 0.5943703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6360 6399 -0.721208 -0.486257 0.680107 -0.2045873 0.0837587 -0.6421169 0.7340398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6360 6420 -0.510995 0.766112 0.380401 -0.0944194 -0.3559694 -0.7337284 0.5709758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6361 6398 -0.538199 0.377056 0.923432 -0.1480334 0.7398904 -0.3968597 0.5226382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6361 6421 0.045643 -0.991580 0.411234 0.7677596 -0.1631797 -0.3341471 0.5217885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6362 6357 0.687438 -0.454854 -0.650840 -0.0489841 0.4713530 -0.2867064 0.8326021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6362 6397 -0.683309 0.456424 0.506585 0.7140484 -0.0680292 -0.2088197 0.6647566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6363 5623 0.678360 -0.750570 -0.041933 -0.7868925 0.4715674 0.2180533 0.3329823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6363 6396 0.237630 -0.208319 0.981306 0.0234737 -0.0979448 -0.0753589 0.9920569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6364 6395 0.130594 -0.113932 -1.086864 -0.3963175 -0.0356498 -0.0734438 0.9144766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6364 6424 0.206892 1.115811 -0.213071 -0.5216906 0.3015686 0.6980438 0.3868205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6365 6394 0.270519 0.732848 0.513538 0.5332110 0.0593022 -0.8438069 0.0126141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6365 6425 -0.591808 0.002547 0.403227 0.4708288 0.4845728 -0.5819850 0.4525515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6366 5626 0.708757 0.680163 -0.087648 0.6742167 0.3714392 -0.3951381 0.5013289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6366 6393 0.190848 -0.277307 -0.994674 0.6758202 -0.6434705 -0.2793928 0.2261691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6367 6392 -0.901420 -0.614709 0.021312 -0.0120188 0.3706965 0.7622774 0.5304459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6368 5628 0.669964 0.297386 -0.649452 0.5755490 0.1048288 -0.6971327 0.4144397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6368 6351 0.570363 0.435838 0.802369 0.2031740 -0.4636969 0.7534513 0.4195433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6368 6391 -0.638625 -0.444696 -0.779094 0.6279834 -0.1961131 0.4347507 0.6149539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6368 6428 -0.438326 -0.493796 0.840617 0.5068705 -0.1167475 0.5382118 0.6631594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6369 6350 -0.674156 0.701878 0.310507 0.6947794 -0.2276026 0.1185407 0.6718829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6369 6429 -0.306101 -0.643143 0.411187 0.4851336 0.3128473 0.5891392 0.5654087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6370 5630 -0.327367 0.033652 -0.949751 0.1671403 0.2387672 0.3563295 0.8877408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6370 6389 -0.972180 0.253778 0.464917 -0.1373956 0.6438276 -0.3468732 0.6680474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6370 6430 0.299187 -0.307342 1.119255 -0.1489983 -0.3653863 0.9009671 0.1804182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6371 6348 0.546775 -0.365760 0.915883 -0.2468011 0.6268877 0.7349577 0.0770595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6371 6431 -0.763474 0.787048 0.505879 -0.2664522 -0.4447653 -0.8410975 0.1540846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6373 6346 0.460441 0.731997 -0.403942 0.0124541 -0.1379192 -0.6948930 0.7056536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6374 6345 -0.439172 -0.092452 0.928906 -0.2860730 0.3500797 -0.2582488 0.8537646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6374 6385 0.339979 -0.169739 -0.881377 0.1547568 0.4575817 0.6893041 0.5399344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6374 6434 0.887289 0.369988 0.326272 0.2608037 0.6951708 -0.3165816 0.5903347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6375 6384 0.494594 -0.539428 0.446925 -0.3240628 -0.7229426 0.2539963 0.5548181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6375 6435 -0.479018 -0.020551 0.824833 -0.1577776 0.2749675 0.5560230 0.7683343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6376 6343 -0.487440 -0.509733 0.769681 -0.0655519 -0.5548849 -0.6377435 0.5301781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6376 6383 0.549395 0.627622 -0.757542 0.5912580 0.5506376 0.5886410 0.0267208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6376 6436 -0.500251 0.834605 0.063219 0.4359886 -0.5560134 -0.7030373 0.0806326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6377 6382 -0.798429 0.515265 0.637165 0.6068976 0.1577024 0.7390644 0.2461483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6377 6437 0.935088 0.724354 0.281841 -0.7210045 0.5067576 0.1818855 0.4361960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6378 6381 0.546417 0.685257 -0.461380 0.9028963 0.3296068 -0.2636417 0.0814291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6378 6438 -1.068525 0.568672 0.130309 -0.6766822 -0.6473300 0.3059314 0.1716712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6379 6439 0.566948 0.806386 0.278171 -0.7066218 -0.2526453 -0.2118222 0.6260889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6380 6400 0.277692 -1.009039 0.241941 0.5872266 -0.0640466 0.1782965 0.7869392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6381 6401 -0.006282 -0.892272 0.187656 0.3251905 -0.7256188 0.2915082 0.5317437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6382 6402 0.598687 -0.530483 0.680339 0.0382204 0.0034438 0.6620292 0.7484950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6383 6403 0.765710 -0.648298 0.001961 -0.0404690 0.1709087 -0.4442653 0.8785106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6384 5604 -0.575115 0.518143 -0.398790 0.1702579 0.6988922 -0.5740933 0.3911250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6385 6405 0.006642 -0.292041 1.278054 0.6191288 -0.0265153 0.5662600 0.5434392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6386 6373 0.171377 0.330124 -0.974736 -0.0496031 0.5601882 -0.4095559 0.7183263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6386 6406 0.604387 0.740630 0.543487 0.1919533 0.9075834 0.2401017 0.2860027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6387 6372 -0.215991 0.509418 -0.851690 -0.3860683 0.2227168 -0.3591542 0.8199736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6387 6407 -0.231035 0.773610 0.580283 -0.5301504 -0.1199500 -0.4719220 0.6941486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6388 6371 -0.603943 0.524674 0.492760 -0.0236730 -0.4787922 -0.7652742 0.4295963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6389 5609 0.565153 0.648906 -0.658930 0.3906821 0.2260044 -0.8749520 0.1753527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6389 6409 -0.673025 -0.468405 0.379322 0.5439816 -0.1765542 -0.8202117 0.0128583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6390 6369 -1.003913 -0.091451 0.314687 0.1969548 -0.1026994 0.3341036 0.9159893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6390 6410 -0.058788 -0.978197 0.218492 0.0949392 -0.0550853 0.2361364 0.9655008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6391 6411 0.110399 1.052481 0.197497 -0.3005131 0.9235772 0.1338173 0.1969516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6392 5612 -0.806298 -0.379876 -0.364345 -0.7048093 0.2807025 0.0615717 0.6485822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6392 6412 0.711254 0.649013 0.498759 0.1348199 -0.7536955 -0.6375641 0.0853152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6393 6413 0.740494 0.607955 0.605456 -0.2037923 -0.2500268 -0.9137874 0.2468764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6394 6414 -0.134600 0.004005 0.936233 0.0799303 0.1963824 -0.9746475 0.0714660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6395 6415 0.031986 0.469967 0.651490 -0.1986867 0.8371588 0.1812027 0.4762923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6396 5616 0.875743 -0.588615 -0.327138 0.0305164 0.7418910 0.6481336 0.1690836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6396 6416 -0.786904 0.474550 0.060699 -0.5900272 0.2238956 0.6254576 0.4588480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6397 6417 -0.066141 0.531843 0.741843 -0.4108390 -0.3576710 -0.0631989 0.8362348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6398 5618 -0.085115 0.848901 -0.455895 -0.3315161 -0.6591025 0.6748094 0.0177012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6398 6418 0.210843 -0.930497 0.363964 0.7464431 0.0381660 -0.5179368 0.4160620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6399 6419 -0.856702 -0.423373 -0.043519 -0.5312835 -0.4596457 -0.0409892 0.7104812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6400 6439 0.127075 0.931563 0.037099 0.3022693 -0.1171003 0.8443234 0.4266600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6400 7180 0.114575 0.074604 1.054867 0.3774165 0.0249680 -0.3300769 0.8648599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6401 6438 0.316611 0.925103 0.190275 -0.5390087 0.5244695 -0.5588967 0.3493362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6401 7181 0.305394 -0.609677 0.946181 -0.1201048 -0.4703381 0.2956272 0.8227767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6402 6437 0.159921 0.740405 0.561269 -0.3506406 -0.5735005 0.4347979 0.5992488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6402 7182 -0.208229 -0.504668 0.803895 0.4820824 0.4677253 -0.5110658 0.5363222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6404 6384 0.723464 0.622260 -0.204632 0.1656734 0.3971725 -0.7799951 0.4543281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6404 6435 0.538388 -0.893009 -0.084793 0.9093508 -0.1311219 -0.3863642 0.0813071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6405 6434 0.619989 -0.243537 -0.687291 0.0079298 -0.7455133 -0.5650272 0.3533997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6405 7185 0.499060 1.042282 0.161994 -0.5001647 -0.2466387 -0.7229561 0.4078470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6406 6433 0.533299 -0.128191 1.034395 -0.6474981 -0.0061439 0.5054472 0.5702908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6406 7186 -0.171194 1.147807 0.199476 -0.2080469 -0.1524860 0.0527523 0.9647184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6407 6432 -0.842108 0.571363 0.029846 0.0932165 0.0316372 -0.8631254 0.4953023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6407 7187 -0.087603 -0.411717 0.931982 0.0630329 0.1645176 -0.1363745 0.9748655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6408 6388 0.170376 0.126513 -0.877744 -0.1840032 -0.4486658 -0.8736868 0.0388993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6409 6430 -0.912442 -0.285811 -0.070258 -0.7703079 0.1846386 -0.0488783 0.6083956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6409 7189 -0.109868 0.907638 0.435115 -0.2471041 -0.0819971 0.9355325 0.2387361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6410 6429 -0.822009 0.352176 0.346180 0.4352458 0.2191569 0.7345932 0.4721273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6410 7190 -0.112231 -1.071303 0.293700 0.2718350 -0.7119778 0.6109232 0.2143972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6411 6428 -0.695179 -0.693178 0.139768 0.3201205 -0.8237127 -0.1249589 0.4510051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6411 7191 -0.708526 0.631500 0.364094 -0.0267112 -0.1995790 0.4824331 0.8524747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6412 6427 0.075715 0.621012 -0.754083 0.0345444 -0.2599228 -0.1220976 0.9572560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6412 7192 -0.910077 0.547961 0.137918 0.3405454 -0.7264603 0.3327597 0.4955353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6413 6426 -0.448203 -0.844336 -0.142797 0.2283701 -0.2560244 0.4551776 0.8216520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6413 7193 -0.610388 0.158453 0.960839 0.5596665 -0.0542273 -0.4438150 0.6977543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6414 6425 -0.599727 -0.571099 -0.254377 0.1923454 0.7319174 -0.6475630 0.0892317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6414 7194 0.005451 -0.240449 0.973581 -0.1195557 -0.4990255 0.8531284 0.0940843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6415 6424 -0.321192 -0.402214 -0.652681 -0.6711070 -0.6068131 0.0136279 0.4256849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6415 7195 -0.902939 0.547613 0.320073 0.0096020 -0.0378696 0.8376973 0.5447356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6416 6423 0.748589 0.740652 -0.029177 0.1384670 -0.3887237 -0.3251065 0.8508975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6416 7196 -0.099854 0.348973 0.917338 0.3872972 -0.0051287 0.8777452 0.2820246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6417 6422 0.828026 -0.164691 -0.594495 0.5144463 0.4284908 0.7089916 0.2215211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6418 6421 -0.667764 0.399899 -0.782664 0.2853809 0.7896951 0.4566758 0.2939161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6418 7198 0.100042 0.955755 0.349786 -0.4864035 -0.5167441 -0.5967883 0.3744741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6419 7199 -0.804833 -0.737496 0.154732 0.8548086 0.1835389 0.0675140 0.4806846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6420 6459 -0.984534 0.041696 -0.405615 0.7892466 -0.0515252 -0.4616314 0.4016608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6420 7160 -0.310274 -0.488109 0.857861 0.4379158 0.3821259 -0.5267895 0.6202438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6421 6458 0.793230 -0.774396 0.135588 -0.3847599 0.1244069 -0.3608254 0.8404093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6421 7161 0.599900 0.699057 0.408135 -0.2941092 0.2588772 0.3687948 0.8428955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6422 6457 -0.511079 -0.438646 0.833780 -0.0186334 0.8560580 0.1308848 0.4996866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6422 7162 0.243975 0.693100 0.459533 0.1534730 0.5890526 0.5810015 0.5402781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6423 6363 -0.313001 -0.483837 -0.701058 0.2951184 0.2505732 -0.4785162 0.7881246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6423 6456 -0.082508 0.984057 -0.394805 0.3690918 0.1172472 -0.3403812 0.8568343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6423 7163 0.380870 0.508084 0.654758 0.3759575 -0.2060834 0.7454568 0.5103721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6424 6455 -0.817832 0.031016 0.564923 -0.2370930 -0.0372772 -0.9610622 0.1369553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6425 6454 0.699738 0.016161 0.813831 0.1509091 0.5989608 -0.5242119 0.5862374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6425 7165 -0.338197 -0.961469 0.117746 0.0867227 0.3203341 -0.7904786 0.5147900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6426 6366 -0.396093 -0.625887 -0.624246 -0.5562000 -0.0067260 0.8296244 0.0481624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6426 6453 -0.766408 -0.157892 0.320022 -0.3813713 -0.3211612 0.0151275 0.8667079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6426 7166 0.348733 0.532329 0.733498 -0.6592904 0.0327676 -0.6260596 0.4151046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6427 6367 0.611807 -0.423058 -0.715539 -0.3462367 0.4217583 0.5623415 0.6212988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6427 6452 -0.399619 0.489875 -0.670004 0.0410839 -0.1649924 -0.3406187 0.9246992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6427 7167 -0.838604 0.228875 0.876521 -0.4321658 -0.6607005 -0.4193206 0.4481940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6429 6450 0.492649 0.573496 -0.465727 -0.3520373 -0.0468247 -0.3760797 0.8558278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6429 7169 -0.413191 0.929263 0.195347 0.2848666 -0.1740235 -0.8199153 0.4650868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6431 6408 -0.205764 -0.685868 -0.062582 0.3397899 0.3489384 0.6383123 0.5961059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6431 6448 0.221651 0.845576 0.185802 -0.2866561 0.7556117 0.1701194 0.5638604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6431 7171 0.880981 -0.416566 0.539572 0.1021592 0.6928006 0.4883162 0.5207093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6432 6447 -0.107835 -1.219761 0.065424 -0.6931304 0.2378790 -0.3299239 0.5950917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6432 7172 0.169943 0.080069 0.902218 -0.5697309 0.0113366 0.7234311 0.3897764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6433 6373 -0.254581 0.291817 -0.966671 -0.2318463 0.2729312 0.9334722 0.0196325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6433 6446 -0.416432 -1.013866 -0.132268 0.4498329 -0.1871586 0.8730011 0.0221606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6433 7173 0.335885 -0.390358 0.915259 0.0138365 -0.6194507 0.6796344 0.3926658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6434 6445 -0.728827 -0.328725 -0.359027 0.1598852 -0.6969471 -0.1865893 0.6737106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6434 7174 -0.598427 0.784920 0.230246 0.3795028 -0.3235944 -0.7665141 0.4046239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6435 7175 -0.426434 0.799062 0.448181 0.3463347 -0.5457920 -0.6975764 0.3091125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6436 6403 -0.280458 -0.739055 -0.161234 0.2586227 -0.5632470 0.1339627 0.7732536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6436 6443 0.379685 1.033679 0.146647 -0.5732701 -0.3324502 -0.2105000 0.7186988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6436 7176 -0.180034 -0.016469 1.019467 -0.1093834 -0.3243857 -0.2794527 0.8970593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6437 6442 1.024274 -0.147768 -0.081227 0.1784009 -0.7729566 0.1027813 0.6001227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6437 7177 -0.192879 -0.575334 0.600220 0.2265864 -0.0509296 0.4769528 0.8476915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6438 6441 -0.536448 -0.570532 -0.109942 0.0092570 -0.8036548 0.4533463 0.3853964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6438 7178 0.717504 -0.629960 0.598504 0.2206707 0.3067226 -0.8899244 0.2554608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6439 7179 0.739265 -0.010848 0.692647 0.2191749 0.4849781 0.4326305 0.7277289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6440 6479 0.846775 0.407891 0.500007 -0.1934665 -0.5552170 -0.6904748 0.4213661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6440 7140 -0.633178 0.717817 0.229542 -0.5860272 -0.2407881 0.4346844 0.6400334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6441 6478 0.402089 -0.291895 1.001256 0.3803826 0.5051745 -0.6501593 0.4211896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6441 7141 -0.253259 -0.931738 0.104562 -0.3635979 -0.7824232 0.2254661 0.4525214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6442 6477 -0.520813 -0.675435 -0.765816 0.6067401 0.5313884 -0.4525254 0.3804123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6442 7142 0.718634 -0.592980 0.301734 0.0361884 -0.2473932 0.9239118 0.2896101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6443 6343 -0.627139 0.713348 -0.074762 0.5485595 -0.2121039 0.5933923 0.5495271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6443 6476 0.215620 0.386962 0.913104 -0.2370067 0.5562142 -0.7565157 0.2492740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6443 7143 0.720061 -0.753619 0.027444 0.0112926 0.9846607 -0.0817867 0.1537100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6444 6435 0.758361 -0.276556 -0.665113 0.2314151 0.7532253 0.5573085 0.2617363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6444 6475 -0.417462 0.255505 0.588648 -0.2059222 -0.0257430 -0.9458960 0.2494274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6445 6474 0.000893 -0.570991 0.788122 0.7384213 0.2411596 0.6246510 0.0799201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6445 7145 0.199950 0.978049 0.623677 0.1796587 0.1116578 0.9758524 0.0544743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6446 6473 0.214002 1.017444 0.052388 -0.0753197 0.7131215 0.6885135 0.1083230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6446 7146 0.579812 0.040242 0.887781 -0.4928251 -0.1900516 -0.8474558 0.0531272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6447 6472 0.621744 0.260629 -0.566514 0.7310535 -0.2837688 0.4751866 0.3990410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6447 7147 0.310214 -0.810795 0.040654 -0.2320096 0.6616189 -0.5544867 0.4483040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6448 6471 -0.526431 0.516093 0.485499 -0.0960904 -0.9086071 0.2844089 0.2903641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6448 7148 -0.553855 -0.898383 0.466712 0.0834946 -0.8948991 -0.0509391 0.4354187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6449 6430 -0.986579 0.211082 -0.010562 -0.2911831 -0.7500272 0.5261875 0.2753147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6449 6470 1.079337 -0.222922 -0.134973 0.5686687 -0.1591379 0.3190393 0.7412860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6449 7149 -0.207308 -0.871815 0.198086 0.6594531 0.0052044 0.6747607 0.3313494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6450 6469 -0.016685 1.027154 -0.031981 0.7937795 -0.0028333 -0.5389983 0.2817568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6450 7150 -0.917926 -0.032767 0.363410 0.1945806 0.1432197 0.5932197 0.7679302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6451 6428 -0.614077 -0.924692 -0.018410 0.8509488 0.4095291 0.3166418 0.0889380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6451 6468 0.488671 0.839630 0.077813 0.2068583 0.4675059 0.6759752 0.5307593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6451 7151 0.867726 -0.507590 0.155748 -0.4077641 0.4596380 0.0094231 0.7889059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6452 6467 -0.892660 -0.049575 -0.517394 0.2533776 -0.0850422 0.2932859 0.9179058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6452 7152 -0.342321 -0.078832 0.788291 -0.0699725 -0.3118537 0.7690351 0.5535667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6453 7153 0.793959 0.180254 0.608304 0.6631877 -0.0798161 0.6717842 0.3201835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6454 6465 -0.793798 0.045897 0.546245 0.8598135 0.2299942 0.0546795 0.4525855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6454 7154 0.259075 -0.750498 0.576077 0.4150232 -0.1792817 -0.3442167 0.8228783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6455 6355 -0.416580 -0.843868 -0.640136 -0.3692090 0.2751309 -0.7934184 0.3980890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6455 6464 0.850671 -0.336495 -0.140177 0.2066380 -0.5245970 -0.7157551 0.4120598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6455 7155 0.499668 0.780917 0.586134 -0.4691119 0.0549389 0.8730982 0.1208936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6456 6463 -0.220519 0.135906 -0.899652 -0.3598405 0.2441922 -0.1133561 0.8933283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6456 7156 -0.274351 0.894551 0.163060 -0.4491052 0.7106343 0.5414937 0.0093789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6457 6462 -0.262145 -0.080010 -0.883074 0.5237535 -0.6225699 -0.5680053 0.1243343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6457 7157 -0.445679 0.858300 0.203736 -0.6721772 -0.4254166 -0.5032073 0.3376106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6458 6461 0.979593 -0.040122 0.085215 -0.2214906 0.2397953 -0.0315688 0.9446923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6458 7158 -0.222004 0.434956 0.879624 -0.5372370 -0.4926510 -0.2181451 0.6489100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6459 7159 -0.628364 0.725712 0.327110 -0.0597412 0.0547146 -0.7045009 0.7050643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6460 6499 -0.881232 0.712032 0.050137 0.0346511 -0.4622492 -0.7255368 0.5086466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6461 6498 0.628747 -0.182655 0.476137 -0.2559039 -0.2359428 -0.6556838 0.6700172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6461 7121 -0.559371 -0.123197 0.851434 -0.3329241 -0.1070360 0.3605588 0.8646977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6462 6497 0.487434 -0.578681 0.344198 -0.3293346 0.3551293 0.4677414 0.7393510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6462 7122 -0.677879 0.215251 0.893586 0.3663381 -0.6896965 -0.5607862 0.2750165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6463 6496 0.146808 0.790257 -0.690496 -0.1758727 -0.4042965 0.8947441 0.0710357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6464 6495 -0.150641 0.388685 -0.871068 -0.6572271 -0.2092097 -0.2807047 0.6674494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6464 7124 -0.810713 0.515359 0.218496 -0.1622124 -0.0971161 0.9540831 0.2323383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6465 6494 -0.643915 0.184688 -0.735441 -0.6867188 -0.3593599 -0.6270462 0.0780434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6465 7125 -0.317958 0.786574 0.489808 -0.1194012 0.7616279 0.4275963 0.4720463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6466 6453 -0.463227 0.106218 0.665375 0.5710319 -0.7364271 0.2101165 0.2957173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6466 7126 -0.248619 -0.806944 0.140829 0.3356808 0.1222965 0.8064803 0.4711173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6467 6327 0.152982 -0.626658 -0.730257 0.2965754 0.0589809 0.7272397 0.6161873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6467 6492 -0.921396 0.250077 -0.254229 0.1211551 0.0822561 0.8949299 0.4214923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6467 7127 -0.160177 0.552382 0.769014 -0.0559508 0.3715371 0.2182361 0.9006679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6468 6328 0.799220 0.394504 -0.486005 0.7414129 0.4896291 -0.4400694 0.1300354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6468 7128 -0.766748 -0.320117 0.513381 -0.7409524 -0.2270809 0.6310570 0.0345091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6469 6490 -0.578775 -0.683110 -0.276360 -0.0241235 0.2473817 0.9053954 0.3442087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6469 7129 -0.722102 0.185035 0.687893 0.2739723 0.1331624 -0.0257152 0.9521269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6470 6330 0.319936 -0.236697 -0.936345 -0.0029904 0.3741015 -0.4697384 0.7996155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6470 6489 0.666841 -0.704015 0.332798 -0.4231543 -0.0155692 -0.4943078 0.7591823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6470 7130 -0.416873 0.186255 1.016467 0.5375002 -0.1360504 0.3964784 0.7317026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6471 6488 1.003502 0.018106 -0.428673 0.2735733 0.4409990 -0.8521318 0.0674448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6472 6487 -0.533447 -0.965373 0.380469 0.0175924 0.2398828 -0.9546348 0.1755540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6472 7132 0.307036 0.316660 0.944178 -0.2722369 -0.6083650 -0.6956660 0.2680074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6473 7133 -0.649414 0.689836 -0.082389 0.3768852 -0.3671304 -0.6692295 0.5246949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6475 6484 0.574935 -0.554305 0.514177 0.6423947 -0.0391662 -0.3445006 0.6834577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6475 7135 -0.620608 -0.006342 0.794386 -0.5976869 0.0366687 0.7813064 0.1760285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6476 6483 -0.378853 -1.046512 0.070828 0.1997321 0.5605493 0.4791509 0.6452178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6476 7136 0.058812 0.028360 0.938536 0.4681819 -0.0164039 0.2674349 0.8420304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6477 6482 0.448477 0.083269 1.025280 0.5879224 -0.1328269 -0.7239312 0.3356006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6478 6481 -0.986906 0.005725 0.186982 0.2735885 0.2070217 0.1531221 0.9267389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6478 7138 0.434748 -0.349690 0.921600 0.1311954 0.5345759 -0.4895227 0.6763017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6479 6339 -0.243672 0.362865 -0.946979 0.0057288 0.1020514 0.6064936 0.7884911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6479 7139 0.381755 -0.360790 0.823733 -0.2755619 -0.3284254 0.1013302 0.8977386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6480 7100 -0.165648 -0.061683 1.020622 -0.2804473 0.0919237 -0.8317741 0.4701608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6481 6301 0.065390 -0.045534 -0.889195 -0.3241010 -0.2092878 0.3064670 0.8701926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6481 6518 -0.904251 0.424605 -0.162706 -0.2887988 0.7101872 0.4981349 0.4050815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6481 7101 -0.189909 0.163085 1.061604 -0.1649145 -0.6479689 -0.7393024 0.0798213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6482 7102 -0.871051 -0.388759 0.367799 0.1843121 -0.2571872 -0.9439144 0.0943894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6483 7103 -0.483992 0.872927 0.184283 0.0686602 0.0998184 0.5907791 0.7976855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6484 6515 0.873815 0.600548 0.227314 0.1034342 -0.4462352 -0.8728444 0.1682801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6485 6474 -0.886954 -0.072451 -0.686404 -0.7191064 -0.6072735 -0.2827949 0.1847484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6485 6514 0.818999 0.294775 0.561282 -0.1808221 -0.6115095 0.1172276 0.7613260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6486 6473 0.081083 -0.942892 0.333773 -0.6819077 0.4274469 0.4162991 0.4230675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6486 6513 -0.082860 0.897913 -0.066348 -0.2143494 -0.8608088 0.2163821 0.4077269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6486 7106 -0.753751 -0.055118 0.386629 0.4826916 -0.3386057 -0.7322434 0.3408441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6487 6512 0.548904 0.581696 0.700043 0.4131112 0.2493656 0.0494859 0.8744753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6487 7107 -0.457387 -0.535500 0.567514 -0.4825314 -0.2873554 0.0764281 0.8238623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6488 6511 -0.742176 0.432187 -0.552433 0.3495484 -0.0188606 0.1218719 0.9287666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6488 7108 -0.698288 0.434768 0.699872 0.5396587 -0.6310924 -0.1605973 0.5335723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6489 7109 0.130259 -0.773657 0.505116 0.7476579 -0.1381671 0.6406068 0.1074262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6490 6509 -0.213070 0.706420 -0.687995 0.0855323 -0.1188958 0.9609369 0.2348368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6490 7110 0.484572 0.592904 0.596048 0.4304537 0.3886369 0.6710881 0.4618568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6491 6468 0.542390 -0.792376 0.473686 -0.7167150 -0.5015037 0.3017206 0.3791811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6491 6508 -0.567566 0.786670 -0.624182 -0.1043043 -0.9308128 0.0831018 0.3402971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6491 7111 -0.761346 -0.438947 0.221563 0.9554535 -0.1592582 -0.2057933 0.1392642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6492 7112 0.595062 0.041030 0.692111 0.4187265 0.4111869 0.8095445 0.0152051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6493 6466 0.682399 -0.633358 -0.712039 0.4163729 -0.5845277 0.6894376 0.0981672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6493 7113 0.547652 0.373398 0.490927 -0.3239338 0.3192660 0.7406837 0.4944934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6494 6314 -0.729747 0.898985 -0.241630 0.3932906 -0.6433449 0.5718090 0.3232094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6494 6505 -0.407619 -0.784699 -0.250078 0.6310045 0.0428119 -0.1497087 0.7599919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6495 6504 -0.744789 0.321580 0.235547 0.1842359 -0.8818116 0.1204709 0.4170757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6495 7115 -0.372835 -0.687228 0.414857 0.3644729 -0.7111958 0.0716529 0.5968466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6496 6503 0.251659 -0.109007 -0.889263 -0.5952962 -0.1718298 -0.7831294 0.0529651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6496 7116 0.709435 -0.802837 0.200986 0.2109725 0.2198314 -0.7093293 0.6356231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6497 6502 -0.565088 -0.803731 -0.138017 -0.2298657 0.7468315 0.6189188 0.0796490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6497 7117 -0.745049 0.523023 0.598090 -0.0069497 0.0891216 -0.8603075 0.5018765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6498 7118 0.493798 -0.514753 0.508582 -0.2667587 -0.2768705 0.6916654 0.6113767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6500 6539 -0.419321 -0.749489 -0.260816 0.7939481 0.5398714 0.1430157 0.2402744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6500 7080 0.724932 -0.761266 0.013154 -0.8028681 0.4703031 -0.3652313 0.0287049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6501 6498 0.824495 0.343934 -0.479006 0.5700915 -0.4381704 0.4993646 0.4833606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6501 6538 -0.596017 -0.435236 0.521564 0.7665015 -0.0855300 -0.0744270 0.6321556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6501 7081 0.768341 -0.548536 0.291502 -0.4484055 0.4002162 -0.7701341 0.2136657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6502 7082 0.252951 0.957042 0.409500 -0.0601639 -0.8105699 -0.4846546 0.3232131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6503 6536 -1.085424 -0.121197 0.258107 -0.6074941 -0.2054274 -0.7660771 0.0433167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6503 7083 0.028898 0.970329 0.304904 -0.5390232 0.0070902 0.8415480 0.0346507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6504 6535 0.639912 0.904236 0.316338 0.2713014 0.8273683 -0.4224366 0.2518025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6504 7084 0.786749 -0.708264 0.409696 -0.1361164 0.4432504 0.5459065 0.6978449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6505 6534 -0.324742 -0.428510 0.747435 0.2604419 0.2097146 -0.2309705 0.9136971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6506 6533 -0.047804 0.455769 0.772017 0.1648486 0.7547581 0.2048118 0.6010136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6506 7086 0.651594 -0.580147 0.658820 -0.2828005 0.2424421 0.2764814 0.8858915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6507 6532 -0.131948 -0.110125 -0.903480 0.6123948 0.1193741 0.4206810 0.6585969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6507 7087 -0.365818 -0.889487 0.129373 0.1702665 -0.2785007 -0.3032740 0.8952494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6508 7088 0.499425 -0.747497 0.384174 -0.5244499 0.7405380 -0.3863379 0.1652230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6509 6530 0.253733 -0.588191 -0.977209 0.2652914 0.8776548 -0.2379543 0.3204999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6510 6489 0.258011 -0.902408 0.623370 -0.1777554 0.3815823 0.6601282 0.6221163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6510 6529 -0.381505 0.644153 -0.631212 -0.5366210 0.7397307 0.3742463 0.1574044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6510 7090 0.729652 0.442985 0.248195 -0.3482951 -0.3765679 -0.8284018 0.2250282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6511 6528 -0.481206 0.153066 -0.779715 0.6581507 -0.1262124 -0.6946152 0.2615681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6511 7091 -0.412521 0.635084 0.195516 -0.1142668 -0.6887399 -0.5513970 0.4566637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6512 6292 0.808163 -0.081769 -0.527245 -0.2988634 -0.3416983 -0.3225102 0.8306083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6513 6526 0.674229 1.096063 -0.035588 0.2620315 0.3923976 0.6475581 0.5983579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6513 7093 0.835153 -0.539040 0.187553 0.8435750 0.4657107 0.2222601 0.1486447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6514 6525 0.675792 -0.311183 -0.738280 -0.5749185 -0.7443930 -0.3358816 0.0503118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6515 6524 -1.039833 -0.198112 0.522755 -0.1610506 -0.0993032 0.4009843 0.8963332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6515 7095 0.440971 -0.145095 0.948999 0.1936344 0.2699934 -0.7036212 0.6281135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6516 6483 -0.234034 0.272005 -1.027185 -0.4783110 0.6792475 0.3039535 0.4663193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6516 6523 0.253695 -0.416820 0.923684 -0.3167941 0.1581190 -0.6232311 0.6972968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6516 7096 -0.704912 0.648139 0.295549 -0.7561252 0.3276666 0.2701872 0.4979038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6517 6482 -0.719709 0.234356 0.388651 -0.4422476 -0.6984981 0.5477967 0.1282040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6517 6522 0.793026 -0.249694 -0.316176 -0.2468524 -0.7723848 0.4024566 0.4248697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6517 7097 0.074693 -0.808854 0.329984 -0.3009909 0.6585054 -0.6725146 0.1532947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6518 6521 0.547469 0.763603 0.014518 -0.4773505 -0.0987432 -0.0340219 0.8724842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6518 7098 -0.799100 0.517535 0.132125 -0.4617410 0.4398028 0.6791529 0.3634833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6519 6480 0.334353 0.728612 0.761801 0.3663189 0.6393721 -0.2150366 0.6409157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6520 6260 -0.827822 -0.502094 -0.499345 0.6755794 0.5453222 0.2733495 0.4141210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6520 6559 0.766685 -0.753711 0.085825 -0.1078821 -0.5471214 -0.8084768 0.1881086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6521 7061 -0.793212 0.219915 0.645859 0.4654461 0.0420383 0.1446045 0.8721710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6522 6262 0.509883 0.954236 -0.112816 0.4753944 0.4327117 -0.1903043 0.7419872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6522 6557 -0.897666 0.079679 -0.449285 0.3344490 -0.6376360 0.5978863 0.3522729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6522 7062 -0.509480 -0.968693 0.166695 0.2449033 0.5172915 0.2109630 0.7924181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6523 6556 0.616404 -0.306996 0.823931 0.3924647 0.2216885 -0.8642309 0.2234514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6524 6264 -0.067909 0.745971 -0.498793 -0.1209293 0.5270933 -0.1145365 0.8333248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6524 6555 -0.504407 0.701067 0.796868 -0.0776830 -0.0383329 -0.9268099 0.3654030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6525 7065 0.287559 0.761934 0.182957 -0.6214221 -0.1457929 -0.7584973 0.1313804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6526 6266 0.462414 0.285772 -0.578612 -0.0480303 0.1919990 -0.1604595 0.9669965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6526 7066 -0.536787 -0.334381 0.852940 -0.0750544 0.2765878 -0.2796079 0.9163435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6527 6512 0.196485 -0.940934 -0.479298 0.0866118 0.7426602 0.5198244 0.4132031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6527 6552 -0.353091 0.887422 0.370610 0.4025423 0.2642329 0.7156036 0.5060160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6527 7067 0.839537 0.022011 0.530768 -0.2471299 -0.0232273 -0.4224529 0.8717344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6528 6551 0.857219 -0.445300 0.211588 0.3944178 -0.4309219 0.8058753 0.0964673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6528 7068 -0.660967 -0.515780 0.330179 -0.6327210 -0.6628010 0.2989174 0.2664721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6529 6269 0.966636 0.705796 -0.084971 -0.4203617 -0.0051452 0.7411537 0.5234125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6529 6550 -0.040683 0.051027 1.064479 0.5053275 -0.5488205 0.1604876 0.6462847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6529 7069 -0.804251 -0.540465 0.165221 -0.2236141 -0.4542664 0.7004508 0.5029984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6530 7070 -0.574585 -0.728413 0.191047 -0.2447697 0.5118782 -0.8216356 0.0546205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6533 6546 -0.667865 0.926099 -0.160814 0.6501382 0.2374160 -0.5460059 0.4720503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6535 6544 -0.382460 0.758712 -0.624859 0.4391904 -0.4541469 -0.7745799 0.0298049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6536 6543 0.508689 -0.162203 -0.811745 0.3838473 0.4343446 -0.1992692 0.7901252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6537 6502 0.681632 0.454737 -0.238270 -0.0408903 0.8040276 0.5923984 0.0305259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6537 6542 -0.794246 -0.478743 0.201388 -0.1687280 0.8444530 0.4725464 0.1874296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6538 6541 -0.391581 0.717871 0.507613 0.0665879 0.4449082 0.3277241 0.8307946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6538 7078 0.794878 0.524249 0.251681 -0.3048767 0.0398129 -0.9206659 0.2404981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6539 6279 0.172732 -0.721610 -0.421166 -0.2064645 -0.3036617 -0.6192827 0.6940107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6539 7079 -0.366370 0.568127 0.533140 -0.1416582 0.0713324 -0.5579467 0.8145798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6541 6241 -0.610683 -0.087118 -0.971814 0.7004248 0.5162820 0.4142984 0.2668609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6541 6578 -0.116399 0.834118 0.088821 -0.0163829 0.2589568 0.9481951 0.1833004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6541 7041 0.527353 -0.081613 0.778350 -0.4689570 0.1408012 0.2400488 0.8382309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6542 6577 0.733889 0.255677 -0.691273 -0.1913375 0.1618918 -0.8439423 0.4742810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6542 7042 0.047318 1.018768 0.331734 -0.1083412 0.4012359 0.5585074 0.7178729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6543 6576 0.963862 -0.383380 0.019367 0.5002109 -0.0933428 -0.8529196 0.1166376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6543 7043 0.044991 0.236292 0.935968 0.3127200 0.4837347 0.2198058 0.7873324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6544 6575 0.445872 -0.652909 0.605839 0.2785487 -0.0016233 -0.6213814 0.7323204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6544 7044 -0.016083 0.669667 0.748256 -0.0019887 0.1602216 0.6812600 0.7142898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6545 6534 -0.676313 0.082423 -0.872854 -0.1437345 0.3561666 0.5861318 0.7133970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6545 6574 0.540761 0.049319 0.737056 -0.5675626 0.4391926 0.6157519 0.3253183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6545 7045 -0.366428 0.632756 0.237761 -0.1971543 -0.2095365 -0.8565564 0.4284108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6546 6573 -0.384662 -0.674068 -0.504905 -0.2061048 -0.2668530 0.2634105 0.9038392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6546 7046 -0.459384 -0.376945 0.673369 0.4787664 -0.0689871 -0.4045467 0.7761221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6547 6532 1.164247 0.365395 -0.029922 0.4220915 0.5268330 -0.1634647 0.7194199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6547 6572 -0.802458 -0.309817 -0.079993 -0.3492925 0.4271221 -0.1648127 0.8175563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6547 7047 0.181827 -0.334048 0.939023 0.3111246 -0.2871454 -0.1305333 0.8964988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6548 6531 0.554984 -0.578838 0.885476 -0.2009558 -0.9145499 0.3497958 0.0292923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6548 6571 -0.421317 0.481961 -0.951323 0.1040227 -0.6665225 0.0192214 0.7379415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6548 7048 -0.925424 -0.564230 0.007454 -0.0331386 -0.7768429 -0.3059199 0.5493905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6549 6570 0.297316 0.050372 -0.721048 0.6038610 -0.7453463 0.2105825 0.1883235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6549 7049 0.678861 -0.788480 0.261294 -0.1676599 0.8511167 -0.1251432 0.4814870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6550 6569 1.002493 0.577943 -0.227387 0.4181361 0.2078248 0.1653441 0.8686958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6550 7050 0.056830 0.198799 0.848787 -0.2026412 0.7217898 0.6026875 0.2733566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6551 6568 -0.359166 -0.238310 0.940921 -0.7128986 0.0701750 -0.5510229 0.4280476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6551 7051 0.865267 0.419810 0.401125 0.2881069 0.6837071 0.5242922 0.4179194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6552 6567 0.838922 0.275460 -0.318246 -0.3497974 0.4209255 0.7767487 0.3116487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6552 7052 0.100151 0.153950 1.048546 0.5200956 0.2680544 0.3765713 0.7182210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6553 6526 -0.844080 -0.242048 0.682765 0.2317838 0.5198445 0.1784082 0.8026260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6553 6566 0.885046 0.106873 -0.517574 -0.2195565 -0.0512786 0.9632593 0.1459349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6554 6254 0.813262 -0.407033 -0.361473 -0.0148879 0.4315036 0.6000229 0.6734653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6554 6525 -0.257837 0.589831 -1.031344 0.0513282 0.3471510 0.6843624 0.6391398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6554 6565 0.247777 -0.409166 0.768049 0.7178237 -0.3743100 -0.2946546 0.5077398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6554 7054 -0.772350 0.337443 0.448664 -0.7550122 0.1520764 0.4511246 0.4509058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6555 6255 -0.644125 -0.636521 -0.572450 0.1231845 0.5709745 0.5443326 0.6020928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6555 6564 0.057038 -0.599090 0.696534 0.0739244 -0.2662724 -0.1291361 0.9523435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6555 7055 0.461582 0.579220 0.694313 0.5985844 0.6615197 0.4512829 0.0207897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6556 6563 -0.603543 0.534287 0.491741 -0.3794889 -0.3354225 0.5800324 0.6379987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6556 7056 0.588917 0.372712 0.820071 0.0831137 0.4549703 -0.8795667 0.1116087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6557 6257 -0.359426 -0.175196 -0.790811 0.4808654 -0.1271485 0.5844255 0.6411307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6557 6562 -0.019402 1.111325 -0.183020 -0.0219043 -0.4423841 -0.2188302 0.8694423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6557 7057 0.333817 0.061835 1.017371 -0.0923115 0.7141356 0.6933519 0.0274224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6558 6521 0.902509 0.434658 -0.433009 -0.0319806 -0.1172091 0.9677540 0.2206613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6559 7059 -0.649765 0.393252 0.549265 0.4290923 0.3104281 -0.6677858 0.5230452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6560 6220 -0.524049 -0.074289 -0.723850 -0.7184141 0.1834286 -0.6633960 0.1007018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6560 6599 0.726172 -0.140720 -0.645996 0.1473645 0.6402567 -0.1134611 0.7453064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6560 7020 0.662258 -0.114874 0.795844 -0.2552318 0.5564519 -0.2811813 0.7390231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6561 6598 -0.054686 0.430064 -1.015573 0.2442433 0.5928561 0.3589566 0.6782455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6561 7021 0.844468 0.683192 0.318494 0.0885594 0.9374461 0.3114726 0.1278159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6562 6597 -0.501204 1.080490 0.025201 0.8877632 0.0604251 0.4492300 0.0801109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6563 7023 -0.237207 -1.178840 0.035499 0.3703253 -0.7336187 0.0617510 0.5664359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6564 6595 0.577858 -0.515201 0.489428 -0.1737654 0.2093783 -0.9585791 0.0842167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6564 7024 0.555947 0.812325 0.121512 -0.6401256 0.1459818 -0.7132599 0.2453340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6565 6594 0.430994 0.774065 -0.162582 -0.6292629 0.0305290 0.7680220 0.1150581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6566 6593 -0.400592 -0.350227 -0.838264 0.1169164 -0.5211012 0.5545745 0.6381467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6566 7026 -0.721044 0.419120 0.070133 -0.0585941 -0.2287228 0.6944003 0.6797506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6567 6592 -0.579187 -1.000218 -0.094873 -0.4846845 -0.1293207 -0.0225617 0.8647821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6567 7027 -0.824857 0.570392 0.331196 -0.2056989 -0.3552838 0.4169978 0.8109095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6569 6590 0.948383 0.007033 -0.070019 0.5059590 -0.8015920 -0.2833039 0.1455840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6569 7029 -0.028437 0.934860 0.013658 0.2326163 0.9395885 0.1451601 0.2049186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6571 6588 -0.947238 0.496628 0.276422 0.2631859 0.2786580 0.8576094 0.3429124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6571 7031 -0.122263 -0.284942 1.110723 0.5906734 0.0074344 0.1883543 0.7845842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6572 7032 -0.435274 -0.885752 0.385039 0.1267132 -0.0836387 0.5302308 0.8341484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6573 6586 -0.857539 -0.358818 -0.470554 -0.3102283 -0.1281152 0.9331160 0.1289940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6573 7033 -0.317721 -0.390619 0.854687 0.5175292 0.0638958 -0.5807805 0.6251199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6574 6585 -0.924788 -0.440587 -0.234568 0.4524130 -0.5477093 -0.2095586 0.6718796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6575 7035 -1.049975 0.319933 0.350878 0.3560397 -0.8488201 0.0213584 0.3902357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6576 6583 -0.414645 0.431637 -1.027141 -0.2583080 -0.3272929 0.9086757 0.0215590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6576 7036 -0.823657 0.247556 0.568536 -0.1266803 -0.2047290 -0.1362478 0.9609759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6577 6582 -0.642213 0.310757 -0.335466 -0.1385676 -0.3537677 -0.4581175 0.8036018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6577 7037 -0.562026 -0.785273 0.288136 0.6237244 -0.5003916 0.5339261 0.2747710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6578 6581 0.607615 -0.556514 0.503137 -0.2305967 -0.0511448 -0.5761814 0.7824476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6578 7038 -0.683660 0.194358 0.755269 -0.4999190 -0.6882838 -0.2584185 0.4577840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6579 6540 -0.797431 0.474472 0.183478 0.4698849 -0.4143890 0.6920824 0.3584855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6579 7039 -0.455921 -0.759409 0.612580 0.1828675 -0.1047969 0.9664081 0.1470800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6580 6200 -0.022338 0.968157 -0.341577 0.9504235 0.1870134 -0.2299095 0.0941425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6580 6619 1.154673 -0.252731 -0.005281 0.8103087 -0.0867584 -0.3881229 0.4303876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6580 7000 -0.027863 -0.992559 0.119823 -0.0183375 0.5161329 -0.8555930 0.0350873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6581 7001 -0.051047 -0.752862 0.778335 0.5947786 0.0284671 0.2254961 0.7710898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6582 6617 -0.874597 -0.300407 0.303198 0.9278071 -0.0275899 -0.2294073 0.2928909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6582 7002 0.449455 -0.908135 0.043143 0.1041928 -0.1758968 0.5913940 0.7800367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6583 7003 0.558266 -0.501600 0.613838 -0.5869451 0.2383439 -0.7439464 0.2126767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6584 6575 -0.862111 0.327987 -0.434003 0.0735058 0.1471614 -0.4426871 0.8814582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6584 6615 0.758585 -0.140315 0.509495 -0.3712709 -0.3966323 -0.3354227 0.7696313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6585 6614 0.010134 -0.127269 0.864318 -0.2907440 0.9396623 0.1333147 0.1213669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6586 6613 1.095950 0.685160 -0.002529 -0.2715537 -0.1644851 0.9466682 0.0549771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6586 7006 -0.351374 0.214473 1.052764 0.0761241 0.0607640 -0.4462727 0.8895805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6587 6612 0.571359 0.370357 -0.768728 -0.7184245 -0.2463009 0.6482461 0.0545815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6587 7007 -0.568357 0.662576 0.091040 -0.1298956 -0.1196971 -0.8887806 0.4229288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6588 6611 1.021444 0.188391 -0.132210 0.2811583 0.2639390 0.7922027 0.4729704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6588 7008 0.239483 1.019869 0.474532 0.1916357 0.0224348 -0.9582767 0.2108983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6589 6570 0.224461 1.120077 0.158324 0.2060468 -0.5279478 0.4282094 0.7038839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6589 7009 0.806990 -0.347418 0.859144 0.0788102 0.0295158 0.3882554 0.9177012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6590 6210 0.926493 -0.488456 -0.135317 0.0198284 -0.5080552 -0.8556556 0.0966444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6590 6609 -0.497986 -0.655615 -0.440553 0.9344988 0.0380948 -0.2997980 0.1881011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6591 6568 0.374475 -0.222997 -0.941078 0.3811483 -0.5269416 0.7596274 0.0049713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6591 6608 -0.334301 0.252362 1.043309 0.2662640 0.6022027 -0.1146807 0.7438439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6592 6607 -0.432745 -0.501593 -0.691645 0.0570728 -0.5470769 0.2170481 0.8064364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6592 7012 -0.828474 -0.388354 0.706726 -0.0635909 -0.0290076 0.1224164 0.9900146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6593 6213 -0.604640 -0.595158 -0.302792 -0.0389186 0.4017234 -0.1363683 0.9047140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6593 7013 0.617768 0.538806 0.385754 0.1099437 -0.7947777 -0.5754213 0.1585281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6594 6605 0.293669 -0.758291 -0.438330 -0.2445513 -0.1126406 -0.6121440 0.7434961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6594 7014 0.066146 -0.320127 1.091792 -0.1485016 0.0025130 -0.9522657 0.2667039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6595 6215 0.660474 0.569111 -0.009619 0.6067643 -0.7728423 0.0050504 0.1858126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6595 7015 -0.482993 -0.627412 0.260242 -0.6408331 -0.6990227 0.0739477 0.3085966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6596 6216 0.792193 0.561526 -0.193951 0.5676779 0.0519074 -0.1630616 0.8052691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6596 6563 -0.151996 0.634371 0.768268 0.2949931 0.8169169 -0.3906871 0.3049417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6596 7016 -0.835358 -0.691051 0.394431 0.4119199 -0.0146603 -0.8939684 0.1758625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6597 6217 -0.581240 0.394528 -0.356619 -0.1294760 0.6575148 -0.1052969 0.7347263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6597 6602 -0.309843 -0.810818 -0.329913 -0.2450517 0.7752519 0.0327786 0.5812571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6597 7017 0.704316 -0.555453 0.629265 -0.0465298 0.3087140 -0.1447533 0.9389234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6598 7018 0.011921 0.654555 1.055077 -0.5025867 -0.1907657 -0.6577475 0.5276205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6600 6639 0.296440 -0.738673 -0.456129 0.0083815 -0.1278252 -0.9807528 0.1473583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6600 6980 -0.588400 -0.555072 0.428363 -0.0554443 -0.7200198 0.5473843 0.4229276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6601 6638 -0.132565 0.100684 1.009389 -0.1209921 -0.9020452 0.4010467 0.1041006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6601 6981 -0.024285 -0.978773 0.082185 0.3995540 -0.4791385 0.5557594 0.5494674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6602 6637 0.716617 -0.325965 -0.223613 -0.1135854 0.9158773 -0.3646632 0.1236440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6602 6982 -0.294481 -1.042525 0.255722 0.5868175 -0.1956813 -0.6241749 0.4772419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6603 6636 -0.936665 -0.218605 -0.073857 0.2429576 -0.4797248 0.4189807 0.7316358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6603 6983 -0.064188 -0.591439 0.848161 0.4554217 0.5053482 -0.4025257 0.6125254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6604 6595 -0.685065 0.550038 -0.561627 -0.2454658 0.1967393 -0.9442104 0.0975036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6604 6635 0.461928 -0.670542 0.671475 0.3767010 0.4453621 0.7360681 0.3434425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6604 6984 0.599851 0.714277 0.241508 -0.1258511 0.5699610 -0.0027283 0.8119720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6605 6185 -0.611559 0.209006 -0.654214 -0.2276195 0.4219865 0.4762845 0.7370683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6605 6985 0.725146 -0.300407 0.538982 0.4395389 0.4466813 -0.0974315 0.7731678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6606 6593 -0.443115 0.910143 -0.559197 0.0408990 0.2808502 0.9249707 0.2527442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6606 6633 0.544683 -0.829153 0.541491 -0.2253863 -0.5731225 -0.3359650 0.7126424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6606 6986 -0.816217 -0.033301 0.383089 0.1585422 -0.2310362 0.6157313 0.7364521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6607 6632 -0.978431 -0.191610 0.172947 -0.0499227 0.3482103 -0.5087382 0.7857753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6607 6987 0.356303 0.012927 0.953150 0.1297508 -0.0716178 0.9541911 0.2599132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6608 6631 -0.709973 0.311407 -0.371914 0.4519723 -0.2899979 -0.6122427 0.5803285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6608 6988 -0.615421 -0.273471 0.580356 -0.5910440 0.1791236 0.7230779 0.3094191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6609 6630 -0.299808 0.419136 0.757719 0.0001294 -0.6937079 0.7197088 0.0280825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6609 6989 -0.758970 -0.591096 0.249047 -0.0523066 -0.5501691 0.1015651 0.8272016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6610 6629 0.252069 -0.412925 0.888178 0.0824262 0.7604975 0.6440412 0.0077700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6611 6628 -0.197806 -0.883757 0.264880 -0.2644556 -0.1221266 -0.6573851 0.6949771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6611 6991 0.785798 -0.115730 0.676217 0.4238135 0.4567116 0.7775999 0.0844690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6612 6627 1.137827 -0.086474 -0.381034 0.0186505 -0.0551734 -0.0811463 0.9949992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6613 6626 -0.591313 -0.545021 -0.550162 0.4220131 -0.4775957 0.0475689 0.7691193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6613 6993 -0.116310 -0.643489 0.970578 0.5923033 -0.0171477 0.6202357 0.5139945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6614 6194 0.849371 -0.550341 0.020932 0.5548238 0.4784234 -0.6794359 0.0406015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6614 6625 -0.141195 0.068282 -0.963825 -0.4312346 -0.7683886 -0.4260174 0.2052437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6614 6994 -0.849921 0.590235 0.122017 0.2822815 -0.7046193 -0.1223284 0.6394251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6615 6624 0.782481 0.443459 -0.270709 -0.1990761 -0.2031888 0.9515761 0.1165591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6616 6583 0.671985 0.559857 0.575223 -0.3505577 0.5526406 -0.5354912 0.5338041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6616 6623 -0.662037 -0.607509 -0.620114 0.3393062 0.7180419 -0.0788397 0.6025541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6616 6996 0.224638 -0.911426 0.384897 0.1150010 0.4372827 -0.5018814 0.7373423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6617 6197 -0.418397 -0.654220 -0.132954 -0.6273148 0.6423166 -0.2543800 0.3594388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6617 6622 -0.696256 0.426306 0.307314 0.1890302 0.6820898 0.5589335 0.4319889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6617 6997 0.534253 1.029940 0.041326 -0.8027601 -0.3717069 -0.3063901 0.3514758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6618 6621 0.697930 0.749117 0.195844 -0.7983698 -0.5518814 -0.1208331 0.2084031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6618 6998 -0.764684 0.581921 0.217711 0.3180862 -0.7156116 -0.5168739 0.3457783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6619 6999 0.476734 0.869831 0.639994 -0.1463140 -0.0867082 -0.8134216 0.5562546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6620 6659 -0.273378 0.995904 0.228371 -0.4892647 0.3741836 -0.7868771 0.0378307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6620 6960 0.494471 0.093070 0.849235 -0.1752413 0.5240201 0.7891860 0.2681024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6621 6658 1.167001 0.379072 0.156650 0.8505435 0.2660886 0.0589298 0.4497777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6622 6962 0.185949 0.283401 0.967711 0.2676151 -0.3752396 0.6475272 0.6068657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6624 6655 -0.730938 -0.207416 -0.587877 -0.4233903 -0.8183590 0.3524908 0.1636444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6624 6964 -0.477735 -0.704445 0.475159 0.2462989 -0.4699511 -0.3685781 0.7633040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6625 6654 -0.602513 -0.457849 0.602142 0.7865444 -0.3886767 0.3910579 0.2781224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6626 6653 -0.487886 -0.506116 0.797464 -0.7618746 -0.2098234 -0.4902910 0.3676084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6627 6652 0.747558 0.079368 -0.564898 0.5071713 0.5201339 0.2618852 0.6353378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6628 6968 0.524214 0.616332 0.719999 -0.4652547 0.6389656 -0.2394755 0.5638373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6629 6650 -0.094919 0.872705 -0.380416 -0.2212584 -0.3886741 -0.3071339 0.8400273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6629 6969 0.153652 0.348473 0.672021 0.0051148 0.1597089 0.8802844 0.4467284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6630 6649 0.074788 -0.779512 -0.315227 -0.6933611 0.0933108 -0.6018455 0.3851305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6631 6648 -0.527990 -0.739801 0.501388 0.0918542 -0.0559931 -0.7084617 0.6975024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6631 6971 0.315339 0.659120 0.959343 -0.6919091 -0.2441891 -0.4738922 0.4868877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6632 6647 -0.421146 -0.911955 -0.372437 0.4134161 -0.0962331 0.5692077 0.7041512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6632 6972 -0.493429 -0.207058 0.840221 0.4744397 -0.3717219 -0.2774265 0.7481740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6633 6646 0.779956 -0.215838 -0.684388 -0.4591286 0.6914799 -0.5560258 0.0434947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6634 6605 -0.791343 -0.149870 -0.212641 0.1034357 -0.3946028 -0.1245316 0.9044786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6634 6645 1.112880 0.288885 0.107344 0.3212337 -0.3650505 -0.8664231 0.1133931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6634 6974 0.192346 -0.572913 0.729585 0.5780986 0.4064849 0.2187271 0.6728525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6635 6644 -0.430774 0.770263 0.516075 0.2092928 -0.1091822 0.5539698 0.7983691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6635 6975 0.368979 -0.358943 0.913367 -0.4448445 0.0235805 -0.5292414 0.7221224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6636 6976 0.768140 -0.541712 0.615820 -0.4180510 0.3121111 -0.5049130 0.6876648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6637 6642 -0.471218 -0.296778 0.784838 0.1922461 0.6372177 -0.2620700 0.6987950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6637 6977 0.561202 -0.738102 0.332961 0.5979686 -0.5324537 0.2857389 0.5265738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6638 6978 -0.305613 -0.698759 0.597709 0.2259656 -0.5525673 -0.0456055 0.8009551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6639 6979 0.913588 0.551600 0.186925 -0.6170232 0.6035699 -0.4846494 0.1417771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6640 6679 -0.706942 -0.638059 -0.098292 0.1954235 0.0367332 0.7471860 0.6341715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6640 6940 0.372063 -0.783398 0.624073 0.3114805 -0.3055201 0.8018421 0.4082728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6641 6638 -0.927898 -0.101538 -0.504639 0.0953014 -0.6507673 0.3260613 0.6790461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6641 6678 0.758081 -0.080687 0.272689 0.8429873 0.4373168 -0.3009591 0.0868905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6641 6941 -0.047447 -1.089636 -0.086764 -0.2192018 -0.5782102 0.7088521 0.3393410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6642 6942 -0.203226 -0.081618 1.011218 -0.5691767 0.2727036 0.0964650 0.7696526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6643 6636 -0.681491 -0.200177 -0.822033 -0.0811921 -0.1810624 -0.9013084 0.3850550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6643 6676 0.513778 0.171894 0.718948 -0.0486423 0.3896486 0.4064562 0.8249856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6643 6943 -0.871106 0.075386 0.475997 -0.3407553 -0.2277095 0.8918725 0.1913050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6644 6675 0.620534 0.841793 0.101199 0.4935648 0.4553340 -0.1623830 0.7229775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6645 6145 0.159082 -0.948744 -0.303064 -0.1256675 -0.3602988 -0.6300723 0.6763146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6645 6674 -0.798251 -0.089740 -0.391302 -0.0868295 -0.4473953 0.4210900 0.7842074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6645 6945 -0.190350 0.945470 0.142686 0.0125112 0.4259213 0.8137458 0.3952877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6646 6673 -0.708152 0.218344 0.984559 -0.5420137 -0.2623512 -0.7983598 0.0038127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6647 6672 -0.851663 0.004484 0.427393 -0.3856805 -0.6183160 -0.6154293 0.3003042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6647 6947 0.054531 0.672393 0.549358 0.0779192 0.1455216 -0.9413428 0.2943226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6649 6670 0.324541 0.967554 -0.198081 0.6601536 0.3822210 -0.0959774 0.6394472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6649 6949 0.576095 0.013536 0.690591 -0.0134074 -0.4338150 0.7699716 0.4677270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6650 6669 -0.655449 0.749427 0.102072 -0.0631990 -0.3726599 -0.8390754 0.3912583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6650 6950 0.732249 0.432183 0.473634 0.7144252 -0.2611111 0.6066076 0.2311815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6651 6628 -0.783842 -0.547291 0.001975 -0.1659383 -0.1601616 0.5891550 0.7744089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6651 6668 0.672723 0.607806 0.119730 -0.2673560 0.1359772 0.8587071 0.4155154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6652 6667 0.627739 -0.265928 1.029383 0.3742836 -0.3661557 0.1885017 0.8308483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6652 6952 -0.769364 0.275233 0.504477 -0.4000325 -0.5516486 -0.4594295 0.5697213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6653 6153 -0.777431 -0.265784 -0.189135 -0.6922896 0.5964983 -0.1092752 0.3911315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6653 6666 0.534580 -0.161875 -0.809126 0.6008853 0.4659057 -0.0880627 0.6435167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6654 6665 0.335460 0.805388 -0.063735 -0.2877921 0.8392448 -0.0830230 0.4538184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6655 6155 0.323307 1.027697 -0.115719 0.3866551 0.7103076 0.0332319 0.5872450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6655 6664 0.213126 -0.098283 1.012072 0.4273815 0.1313944 -0.7401081 0.5023152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6655 6955 -0.248718 -0.904996 -0.133000 -0.1348401 -0.8010022 -0.0051340 0.5832557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6656 6663 -0.562554 -0.031795 0.948915 0.3754022 -0.1440105 0.2959747 0.8664486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6656 6956 0.977496 -0.402269 0.383766 -0.0928058 -0.3187086 0.9040643 0.2692205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6657 6662 0.535669 -0.903521 0.459666 0.0458783 0.4385621 0.1186369 0.8896537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6657 6957 0.404407 0.441262 0.888437 -0.1528014 0.4729791 0.6003321 0.6265332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6658 6661 0.832595 0.562666 -0.084489 -0.0809465 -0.1259541 0.4846100 0.8618215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6658 6958 -0.325511 0.711865 0.546838 -0.4975000 -0.5955367 0.2251025 0.5892017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6660 6120 0.312735 0.842028 -0.273091 0.1367005 -0.5554450 -0.4506108 0.6853786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6660 6699 -0.875262 0.315233 -0.434233 0.1573039 -0.1284197 0.9095603 0.3625795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6660 6920 -0.216351 -0.915179 0.099027 -0.0437253 0.0035560 -0.9877463 0.1497754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6661 6121 -0.474845 -0.270944 -0.615023 0.3945770 0.4471845 0.0214269 0.8024188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6661 6698 0.808527 -0.520391 -0.355637 -0.4767907 0.3408577 0.1411360 0.7978517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6661 6921 0.670406 0.370886 0.638344 0.6840521 -0.1259221 0.6791540 0.2344489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6662 6697 0.049811 -0.728068 0.580971 -0.0624339 -0.8102161 -0.1945293 0.5493725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6662 6922 -0.235602 0.527929 0.835702 0.0577039 0.3046920 -0.6540489 0.6899660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6663 6123 -0.915512 0.602506 -0.613658 0.8981773 0.2853563 0.2789617 0.1844711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6663 6696 -0.142496 0.689021 0.483738 0.1257478 -0.1723106 -0.6369260 0.7408251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6664 6695 -0.785237 0.412697 0.617296 -0.6365398 -0.0665852 -0.3276696 0.6949936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6664 6924 0.737215 0.258832 0.761091 0.5464471 -0.1727101 0.6535962 0.4943469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6665 6694 -0.600881 0.551568 0.623417 0.5364409 -0.3904504 -0.7103480 0.2349156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6665 6925 -0.494595 -0.874702 0.293532 0.2393570 -0.0326574 0.5748951 0.7817527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6666 6693 0.766268 -0.155671 0.699061 -0.7013401 0.5477988 0.4481449 0.0848808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6666 6926 0.023816 0.781683 -0.008510 -0.6130731 -0.0211715 0.3562193 0.7048410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6667 6692 0.881437 -0.254539 0.245529 0.2345240 -0.4831193 -0.8009166 0.2648146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6667 6927 -0.110692 0.855219 0.583910 -0.2287616 -0.8457592 -0.4766161 0.0720877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6668 6691 -0.200362 -0.910710 0.091531 0.1916794 -0.5568168 -0.7584393 0.2792558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6668 6928 0.581325 0.083819 0.917382 0.0308531 0.6871638 0.2443551 0.6834798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6669 6929 -0.360652 0.571791 0.684714 -0.4934436 0.1771154 -0.3074247 0.7941244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6670 6689 0.602236 0.176776 -0.747333 -0.6731186 0.6340217 0.1138432 0.3632734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6671 6648 -0.129034 0.951604 0.520895 0.3341793 0.5183754 -0.4597486 0.6389384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6671 6688 -0.143849 -0.846082 -0.505212 -0.1715280 0.3405492 -0.6528434 0.6545227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6672 6687 0.724302 -0.670418 -0.244752 -0.1738775 -0.0553159 0.3247629 0.9280279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6672 6932 0.527195 0.315235 0.814548 -0.5202573 0.1934697 -0.6799446 0.4791421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6673 6686 0.978267 -0.082307 -0.068553 -0.5715993 0.2540897 0.1171451 0.7713558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6673 6933 0.107791 1.172559 0.303004 -0.2686941 0.7104718 0.5873589 0.2793614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6674 6685 -0.612450 0.664182 0.343758 -0.2910202 -0.1970880 -0.1572822 0.9228900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6674 6934 0.776792 0.894273 0.270986 -0.6012303 -0.7850149 -0.1245986 0.0821518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6676 6683 0.042190 -0.277207 1.046227 -0.5866509 0.6482664 0.2125643 0.4363573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6676 6936 -0.658027 0.658556 0.244588 0.0126702 -0.6679319 -0.0520616 0.7422911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6677 6642 -0.886581 0.614289 -0.012165 -0.2002666 0.0770314 0.7941564 0.5685729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6677 6682 0.740862 -0.541645 0.068254 -0.2100413 0.5701799 -0.5005857 0.6165967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6677 6937 0.066593 0.341693 0.951671 -0.3754347 -0.1063213 -0.4580615 0.7987016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6678 6938 -1.015296 0.466991 0.373303 -0.5680591 0.0606516 0.7296561 0.3758089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6679 6939 -0.517898 -0.031503 0.987104 -0.0240864 -0.3847705 0.8972519 0.2151987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6680 6100 0.688947 -0.686377 -0.565474 -0.0149448 0.1260399 0.7403817 0.6600951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6680 6719 -0.558787 -0.028574 -0.723689 -0.6193551 -0.1515347 0.7282102 0.2512896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6681 6678 -0.015554 -0.634073 0.620608 -0.0049176 0.4133119 -0.3387379 0.8452252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6681 6901 -0.043914 0.720839 0.750983 -0.8278067 -0.3211867 -0.2636669 0.3769019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6682 6717 0.318454 -0.115821 0.957494 0.3519136 0.0610788 0.4854090 0.7980002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6682 6902 -0.749344 -0.536390 0.211503 -0.4382373 -0.7185240 0.5244805 0.1288084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6683 6716 -0.653863 -0.344805 -0.815858 -0.6714024 0.2598980 0.5967010 0.3544288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6683 6903 -0.661208 0.530674 0.430440 -0.1040401 -0.1853687 -0.8401964 0.4988829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6684 6675 -0.846703 0.465939 -0.039143 0.8974392 0.1859686 -0.3800079 0.1249498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6684 6715 0.813039 -0.607661 0.104286 0.2251738 -0.1857696 0.9508824 0.1030005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6684 6904 -0.413679 -0.698842 0.436354 -0.4367284 0.0954583 0.8944922 0.0063049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6685 6714 -0.562762 0.137469 0.923262 0.0075778 0.9119202 0.0568500 0.4063401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6685 6905 0.661787 0.744116 0.375205 -0.7156395 -0.6367483 -0.2862129 0.0222215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6686 6906 -0.184183 0.199666 1.020828 -0.0171449 -0.0232720 -0.9550082 0.2951674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6687 6712 0.563474 -0.781950 -0.529338 -0.4758152 0.2832746 -0.8326507 0.0069442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6687 6907 0.557344 -0.185811 0.811125 0.2790384 0.5643477 -0.6613461 0.4077629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6688 6908 0.075747 -0.314301 1.049600 0.5352095 0.1543109 -0.5885022 0.5860069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6689 6710 0.625538 -0.332992 0.682850 0.3465162 0.0516066 -0.8139622 0.4633885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6689 6909 -0.836187 0.045433 0.649054 -0.2359589 -0.5267437 -0.3642972 0.7308570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6690 6669 -0.980994 0.509829 0.094644 0.1167632 0.5664273 0.2637712 0.7719788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6690 6709 0.938406 -0.348776 0.045393 0.0554734 0.7994373 0.3033985 0.5155308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6690 6910 0.576287 0.442132 0.689608 -0.0904666 0.4781428 -0.7871940 0.3788414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6691 6708 0.573977 0.276023 -0.821023 -0.3776367 -0.3184353 0.3210049 0.8080504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6692 6707 -0.660487 0.635715 -0.502038 -0.7660610 -0.3177762 0.5484701 0.1065337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6692 6912 -0.488632 0.019843 0.669768 0.3097087 0.3426807 0.2791038 0.8418738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6693 6706 -0.196614 0.067202 -1.006205 -0.2030236 -0.9058285 -0.1365992 0.3458277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6693 6913 -0.810439 -0.493318 0.398414 0.3218555 -0.4361628 -0.7158151 0.4402043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6694 6705 -0.611288 -0.067116 0.675649 -0.4772749 0.2081835 -0.7103530 0.4735682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6694 6914 0.697152 0.735672 0.168045 -0.8261621 0.2328298 -0.2246307 0.4612891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6695 6704 -0.631411 -0.958491 0.384831 0.1848002 -0.1707194 0.9425330 0.2198529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6695 6915 0.828430 -0.106513 0.346822 0.4286325 0.4794376 -0.6257430 0.4414289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6696 6916 0.578646 0.734116 0.206166 0.4036578 0.4392434 0.6973766 0.3972298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6697 6917 0.701534 0.605627 0.093387 -0.1977754 0.1532680 -0.5873615 0.7696754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6698 6701 0.955854 -0.251040 -0.224573 -0.2112093 -0.1564058 0.1797913 0.9479467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6699 6919 -0.182060 0.964741 0.376722 -0.4678398 0.3696701 0.7637047 0.2474371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6700 6880 -0.556816 0.357014 0.846191 0.2144660 -0.0597975 -0.8534324 0.4712555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6701 6738 0.609545 -0.416846 -0.584358 0.4016549 -0.1381381 -0.7443067 0.5153627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6701 6881 -0.154124 -0.924100 0.404670 0.2157868 0.0394891 -0.5905291 0.7766287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6702 6697 -0.081625 -0.391610 -0.924772 0.8595761 -0.2773386 0.4280291 0.0316758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6702 6737 0.379402 0.276578 1.000925 0.0972676 0.1319178 -0.4142651 0.8952771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6703 6696 -0.290461 0.380165 1.004572 -0.6390800 -0.7200119 -0.1646941 0.2145587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6703 6736 0.394538 -0.383766 -1.005360 -0.6557467 -0.7238402 -0.2113872 0.0369735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6704 6735 0.039316 0.871766 0.334051 0.2298475 -0.0609923 0.5965940 0.7665022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6704 6884 -0.417897 -0.285038 0.717171 0.5132701 -0.1114943 0.8326247 0.1756671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6705 6734 0.515843 -0.943125 -0.328969 -0.1926031 0.4454333 -0.5651754 0.6671356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6705 6885 -0.471582 -0.289686 0.673737 -0.1814784 -0.0870639 0.4191662 0.8853164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6706 6733 -0.513371 -0.282757 0.940861 0.5331497 -0.5719145 0.5498872 0.2937504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6706 6886 0.479315 -0.785691 0.196463 -0.3707985 0.1928771 -0.6266393 0.6577462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6707 6732 0.542339 -0.354010 0.762919 0.5020401 0.4256814 -0.1710106 0.7331483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6708 6731 0.281255 0.716288 -0.727444 0.3937663 0.2763292 0.8137534 0.3261836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6708 6888 0.452696 0.523992 0.634677 -0.1527346 -0.2393380 0.9512688 0.1203211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6709 6730 -0.583877 -0.595426 0.393495 -0.4080064 -0.5224783 -0.6554782 0.3617948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6709 6889 -0.693084 0.695350 0.109512 0.4147207 -0.4100567 -0.7617529 0.2821220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6710 6090 0.018319 0.631595 -0.936558 0.2713317 0.6409796 -0.3011698 0.6517829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6710 6729 -0.096018 0.639377 0.697809 0.6140885 0.4000214 -0.4132965 0.5404296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6711 6688 0.526593 -0.821639 -0.068901 0.0967118 0.3165597 0.7284045 0.5998864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6711 6728 -0.602884 0.803782 -0.022955 0.1130146 0.6758113 0.7256963 0.0622222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6711 6891 0.739628 0.589481 0.678975 -0.8487456 0.0900493 0.1481136 0.4995842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6712 6727 -0.141613 0.758119 0.347694 -0.3003617 -0.4850166 0.6658755 0.4807823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6712 6892 0.353237 -0.231609 1.045500 -0.0111819 0.7086440 -0.4729023 0.5235094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6713 6093 0.122687 -0.701145 -0.723477 0.0464998 -0.5837428 0.1169924 0.8021190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6713 6686 -0.541712 -0.614088 0.671381 -0.2766220 0.2962163 0.5428310 0.7355751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6713 6726 0.586692 0.643353 -0.305739 -0.5746146 -0.0214438 -0.2803022 0.7686279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6713 6893 -0.176282 0.641705 0.838450 -0.5951181 0.1264183 0.7923743 0.0446750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6714 6725 -0.498779 0.376638 -0.735063 -0.3966750 0.4204672 0.2907403 0.7624476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6714 6894 -0.530271 0.752439 0.276160 -0.3891256 -0.2741874 0.6505203 0.5917989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6715 6724 -0.697514 0.199459 0.560901 0.2817096 -0.4473804 -0.6910009 0.4929587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6716 6096 0.488902 0.037696 -0.887456 0.4033677 0.0193893 0.2203251 0.8879051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6716 6723 0.412723 0.842247 0.444578 0.0885658 -0.3115553 -0.2224916 0.9195580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6716 6896 -0.385230 -0.071233 0.892642 0.5375675 -0.3867973 0.4702965 0.5832926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6717 6722 0.615534 0.304882 0.869307 0.2418716 0.1371628 -0.9340584 0.2240967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6718 6721 -0.753092 -0.428069 -0.210162 -0.1972401 0.3830272 -0.8360807 0.3396404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6718 6898 0.220562 -0.861903 0.595494 0.7562423 -0.3650605 0.2878382 0.4604103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6719 6099 -0.009622 0.666324 -0.722548 -0.4646154 -0.0997605 0.8599784 0.1860579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6719 6899 -0.254469 -0.518389 0.853839 0.1716839 0.3355313 0.1932163 0.9058757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6720 6759 0.699607 -0.588727 0.518826 -0.7408245 -0.3238693 0.1957157 0.5549622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6721 6758 0.919496 0.221122 -0.426927 0.5439351 0.5851372 0.3994036 0.4496952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6721 6861 0.428824 -0.149606 0.956588 -0.5250160 -0.2092999 -0.2030672 0.7995721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6722 6757 -0.867312 -0.043098 0.253703 -0.2363488 0.5706740 -0.5495757 0.5625274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6722 6862 0.201915 -0.644325 0.542107 0.2644046 -0.2334714 0.0978818 0.9305915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6723 6063 -0.127001 -0.308617 -0.761058 -0.3649236 0.6429086 0.6523567 0.1671224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6723 6756 0.124819 0.996382 -0.387549 0.3524305 -0.4335950 -0.4229877 0.7133509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6723 6863 0.238891 0.206800 1.261422 -0.2235729 0.5088452 0.2021397 0.8063692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6724 6064 0.701584 -0.431955 -0.031788 -0.5688739 -0.5592004 0.4670624 0.3814841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6724 6755 0.346729 0.244256 0.925169 -0.3835725 0.1173904 0.3243309 0.8566803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6725 6865 -0.293868 0.581085 0.716086 -0.2173452 0.2230983 0.2563763 0.9150188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6726 6753 -0.111239 0.914010 0.841137 -0.2311757 -0.1824570 -0.3322091 0.8960493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6726 6866 -0.238245 -0.626152 0.613785 0.2398341 0.8120350 -0.3335158 0.4145431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6727 6867 -0.457875 -0.742988 0.028007 0.7921453 -0.2009486 -0.4673898 0.3371533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6728 6751 0.706387 -0.230988 0.803389 -0.4804030 0.4829671 0.6417387 0.3523169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6728 6868 -0.369153 0.451922 0.718246 0.0144289 -0.8194899 -0.4300310 0.3785518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6729 6750 -0.596584 0.020725 -0.861499 0.0705442 0.1337122 -0.6826140 0.7149704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6730 6749 0.893511 -0.280179 -0.642404 0.1004359 0.5034298 0.0195785 0.8579556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6730 6870 0.417562 -0.591312 0.562656 0.1175421 0.5065942 -0.8419517 0.1437481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6731 6748 -0.102332 -1.135524 0.398712 -0.1140136 0.4544720 -0.8613420 0.1963315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6731 6871 0.338323 0.145820 0.816201 0.2546097 0.6622157 0.5709785 0.4130712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6732 6747 -0.412662 0.495371 0.848837 0.7183686 0.0874306 -0.5430920 0.4258563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6733 6746 0.838997 0.262160 0.136412 0.0267279 0.5988255 -0.3707978 0.7093677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6733 6873 0.276268 -0.429838 0.899523 0.0024867 0.0135094 0.9287537 0.3704428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6734 6874 0.059327 -0.935086 0.224101 0.1449574 -0.1112719 0.3623807 0.9139399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6735 6744 1.004600 -0.043810 0.161425 0.1924894 0.2469972 0.0307298 0.9492080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6735 6875 -0.226800 0.583068 0.834432 0.3256346 0.0465464 -0.9205294 0.2107632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6736 6743 -0.349987 -0.057085 0.668136 0.0450397 0.3876933 -0.5578597 0.7324329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6736 6876 0.340028 0.601337 0.249280 0.3880439 -0.1305648 0.8279511 0.3832385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6737 6877 0.505538 -0.442816 0.727191 0.3422739 0.3393768 -0.7126797 0.5096662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6738 6741 0.632070 0.365886 -0.878596 -0.1893612 0.2376892 0.6683477 0.6789385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6738 6878 0.492459 0.647859 0.516645 -0.6067386 -0.0685975 -0.7612694 0.2182465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6739 6700 -0.002587 -0.838393 0.834246 -0.2384868 -0.1709952 -0.8740112 0.3872842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6739 6879 0.969807 0.559493 0.382000 -0.6104337 0.5739900 0.2424808 0.4889880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6740 6779 -0.653135 0.799890 0.341328 -0.1826881 -0.0689518 -0.7220039 0.6637628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6740 6840 0.686949 -0.062583 0.716901 0.3982982 -0.0975619 -0.8310319 0.3758008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6741 6841 0.043133 -0.458049 0.887686 0.4663263 -0.0423147 -0.8803254 0.0760027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6742 6737 0.847922 0.672892 0.261015 -0.0302232 -0.5090629 0.6235896 0.5925180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6742 6777 -0.802777 -0.772646 -0.230936 0.1987551 -0.5447712 -0.4824184 0.6565007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6742 6842 -0.284004 -0.084992 0.969264 0.0331006 -0.2459460 -0.9468804 0.2045300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6743 6843 -0.783793 0.552883 0.286491 -0.8457726 0.0374023 0.1403117 0.5134028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6744 6775 0.761335 0.144694 0.559070 -0.2699105 -0.8837888 -0.3766049 0.0650720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6744 6844 -0.491679 0.865295 0.334235 -0.7798529 -0.3095447 0.3604136 0.4075703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6745 6734 -0.348498 -0.942861 0.236848 -0.7320392 -0.4018580 0.1865295 0.5175282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6745 6774 0.210147 0.917332 -0.342485 0.1418103 -0.3224075 -0.0111537 0.9358519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6745 6845 -0.454887 0.256654 0.719329 -0.6949210 -0.5322636 0.3639938 0.3182590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6746 6773 -0.122760 0.814784 0.605627 -0.0459259 -0.3435141 -0.5527735 0.7578459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6746 6846 -0.471299 -0.529848 0.684324 0.4379502 -0.1206728 0.8668791 0.2053252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6747 6772 -0.946481 -0.361656 -0.078306 -0.2123797 -0.6870190 0.6020036 0.3471188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6747 6847 -0.014426 -0.033289 1.121926 0.4305651 -0.5855152 -0.6689871 0.1556983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6748 6771 0.535289 0.533815 0.655670 0.6708021 -0.0497820 -0.2556971 0.6943812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6748 6848 -0.565208 -0.442127 0.608232 -0.0041378 -0.5661965 0.1822446 0.8038603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6749 6770 0.994194 -0.348190 0.432946 -0.1985746 -0.2302509 0.9498348 0.0732560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6750 6769 0.321648 -0.567058 -0.652191 -0.3027168 0.1201150 -0.9423232 0.0772139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6750 6850 -0.602788 -0.805148 0.482071 0.1769223 0.0230084 -0.3963057 0.9006170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6751 6051 0.632070 -0.303288 -0.804441 -0.1762378 0.0981417 0.0796014 0.9762029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6751 6768 -0.838342 -0.381183 -0.356970 -0.3698248 0.3175398 -0.3380317 0.8050669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6752 6727 -0.387420 -0.234033 -0.810912 -0.8218574 -0.0643836 -0.4832584 0.2947313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6752 6767 0.460914 0.305281 1.024293 -0.0546141 -0.8968804 -0.4382027 0.0245218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6753 6853 0.596374 -0.721430 0.462878 -0.1545847 0.8305353 -0.4945118 0.2043837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6754 6054 0.531236 -0.391917 -0.808106 -0.4757650 -0.5276341 0.5693853 0.4135824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6754 6725 0.040338 -0.983118 0.393853 -0.0163243 0.2392102 0.2873524 0.9273298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6754 6854 -0.449859 0.261332 0.897950 0.1495402 0.2960202 0.4094959 0.8498958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6755 6764 -0.226929 -0.562133 0.648744 -0.2209954 -0.7906629 -0.3156624 0.4757841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6756 6856 0.233407 1.082955 0.038670 -0.5389331 0.7747288 0.2300127 0.2375723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6757 6857 0.650212 -0.549493 0.710460 -0.2271323 -0.4655861 0.7157178 0.4683893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6758 6858 -0.078728 0.913491 0.139343 -0.0681752 -0.4025983 -0.5620979 0.7192446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6760 6799 0.516146 0.890742 0.449189 -0.1899609 0.4867320 0.3457474 0.7794008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6760 6820 0.169771 -0.482938 0.687083 0.3752238 -0.6203892 0.6707971 0.1560629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6761 6758 -0.856501 0.228325 -0.515214 0.5510463 -0.1104398 0.8056664 0.1872237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6761 6798 0.842717 -0.348571 0.539945 -0.0490677 -0.5478864 0.6893113 0.4714475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6762 6022 -0.779563 -0.524402 -0.422466 -0.4548996 0.6615471 -0.4993910 0.3256230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6762 6757 0.665472 -0.610874 -0.469610 -0.8057102 0.0210803 -0.5643800 0.1784992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6762 6797 -0.624170 0.325571 0.641295 0.2346270 0.1794227 0.2106805 0.9318645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6762 6822 0.716982 0.486038 0.477820 0.3600628 0.5590852 0.3317951 0.6690968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6763 6756 -0.444063 -0.046596 -1.092243 -0.1946663 0.8716517 0.2081021 0.3987755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6763 6796 0.294983 0.195422 0.966837 -0.2414587 -0.4992115 0.5566679 0.6185519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6763 6823 -0.423811 0.799831 -0.023869 -0.5422208 -0.4882999 -0.1106967 0.6747637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6764 6824 0.595323 0.190008 0.627438 -0.4899297 -0.0739981 -0.6825004 0.5372955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6765 6754 0.518128 0.909766 0.338344 0.3874280 -0.0154766 0.9185063 0.0775002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6765 6794 -0.219429 -0.850330 -0.285179 0.3295514 0.4828179 0.7624526 0.2773965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6765 6825 0.862127 -0.583633 0.166451 0.6961671 -0.0701740 0.6928270 0.1744067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6766 6753 0.737126 -0.476711 -0.640863 -0.3708077 0.0241428 0.6131838 0.6970828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6766 6793 -0.582118 0.465414 0.593557 0.6294037 0.5433590 0.4183088 0.3655540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6766 6826 0.618945 0.508937 0.380678 -0.4354107 0.4548064 -0.7042160 0.3280984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6767 6792 -0.445041 0.923206 -0.301527 -0.8021778 0.0178018 -0.5670397 0.1861718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6767 6827 0.508771 0.336269 0.643069 -0.2039225 0.5270115 0.7703959 0.2952365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6768 6791 0.110179 -0.011153 -0.943706 0.1937788 -0.0507818 0.0856703 0.9759773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6769 6790 -0.722485 0.654808 -0.131845 0.4519893 0.3608437 0.7856012 0.2198369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6769 6829 0.519617 0.632003 0.024933 -0.0932476 0.8765711 0.4716803 0.0211137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6770 6830 0.140117 0.229383 0.934358 0.1430960 0.3829340 0.7062109 0.5780582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6771 6788 0.116076 0.904887 -0.574662 -0.5838862 -0.1823388 0.3935024 0.6862838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6772 6787 0.420715 0.163395 0.762017 0.0288609 -0.7857096 0.2899133 0.5456901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6772 6832 0.231796 -1.092638 0.102242 0.1885021 0.3709486 -0.7210635 0.5540140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6773 6786 -0.529799 0.283749 0.797494 0.9050786 0.2355971 0.3416934 0.0925869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6773 6833 0.729269 -0.089287 0.717098 -0.4595589 0.7019237 -0.3821430 0.3873957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6774 6785 -0.090093 0.697977 -0.430739 -0.6247032 0.3422601 -0.4724961 0.5189907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6774 6834 -0.049922 0.550236 0.870797 0.2055240 -0.4614335 -0.6623571 0.5532830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6775 6784 -0.320366 0.869008 -0.283762 0.0048141 -0.3261342 -0.8804807 0.3440453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6775 6835 0.935678 0.463943 0.491912 -0.6277557 0.2676854 -0.6969589 0.2202626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6776 6783 -1.111472 -0.085615 -0.351036 0.5775987 -0.1435641 0.6710611 0.4420928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6776 6836 -0.368514 -0.104391 1.034134 0.4165362 -0.3015317 0.0821881 0.8537104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6777 6782 0.404940 -0.620652 0.220004 -0.4006120 0.1751517 -0.6878317 0.5794131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6777 6837 0.491987 0.545733 0.576895 0.1756282 0.0888000 -0.4445649 0.8738600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6778 6741 -0.035561 1.000286 0.086802 -0.1606627 0.2471816 -0.3284145 0.8973476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6778 6781 -0.024033 -0.866125 -0.199103 0.1168261 0.2644354 -0.8141156 0.5036281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6779 6839 0.045571 0.565437 0.826381 -0.2816463 -0.4552833 0.1957829 0.8216213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6780 6000 -0.898709 0.697663 -0.280280 0.6260203 0.0923539 0.5510144 0.5440151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6780 6800 0.960565 -0.408829 0.255588 0.6307668 0.0788952 0.5690528 0.5216203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6781 6001 0.513665 0.092087 -0.973269 0.0620110 0.0084278 -0.5964566 0.8002019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6781 6801 -0.461514 -0.128407 0.886075 0.1508097 0.3358720 0.9150494 0.1647150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6782 6802 -0.204090 -0.177862 0.945637 -0.4899918 0.0565053 -0.1428074 0.8580917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6783 6003 -0.885547 -0.456743 0.040658 0.8074514 0.5430240 0.2303703 0.0087519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6784 6804 -0.869663 0.368714 0.495597 -0.4976306 -0.5104805 0.6999637 0.0427111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6785 6805 -0.411744 -1.084776 -0.004986 0.1202598 0.6590190 -0.7054182 0.2315527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6786 6006 -0.891527 -0.707622 0.134396 -0.7456452 0.1074142 -0.5229058 0.3988044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6786 6806 0.687888 0.638218 -0.124280 -0.5892251 0.4760231 0.2710491 0.5939261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6787 6807 -0.339561 -1.016926 0.109930 0.5700174 0.3206192 -0.5772677 0.4889228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6789 6770 0.458046 -0.893167 0.020082 0.1562144 -0.0712104 -0.4473869 0.8777079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6789 6809 -0.001136 -0.268469 0.967525 -0.3698535 -0.5793184 -0.0193206 0.7261028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6790 6010 -0.201093 0.542187 -0.951413 0.0341557 0.1269422 0.9221329 0.3638544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6790 6810 0.092351 -0.700102 0.864395 0.6411488 0.1315272 0.6131341 0.4423747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6791 6811 -0.882378 -0.427938 0.371562 0.0540579 -0.1616362 0.9763082 0.1333187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6792 6812 0.621491 -0.435118 0.563487 0.8230593 -0.2116443 0.3955972 0.3482570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6793 6013 -0.622587 -0.312352 -0.565625 -0.1435080 0.0461957 0.4920544 0.8574111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6793 6813 0.805133 0.432790 0.450128 -0.0004858 0.6105690 0.0196430 0.7917193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6795 6764 -0.976113 0.421441 0.223039 -0.2694270 -0.1059063 0.1040058 0.9515124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6795 6815 0.632294 0.795677 0.438885 -0.2137402 -0.0747008 -0.8500815 0.4754959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6796 6816 0.836922 0.459829 0.418773 0.5943092 0.4109266 0.6501817 0.2349462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6797 6817 0.827887 0.255268 0.431699 -0.3723788 0.3530435 -0.8456899 0.1466386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6798 6018 0.620517 -0.238984 -0.873958 -0.0121179 -0.6652391 0.7015607 0.2551913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6798 6818 -0.244547 0.127784 1.092349 -0.2723944 0.4465717 0.7295524 0.4405999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6800 7580 0.021380 -0.006420 0.881143 0.0878712 0.4041768 -0.4499157 0.7915148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6801 7581 0.539617 0.931417 0.240737 -0.4520040 -0.5759317 -0.4691186 0.4938854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6802 6837 -0.676205 -0.033560 -0.840025 0.7101859 -0.0425832 0.6061816 0.3554808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6802 7582 -0.345834 -1.131609 0.377243 0.3741013 0.1938372 -0.7402928 0.5238721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6803 6783 0.450077 0.700192 -0.074168 0.2250918 -0.2955753 -0.8705200 0.3227443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6803 7583 -0.255720 -0.676256 0.130740 0.4475307 -0.4736344 0.2058252 0.7300841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6804 6835 0.621785 0.057017 -0.800128 0.0855495 0.6599518 -0.2498717 0.7033555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6804 7584 0.280707 -0.980854 0.073468 0.5246166 -0.0411911 -0.4917426 0.6937362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6805 6834 -0.687038 0.586615 0.555717 0.3157273 0.3807200 0.7692315 0.4045385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6805 7585 0.370100 -0.315347 0.854938 0.0919474 0.1032082 -0.9051693 0.4019481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6806 6833 -1.078079 -0.214574 0.010402 -0.0816782 -0.5637455 0.6907526 0.4453993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6806 7586 0.342066 -0.360767 0.819230 -0.0819293 -0.0120946 0.9922406 0.0927353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6807 7587 0.067076 0.016853 0.844304 0.0130272 0.5297824 -0.7404047 0.4134753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6808 6831 -0.476213 -0.491966 0.777065 -0.1778060 0.8454905 0.3631997 0.3487360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6808 7588 0.078324 0.673279 0.339290 -0.0234731 -0.2838272 0.0905261 0.9543040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6809 7589 0.689629 -0.737096 0.044741 0.8971580 -0.2648735 0.2631661 0.2359942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6810 6829 0.454849 0.308898 -0.735767 0.1259439 -0.3566477 -0.8342601 0.4011866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6810 7590 0.330723 0.606785 0.581987 -0.2218699 -0.0368147 -0.9620058 0.1548008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6811 6828 0.105862 -0.995872 0.443767 -0.7288914 0.3187596 -0.0856520 0.5998110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6811 7591 0.782488 0.487914 0.762588 -0.2772283 0.1714026 0.4168032 0.8485521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6812 6827 0.332796 -1.136062 -0.564924 0.0599319 0.4231294 0.8753035 0.2263038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6812 7592 0.971166 -0.073381 0.676861 -0.3060261 -0.4493675 -0.6560513 0.5234630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6813 6826 -0.807292 -0.102863 -0.110276 -0.7623610 0.0963555 0.5488089 0.3291354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6813 7593 -0.288239 0.413963 0.701585 0.4130538 0.0102685 -0.2149907 0.8849068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6814 6794 0.646119 -0.225227 -0.804717 0.5868148 -0.2964703 -0.6906272 0.3013101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6814 6825 -0.864232 -0.423905 -0.287338 0.0261443 -0.4342330 -0.7519253 0.4953448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6815 6824 0.057421 -0.990979 0.018280 0.1165931 -0.4943925 0.0074194 0.8613519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6815 7595 -0.711464 -0.096779 0.764593 0.2478575 -0.1252773 0.8103912 0.5158860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6816 7596 0.354574 -0.014203 0.897569 0.2268874 0.4688438 -0.1234160 0.8446751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6817 6822 0.195264 0.671070 0.793537 -0.0040853 -0.0792880 0.9855309 0.1497519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6817 7597 -0.728952 -0.496546 0.533334 0.2502033 -0.0134093 -0.2214461 0.9424331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6818 7598 -0.372211 0.567916 0.779027 -0.0293587 -0.7133397 -0.3097205 0.6279791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6819 6799 -0.814055 0.151306 -0.538443 -0.0800665 -0.7007441 0.7074982 0.0446470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6819 7599 0.831971 -0.258122 0.502829 -0.3995937 0.6783446 -0.4069048 0.4632514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6820 6859 -0.202145 0.680121 0.778845 -0.4609390 0.2535142 -0.8361430 0.1553404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6820 7560 0.253850 -0.639800 0.738314 -0.0126302 0.6783096 -0.4448172 0.5847001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6821 6761 -0.356034 -0.681693 -0.383674 -0.0959085 0.2976254 -0.9470124 0.0734038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6821 6818 -0.720019 -0.108167 0.682795 -0.1077975 0.8081822 0.4147962 0.4039373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6821 7561 0.160700 0.840974 0.511700 -0.0248906 0.7470906 0.3338842 0.5742451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6822 7562 0.471496 0.435880 0.713031 0.5702936 0.4609327 0.6756969 0.0757629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6823 6856 -0.900966 0.164968 0.133797 0.3431891 0.4290455 -0.5750894 0.6061464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6823 7563 -0.162860 -0.128047 0.986884 0.0062122 0.0097189 0.9817670 0.1897382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6824 6855 0.437077 -1.027158 0.145673 -0.2436960 -0.4067147 0.6273024 0.6178083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6825 6854 0.602868 -0.757731 0.068101 0.3167831 0.5560025 0.3970463 0.6579239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6825 7565 0.218205 0.172885 1.166837 0.0232408 -0.4959846 -0.8441381 0.2022129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6826 6853 -0.176549 0.621629 0.822904 -0.0552446 -0.3390852 -0.0380885 0.9383595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6826 7566 -0.927774 -0.343489 0.330687 -0.2251438 -0.1300140 0.8815106 0.3941392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6827 6852 -0.489750 0.257695 -0.905552 -0.2716081 -0.1532552 0.4891997 0.8145094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6828 6768 -0.124848 0.934793 -0.740057 0.3562776 0.8580939 -0.2608753 0.2620786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6828 6851 0.389530 -0.420591 -0.808833 0.5725349 -0.0194898 -0.4275830 0.6992830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6828 7568 -0.014346 -0.838322 0.671330 0.2025707 0.8856737 -0.1557012 0.3876911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6829 7569 -0.792229 0.201525 0.619241 -0.2372930 -0.4308780 0.0903331 0.8659539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6830 6809 0.272596 0.842457 -0.346020 -0.7300087 -0.4312173 -0.1841779 0.4972096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6831 6771 0.566346 -0.764123 -0.455416 0.3758065 -0.5853757 -0.5674756 0.4405407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6831 6848 -0.315753 0.256491 -0.807120 -0.4854777 -0.5334529 -0.2979636 0.6252656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6831 7571 -0.443670 0.724254 0.565476 -0.2835585 0.0268465 -0.3543455 0.8906812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6832 6807 -0.906695 -0.023834 0.459027 0.2113335 0.2567917 0.8880520 0.3174269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6832 6847 0.725804 0.027706 -0.485435 0.0610968 -0.6663531 -0.6815206 0.2962605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6833 7573 -0.101113 -0.888693 0.316551 0.3703547 -0.3519235 -0.5816615 0.6329749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6834 6845 0.976221 0.588396 -0.089417 -0.1503573 0.2086429 -0.9496526 0.1789435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6835 6844 0.634445 0.215379 0.345777 -0.1594904 0.2850913 -0.5294208 0.7829428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6835 7575 -0.115903 -0.627122 0.765962 0.7568549 0.2714528 -0.3601999 0.4730116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6836 6803 -0.864241 0.044639 0.272020 0.0256824 0.2507225 -0.9628256 0.0971880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6836 6843 0.830156 -0.168351 -0.048483 -0.5166742 0.4980268 -0.0312723 0.6957291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6836 7576 0.118486 0.862968 0.552850 -0.1465943 0.5163396 -0.2539989 0.8046043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6837 6842 -0.840849 -0.085933 -0.542043 -0.3029943 -0.5237896 -0.1058983 0.7890655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6837 7577 -0.182759 1.102904 0.313691 0.0607992 0.0123251 0.9785398 0.1964978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6838 6778 -0.289309 -1.035979 -0.205465 0.4203692 0.4750033 0.7716019 0.0478750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6838 6801 -0.359415 0.211766 -0.819378 -0.4661389 -0.7539163 -0.1765117 0.4279818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6838 6841 0.494919 -0.373720 0.789449 -0.1865398 0.4736158 -0.3326887 0.7938571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6838 7578 0.319816 1.084230 0.410829 -0.8069700 0.4418452 -0.3237553 0.2208047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6839 6800 -0.130602 -0.837277 0.483665 0.4863031 0.0923357 0.8381797 0.2289939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6839 7579 0.817737 0.080373 0.498079 -0.0908520 -0.1432434 0.8805211 0.4426170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6840 6879 0.448239 0.649701 -0.745493 0.2689411 -0.1869764 -0.8355272 0.4411403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6841 7541 -0.855586 0.621058 0.231627 -0.3994427 -0.4129723 -0.0223008 0.8181700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6842 6877 -1.015961 -0.017940 0.330661 -0.0942770 0.6139320 0.7836799 0.0067237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6842 7542 0.399452 0.584131 0.738133 -0.5426919 -0.0388013 -0.5894940 0.5970567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6843 6876 0.473713 -0.182103 0.703381 -0.1737934 -0.7890535 0.5878694 0.0399990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6844 6875 -0.467802 0.522240 0.847529 -0.1007124 -0.3825162 0.7282578 0.5596239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6844 7544 0.366822 -0.828187 0.608220 0.6901157 -0.3196758 0.5059117 0.4069410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6845 6874 -0.949657 -0.104522 0.231882 0.2717170 0.1940448 0.2573268 0.9068073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6845 7545 0.139827 -0.932909 0.065779 -0.1626272 0.3666790 -0.4142634 0.8169974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6846 6833 0.645843 -0.684546 0.005342 -0.3806016 0.3077685 0.7059960 0.5118502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6846 6873 -0.826774 0.766610 0.156759 -0.0771832 0.7739734 0.3763990 0.5033207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6846 7546 0.604785 0.504055 0.376861 -0.5098619 -0.2912625 -0.4281516 0.6869449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6847 7547 -0.053171 1.094739 0.098545 -0.0611895 0.0224590 0.9526947 0.2968574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6848 6871 -0.922593 0.002512 0.243945 0.1314362 -0.1236538 -0.9703424 0.1608412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6848 7548 0.440539 -0.371211 0.886978 -0.1967648 -0.5315055 0.4012036 0.7195980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6849 6749 -0.589012 -0.241939 -0.900898 -0.3675437 0.4992174 0.1443322 0.7712729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6849 6830 0.895478 -0.027663 -0.464658 -0.0141281 0.0436962 -0.5688805 0.8211370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6849 6870 -0.882874 0.148490 0.388481 -0.1358376 0.1517612 -0.8570477 0.4732716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6849 7549 0.515099 0.301867 0.853973 0.3237606 0.3338730 0.8242000 0.3231134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6850 6869 -0.883691 0.173025 0.384106 0.6584543 0.4926173 -0.3646285 0.4368205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6850 7550 0.146648 -0.676039 0.734713 -0.0364804 -0.1813257 -0.3063898 0.9337641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6851 6751 -0.449497 -0.357836 -0.732629 -0.0110449 0.2273934 -0.4851050 0.8443005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6851 6868 1.000509 -0.393000 -0.241188 0.4510573 0.2633287 0.4336012 0.7342992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6851 7551 0.321549 0.445361 0.729765 -0.2516610 -0.1909162 0.8874214 0.3357097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6852 6752 0.157346 -0.110604 -0.858899 0.6776029 -0.1385780 -0.2088630 0.6913948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6852 6867 -0.032089 1.140571 -0.089268 0.1601069 -0.5464918 -0.7723069 0.2815219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6853 6866 0.170884 0.451725 0.685250 -0.3788368 -0.0792315 0.2460694 0.8886253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6853 7553 -0.342059 -0.663304 0.593190 0.3071312 0.5676568 -0.5439882 0.5362024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6854 7554 -0.294902 0.984052 0.204481 -0.3649987 0.1809543 0.8927301 0.1925216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6855 6864 -0.770400 -0.271493 0.059319 0.5960470 -0.4023345 0.2376240 0.6529853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6855 7555 0.271361 -1.011768 0.239848 -0.0671415 -0.3344973 0.9383259 0.0561068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6856 6863 -0.181016 -0.834858 -0.224463 -0.1154301 -0.0175307 0.0010766 0.9931603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6856 7556 -0.760271 0.061694 0.491811 -0.1157072 -0.5589806 0.8149010 0.1004437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6857 6862 0.607828 -0.562326 0.167623 0.1798557 -0.6062330 -0.2038096 0.7473923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6857 7557 -0.771719 -0.762215 0.301143 0.7788872 -0.3851121 0.3106574 0.3853768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6858 6821 0.678452 0.279821 0.573946 -0.1711187 0.5147108 0.7861023 0.2963686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6859 6759 -0.447368 -0.290233 -0.659060 0.1825658 0.5364224 -0.8130082 0.1339341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6859 7559 0.485491 0.240664 0.739259 -0.6868905 -0.1017383 -0.6314881 0.3450414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6860 6720 -0.058835 -0.891201 -0.234611 -0.7521220 0.4263468 0.4931078 0.0968795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6860 7520 -0.180717 1.019159 0.332072 0.0842014 0.0042588 0.9808579 0.1755273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6861 6898 -0.374104 -0.739596 0.261293 -0.3572862 0.0575912 -0.5377138 0.7615075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6861 7521 0.823177 -0.544873 0.186948 -0.6263554 0.2112743 -0.6514963 0.3722830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6862 6897 0.675715 -0.451890 -0.506907 -0.1054482 0.0529395 -0.0361456 0.9923566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6862 7522 0.427402 -0.683646 0.714618 -0.1229801 0.2685832 -0.8930514 0.3394085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6863 6896 -0.194688 -0.931872 -0.467208 0.3850748 -0.5375191 0.5968858 0.4544424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6863 7523 -0.871373 0.035848 0.682760 0.3176282 -0.1843373 0.4775965 0.7981439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6864 6724 -0.553116 0.183881 -0.839089 0.5373494 0.6691116 -0.2955282 0.4197719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6864 6895 -0.486501 0.669909 0.581516 0.4266661 0.4356030 0.1864176 0.7703600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6864 7524 0.639301 -0.345851 0.798810 -0.2135608 -0.3075275 0.7476311 0.5485129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6865 6854 0.935756 0.236065 0.396540 0.3448848 -0.3697849 -0.0736306 0.8595884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6866 6893 0.413832 -0.101612 0.782369 0.6136111 0.3362549 -0.1811208 0.6910929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6866 7526 -0.757513 -0.768811 0.106872 0.6962587 -0.3044026 -0.3994547 0.5128341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6867 6892 -0.712296 -0.317891 0.618444 0.1250476 0.2198000 -0.9484767 0.1909006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6867 7527 0.402066 0.876451 0.508308 0.0070302 -0.2179651 0.0429809 0.9749843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6868 7528 0.584401 0.692097 0.253830 0.2507396 0.4288098 0.5296516 0.6875471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6869 6729 0.632733 -0.216624 -0.430803 0.7608242 -0.2466292 -0.4733470 0.3691385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6869 6890 -0.601947 -0.621508 -0.500031 0.8883582 0.2941028 -0.3512087 0.0312368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6869 7529 -0.900179 0.300716 0.422545 0.0038656 -0.0682385 -0.3542401 0.9326535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6870 6889 0.469514 -0.973855 0.093788 -0.3659382 -0.1635198 0.4921456 0.7727504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6870 7530 -0.458019 -0.131061 0.905408 0.2349063 -0.3390791 0.6836019 0.6021070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6871 6888 0.954142 -0.063018 0.874239 -0.3150332 0.2162126 -0.7729382 0.5065302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6871 7531 -0.557280 0.755340 0.608255 -0.6506851 0.6241744 0.4316849 0.0257555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6872 6732 -0.053836 -0.956215 -0.340094 -0.4768886 0.3424454 -0.6125660 0.5292176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6872 6847 0.772701 0.152421 -0.381914 0.0646673 0.5397575 0.0496189 0.8378651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6872 6887 -0.796415 -0.295685 0.410722 -0.3074197 0.1830338 0.6910559 0.6280394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6872 7532 -0.327004 1.031954 0.399841 -0.7154629 -0.0561891 -0.5980039 0.3568569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6873 7533 -0.542350 0.318939 0.788706 -0.4180759 -0.2938420 -0.3498478 0.7851598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6874 6885 -1.044052 0.217780 -0.398635 -0.2692756 -0.4607840 0.6066100 0.5892309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6875 7535 -0.376191 -0.780371 0.749714 0.8298803 0.1657326 -0.1891031 0.4980676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6876 7536 0.544651 -0.881733 0.074390 -0.1409500 0.3611168 0.1142417 0.9147003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6877 7537 -0.281756 0.652111 0.750829 0.5974789 -0.4567639 -0.5044597 0.4241534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6878 6841 -1.117185 0.169539 0.204597 0.3191463 0.4393121 0.5295573 0.6517052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6878 6881 0.865762 -0.042353 -0.414467 0.4422186 -0.3931708 0.7841324 0.1870716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6878 7538 0.261999 -0.316071 0.856824 0.3147473 -0.4337929 0.3701497 0.7587800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6879 7539 -0.213747 -0.804978 0.416392 -0.5557600 -0.5722891 0.3817352 0.4667915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6880 6919 -0.978801 0.300138 -0.184822 -0.0347995 -0.2340204 0.2944939 0.9259033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6880 7500 -0.305506 -0.354576 0.888982 0.6299381 0.1050086 -0.5534832 0.5346097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6881 6918 -0.587240 -0.498458 0.579489 0.3391669 -0.1100779 -0.0444096 0.9332076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6881 7501 0.558399 -0.044668 0.757998 -0.5863601 0.0002458 -0.8056237 0.0845709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6882 6702 0.130543 -0.819373 -0.416136 -0.8375505 -0.1577588 0.4788923 0.2104365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6882 6877 -0.771625 -0.048621 -0.886567 -0.0034991 -0.4354299 -0.3571145 0.8263521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6882 7502 -0.165340 0.838440 0.348510 -0.7884746 -0.2117278 -0.5493772 0.1779434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6883 6703 -0.372483 0.473064 -0.884843 -0.8159392 -0.0778915 -0.5728450 0.0049671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6883 6876 -0.740110 0.187147 0.593648 0.2026816 -0.6917120 0.4130397 0.5566442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6883 6916 0.991772 -0.160922 -0.627879 0.4922463 -0.3256859 0.6510977 0.4771731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6883 7503 0.490701 -0.363716 0.940252 -0.2760731 0.2921577 -0.3920296 0.8274904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6884 6875 0.601372 -0.859174 0.020634 -0.0360744 0.3992015 0.8996683 0.1730137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6884 6915 -0.495368 0.686906 -0.173759 0.0555212 0.7758881 -0.3816979 0.4992212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6884 7504 0.748716 0.476304 0.210461 0.2321792 0.4099344 -0.0704551 0.8792512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6885 6914 0.375858 0.948906 0.455831 -0.2749943 -0.3316726 -0.2855570 0.8560541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6885 7505 -0.535989 -0.199458 0.796456 0.2689277 0.2287453 -0.3844996 0.8529441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6886 6873 0.414483 -0.982095 -0.105184 0.0150107 0.7788041 0.2392244 0.5796641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6886 6913 -0.398876 0.963182 0.014023 -0.2112513 0.1752392 0.0223032 0.9613359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6886 7506 0.897571 0.356151 0.307643 -0.2744817 0.2238540 -0.9297480 0.1005874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6887 6707 -0.387544 0.129795 -1.048108 -0.1359734 0.7511588 -0.3772919 0.5243306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6888 7508 -0.130513 -0.991522 0.269824 -0.1977565 -0.7441244 0.6379767 0.0125289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6889 6910 -0.423962 -0.726054 -0.402382 -0.0973161 0.3535844 -0.1894827 0.9108260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6889 7509 -0.255960 -0.306299 0.945826 0.5251697 -0.2776583 -0.7908164 0.1473503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6890 7510 -0.587991 -0.791209 0.063921 0.0964929 -0.5829786 0.7998187 0.1054282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6891 6868 -0.412693 -0.042192 0.853383 0.9574494 -0.1796059 0.1667556 0.1523971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6891 6908 0.476194 0.215746 -0.905406 0.7207243 0.4036884 0.4642781 0.3194339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6892 6907 0.570546 -0.211981 0.810427 -0.7384215 -0.3183162 0.5298147 0.2696385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6893 6906 -0.161969 0.736899 0.365338 -0.4069527 -0.4689923 0.7680679 0.1565485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6893 7513 -0.648555 -0.398327 0.359010 0.4460919 -0.0975791 -0.6741917 0.5804704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6894 6865 0.504541 0.936394 -0.304042 0.3552093 0.6242481 0.3160540 0.6198794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6894 6905 -0.427503 -0.921488 0.273686 0.5848997 -0.0354911 0.1138489 0.8022912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6894 7514 0.885948 -0.217113 0.638187 -0.0059656 -0.3533143 -0.9352971 0.0187792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6895 6715 0.299758 -0.645805 -0.753460 0.2420881 0.2587577 0.6134876 0.7057413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6895 6904 -0.313106 0.764137 -0.581392 -0.0397205 0.6820781 0.7043990 0.1923895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6895 7515 -0.336298 0.510152 0.646505 -0.6024582 -0.0690919 -0.1709036 0.7765709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6896 6903 -0.761401 0.516174 0.858819 -0.2753485 0.4534232 0.7139851 0.4569638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6896 7516 0.698543 0.533340 -0.014745 -0.6983910 -0.6041766 -0.2858218 0.2559815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6897 6902 0.635752 -0.344785 -0.490567 -0.0479679 0.6153515 -0.3998080 0.6776394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6897 7517 0.371633 -0.596571 0.656035 0.4808491 0.0247262 -0.4856224 0.7296189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6898 6901 0.442460 -0.849291 -0.646164 -0.5570827 0.0016884 0.3600787 0.7483311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6898 7518 0.858084 0.358169 0.403607 0.0598880 0.2780296 0.8970851 0.3381588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6899 6860 0.321809 0.535536 0.710032 0.6835007 -0.4682296 -0.0760933 0.5547951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6899 7519 -0.801362 -0.061811 0.596907 0.1999587 -0.7267605 -0.6533603 0.0703990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6900 6680 0.111598 -0.944957 -0.242273 0.3260643 -0.6600048 -0.5587165 0.3819838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6900 6939 -1.029436 0.124354 0.142825 -0.6265023 -0.0520934 0.3703988 0.6838025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6901 6938 0.413669 0.153877 -0.868505 0.5205526 -0.3314536 0.7775782 0.1205636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6901 7481 0.679416 -0.656958 0.164117 -0.0829973 0.7355729 -0.6719524 0.0228912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6902 6937 0.497774 0.692627 0.645029 -0.1482960 0.3850695 -0.8164387 0.4039277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6902 7482 0.006003 -0.523096 0.729589 -0.3155327 0.2763505 -0.8728876 0.2492725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6903 6936 -0.285065 0.797596 0.562681 0.6211271 -0.0160027 -0.5241279 0.5824388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6903 7483 -0.280689 -0.740879 0.667304 0.3449161 -0.2363549 0.6840798 0.5976655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6904 7484 -0.114552 0.690393 0.579247 -0.2995771 -0.1233874 -0.3819743 0.8655200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6905 6934 -0.492257 0.165922 0.806593 0.4040652 0.3113802 -0.1635860 0.8444012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6905 7485 0.823414 0.577885 0.571325 -0.4928851 0.8044547 -0.0583864 0.3263555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6906 6933 0.451378 -0.852255 -0.228230 0.1984440 0.0211361 -0.8299553 0.5209101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6906 7486 0.158257 -0.201876 1.001771 -0.2089871 0.3820684 -0.0279094 0.8997607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6907 6932 -0.476043 -0.458121 -0.887938 -0.1298971 -0.3286721 -0.4362010 0.8275446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6908 7488 -0.845838 0.537896 0.139127 -0.1555627 -0.1280346 -0.8605013 0.4679155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6909 6890 0.874158 0.152203 -0.173276 -0.3560978 -0.2200099 0.5988930 0.6827277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6909 6930 -0.967911 -0.022294 0.279482 -0.3781594 0.5910960 -0.4449378 0.5564452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6910 6929 0.253928 -0.489678 -0.874373 -0.6732783 -0.5185860 0.3784541 0.3667933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6910 7490 -0.661759 -0.673727 0.455130 0.2029139 0.1626739 -0.9479847 0.1835433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6911 6691 -0.304538 0.686068 -0.478092 0.3632823 0.4574950 0.7675081 0.2639236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6911 6888 -0.900737 0.033143 0.254007 -0.0517546 0.7752245 -0.2190168 0.5902373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6911 6928 1.010206 -0.144224 -0.324217 0.5735627 0.5125868 -0.3041977 0.5619113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6912 6887 -0.115669 0.171997 -0.944245 -0.2281784 0.4483314 0.8581318 0.1026811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6912 7492 -0.626079 0.785726 -0.044095 -0.0891154 -0.7763081 -0.4645151 0.4166892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6913 7493 0.795016 0.148603 0.742120 0.0350043 0.0872238 -0.0926635 0.9912518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6914 6925 0.389655 0.569568 0.785692 -0.4457376 -0.2559696 0.8537660 0.0829526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6914 7494 -0.107052 -0.772485 0.683258 0.2761014 -0.0722426 -0.1020676 0.9529592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6915 7495 -0.821406 0.592592 0.348186 -0.8723465 0.1599084 -0.1703718 0.4294349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6916 6923 -0.400625 -0.645660 0.405137 0.2387782 0.3948206 -0.6523369 0.6012971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6916 7496 0.393711 -0.208606 0.530750 0.2668150 0.2537257 -0.4538881 0.8114300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6917 6882 0.986793 0.490169 -0.319959 0.3488355 -0.6563265 -0.2544297 0.6187204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6917 6922 -0.855336 -0.504390 0.166165 -0.8217377 0.3214509 0.0872867 0.4623825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6917 7497 -0.193258 0.597052 0.477520 -0.2856573 -0.0705073 -0.0056079 0.9557181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6918 6921 -0.647116 -0.020220 0.817823 0.8787495 -0.0928321 0.4643356 0.0597836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6918 7498 0.781322 0.352933 0.332341 0.1332647 0.9493705 0.2349071 0.1604834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6919 7499 -0.229023 -0.400218 0.937856 0.4046526 -0.5904963 -0.2420724 0.6549590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6920 6959 -0.743537 0.380741 0.453186 0.4715986 0.4601235 0.7110158 0.2456372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6920 7460 0.702548 0.701533 0.128669 -0.3649474 0.7392133 0.4189689 0.3805813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6921 6958 0.561790 0.130886 -1.064330 0.7851345 -0.4376579 0.3605141 0.2490963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6921 7461 0.724858 -0.451301 0.456266 0.0446801 0.1218843 -0.0589474 0.9897844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6922 7462 -0.771349 -0.385869 0.203130 0.7539605 0.4925243 -0.2733312 0.3380140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6924 6915 0.551613 0.682249 -0.616961 0.4111121 0.6839179 0.5610162 0.2202360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6924 7464 0.666586 -0.582886 0.462024 0.1083720 -0.8113938 0.5588067 0.1327807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6925 6954 -0.446750 -0.766083 -0.120401 0.1553202 0.1552631 -0.7667600 0.6031982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6925 7465 -0.866451 0.336233 0.651856 0.1994548 -0.1857170 -0.9611553 0.0436756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6926 6913 0.245386 -1.012789 -0.373368 0.1037445 -0.0657689 -0.1457512 0.9816660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6926 6953 -0.126536 0.830673 0.520304 0.6447439 0.6016617 0.1093813 0.4586330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6926 7466 0.698317 -0.358124 0.854810 -0.1956976 0.0091655 -0.7744873 0.6014881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6927 6912 -0.626508 0.585297 -0.141183 0.1346495 0.7095512 -0.2982096 0.6240814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6927 6952 0.735219 -0.585968 0.208294 0.0361314 -0.0224357 0.8038986 0.5932438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6927 7467 0.443570 0.567672 0.218425 -0.6482959 -0.2719370 -0.4358195 0.5619822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6928 6951 0.384129 0.741544 0.342418 0.3384755 -0.3819992 -0.2744601 0.8149740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6928 7468 -0.881164 0.153043 0.532970 0.0093497 -0.2063629 0.2214129 0.9530494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6929 6950 -0.523897 0.992009 0.131461 -0.1912601 -0.6346290 -0.4366766 0.6082591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6929 7469 -0.892760 -0.462255 0.580136 0.1133084 0.0940674 0.9853009 0.0865718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6930 6670 -0.350570 0.779681 -0.563724 0.8683629 0.2163412 0.3966484 0.2044806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6930 6949 0.099367 -0.496461 -0.956050 0.0441836 -0.8943345 0.4162306 0.1580054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6931 6671 -0.927651 0.089668 -0.622347 0.6506843 -0.1449433 0.6319030 0.3953480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6931 6908 0.387823 0.942439 -0.223748 0.4002976 0.6497452 -0.4689249 0.4446375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6931 6948 -0.256261 -1.000794 -0.007068 -0.2409861 -0.0431281 -0.4384124 0.8647891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6931 7471 0.883839 -0.207432 0.719121 -0.6754471 0.2244654 -0.2966689 0.6366899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6932 6947 -0.310283 -0.796739 -0.516742 -0.4097010 -0.1467687 0.5473574 0.7148454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6932 7472 -0.109886 -0.448773 0.805270 0.7478800 -0.0317948 -0.4794371 0.4580443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6933 6946 0.368695 0.898539 -0.164820 -0.4627045 0.0040243 0.6066948 0.6463820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6933 7473 -0.095099 0.445294 0.886510 0.1774478 -0.3174100 0.2023917 0.9092859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6934 6945 -0.900323 0.256411 0.075756 -0.6759823 -0.1680285 0.1196968 0.7074510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6934 7474 0.338967 0.766060 0.229821 -0.5757433 0.7602106 0.2466368 0.1725393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6935 6675 -0.479812 -0.742940 -0.024458 -0.1145885 0.2072883 -0.6735125 0.7002013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6935 6904 0.591050 -0.296535 -0.772912 -0.4223947 -0.4234653 -0.4662318 0.6518342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6935 6944 -0.278606 0.341480 0.823699 -0.0674681 -0.7557497 -0.4226790 0.4956137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6936 6943 -1.033136 -0.096225 -0.279853 -0.1143748 0.1385300 0.9163835 0.3577278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6936 7476 -0.226332 0.692368 0.645414 0.2010868 -0.2393845 -0.8812520 0.3544772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6938 6941 -1.075930 0.256281 0.067937 -0.4028668 0.0961023 0.8172642 0.4006770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6938 7478 -0.050778 0.094944 1.094582 -0.4324694 0.2745732 -0.5771020 0.6360291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6939 7479 0.626315 -0.238347 0.928352 0.3488460 0.4451167 -0.3946930 0.7241513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6940 6979 -0.006305 -0.847836 -0.337816 -0.2396480 0.6021998 -0.3210748 0.6905326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6940 7440 0.169033 -0.354068 0.732746 0.2691856 0.3017638 0.8741687 0.2688992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6941 6978 0.694388 0.563046 0.540284 -0.2146313 -0.5856129 -0.5024242 0.5987995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6942 6937 -0.389705 0.256854 -0.881991 0.3029946 0.6625213 -0.6425381 0.2374966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6942 6977 0.291667 -0.272790 0.947720 -0.0267209 0.8456793 -0.5288959 0.0661933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6942 7442 -0.701640 -0.753190 0.108663 -0.4096619 -0.0540129 0.6386253 0.6491667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6943 6976 0.743333 0.600511 -0.070965 -0.0024901 -0.1436432 -0.0262450 0.9892783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6943 7443 0.121954 -0.471436 0.870892 0.2947822 -0.7518915 0.5883830 0.0395996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6944 6644 0.426213 -0.845753 -0.229503 -0.5889942 0.2789887 0.6963868 0.3004939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6944 6975 0.735435 0.289135 0.487338 -0.6874056 -0.6579451 -0.1178939 0.2840473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6944 7444 -0.416053 0.784551 -0.037523 -0.1547115 -0.0034939 0.0119243 0.9878815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6945 6974 -0.581344 -0.224357 0.687120 0.3506325 0.7610794 0.0835013 0.5392982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6945 7445 0.673435 0.217143 0.584589 -0.5795699 -0.1984512 -0.6658673 0.4258363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6946 6646 0.304049 0.520659 -0.904659 -0.2100820 -0.4721293 -0.0833339 0.8520651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6946 7446 -0.437558 -0.587006 0.761989 -0.0865283 0.1097017 -0.2051053 0.9687157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6947 7447 -0.784593 -0.605275 0.044482 -0.3376656 -0.7268412 0.5633692 0.2007462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6948 6648 -0.853142 -0.396929 -0.441902 0.1920251 0.5385350 0.8193271 0.0425387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6948 6971 0.519990 -0.908399 -0.443934 0.6904264 0.0105114 0.6050421 0.3963900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6948 7448 0.916400 0.407837 0.585214 -0.2624454 0.4617770 -0.7405161 0.4117285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6949 6970 -0.347582 0.083946 0.816209 0.5519528 -0.3309910 0.6114644 0.4603306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6949 7449 -0.347224 -1.003412 0.129375 -0.0193210 -0.1947610 0.9236563 0.3294751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6950 6969 -0.142529 0.040603 0.977505 0.3328680 0.5200045 -0.0240887 0.7862659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6950 7450 0.704532 -0.759178 0.277363 -0.8517852 -0.1412356 -0.4808719 0.1525672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6951 6651 0.356513 -0.539241 -0.797954 0.6057727 -0.3031241 -0.5012228 0.5384523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6951 6968 -0.298030 0.786712 -0.646160 0.0049797 0.2888853 -0.5087502 0.8109832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6951 7451 -0.503043 0.546453 0.797578 -0.2930031 -0.6282992 -0.4166606 0.5880334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6952 6967 -0.777160 -0.421326 0.263597 0.7852624 0.1596044 -0.3820188 0.4603814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6952 7452 0.297921 -0.611170 0.570456 0.6551768 0.4353690 0.4308835 0.4421952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6953 6653 0.379187 -0.997292 -0.091132 -0.4430080 -0.8260592 -0.3386254 0.0818713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6953 7453 -0.366369 0.979538 0.221739 -0.7970328 -0.2117762 0.5107228 0.2430058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6954 6965 0.936207 -0.329939 0.182786 0.1276238 -0.1441452 0.8468490 0.4957631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6954 7454 -0.187346 -0.716919 0.398455 0.5089756 0.5889364 -0.6188512 0.1054564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6955 6924 0.965885 -0.095902 -0.392640 0.2062674 -0.0147541 -0.5110953 0.8342767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6955 6964 -1.004612 0.038302 0.361348 0.6370698 -0.6478571 0.2552430 0.3305667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6956 6923 0.451759 -0.387625 1.147130 0.8659802 -0.1023993 -0.3990341 0.2834863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6956 6963 -0.691590 0.250442 -0.740167 0.2771423 -0.6182722 0.6249415 0.3877884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6956 7456 -0.753345 -0.418251 0.131904 0.2725278 -0.3486244 -0.0486491 0.8954457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6957 6922 -0.764376 -0.712466 -0.448155 0.4821580 0.3341207 -0.7059513 0.3968876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6957 6962 0.724111 0.489840 0.178179 -0.4833172 -0.2585671 -0.6616590 0.5116198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6957 7457 -0.388456 -0.038344 0.738639 -0.6820305 -0.1646677 0.1574465 0.6949313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6958 6961 -0.544322 -0.637904 0.771226 0.9178779 0.3198817 0.0665632 0.2252668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6959 6659 -0.154642 0.227759 -0.784908 -0.5431338 0.2450088 -0.5987234 0.5352632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6960 6999 -0.585237 -0.074103 -0.819573 0.5693620 -0.3103261 -0.6451073 0.4041796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6960 7420 -0.820010 0.428520 0.502627 -0.2787805 -0.4551259 0.5440768 0.6473966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6961 6621 -0.515736 -0.700751 0.002983 -0.8751908 0.0158463 -0.4834882 0.0054013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6961 6998 -0.654908 0.304574 -0.623893 0.0445547 0.7914023 0.5557279 0.2507265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6961 7421 0.368120 0.868384 0.109315 0.1254168 0.4705683 0.5616492 0.6688694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6962 6997 -0.026484 0.509110 0.726976 0.5147107 0.0765702 0.0119342 0.8538545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6962 7422 0.858347 -0.554606 0.188128 -0.7748356 -0.3772954 -0.4933310 0.1179091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6963 7423 0.714124 0.360401 0.718618 -0.2723325 0.3406777 -0.1076893 0.8934074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6964 7424 0.884264 -0.019355 0.797819 -0.3612295 -0.2711757 -0.8114234 0.3709031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6965 6625 0.463758 -0.533920 -0.705702 -0.3976116 -0.2046052 -0.8845226 0.1328964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6965 7425 -0.461131 0.632403 0.717277 0.5953498 0.0859642 -0.7529367 0.2669366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6966 6626 0.131167 1.094340 -0.141029 -0.3892822 0.5844564 -0.6930670 0.1628750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6966 6993 -0.982499 -0.071365 -0.096308 0.2307046 0.1155506 -0.9491271 0.1805025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6966 7426 -0.124653 -0.810771 0.266017 0.4556259 -0.8577400 0.2357845 0.0330571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6967 6627 -0.288918 -0.972792 -0.104821 -0.6871913 -0.0481385 0.6074465 0.3955497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6967 7427 0.217177 0.907767 0.153307 0.0782215 0.3852367 0.7895249 0.4713009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6968 6991 -0.549797 0.267754 -0.873303 0.7393963 -0.2779302 -0.5334242 0.3025006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6968 7428 -0.862909 -0.459049 0.259196 0.1904429 -0.6789589 -0.5025992 0.5001404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6969 6990 -0.804988 0.615404 0.042443 -0.3951480 -0.0925106 0.9119266 0.0607428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6969 7429 -0.038776 -0.148860 1.000130 0.4158150 0.0758870 0.8653960 0.2691261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6970 6630 -0.072170 -0.408594 -0.869419 -0.5239157 -0.4230268 -0.5059307 0.5390685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6970 6989 1.214687 0.340545 -0.362547 0.1793830 0.0860578 -0.9773657 0.0719176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6970 7430 -0.114601 0.537234 0.719805 -0.2455481 -0.2102865 0.3756431 0.8685493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6971 6988 -0.592577 -0.006267 0.827136 0.4913984 0.7374295 -0.1949037 0.4204021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6971 7431 0.986911 -0.524999 0.546786 0.1583212 0.8591802 -0.1825051 0.4510385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6972 7432 0.134298 0.724591 0.623882 0.1080026 0.1122749 -0.9876957 0.0136755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6973 6633 0.212014 -0.373250 -0.887683 -0.1130060 0.2219883 -0.9624324 0.1080496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6973 6946 -0.893342 0.329053 -0.399423 -0.3233444 0.0590473 0.0715343 0.9417243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6973 7433 -0.427349 0.167278 0.883018 0.2184796 -0.4027146 -0.8386761 0.2944657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6974 6985 -0.299802 -0.116900 -1.011661 -0.0846116 -0.4442554 0.0519910 0.8903791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6974 7434 -0.644067 0.520926 0.591124 0.0520209 -0.7672153 0.3588739 0.5290406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6975 6984 0.672640 0.700461 -0.392061 0.3656514 0.3796505 -0.4488521 0.7215929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6976 6983 0.754259 0.798441 -0.099070 0.3468507 0.6956538 -0.2561576 0.5745813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6976 7436 0.456753 -0.115545 0.838317 0.0629112 0.3347176 -0.4727438 0.8127236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6977 6982 -0.564830 -0.932645 -0.065599 0.6438681 0.0900420 0.1247527 0.7495085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6977 7437 0.497844 -0.310412 0.781021 0.5544516 -0.1138231 0.8091192 0.1579680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6978 6981 0.408264 0.902639 0.518330 -0.1381397 0.3918842 -0.7311344 0.5410977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6978 7438 0.863242 -0.412953 0.324570 -0.1052097 0.0303543 0.2318887 0.9665595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6980 7019 1.039326 -0.208663 -0.245992 -0.2461652 -0.2366069 -0.2843881 0.8958478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6980 7400 0.411598 -0.277411 0.810424 0.1520247 0.0341052 -0.8032845 0.5748559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6981 7018 -1.017113 -0.056648 0.055943 -0.3647811 -0.2325217 -0.5812708 0.6891971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6981 7401 -0.103751 0.154605 0.954187 -0.4927370 0.2433373 -0.5857026 0.5957766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6982 7017 -0.600988 -0.354438 0.775576 -0.0552545 0.0821744 0.6462065 0.7567109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6982 7402 0.583871 0.447977 0.722121 -0.1850655 -0.4138211 -0.8912622 0.0124303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6983 7016 0.034574 0.888599 -0.087964 0.2827482 -0.4921100 -0.7878778 0.2390184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6983 7403 -0.847520 0.227810 0.494554 -0.1884240 -0.3184745 0.4097253 0.8337839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6984 7015 0.153525 0.829871 -0.622076 -0.6398972 0.4095548 -0.3919545 0.5188141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6984 7404 -0.043324 0.578959 0.583776 0.1180273 -0.4157584 -0.7410188 0.5139121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6985 7014 -0.930271 -0.041015 0.027660 -0.2756434 -0.4808623 -0.4581995 0.6948707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6985 7405 0.213845 0.595178 0.947331 0.1416558 -0.1518946 0.8548803 0.4754381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6986 7013 0.280107 0.719732 -0.610312 0.3375551 -0.2457000 -0.6201782 0.6641288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6986 7406 -0.024037 0.767451 0.627073 -0.2175444 0.2387194 -0.6385690 0.6985107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6987 6972 0.649944 0.743700 0.138668 0.3808997 0.1844375 0.7992984 0.4266384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6987 7012 -0.625397 -0.646230 -0.210173 0.3474544 0.2502814 -0.8958207 0.1189114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6987 7407 0.161221 -0.270866 0.975140 0.3579915 -0.2232234 0.8882080 0.1819342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6988 7011 -0.560925 -0.267740 -0.719204 -0.7672951 -0.2661648 0.5832050 0.0169265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6988 7408 -0.749930 0.542549 0.482740 -0.6073701 -0.6259532 0.3643418 0.3264034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6989 7010 -0.981345 -0.295783 -0.606297 0.1252045 -0.3789433 -0.7563944 0.5182599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6989 7409 -0.322986 -0.643230 0.819938 0.7723377 0.2704602 -0.3384382 0.4645485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6990 6610 0.849745 0.018181 -0.771814 0.5670398 -0.5955698 -0.5682119 0.0299604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6990 7410 -0.693888 0.171612 0.482898 -0.4973413 0.1407329 0.6405507 0.5679266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6991 7008 0.156344 -0.539218 0.518458 -0.2297757 0.2495705 -0.7633916 0.5496826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6991 7411 -0.042344 0.547852 0.591957 0.2150169 0.6668719 0.6993261 0.1413954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6992 7412 0.132353 -0.957515 0.425890 0.0861374 -0.5275187 0.8221074 0.1960707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6993 7006 0.870379 -0.378797 0.114798 -0.4939271 0.5579068 0.3416514 0.5727568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6993 7413 0.471959 0.860043 0.512788 0.2289587 0.3183020 0.3721886 0.8412713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6994 6965 -0.826829 -0.429526 0.126350 -0.3108242 0.6523782 0.6583725 0.2105627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6994 7005 0.914167 0.559893 -0.159749 -0.6206500 0.1766790 0.7623634 0.0487878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6994 7414 -0.223254 0.655666 0.647847 -0.3092609 0.2220190 0.3731792 0.8460512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6995 6615 -0.564078 -0.709786 -0.428820 -0.5126154 -0.0064058 -0.4494466 0.7315615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6995 7004 -0.706100 0.705741 -0.125787 0.0386979 0.4580753 0.1806431 0.8695042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6995 7415 0.503270 0.548931 0.140002 -0.0159196 0.0883876 -0.6875892 0.7205243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6996 6963 0.506333 -0.664998 -0.287931 0.4702708 -0.1888966 0.1415118 0.8503751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6996 7003 -0.675251 0.732831 0.303728 0.4721791 -0.1991396 0.8152301 0.2697966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6997 7002 0.002917 0.977105 -0.044012 0.0054195 -0.3602061 0.9179884 0.1658898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6998 7001 1.005506 -0.186026 0.190822 -0.1763794 0.3881652 0.9003270 0.0873467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6998 7418 0.055699 0.391786 0.839351 0.2012443 0.1237798 0.9247569 0.2983352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6999 7419 -0.581381 0.215643 1.081973 0.1400941 0.3185990 -0.7976660 0.4925416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7000 7039 0.970384 -0.164191 -0.078130 0.2542309 -0.0998997 -0.0126577 0.9618869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7000 7380 0.015784 0.257235 1.065404 0.0288594 0.2574962 -0.8730724 0.4130466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7001 7038 -0.820516 -0.032745 -0.188379 -0.4785658 -0.6887429 0.1997820 0.5066510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7001 7381 -0.363268 0.600264 0.707962 0.0278850 0.4020748 0.9098198 0.0989257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7002 7037 0.380756 -0.775042 -0.410584 0.7169924 -0.5414912 0.0141702 0.4387578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7002 7382 -0.794734 -0.701229 0.438533 -0.4886876 -0.2905945 0.1904536 0.8002916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7003 7036 0.675426 -0.248723 -0.558769 -0.1241508 0.6280659 0.1740378 0.7482183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7003 7383 0.615747 -0.051891 0.863547 0.7499705 -0.3570449 0.5133328 0.2157605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7004 7035 0.006541 0.955454 -0.475666 -0.1808170 -0.7645223 -0.6173629 0.0409134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7004 7384 0.263136 0.465644 0.844404 -0.1802247 0.3203437 -0.6343246 0.6800965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7005 6585 0.775826 0.349112 -0.743116 -0.0757862 0.3618465 0.9067597 0.2027570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7005 7034 0.003616 -0.834823 -0.785620 0.3798340 -0.4865268 -0.4827117 0.6212947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7006 7033 0.147075 -0.944367 0.040697 -0.3912222 0.0869401 0.8882695 0.2244193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7006 7386 -0.663220 -0.143154 0.785086 -0.0436778 -0.2344535 0.1863855 0.9530919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7007 6992 -0.822584 -0.184907 -0.469377 -0.0632843 -0.8904993 0.4224943 0.1565395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7007 7032 0.912022 0.071551 0.268389 0.3435995 0.1851258 0.3898341 0.8340846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7007 7387 0.033261 -0.949632 0.358402 0.3478548 0.2510614 0.4893199 0.7592966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7009 6990 -0.854719 -0.456288 -0.295563 -0.0434667 0.2824025 0.5933737 0.7525073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7009 7389 0.245944 -0.326685 0.874223 -0.0118889 -0.7057867 0.6190294 0.3442766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7010 7029 0.435284 -0.861922 -0.020985 -0.1207002 -0.4170108 -0.4092863 0.8025074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7010 7390 0.804612 0.508119 0.344627 -0.5080967 0.1978094 -0.8312810 0.1080793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7011 6591 0.370764 0.851328 -0.370714 0.0331319 -0.8834025 0.2474217 0.3965915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7011 7391 -0.178807 -0.964586 0.278043 0.5576349 -0.1630272 0.8138253 0.0123993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7012 7027 0.679681 0.273369 0.684714 0.2371093 -0.4109907 0.0558191 0.8784931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7012 7392 -0.767263 0.023367 0.692400 0.3326304 0.0360924 -0.5261764 0.7817882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7013 7026 -0.455852 -0.358629 -0.919788 0.2256449 -0.8635217 -0.3921051 0.2228638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7013 7393 -0.804679 0.566373 0.345168 0.7684797 -0.4847025 -0.1841101 0.3749746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7014 7025 -0.056398 -0.689738 0.303167 -0.2786731 0.4147330 -0.8155263 0.2919842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7014 7394 0.472383 0.328727 0.799679 0.4947681 0.0194959 0.7805631 0.3815046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7015 7395 -0.587973 -0.848765 -0.070829 0.7057336 -0.3326781 0.3384021 0.5260698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7016 7023 -0.653979 -0.645179 0.532067 -0.3765101 -0.2326362 0.5228874 0.7284980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7017 7022 -0.521050 0.530141 0.544657 -0.0287529 0.6323021 0.1308396 0.7630520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7017 7397 0.419771 -0.381076 0.618591 0.7889530 0.1070619 -0.0023367 0.6050500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7018 7021 -0.155245 -0.948094 -0.242780 0.1383025 0.5795129 0.7768148 0.2039511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7018 7398 0.688793 -0.235404 0.873903 0.0729439 -0.2151594 0.9635596 0.1412039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7019 7399 0.772485 -0.342630 0.514300 0.0120037 0.5146802 0.2158038 0.8296921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7020 7360 -0.438021 -0.208420 0.865753 0.1933841 0.4019273 -0.2565014 0.8574754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7021 7058 -0.371034 0.082358 -0.797968 0.6373144 -0.0777930 -0.7508205 0.1550712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7021 7361 -0.443481 0.680873 0.168869 -0.4256426 -0.3606921 0.3259888 0.7631912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7022 7057 -0.512505 1.069509 -0.209025 0.5753004 0.0738941 0.3632269 0.7291333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7022 7362 -0.888723 -0.216521 0.488306 -0.3695271 -0.5876329 0.3542544 0.6266108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7023 7056 -0.780991 -0.118804 0.607891 0.0881287 0.2917328 0.4808128 0.8221583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7023 7363 0.508136 -0.899504 0.532992 0.2589027 0.1806252 -0.7940072 0.5195157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7024 7015 0.711610 0.380504 0.685993 -0.5338671 -0.4669443 0.2877769 0.6435320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7025 6565 0.459392 0.741632 -0.638949 -0.3555390 0.0407591 0.7944391 0.4907110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7025 7054 0.877373 0.204727 0.518578 0.3939354 0.0926138 0.1292948 0.9052737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7025 7365 -0.381865 -0.604161 0.658218 0.4131793 -0.2433914 0.1497162 0.8646552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7026 7053 0.539769 -0.877133 0.445366 -0.1983582 0.4403148 0.6513105 0.5852961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7026 7366 0.423714 0.791069 0.423697 -0.4396540 0.0945087 0.8460833 0.2862090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7027 7052 0.835869 0.250343 -0.189684 0.1125144 -0.6392349 -0.5959897 0.4727743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7027 7367 -0.054040 0.354453 1.020520 -0.0711165 0.7096713 0.1415998 0.6864827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7028 6568 0.339538 0.929033 -0.420092 0.4068279 0.0636588 -0.4715780 0.7797774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7028 7011 -0.080637 -0.324998 -0.893104 -0.0379838 -0.2113701 0.0831763 0.9731195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7028 7051 0.146088 0.364458 0.956011 -0.0335773 -0.4116932 0.8672914 0.2778253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7028 7368 -0.428982 -0.872779 0.498827 -0.5295418 -0.5988220 0.4012103 0.4472450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7029 7369 0.376940 0.872657 -0.022508 -0.4475464 0.2309397 0.8436506 0.1860718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7030 6570 -0.130863 -0.572186 -0.933362 -0.3582678 -0.4581792 0.3494512 0.7345746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7030 7009 -0.787318 -0.287329 0.332334 -0.4532991 -0.0550220 -0.0083155 0.8896198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7031 7008 -0.721024 0.648712 -0.644886 -0.5318658 0.2654750 -0.5730793 0.5641116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7031 7048 0.643816 -0.337623 0.527942 -0.8511131 -0.2321544 -0.0635105 0.4665589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7031 7371 0.213449 0.835201 0.706246 0.2547296 0.1953243 -0.8611229 0.3942443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7032 7047 0.673786 -0.009233 0.704269 0.2720648 -0.7370613 -0.1053093 0.6096157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7032 7372 -0.719440 0.033212 0.674063 0.3105961 -0.0205598 0.0514923 0.9489235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7033 7046 -0.196206 0.884442 -0.442762 0.0722373 -0.0282143 -0.1300772 0.9884663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7034 6574 -0.488624 -0.291451 -0.921343 -0.0505645 0.1627505 -0.6588582 0.7327082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7034 7045 0.672884 -0.936194 -0.009209 -0.4346408 0.0738832 0.4041791 0.8014162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7034 7374 0.542765 0.106162 0.713018 -0.5696040 0.4249687 0.5687611 0.4140818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7035 7375 0.167367 0.913048 0.051588 0.1473225 0.1166128 -0.3615146 0.9132386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7036 7043 0.719634 -0.446948 0.557436 0.7093638 -0.3737796 -0.5975635 0.0031066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7036 7376 -0.621860 -0.049232 0.799859 0.0994255 0.1221398 -0.8260778 0.5411025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7037 7042 0.506734 -0.602980 0.707794 0.3752887 0.6105531 0.6203669 0.3186349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7038 7041 -0.241743 -0.223751 1.221479 -0.4730588 0.8263349 -0.1078256 0.2859365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7040 6540 0.657881 0.048803 -0.675126 0.2281372 -0.5596434 -0.7265347 0.3269556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7040 7340 -0.774143 -0.094110 0.599116 -0.8758334 -0.3298822 0.3261007 0.1332367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7041 7078 -0.268621 -0.537078 -0.964573 -0.1411513 -0.4353278 0.8098244 0.3670836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7041 7341 0.265285 -0.889439 0.418735 0.0369070 -0.7091682 0.1123781 0.6950464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7042 7077 -0.674343 0.667516 -0.052531 0.0244884 -0.1924917 0.9718637 0.1335222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7042 7342 0.452036 0.451111 0.772522 -0.7097529 0.3967798 -0.5600540 0.1586071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7043 7076 -0.304475 0.177959 -0.894151 -0.7187845 0.0227190 -0.0339340 0.6940325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7044 7035 -0.763632 -0.233502 0.545137 0.6073495 0.5434088 0.4703398 0.3385468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7044 7075 0.473431 0.583967 -0.386873 0.1942874 0.3404665 0.8609562 0.3241750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7044 7344 0.592212 0.235914 1.060604 -0.0568638 0.1176317 0.7047450 0.6973261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7045 7345 -0.120800 -0.902172 0.554225 0.7608442 -0.0809188 0.3719987 0.5255332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7046 7073 -0.421147 0.871927 -0.379996 -0.7272745 -0.1403988 -0.1517820 0.6544632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7046 7346 -0.307432 0.336534 0.909017 0.2994843 -0.6846237 -0.6584066 0.0900021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7047 7347 0.701133 0.525510 0.555399 0.2429511 0.8187998 0.5129535 0.0861412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7048 7348 0.471940 -0.765800 0.420325 0.0413154 0.8268006 0.2019536 0.5233627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7049 7030 0.647571 0.218308 0.956468 0.2180905 0.3394862 -0.9037882 0.1426621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7049 7070 -0.654573 -0.264245 -0.915675 -0.4627918 0.3527918 -0.8039430 0.1226268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7049 7349 -0.119338 -1.045201 0.204601 -0.4494912 0.6168061 -0.6434997 0.0584463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7050 7029 -0.435181 -0.682792 0.610252 0.1294977 0.0135427 0.4381913 0.8894017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7050 7069 0.291657 0.539734 -0.800119 -0.1734675 -0.4057053 -0.1302052 0.8878957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7050 7350 -0.612101 0.790767 0.252928 -0.2637741 0.8944860 0.3106759 0.1838434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7051 7068 0.444654 -0.761996 0.498780 -0.1523414 0.4361988 -0.6446014 0.6091073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7051 7351 0.001515 0.367519 0.762336 -0.4567338 -0.3301693 0.1277522 0.8161261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7052 7067 -0.831488 0.496224 -0.499405 0.1508923 0.4353011 0.6664304 0.5861868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7053 7353 -0.158059 -0.204218 0.975507 -0.2022399 -0.4802937 -0.8089147 0.2721653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7054 7354 -0.699934 0.043807 0.682599 0.1788776 -0.0579561 0.6893580 0.6995923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7055 7024 -0.261728 0.569918 -0.689984 -0.5196743 0.4988064 0.5177187 0.4616256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7055 7064 0.248925 -0.587988 0.738200 -0.1753404 0.0929239 0.1824415 0.9629829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7056 7063 -0.353018 0.870239 0.105496 0.1809361 0.3163467 -0.5882850 0.7218778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7056 7356 -0.655729 -0.489025 0.542822 0.2334783 0.1041371 -0.3062740 0.9169730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7057 7062 0.011284 0.143977 -0.864962 -0.9750269 0.1533609 -0.0820943 0.1380703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7057 7357 -0.623633 0.547970 -0.030197 -0.6330934 -0.6693562 0.1467906 0.3600104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7058 6558 0.558410 0.730884 -0.377247 0.1503720 -0.3510467 -0.3530827 0.8541001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7058 7061 0.952050 -0.498205 0.220973 -0.1283634 0.2482040 0.7940528 0.5398127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7058 7358 -0.428796 -0.850995 0.586486 -0.3572763 -0.8901775 0.2826665 0.0060994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7059 7020 0.491536 -0.602223 -0.720020 0.7270862 0.4148510 -0.4323944 0.3350810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7059 7359 -0.805494 -0.757634 -0.028387 -0.1680268 -0.4586063 0.0345382 0.8719257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7060 6520 -0.806602 0.010388 -0.979691 0.6602794 0.0359029 0.2525112 0.7063853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7060 7099 -0.676258 0.027293 0.653504 0.4938188 0.4143620 0.7628602 0.0499146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7060 7320 0.565748 -0.050798 0.694835 -0.6129250 0.0641846 -0.6815750 0.3945361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7061 7098 -0.795259 -0.509494 -0.269672 -0.4376953 0.4166722 0.6315990 0.4856849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7061 7321 -0.710375 0.802265 0.055553 0.7585752 0.1539754 -0.5838512 0.2448940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7062 7097 -0.117293 0.232192 0.782386 0.0422750 -0.8892203 0.3243900 0.3197988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7062 7322 -0.886560 -0.360489 -0.099512 0.2947758 -0.6823150 0.4755470 0.4705407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7063 7323 0.184420 -0.782061 0.474178 -0.7219380 -0.2237653 0.6508713 0.0714228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7064 6524 -0.684497 -0.361372 -0.635499 -0.6104639 0.3721651 -0.3271024 0.6179247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7064 7324 0.647639 0.309501 0.872850 -0.6914145 -0.0410286 -0.1434682 0.7068801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7065 7054 0.684287 -0.278348 -0.572272 0.0252634 -0.1146463 0.8172235 0.5642373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7065 7094 -0.630959 0.604804 0.504967 -0.0169707 -0.0046681 -0.9982299 0.0568084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7065 7325 0.126280 -0.752364 0.744507 0.5203472 -0.0547264 0.7270963 0.4444938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7066 7093 -0.542510 0.192123 -0.784704 0.7006824 -0.2629749 0.5349506 0.3920666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7066 7326 -0.531818 -0.616807 0.241874 -0.1195342 -0.1884507 0.9343716 0.2777546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7067 7092 0.652976 0.204176 -0.699478 -0.3442653 -0.2858282 0.5199505 0.7276230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7067 7327 0.455537 0.308198 0.632809 -0.3903664 0.5990122 -0.0391886 0.6980421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7068 7091 0.379694 -0.341093 0.583719 0.6001858 -0.1969210 -0.4177652 0.6530478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7068 7328 -0.521939 -0.804028 0.203043 -0.0516453 -0.2925410 0.0581232 0.9530867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7069 7090 -0.314522 0.843248 -0.417432 -0.0685515 0.1599319 0.2102215 0.9620444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7069 7329 -0.129627 0.414345 0.943968 0.3907596 0.1510437 0.7929476 0.4424103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7070 7089 -0.165704 0.840341 -0.574127 0.6105492 0.1199941 0.6445193 0.4443265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7071 6531 0.744588 0.176831 -0.543679 -0.3192575 -0.7216914 0.6039044 0.1119628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7071 7048 -0.541710 -0.029128 -0.739020 -0.3787968 -0.7613584 -0.0934914 0.5177893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7071 7331 -0.715865 -0.055693 0.533468 0.2338742 0.3608952 -0.8939146 0.1263889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7072 7087 -0.508467 0.134358 -0.619038 -0.6657004 0.1091170 0.5961650 0.4353432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7072 7332 0.228971 0.749527 0.175528 -0.2024404 0.8709437 0.3811921 0.2348777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7073 6533 -0.024922 0.850104 -0.219932 -0.3793429 -0.6962822 0.5485725 0.2652513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7073 7086 -0.584275 0.158683 0.885285 0.0354028 0.9772974 -0.1759467 0.1126021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7073 7333 0.083975 -0.857308 0.122299 0.3154114 -0.1987138 -0.7822326 0.4991399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7074 6534 -0.560821 0.457437 -0.658772 0.5556325 0.2202924 0.8015895 0.0140757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7074 7045 0.799199 0.578652 -0.391563 -0.3631339 0.5145890 -0.2721847 0.7274939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7074 7085 -0.827415 -0.394309 0.363277 -0.3043127 0.6483791 -0.6492480 0.2558813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7074 7334 0.574706 -0.590048 0.762732 0.6137776 0.1649676 0.5083374 0.5810816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7075 6535 0.274657 -0.205522 -0.815868 0.2088591 0.2588575 -0.4889495 0.8064112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7075 7084 -0.118596 -0.841792 0.147209 -0.7632203 0.2055393 0.1376886 0.5969005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7076 6536 0.479344 0.332465 -0.691698 -0.2404976 -0.3590410 -0.5195697 0.7370874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7076 7083 -0.177138 0.834718 0.537615 0.3218339 0.5862538 -0.5629585 0.4855998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7076 7336 -0.734401 -0.270873 0.694997 -0.4955344 0.3479612 0.7767306 0.1733732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7077 6537 0.420645 0.858811 -0.677550 0.8184531 0.0479828 -0.4633645 0.3363414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7077 7082 0.767106 -0.549434 -0.107005 0.8923921 -0.0533010 -0.1542439 0.4207186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7077 7337 -0.276422 -0.819623 0.377381 -0.2505055 0.5097574 -0.6784501 0.4659397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7078 7081 -0.290341 0.795186 -0.138661 0.1734580 -0.4633711 -0.4345195 0.7525904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7078 7338 -0.589257 0.071664 0.705936 -0.4285839 0.0012820 -0.4784112 0.7664444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7079 7040 -0.029507 -0.876271 -0.355476 -0.7388603 -0.1333370 0.5766053 0.3222313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7079 7339 -0.594264 -0.078905 0.736343 0.1837460 0.5369166 -0.7362897 0.3685585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7080 7119 -0.338852 -1.096511 -0.007901 0.4450786 0.0016548 0.6006906 0.6641333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7080 7300 0.822134 -0.313515 0.782316 0.7295472 0.2219346 -0.1956688 0.6166195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7081 7118 -0.799711 0.070120 0.230435 -0.5887017 0.3421324 0.3494391 0.6436365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7082 7302 -0.157293 0.987193 0.472940 0.3979713 0.1119967 -0.9091290 0.0505975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7083 7116 -0.188240 -0.288486 -0.796767 0.8269180 -0.3738600 0.0989728 0.4082152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7083 7303 -0.271284 -0.884031 0.265460 0.5949259 0.2296134 0.5659603 0.5225225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7084 7304 -0.548799 -0.833894 0.143281 0.7968020 -0.5440474 0.2592701 0.0435652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7085 7114 0.909037 -0.127591 -0.176676 0.6294066 -0.4429445 -0.3665406 0.5227767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7085 7305 0.020099 -0.506205 0.923427 0.2369160 0.3024385 -0.4328858 0.8154824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7086 7113 0.554479 -0.084462 -0.825727 0.2086848 -0.0809169 0.3656530 0.9034384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7087 7112 0.440090 0.408059 0.499678 0.8283280 0.1278833 0.0536881 0.5428040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7087 7307 0.573944 -0.813591 0.300787 0.4059042 0.4750351 -0.7114339 0.3216292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7088 7071 -0.686208 -0.507229 -0.435409 0.3257597 0.2992101 0.5785508 0.6852976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7088 7111 0.967559 0.527547 0.333596 0.7921904 0.5411309 0.0483492 0.2779820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7088 7308 0.430554 -0.835637 0.179760 0.1345178 -0.7995745 0.5823917 0.0583563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7089 7110 0.295462 -0.680440 -0.524721 0.6961333 -0.0344790 0.7162059 0.0354781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7089 7309 0.709558 -0.370408 0.600104 0.4572370 0.3175500 -0.4495484 0.6985718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7090 7109 0.213100 1.057130 -0.255478 0.3268911 -0.5614909 0.2177557 0.7283218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7090 7310 -0.195808 0.353159 0.970313 0.0993197 0.5071380 -0.7661051 0.3821382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7091 7311 -0.069534 0.326999 0.936259 -0.3246743 0.3626527 -0.3963181 0.7784610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7092 6512 -0.332367 0.759546 -0.129653 0.3719567 0.2583201 0.7574904 0.4702417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7092 7107 0.406108 0.109562 -0.833905 0.1655687 -0.7419200 0.4126975 0.5018192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7093 7106 -0.900474 -0.020592 -0.118305 -0.2652955 0.6049839 0.5324482 0.5292558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7093 7313 0.104935 1.035152 0.406751 -0.1101141 0.9765199 0.1655578 0.0829125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7094 6514 -0.031395 -0.658021 -0.788352 0.3139312 0.4201853 0.6565008 0.5421238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7094 7105 0.686091 -0.509492 0.502679 -0.2295071 0.0219394 -0.0269647 0.9726860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7094 7314 -0.052609 0.742169 0.708876 -0.1969752 -0.2181578 0.2710464 0.9165925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7095 7064 -0.329767 -1.006869 0.187139 -0.1225480 -0.3604635 -0.9235985 0.0448762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7095 7104 0.301089 0.950108 -0.112116 0.4472616 -0.6109841 -0.6404694 0.1282747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7095 7315 -0.548441 0.390718 0.903092 -0.0581966 0.2613645 -0.2027766 0.9419041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7096 7063 -0.540247 -0.635059 -0.558913 0.4045117 0.4984986 -0.7595248 0.1048402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7096 7103 0.702176 0.504319 0.674105 0.3006264 0.0773032 0.8105852 0.4965880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7096 7316 -0.736814 0.119812 0.768276 -0.4538216 -0.5544222 -0.3834578 0.5827710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7097 7102 0.702045 -0.189345 -0.570442 -0.4522831 -0.1445394 -0.7081447 0.5225700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7097 7317 0.435286 -0.295865 0.709074 -0.2062424 0.2927791 0.1424236 0.9227459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7098 7101 0.225174 0.670132 -0.539114 0.0409035 -0.5027343 -0.2075364 0.8381609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7098 7318 0.123621 0.478877 0.744447 0.3497060 0.6279375 0.6770327 0.1581989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7100 7280 0.479324 -0.479470 0.709313 0.4725926 -0.7545969 0.4504553 0.0658011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7101 7138 -0.788772 0.439377 -0.295461 -0.4296238 0.7136003 0.4293659 0.3490601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7101 7281 0.539492 0.723892 0.170936 -0.3038059 0.2835571 -0.7285077 0.5445859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7102 7137 -0.338369 0.981113 -0.396052 -0.4149049 -0.7066149 -0.5711982 0.0477694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7102 7282 0.661351 0.649480 0.319465 -0.3554928 -0.6167570 -0.4342494 0.5519630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7103 7136 0.609165 -0.334077 0.905887 -0.4608821 -0.5796733 -0.3146932 0.5937464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7103 7283 0.690817 0.961107 0.087561 -0.7254978 0.4018991 -0.5500324 0.0979510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7104 6484 0.406777 -0.963616 -0.577927 -0.2548369 0.3336884 -0.0422755 0.9065997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7104 7135 -0.619580 -0.371209 0.446802 0.0467490 -0.3227907 -0.6347801 0.7004819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7104 7284 -0.570928 0.921400 0.432645 -0.6381639 0.2335021 0.6482702 0.3434666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7105 6485 0.025777 -0.466996 -0.852672 -0.1590665 0.6940053 0.6830656 0.1627144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7105 7134 0.496259 -0.723499 0.081675 -0.4013045 0.4761697 -0.0451849 0.7811372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7106 7286 0.025321 0.273813 1.026491 0.3671843 -0.4528614 -0.3769754 0.7197095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7107 7132 -1.091933 0.423946 -0.143625 0.7872958 -0.3129209 -0.4801267 0.2274296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7107 7287 -0.144458 -0.836854 0.273886 0.3024922 -0.1595020 -0.9362037 0.0811187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7108 7091 -0.921170 -0.189381 0.589997 -0.6017149 -0.2472165 -0.0743147 0.7558443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7108 7288 -0.163834 1.046992 -0.035042 0.0869509 0.4843721 0.7114938 0.5015973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7109 7130 -0.190984 0.385170 -0.904202 -0.0288403 -0.0211585 -0.1282320 0.9910989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7109 7289 0.819706 0.494798 0.203004 -0.1917344 -0.6499133 -0.6891601 0.2567273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7110 7290 0.639520 0.417974 0.584839 -0.0547994 0.6625269 0.7467949 0.0187741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7111 7128 0.756209 0.685075 -0.488551 -0.6954138 0.1215177 0.1638940 0.6890369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7111 7291 -0.534646 0.593112 0.365705 0.2835808 -0.7643828 -0.5789587 0.0103782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7113 7126 -0.131406 -0.400449 -0.830692 -0.7817850 0.1008210 0.6028791 0.1232236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7113 7293 -0.659353 -0.700379 0.410964 0.2842142 -0.3448429 -0.5196279 0.7282118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7114 7294 0.766008 0.799735 0.244670 0.2510563 0.2743039 0.6051653 0.7039198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7115 7084 -0.093758 0.882694 0.318207 -0.4206232 0.2400686 0.6748194 0.5568322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7115 7124 0.168359 -0.918016 -0.211851 0.5740595 -0.1928414 0.4767622 0.6371543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7116 7123 -0.583210 -0.514762 0.694085 -0.2429489 0.5935477 0.2095896 0.7380712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7116 7296 0.160268 0.643786 0.481202 -0.6188527 0.4080737 0.6496358 0.1687322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7117 7082 0.829458 -0.184262 -0.019954 -0.1099296 0.0167497 0.9757796 0.1883855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7117 7122 -1.083359 0.148496 -0.073748 0.6789549 -0.0445234 -0.6789294 0.2758492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7117 7297 -0.013903 -0.930793 0.355535 0.1636069 -0.1421906 0.6734449 0.7067437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7118 7121 -0.754232 0.656513 0.138285 0.3323169 -0.2738625 0.1554160 0.8890504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7118 7298 -0.440686 -0.790112 -0.112443 0.6165122 -0.0264063 -0.1974960 0.7617157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7119 6499 -0.407625 0.138993 -0.981231 0.7043509 -0.1428790 0.5039890 0.4790308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7119 7299 0.364086 -0.235003 0.923755 0.5736418 -0.0473770 0.5105707 0.6387551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7120 6460 -0.877000 -0.212939 -0.463087 -0.4975558 0.5154755 -0.4963998 0.4902148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7120 7159 0.117589 -1.037464 0.577208 -0.3334875 0.5102874 0.7186598 0.3345459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7120 7260 0.921565 0.176269 0.352372 0.4949922 0.1946305 0.7570779 0.3793874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7121 7158 -0.507625 0.867507 -0.026559 -0.3242570 -0.2122575 -0.7250346 0.5693232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7122 7157 -0.443051 -0.386075 0.995904 -0.5895982 -0.1459254 -0.7619355 0.2247978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7122 7262 0.096046 0.834738 0.297704 0.0205409 -0.1798080 -0.4261455 0.8863674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7123 7156 -0.953424 -0.028460 -0.345408 -0.1515058 0.0866151 0.3714782 0.9118924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7123 7263 -0.482556 0.125202 0.815364 0.1468183 -0.1370221 -0.3070006 0.9302795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7124 7155 -0.475758 -0.129935 0.897778 -0.0005913 -0.4015030 0.7907348 0.4620968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7124 7264 0.766603 -0.330148 0.466863 0.7282207 0.1252325 -0.1224012 0.6625929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7125 7114 1.057653 0.110316 -0.140028 0.3981388 0.8383094 0.3236827 0.1842617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7125 7154 -0.951671 -0.075717 0.154203 0.4248522 0.6251748 0.6382650 0.1458591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7125 7265 0.141193 1.045843 0.530202 -0.1211435 0.1410070 -0.9815519 0.0446900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7126 7153 0.786068 0.532082 0.046052 -0.3425785 0.1412350 0.8848612 0.2823354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7126 7266 -0.665942 0.680247 0.116693 0.6511430 -0.4224253 -0.6295772 0.0346724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7127 7152 0.259628 -0.557023 0.768104 -0.4201378 -0.2908217 0.3074179 0.8027460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7127 7267 -0.470918 0.737695 0.579922 0.3257348 -0.5168901 0.0809588 0.7875069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7128 7151 0.774939 -0.046415 0.719776 -0.3488399 -0.7515020 0.2213783 0.5143416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7129 7110 -0.258214 -0.937947 0.064762 0.0768809 -0.8082469 -0.2707901 0.5172031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7129 7150 0.204847 1.057499 -0.067675 0.6900336 -0.6746213 -0.2574643 0.0495157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7129 7269 -0.953697 0.415701 0.537048 0.4302201 -0.7961517 -0.0786189 0.4181772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7131 6471 0.762049 0.743551 -0.224189 -0.2175708 -0.8949298 0.3347308 0.1992960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7131 7108 -0.595462 0.622246 0.220320 -0.8139300 0.2964562 0.4938293 0.0759232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7131 7148 0.636363 -0.791664 -0.311819 0.0794215 -0.9552387 0.0656023 0.2773221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7131 7271 -0.777930 -0.753258 0.238370 0.0326813 0.1386858 0.6472722 0.7488237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7132 7272 0.484495 0.734224 0.403838 0.5065431 0.7267888 0.3680834 0.2823238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7133 7106 0.039318 0.755051 0.605707 0.3544067 0.0373050 -0.9217195 0.1530926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7133 7146 -0.105244 -0.855951 -0.433908 -0.0623910 -0.0384254 0.9940127 0.0810525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7133 7273 -0.471081 -0.540510 0.683978 0.0597308 -0.3217357 -0.2998402 0.8961106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7134 6474 0.907482 0.328204 -0.463963 0.0201593 -0.9685477 0.2178346 0.1185626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7134 7145 0.549803 -0.938183 -0.003862 -0.1532525 -0.7112754 0.0877392 0.6803696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7134 7274 -0.934809 -0.442738 0.477354 0.1167172 -0.0982688 -0.1828298 0.9712330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7135 7144 0.785176 -0.450209 0.444478 -0.2429097 -0.5566688 -0.0952401 0.7886977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7136 7143 0.653785 0.162412 -0.733826 -0.8507278 0.4323647 -0.0158339 0.2984497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7136 7276 0.260872 0.675937 0.623075 -0.8214183 -0.2296972 0.2043185 0.4803802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7137 6477 -0.052200 -0.845633 -0.644127 0.1708106 -0.8585804 -0.4817358 0.0399257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7137 7142 0.593546 -0.526281 0.710843 -0.4649548 0.4158354 -0.2375074 0.7446396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7137 7277 0.035170 0.901446 0.446344 -0.3720304 0.8299857 0.3303388 0.2521773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7138 7141 0.308737 0.952080 0.499194 -0.1460344 0.1760483 -0.2508018 0.9406271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7138 7278 -0.652382 -0.174427 0.794371 -0.1720586 0.1451688 -0.7516877 0.6199093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7139 7279 0.231298 -0.949308 0.401858 -0.0834322 0.4173608 -0.6679451 0.6104902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7140 7179 -0.671981 0.896839 0.096596 0.2467125 0.3290976 0.3932224 0.8223162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7140 7240 0.337484 -0.119910 1.020952 -0.5725454 -0.0219324 -0.6853020 0.4495241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7141 7178 -0.222314 0.686336 0.870413 0.9015703 0.0112445 -0.2371338 0.3616796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7143 7176 0.486433 -0.162227 0.808563 0.2106118 -0.7750474 0.4889087 0.3404591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7143 7243 -0.753573 -0.780835 0.135757 0.2088331 -0.3679157 0.8223204 0.3805470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7144 6444 -0.518288 0.469916 -0.654097 0.3342258 -0.1444528 -0.1804191 0.9137152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7144 7175 0.680193 -0.142173 -0.744342 0.3344804 0.4824666 -0.3170081 0.7448857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7144 7244 0.424742 -0.423421 0.698338 -0.2296107 0.4964658 -0.7724002 0.3227981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7145 7174 -0.434787 -0.912737 -0.500814 0.0552212 -0.0755954 0.7452948 0.6601300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7145 7245 0.442974 -0.629484 0.740622 0.3844802 0.5949662 0.3910337 0.5876077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7146 7173 0.072949 0.869225 -0.552650 0.0545231 -0.2808300 0.9044713 0.3163753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7146 7246 0.314264 0.511328 0.917263 0.2210027 -0.3395461 -0.8408754 0.3588800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7147 7132 -0.204674 0.796184 0.511622 0.7747962 0.2299166 0.3499161 0.4736960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7147 7172 0.105020 -0.912680 -0.759492 -0.1047291 0.8337839 -0.0736943 0.5370339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7147 7247 0.476747 -0.404338 0.656889 -0.0253900 0.5303799 -0.8163763 0.2271170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7148 7171 -0.853856 -0.778021 0.280936 0.3055262 0.8041884 0.2102688 0.4644586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7148 7248 0.727605 -0.427414 0.184626 -0.0252601 0.8545678 -0.2928212 0.4281724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7149 7170 0.127383 0.448090 -1.016730 -0.6948949 0.0834990 0.4084052 0.5859643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7149 7249 0.179250 1.134733 0.294829 -0.1875827 0.4378739 -0.1884160 0.8588240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7150 7169 -1.059872 -0.420606 0.263337 0.4892185 -0.2657236 -0.7781790 0.2906778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7150 7250 -0.382828 1.099609 -0.017476 -0.0002275 -0.0027088 -0.8846705 0.4662089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7151 7168 0.158532 -0.385605 -0.918590 0.6046300 0.5623116 -0.0640209 0.5604727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7151 7251 0.576363 -0.733943 0.437858 -0.0664215 -0.0272614 0.2790363 0.9575927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7152 7167 -0.028996 -0.985821 -0.176584 -0.6112591 0.0704157 -0.5601125 0.5546872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7153 7166 -0.360484 -0.908003 0.039444 0.3098366 -0.3301393 0.7726126 0.4450609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7153 7253 0.498256 -0.172223 0.643803 0.0520444 0.4391363 -0.8476318 0.2932082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7154 7254 0.869658 0.069192 0.637516 -0.2533151 0.0288252 -0.7506400 0.6095409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7155 7164 0.582956 0.013452 0.804971 -0.3775822 0.4397025 -0.8147812 0.0150012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7155 7255 -0.503114 -0.771576 0.295164 0.2939527 0.6354461 -0.0521215 0.7120979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7156 7163 -0.448090 0.684717 -0.630719 -0.4343653 -0.7130637 -0.0026459 0.5503271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7156 7256 -0.448148 0.393421 0.958749 -0.2034670 -0.0798733 -0.8274033 0.5173250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7157 7162 1.011795 0.210931 -0.068407 0.7259797 -0.1275521 0.4931750 0.4620199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7158 7161 -0.438352 -0.637016 0.696868 0.7128004 -0.0966326 0.5483496 0.4264863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7158 7258 0.880469 -0.434412 0.182195 -0.7949077 -0.3949506 -0.4590559 0.0374619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7159 7259 -0.783671 -0.466290 0.628754 0.1749263 -0.3120619 -0.5134819 0.7799708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7160 7199 -0.009556 0.968816 0.268895 -0.6343591 0.1608913 0.5922891 0.4699958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7160 7220 -0.516770 -0.084836 0.567142 -0.4295280 -0.2025101 -0.0611238 0.8779290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7161 7198 -0.202153 1.133437 0.168873 0.0975451 -0.0332217 0.3209188 0.9414841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7161 7221 0.605285 0.195766 0.884974 0.1609984 -0.1075076 -0.5255234 0.8284605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7162 7197 0.423648 -0.777678 0.501740 0.3125456 0.4986223 -0.0283263 0.8080153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7162 7222 0.220923 0.581116 0.777826 -0.3904097 0.6232115 0.3682807 0.5688207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7163 7223 0.771196 -0.519986 0.088845 0.8752845 -0.1837011 0.3431619 0.2870032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7164 7195 0.112739 -0.841619 0.647918 0.0846512 -0.0929998 -0.0905558 0.9879195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7164 7224 0.850384 0.576635 0.515556 0.1768562 0.3179303 0.8043442 0.4697581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7165 7154 -0.631769 0.177385 0.922400 0.1074196 0.0106718 -0.2168176 0.9702254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7165 7225 0.770292 -0.278524 0.723899 -0.2990264 0.6553573 -0.6895171 0.0752074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7166 7193 -0.366321 0.470203 0.871357 0.5902734 0.5433183 -0.1807888 0.5689445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7167 7192 0.733469 0.465772 -0.770637 0.9130067 0.2330187 -0.0788604 0.3254261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7167 7227 0.731884 -0.749340 0.204098 0.9388560 0.2285287 0.2569952 0.0166597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7168 6428 0.384327 -0.445264 -0.758301 -0.0906896 0.6765464 0.6642780 0.3046229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7168 7191 0.575736 -0.557520 0.492563 0.2589478 -0.7128465 -0.2778538 0.5895703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7168 7228 -0.383467 0.584107 0.930248 0.0269581 0.3468393 0.3804741 0.8568636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7170 6430 -0.196309 0.523554 -0.737576 -0.1659790 0.0773555 0.3416415 0.9218179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7170 7189 0.742404 0.729570 0.192148 0.1663124 -0.6668412 0.7077534 0.1635485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7170 7230 -0.034172 -0.566514 0.696109 -0.3176918 -0.0658486 0.5375226 0.7783350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7171 7188 -0.450705 -0.506588 -0.521123 0.0052868 0.4710185 -0.8419859 0.2630084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7171 7231 -0.901174 -0.220535 0.777401 -0.1511742 -0.2119141 0.4467894 0.8559311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7172 7187 0.495241 -0.702089 0.377179 0.3114429 -0.2997643 -0.0718336 0.8988797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7172 7232 -0.953383 -0.397497 0.175346 0.4422000 0.0287793 -0.7650887 0.4671939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7173 7186 0.285102 -0.317130 -0.894619 0.2112103 -0.1252972 0.9678446 0.0544760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7173 7233 0.083691 -0.824061 0.210673 -0.1064586 0.7781857 -0.2239438 0.5770119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7174 7234 -0.492275 -0.333916 0.805279 0.6368561 -0.3698944 0.1644078 0.6561726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7175 7184 0.850004 0.377410 0.206706 0.1772135 -0.0462350 0.3844220 0.9048079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7175 7235 -0.367583 0.118516 0.871839 -0.4629173 -0.1451018 -0.4843798 0.7280310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7176 7236 0.514482 -0.087253 0.683137 0.5630102 0.1192227 -0.4129868 0.7058663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7177 7142 0.229260 -0.823232 0.070461 -0.7392490 -0.0213467 0.6633201 0.1142875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7177 7237 -0.611746 -0.085729 0.765661 0.4412949 0.2650122 -0.8012058 0.3051173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7178 7181 -0.686231 0.018341 -0.721384 -0.7785186 -0.3155277 -0.3561089 0.4093134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7178 7238 -0.429646 0.511455 0.433441 0.3867418 0.1502774 -0.7886482 0.4537417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7179 7239 -0.264682 0.424410 0.827143 -0.1876315 -0.5206614 0.2521391 0.7938086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7180 7200 -0.289664 0.593776 0.690212 -0.3298371 -0.0030320 0.3451157 0.8786885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7181 7201 0.387412 -0.919753 0.064066 0.3049822 0.7272941 0.1414629 0.5983455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7182 7177 -0.460701 0.101060 -0.778731 0.6464635 0.1157428 -0.4906789 0.5726454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7182 7202 -0.773179 -0.665108 0.557705 -0.5343141 -0.2023878 0.3653305 0.7349023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7183 7176 0.124735 0.811243 0.647563 0.2328735 0.2390657 -0.0918964 0.9381751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7183 7203 0.829222 -0.324034 0.584861 -0.7212394 -0.0038426 -0.6803227 0.1302305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7184 6404 -0.177046 -0.756504 -0.822496 0.1947960 0.1560903 -0.8829705 0.3975592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7184 7204 -0.024104 0.853027 0.527249 0.2697629 0.1332337 0.2564539 0.9185359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7185 7174 -0.762622 0.796452 -0.071096 -0.3778667 -0.1330924 0.8920087 0.2093411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7185 7205 -0.265584 -0.280803 1.056980 -0.0398416 -0.3613688 0.2774372 0.8892996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7186 7206 -0.031272 0.762380 0.722265 0.1992740 -0.3101492 -0.2973102 0.8807406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7187 7207 -0.075599 -0.290387 0.808816 -0.2939749 -0.1767937 0.8568809 0.3848089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7188 6408 -0.476503 0.798867 -0.233552 -0.0382344 0.6605725 -0.7477518 0.0552203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7189 7209 0.278437 -0.693915 0.613404 0.0109730 0.6809436 -0.6739516 0.2863297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7190 7169 0.632535 0.598840 -0.329774 -0.0681602 -0.3785028 0.8698914 0.3088346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7190 7210 0.604259 -0.299596 0.646141 -0.0941025 -0.5965314 0.6745652 0.4245666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7191 7211 0.346082 0.848589 0.361204 -0.8888478 0.0042460 -0.3418532 0.3050705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7193 7213 -0.802484 0.403449 0.314192 0.0392969 0.1617440 -0.9860478 0.0021084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7194 7165 0.433169 0.551556 0.496485 -0.1338192 0.0901279 -0.7592467 0.6304870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7194 7214 -0.130035 -0.464523 0.710889 -0.1053062 -0.3783644 -0.9107983 0.1272693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7195 7215 0.807795 0.566698 0.122730 -0.3769949 -0.7727748 -0.3656950 0.3563159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7196 7163 -0.018950 -1.127007 0.351947 -0.7375133 0.0039527 -0.0000811 0.6753211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7196 7216 0.897663 0.202978 0.475269 0.7777686 -0.0524624 0.5603716 0.2798346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7197 6417 0.353253 -0.969362 -0.156805 -0.3639589 0.0306551 0.6569212 0.6595822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7198 7218 0.230049 -0.277407 0.948290 0.0827025 0.4565151 0.7141851 0.5241124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7199 7219 -0.753426 0.277550 0.385635 0.6116990 -0.5033175 -0.5495297 0.2655426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7200 7239 0.012181 0.954248 0.057512 -0.4848143 -0.0515014 -0.8460037 0.2158249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7200 7980 0.043166 0.062354 0.974551 -0.3250803 -0.3269047 -0.1902630 0.8667503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7201 7238 0.154015 0.592593 0.768135 0.3641991 0.3904559 -0.2119822 0.8185150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7201 7981 -0.669213 -0.462956 0.585737 -0.4797274 -0.4636203 0.4315942 0.6071609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7202 7237 -0.235786 0.906585 0.073102 -0.1983414 -0.3457616 -0.0073273 0.9170910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7204 7235 -0.596030 0.335435 -0.480947 0.6248906 0.1176724 0.7717599 0.0071847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7204 7984 0.324253 0.987270 0.432893 -0.2735077 0.1226471 -0.9065525 0.2971765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7205 7234 -0.177206 0.929529 0.554356 0.5899004 0.3786729 0.6851743 0.1978902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7206 7233 0.954186 0.135963 -0.181814 -0.2418870 -0.0662388 0.9644445 0.0833664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7206 7986 -0.146702 0.742729 0.257758 -0.0895469 -0.3028953 -0.3725131 0.8726224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7207 7232 0.781398 0.357243 0.258226 -0.0116896 -0.2542829 0.8618208 0.4387122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7207 7987 -0.392598 -0.027617 0.932517 -0.1013363 -0.1656822 0.7089000 0.6780421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7208 7188 0.822952 0.326198 -0.224529 -0.2337388 -0.6181318 -0.4695677 0.5854788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7208 7988 -0.982671 -0.517644 0.232257 -0.2960518 -0.6242302 0.5350037 0.4862726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7209 7230 -1.082049 -0.137354 -0.194922 -0.3434331 -0.0181056 0.3834925 0.8571227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7209 7989 -0.114950 -0.548740 0.948298 0.5559440 0.0202300 -0.2066143 0.8048773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7210 7229 0.007651 -0.059707 -0.884580 0.5452132 -0.3485645 -0.6097761 0.4576225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7211 7228 -0.125684 -0.502859 -0.909872 0.1981377 0.0455650 -0.9784859 0.0350811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7212 7227 0.095281 0.907832 -0.680513 0.4119641 -0.3311337 0.0243444 0.8485537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7212 7992 -0.034855 0.402387 0.827324 -0.4888336 -0.4053175 -0.7131299 0.2969936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7213 7226 -0.436524 0.001671 1.003684 -0.0009210 -0.0750811 0.7637530 0.6411266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7213 7993 0.896980 -0.460586 0.297401 0.2392031 0.0633591 0.9616395 0.1183934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7216 7996 0.611277 -0.349250 0.595538 0.2213166 -0.1725789 0.9300085 0.2373178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7217 7197 0.289731 1.052800 -0.015152 -0.0151357 -0.0557116 0.9298080 0.3634889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7217 7222 -0.354305 -0.008306 -1.054638 -0.5594820 -0.5417298 0.5519776 0.2980428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7217 7997 -0.459184 -0.783539 0.152699 0.5280575 -0.5749536 0.5672836 0.2622460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7218 7998 -0.661742 0.447184 0.653487 -0.2566762 0.1240233 -0.8045929 0.5209278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7219 7999 -0.356382 0.430633 0.524223 -0.5374490 -0.3101195 0.7320361 0.2812431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7220 7259 0.044268 -0.207739 -0.884165 0.0984207 0.6757362 -0.6372140 0.3572844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7220 7960 -0.276693 -0.895872 0.398513 0.8275267 0.1110995 0.1474451 0.5302041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7221 7218 -0.920201 0.373856 -0.254441 0.1856858 -0.4175066 -0.8185686 0.3480725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7221 7258 1.027799 -0.307247 0.117751 0.3611037 0.3726441 0.2308761 0.8230655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7221 7961 0.107367 0.574119 0.601677 -0.3070459 -0.1182682 0.6924219 0.6420960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7222 7257 0.522847 0.618895 0.375410 -0.2201531 -0.0040640 0.9568866 0.1894309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7222 7962 -0.784555 -0.265879 0.727580 -0.0499181 -0.3258780 -0.9320318 0.1504273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7223 7216 0.682661 0.347726 -0.732911 0.4955486 -0.1420435 0.5225446 0.6791188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7223 7963 0.814082 0.150189 0.807825 0.0409246 0.0844837 -0.9441851 0.3157564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7224 7215 -0.712002 0.532184 0.261422 0.6331856 0.2759413 0.4573827 0.5601191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7225 7214 -0.487242 0.546037 0.401946 0.7937302 -0.1480072 0.5472572 0.2204444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7225 7254 0.576670 -0.397798 -0.682356 0.5892803 -0.1375145 0.2378647 0.7597755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7225 7965 -0.236840 -0.795620 0.717344 0.0741452 0.2301437 0.0122600 0.9702505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7226 7253 0.131731 0.519534 0.848146 0.6490110 0.5631556 -0.4777420 0.1827652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7226 7966 -0.555382 -0.650420 0.257677 -0.3083732 -0.5251655 0.7530265 0.2491149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7227 7252 -0.375644 0.243741 -0.856151 0.1703556 0.8173629 0.5262676 0.1610565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7227 7967 0.511106 0.852051 -0.047115 -0.3721366 0.7211363 0.5787743 0.0806046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7228 7251 0.257063 0.593336 -0.736825 -0.8961928 -0.1976393 -0.2528857 0.3063104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7228 7968 -0.324872 0.740277 0.322543 -0.1088831 0.1061927 -0.9502557 0.2718117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7229 7169 -0.848742 -0.329604 -0.390667 -0.3138236 0.5141670 0.6653294 0.4410031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7229 7250 0.466509 -0.895475 -0.009412 -0.1620025 0.0250310 0.9442398 0.2855519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7229 7969 0.914181 0.243313 0.401452 0.6617256 0.1076265 0.6665954 0.3258624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7230 7249 -0.669162 0.595376 0.181885 0.9557827 0.0475770 -0.2890703 0.0255798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7231 7208 -0.775835 0.190703 -0.437677 -0.7494091 0.0331628 0.6386041 0.1716711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7231 7248 0.937635 -0.133002 0.474352 0.2465841 0.1097421 -0.8689368 0.4148516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7231 7971 -0.498065 0.242265 0.922407 -0.6474812 0.1965172 0.4655045 0.5704864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7232 7247 -0.039318 -1.019440 0.000531 -0.1848200 0.3824727 0.1540741 0.8920859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7232 7972 0.457388 0.000735 0.916714 0.1162296 0.7670287 -0.5478818 0.3130228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7233 7246 -0.697901 -0.243644 -0.722921 -0.1991820 -0.2519866 0.9164200 0.2387544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7233 7973 0.288159 -1.062976 0.277340 0.2678900 0.7439364 -0.5912798 0.1586880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7234 7245 0.912347 -0.228619 0.246474 0.0576645 0.0817640 -0.5809742 0.8077490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7234 7974 0.267122 0.866714 0.610496 -0.8581432 0.3258060 0.2285189 0.3243760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7235 7244 -0.329567 -0.646162 -0.640169 0.2466719 0.2782985 -0.1957096 0.9074143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7235 7975 0.509590 -0.793588 0.480448 -0.3563913 0.5917943 -0.3774127 0.6167045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7236 7976 -0.309891 0.974183 0.167633 -0.8925753 0.0879625 -0.3412358 0.2813006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7237 7242 0.219041 0.784387 0.584292 0.0874176 0.4065516 -0.5086202 0.7539095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7237 7977 -0.508014 -0.672981 0.914349 0.4668159 0.1724931 -0.1430891 0.8554850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7238 7241 -0.801174 0.696987 0.318331 0.0558624 -0.8034696 -0.3836690 0.4517898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7238 7978 -0.671764 -0.542692 0.166006 -0.1186528 -0.0472741 0.6241059 0.7708298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7239 7979 0.824055 -0.315210 0.515736 0.3001574 0.6379790 -0.3810951 0.5980425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7240 7279 0.489402 1.093107 0.011940 -0.5306930 0.1987872 -0.6233928 0.5387299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7240 7940 0.826471 -0.279234 0.309035 0.5277338 0.7324349 0.4000740 0.1580408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7241 7141 -0.937516 0.527904 -0.017533 0.2589221 -0.7904375 0.5131971 0.2116523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7241 7278 0.026137 0.505657 1.001313 0.5912546 -0.5170392 0.3115292 0.5348253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7242 7142 0.260235 0.811311 -0.654892 0.1462543 0.0916269 0.4316551 0.8853745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7243 7236 0.047058 -0.736152 0.797464 0.2565240 -0.3234777 -0.2690965 0.8701406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7243 7276 -0.053582 0.756159 -0.693956 -0.6815205 -0.0293046 -0.7297505 0.0462090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7243 7943 0.080840 0.787884 0.645217 -0.6794544 -0.2065474 0.5526875 0.4361380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7244 7275 0.387914 -0.720192 -0.356084 -0.3935457 0.2145039 -0.0889541 0.8894926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7244 7944 -0.029847 -0.250305 1.075999 0.3909790 -0.3625704 0.8275171 0.1757655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7245 7274 0.641273 0.991036 0.299163 0.1808333 -0.1631163 -0.6076844 0.7559180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7246 7273 0.658325 0.792393 0.019800 -0.2334140 -0.5204367 -0.4718621 0.6723166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7246 7946 -0.872694 0.661694 0.517506 0.3889604 -0.7306100 -0.0219775 0.5607458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7247 7947 -0.552175 -0.381083 0.847907 0.2646101 -0.0765603 -0.4004097 0.8739520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7248 7271 -0.598828 0.812565 0.129707 -0.1103294 0.3926148 0.6139785 0.6758042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7250 7269 -0.872403 0.628943 -0.210690 -0.2752971 0.0174584 0.9537404 0.1195236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7250 7950 -0.612358 -0.831098 0.110780 -0.2291698 -0.8717244 -0.0568392 0.4293566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7251 7951 0.114614 -1.060344 0.230853 0.6064527 0.1514227 -0.2465114 0.7406203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7252 7152 -0.074510 -0.347166 -0.871226 -0.1596784 -0.1421774 -0.9402792 0.2648838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7252 7267 0.402733 -0.760437 0.460440 0.2296376 0.6964613 0.6332987 0.2472670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7253 7953 -0.660650 -0.042814 0.742870 -0.2770029 0.3168680 0.7017872 0.5747685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7254 7265 0.050986 -1.064308 0.412057 -0.5524478 -0.3613228 0.7066405 0.2547675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7254 7954 -0.171951 0.425647 0.946450 0.0826602 -0.3538056 -0.2957207 0.8834807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7255 7224 -0.744053 0.532070 0.672987 0.4785168 -0.2299058 -0.1981883 0.8239456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7255 7955 -0.605954 -0.773381 0.073772 0.6474637 -0.0739258 -0.6710513 0.3535758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7256 7223 -0.381866 -0.734699 -0.275808 -0.3160573 0.1189932 -0.8075453 0.4835484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7256 7263 0.509842 0.767372 0.355517 0.3378441 0.2682797 0.2365331 0.8705972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7257 7262 -0.276925 -0.837827 0.364057 -0.0177869 0.7506609 0.5091460 0.4206688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7258 7261 0.217245 -0.184718 0.961979 -0.3133990 -0.0216490 -0.9393981 0.1372721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7258 7958 0.145400 0.921361 0.223637 -0.2663661 -0.7343087 -0.6206671 0.0679131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7259 7959 0.460518 -0.599122 0.600491 0.7040686 0.2967175 -0.5798991 0.2827776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7261 7298 0.499862 0.105581 1.005716 0.2690023 -0.2718721 0.3576217 0.8519566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7261 7921 -0.291267 -0.909431 0.281597 0.1054014 -0.4671519 -0.2720839 0.8346436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7262 7922 -0.519912 0.716658 0.507508 -0.3022603 0.2198046 0.9274939 0.0089322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7263 7296 0.584273 0.684661 0.202844 -0.7974304 0.0073395 0.3989948 0.4526080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7264 7255 -0.852530 0.634330 -0.085799 -0.7803542 0.5211511 0.3011753 0.1695356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7264 7295 0.955769 -0.517108 -0.190774 -0.0952405 0.2262305 0.4461068 0.8606612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7264 7924 0.553326 0.835063 0.105698 -0.5446355 0.2396143 -0.7482744 0.2933301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7265 7294 -1.034989 -0.002951 0.291214 0.4870091 -0.7902934 0.2837616 0.2402870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7265 7925 -0.231697 -1.073629 0.203265 0.5841671 0.3457272 0.2322062 0.6966360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7266 7293 0.611315 0.649778 0.304071 -0.0752109 -0.3649461 -0.6091016 0.7001092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7266 7926 -0.577637 -0.208783 0.764116 -0.4444926 0.6324060 0.6151068 0.1553470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7268 7291 -0.215691 -0.754556 0.639508 0.2771540 -0.6344201 -0.6386874 0.3358204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7268 7928 -0.811873 0.528915 0.768749 -0.2740352 0.2748654 0.8328277 0.3946540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7269 7290 0.800383 -0.102950 0.305836 0.2799544 -0.7845742 -0.5326015 0.1496815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7269 7929 0.217917 1.019832 0.136024 -0.6844847 -0.1594653 -0.3487236 0.6200350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7270 7130 -0.219095 0.007303 -0.951265 0.7711498 0.0820260 0.3194582 0.5445605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7270 7249 -0.765291 0.590738 0.210509 0.1283991 0.7032881 0.4964579 0.4923708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7270 7289 0.746370 -0.679596 -0.254434 0.3900563 0.1040130 -0.7385125 0.5400339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7270 7930 0.178943 -0.169386 0.851207 0.4161631 -0.3452889 0.0941408 0.8358955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7271 7288 0.403292 0.943308 0.203850 -0.2412061 -0.9323790 -0.0504262 0.2644736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7271 7931 -0.944540 0.574837 -0.040854 -0.3359599 -0.6597411 0.2277139 0.6324705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7272 7247 -0.296127 0.469405 -1.019697 -0.5568901 0.5673621 -0.1246545 0.5936622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7272 7287 -0.287699 -0.465251 0.781698 0.5404945 0.7230502 0.1779702 0.3916513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7272 7932 0.814241 0.641821 0.463600 -0.7407240 -0.0285039 0.1535177 0.6534125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7273 7933 0.437164 -0.506564 0.946161 -0.3913347 -0.0796302 0.8030370 0.4423208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7275 7135 0.112219 0.832686 -0.210409 -0.2135085 -0.5244751 0.7198636 0.4014179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7275 7284 0.607694 -0.404252 -0.589230 0.5074448 0.0032295 0.0761725 0.8583048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7275 7935 -0.271350 -1.039447 0.265311 0.7310854 0.1170459 -0.6674907 0.0791869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7276 7936 0.690977 -0.667227 0.069679 -0.0096545 0.1420140 -0.9717942 0.1880288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7277 7242 -0.686368 -0.526133 -0.725297 0.4232035 0.0582511 -0.8409421 0.3321476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7277 7282 0.617583 0.323958 0.782170 0.2624996 -0.8372389 0.0954344 0.4701247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7277 7937 -0.754550 0.548516 0.372883 -0.1775686 -0.7468121 -0.5918027 0.2459891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7279 7939 0.419970 0.121699 0.854966 -0.2976187 -0.6274687 -0.7173436 0.0558954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7280 7319 -0.503392 -0.393915 -0.703221 -0.0982624 -0.7105991 0.5150411 0.4691759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7280 7900 0.439537 -0.831131 0.075737 -0.8746135 -0.0076384 -0.4835554 0.0341610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7281 7278 -0.423792 -0.402278 -0.761526 -0.4908048 -0.7334830 0.0639473 0.4658584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7281 7318 0.477419 0.290816 0.631049 0.4541792 -0.7330431 -0.3581492 0.3579081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7281 7901 -0.853210 -0.004867 0.534517 0.2890137 0.2475330 -0.9104139 0.1623115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7282 7317 0.389330 0.187586 -1.063446 -0.7439054 0.0157994 -0.6292530 0.2244900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7282 7902 0.300196 0.986554 0.169999 0.0086811 0.3901500 0.7343943 0.5553132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7283 7276 0.741288 -0.451436 0.404986 -0.0746855 -0.1575144 -0.5220045 0.8349387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7283 7316 -1.028759 0.318144 -0.237112 -0.0084013 0.0351570 -0.4709147 0.8814379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7283 7903 -0.348963 -0.683214 0.348142 0.4447012 0.3524297 -0.7397603 0.3616475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7284 7315 0.549066 -0.714388 -0.055464 -0.1005369 0.3064120 0.2882229 0.9016272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7285 7105 -0.185841 -0.871375 -0.399216 0.0662216 0.6044788 0.7713057 0.1879029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7285 7274 -0.419259 0.483698 -0.718610 -0.3441620 0.2756120 0.8882170 0.1290781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7285 7314 0.472212 -0.842541 0.721854 0.4092575 0.5202722 0.7201970 0.2077050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7286 7273 -0.513578 0.250299 -0.789267 0.3336634 0.4391434 0.8314611 0.0670401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7286 7313 0.787738 -0.057374 0.751329 -0.0840021 0.9462648 0.0919111 0.2984610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7286 7906 0.109836 1.069066 0.317550 -0.6791752 -0.2973249 0.0664969 0.6677553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7287 7312 -0.762773 0.339665 -0.652171 -0.3155010 0.1402010 0.9270005 0.1465360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7287 7907 0.557253 0.806619 0.198887 0.4480878 0.6372468 0.4884384 0.3931434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7288 7311 0.199963 1.090948 -0.350665 0.1562565 -0.0637876 0.8933508 0.4164607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7288 7908 0.763767 -0.107024 0.547108 0.2202600 -0.0791535 0.3408376 0.9105218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7289 7310 0.700717 0.723669 -0.399149 -0.9107374 -0.0970964 -0.0451596 0.3988612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7289 7909 -0.353198 0.613358 0.603025 -0.1691704 -0.8043473 -0.5689480 0.0265507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7290 7309 -0.512611 -0.067910 -0.986357 0.0388777 -0.2292251 0.2045903 0.9508350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7290 7910 -0.686720 0.539378 0.575933 0.2454899 -0.1724789 0.0339244 0.9533283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7291 7911 0.151694 0.661332 0.701264 -0.0536669 -0.1347342 0.8021402 0.5792561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7292 7112 -0.542646 0.498932 -0.495809 0.6167202 0.1128651 0.7699514 0.1187120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7292 7267 -0.533124 -0.080735 0.800245 -0.2244729 -0.2398757 -0.8634581 0.3827684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7292 7912 0.796968 -0.357559 0.422120 0.9509340 0.0945200 0.1071037 0.2744435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7293 7306 -0.407038 0.898101 0.508900 -0.3513870 0.6045076 -0.4928277 0.5178983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7294 7305 0.235937 0.869115 0.009920 -0.4028257 0.3922986 -0.8148378 0.1409707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7294 7914 0.903229 -0.302989 0.480597 -0.7339707 0.3384706 -0.5435073 0.2265490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7295 7115 -0.784510 0.047768 -0.761152 0.7285477 -0.0657563 0.6687434 0.1329537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7295 7304 -0.078497 -1.053096 -0.026544 -0.1146579 -0.4504930 -0.5755855 0.6727636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7296 7303 0.662342 -0.838303 -0.056539 0.9801852 -0.0472533 -0.0102760 0.1920897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7297 7262 0.200955 0.835096 0.035992 -0.4133138 0.3067342 0.5670127 0.6431037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7297 7917 -0.619809 -0.051390 0.622183 0.3021488 -0.1300649 0.2855690 0.9001331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7298 7301 1.006643 0.039091 0.266619 0.5585835 0.2694070 -0.2336381 0.7488776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7298 7918 -0.524592 -0.321246 0.938993 0.6876088 0.0910121 -0.6469293 0.3168492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7299 7260 0.086986 0.845902 -0.417783 -0.4364605 0.0903574 -0.2767496 0.8513210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7299 7919 0.627178 0.551027 0.773214 -0.1417973 -0.0414504 0.5543161 0.8190904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7300 7339 0.311062 -0.112768 -0.744165 -0.9790817 0.0898469 0.1309458 0.1272000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7300 7880 0.213280 0.995832 -0.106124 0.2426730 0.7665063 0.5789291 0.1357166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7301 7081 0.909586 -0.476568 -0.381889 -0.4209577 -0.3764663 0.4851142 0.6676316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7301 7881 -0.908311 0.374697 0.461815 -0.6736691 -0.1822427 0.7135533 0.0616374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7302 7882 -0.197443 -0.799014 0.036731 0.7200058 0.5705693 -0.2786985 0.2799456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7303 7336 0.769792 0.633156 0.245355 0.3063401 -0.6862401 0.0022074 0.6597162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7303 7883 -0.711204 0.612252 -0.153979 -0.6808848 -0.0985239 0.1331942 0.7134061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7304 7335 0.785352 -0.151557 -0.628389 -0.3481207 -0.6076493 -0.1554270 0.6967185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7305 7334 -0.816095 -0.632075 -0.172510 0.2814916 -0.1498430 -0.6310498 0.7071674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7306 7086 0.043168 0.706219 -0.842603 -0.3011285 -0.6860557 0.3497017 0.5624570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7306 7333 -0.972244 -0.153205 -0.535642 -0.3392063 0.0205524 -0.9161699 0.2124838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7306 7886 -0.082590 -0.744107 0.801285 0.7862114 -0.3257640 -0.1951525 0.4875090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7307 7292 -0.896148 0.105964 -0.674944 -0.4888971 -0.5996649 -0.0121623 0.6334302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7307 7332 0.738449 -0.106266 0.717995 -0.4473277 0.4371778 0.7711642 0.1186559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7308 7291 -0.768016 -0.356425 -0.509905 0.6005860 -0.1748048 0.0013846 0.7802165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7308 7888 -0.284584 -0.690590 0.684545 0.7539603 -0.0082644 -0.3272734 0.5695329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7309 7330 -0.784182 0.063151 -0.666852 -0.9053498 0.1503450 0.1466484 0.3690968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7309 7889 0.022749 0.784937 0.565518 -0.1033193 -0.5318026 0.0495263 0.8390818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7310 7329 0.605536 -0.258547 0.689835 0.2252241 0.0399907 -0.8939649 0.3853589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7310 7890 -0.303861 -0.879056 0.128599 0.4308025 -0.7692484 0.4312147 0.1916247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7311 7328 0.481935 -0.643843 -0.526939 -0.3507935 -0.6093597 0.5971913 0.3859886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7311 7891 -0.295664 -0.730215 0.772356 0.0752756 0.0508913 0.5110034 0.8547627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7312 7092 0.174209 0.920246 -0.398275 -0.1863297 0.7583704 -0.4337275 0.4494842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7312 7327 1.051170 -0.209667 0.012731 -0.3081998 -0.6634422 0.5758689 0.3650102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7312 7892 -0.307186 -0.928083 0.219019 0.3529939 0.1123773 0.8798187 0.2978016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7313 7326 -1.086965 -0.332672 -0.284264 -0.1579267 -0.5471815 -0.1581213 0.8066283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7313 7893 -0.339318 1.002904 0.141727 -0.1838760 0.3671117 0.7797455 0.4726685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7314 7325 -0.498408 0.925779 0.019022 -0.1212686 -0.1896242 -0.7090441 0.6682762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7315 7324 -0.100940 -1.045398 0.123234 0.0902604 0.2938339 -0.9512638 0.0247347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7315 7895 -0.950353 0.182576 0.482108 -0.0932630 -0.2586520 0.9155579 0.2935216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7316 7323 -0.561098 -0.622261 -0.368519 0.5449939 0.5205609 0.6274904 0.1955858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7317 7322 -0.952633 0.415099 0.421373 0.6226924 -0.1390857 -0.2657434 0.7226962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7317 7897 -0.165676 -0.795306 0.789109 0.2430371 0.1316306 0.2835523 0.9182616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7318 7321 -0.387455 0.736548 -0.603562 0.0864266 -0.3108396 0.9465182 0.0035279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7318 7898 0.309425 0.684194 0.540641 0.2787777 -0.3713219 -0.6443266 0.6076564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7319 7099 0.538605 0.652442 -0.376673 0.6819300 -0.0998635 -0.7082956 0.1526964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7319 7899 -0.516264 -0.802950 0.198296 -0.0224901 0.0254359 0.6845123 0.7282102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7320 7359 -0.450521 0.881103 0.633693 -0.2767422 0.7745162 -0.4607592 0.3335257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7320 7860 0.826606 -0.053930 0.662466 0.1316942 0.0959860 -0.9860681 0.0333611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7321 7358 -0.099758 -0.140694 -1.152613 0.2131656 0.7021216 -0.0489837 0.6776329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7321 7861 -0.276371 -1.027342 0.163345 0.7529542 0.2046118 -0.4255021 0.4584124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7322 7862 0.246298 0.580626 0.903279 0.1148841 0.1977680 -0.6755318 0.7009609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7323 7863 -0.984607 0.637457 0.253342 -0.6784526 0.1264530 0.6262996 0.3625749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7324 7355 -0.171169 0.545484 0.720457 0.3448624 0.5937517 0.3517252 0.6362532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7324 7864 0.679858 -0.479147 0.409407 0.3824419 0.6396707 -0.3624561 0.5596295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7326 7353 -0.611532 -0.410172 0.668529 0.3369619 0.0787466 0.5960388 0.7245642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7327 7352 -0.438870 -0.216549 -0.689694 0.7517040 0.0985327 -0.0352978 0.6511424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7327 7867 -0.672738 -0.367368 0.669008 0.2005706 -0.4593039 0.0972099 0.8598614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7328 7351 -0.964955 0.396462 0.198539 0.1404013 -0.6488884 0.3134420 0.6789591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7328 7868 -0.436843 -0.812590 0.643463 0.0474426 -0.3578677 0.6301838 0.6874215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7329 7350 -0.565559 0.684621 0.578896 0.5315876 0.7298239 0.1027644 0.4173861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7329 7869 0.973822 0.392362 0.440462 -0.6460635 0.1157541 -0.6726103 0.3417578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7330 7070 0.241507 0.684337 -0.292823 0.0177912 0.0614846 -0.9625345 0.2634964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7330 7349 -0.660482 0.620441 0.576007 -0.0721417 0.4079771 -0.8363977 0.3588720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7331 7348 0.913566 0.075457 -0.520461 -0.3028209 -0.5173738 0.7180866 0.3535188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7331 7871 0.473124 -0.502373 0.509522 0.6689106 0.6249696 0.0657086 0.3970567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7332 7347 -1.027341 0.068082 -0.538272 -0.1429247 0.5638444 0.4381149 0.6853519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7333 7873 0.617358 0.552778 0.252355 -0.1244144 0.6440653 -0.0955643 0.7487112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7334 7345 0.533369 -0.743229 0.315600 -0.0760909 -0.4402807 -0.6319485 0.6332489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7334 7874 0.110514 0.583033 0.795348 -0.8148789 0.1130060 0.2615162 0.5047884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7335 7075 -0.238446 -0.899166 -0.334038 -0.3648836 0.4109326 0.2345145 0.8018711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7335 7344 -0.584337 0.381422 -0.788655 -0.7295446 0.1655017 -0.0373071 0.6625572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7335 7875 0.298664 1.003377 0.233130 -0.5329292 0.4694834 -0.1963001 0.6760459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7336 7876 -0.492513 0.890231 0.483771 -0.1922320 -0.1961878 0.9543989 0.1169616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7337 7302 0.006045 0.794196 0.858784 -0.3385332 0.8980177 -0.0938498 0.2648618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7337 7877 0.691139 -0.624274 0.346612 0.0657690 -0.0650382 0.1670023 0.9816082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7338 7301 -0.845658 0.128598 0.203181 0.8500752 0.4655518 -0.1770331 0.1711517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7338 7341 0.952378 -0.095272 -0.265395 -0.0077553 0.0367145 -0.1593458 0.9865094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7338 7878 -0.101061 -1.154258 0.016637 -0.2194237 0.8156301 -0.2723698 0.4608854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7340 7840 -0.943918 -0.303872 0.122358 0.2284842 -0.4246571 0.7780413 0.4026328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7341 7378 0.947113 0.310724 -0.235266 0.7351855 -0.0605518 0.6082549 0.2930218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7342 7337 -0.638049 -0.212925 -0.847714 0.5661256 -0.8008703 0.1615473 0.1095946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7342 7377 0.538999 0.195113 0.612935 0.3927842 0.3929145 -0.8313954 0.0109703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7342 7842 0.079347 -0.924108 0.236222 0.5180880 -0.0785062 0.8151243 0.2469696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7343 7043 0.022984 -0.937007 -0.231636 -0.1517137 -0.0040735 -0.2734636 0.9498337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7343 7336 -0.146173 0.125990 -1.217202 0.1414848 -0.9538518 -0.2515899 0.0827726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7343 7376 0.142911 -0.203454 0.876729 -0.8658186 0.0094023 0.0825101 0.4934185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7343 7843 0.229294 0.999462 0.104523 -0.0426409 -0.0030360 -0.8837271 0.4660462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7344 7375 -0.376284 0.793280 0.486655 0.7909464 0.2675813 0.0134662 0.5501116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7345 7374 0.807206 0.423345 -0.576622 -0.5755096 0.6019224 -0.2578387 0.4898952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7345 7845 0.241906 0.802320 0.715483 -0.2987487 0.7103420 0.2991023 0.5627621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7346 7373 -0.248623 0.515622 -1.067937 -0.2563694 -0.9216999 -0.0974634 0.2743082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7346 7846 -0.050435 0.869247 0.470755 0.2711700 -0.7954071 -0.4927876 0.2257313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7347 7372 0.562198 0.397159 -0.559753 0.3092732 -0.4753395 -0.5101477 0.6466465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7347 7847 -0.387242 0.827908 0.297860 0.7651444 0.0063386 -0.6085619 0.2101577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7348 7371 -0.394594 0.123871 -0.929421 0.4721592 0.3598840 -0.0148994 0.8045665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7348 7848 -0.709553 -0.475237 0.119946 0.7073439 -0.2108197 0.1564036 0.6563212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7349 7370 -0.330026 -1.082403 -0.178835 0.3750005 0.6829426 0.0780121 0.6219953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7349 7849 0.928816 -0.063281 0.506124 0.1523900 0.0914299 -0.6809217 0.7104671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7351 7368 -0.074783 1.026056 0.456918 -0.0774930 0.7153789 0.1936598 0.6668761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7351 7851 0.389987 -0.489761 0.593437 0.4515965 0.1500071 0.2170672 0.8523147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7352 7052 0.693461 -0.533049 -0.200450 0.2500265 -0.7895218 -0.0930447 0.5527068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7352 7367 -0.712365 -0.769617 0.138610 -0.5648814 0.4287126 0.1085229 0.6966616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7352 7852 -0.776172 0.586451 0.323357 -0.0888796 -0.8450816 0.1620785 0.5016653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7353 7366 -0.415887 0.662279 0.523940 0.0841209 -0.0154604 0.9744849 0.2075183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7354 7325 0.594712 -0.496899 0.744548 -0.2309406 -0.4621735 -0.4924693 0.7003828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7354 7365 -0.543835 0.531630 -0.664820 -0.3196388 -0.0928185 -0.4866120 0.8077280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7354 7854 0.345156 0.872489 0.626093 -0.5248873 -0.6137448 -0.3262162 0.4913182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7355 7055 0.582123 -0.038881 -0.719271 0.3513714 -0.6454525 0.1368381 0.6642324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7355 7364 0.067065 0.924200 0.125456 0.0381795 0.1448327 0.9520256 0.2668578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7356 7363 0.954378 -0.428955 0.374297 0.6105822 -0.2552564 -0.6119370 0.4330897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7356 7856 -0.262120 -0.606773 0.630368 0.4065771 -0.4243142 0.7888309 0.1799952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7357 7322 -0.165256 0.945250 0.678752 0.6801143 0.1959459 0.6713679 0.2198065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7358 7361 1.106702 -0.347507 0.131288 0.5815012 -0.6152055 0.2841581 0.4501474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7359 7859 -0.688575 -0.738393 0.265094 -0.1876000 0.1901319 -0.9615284 0.0641814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7360 7399 0.122156 0.639278 0.582395 0.4792414 0.0699692 -0.6302843 0.6067732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7360 7820 -0.735348 -0.383607 0.290193 -0.4459293 -0.8031059 0.3935985 0.0353283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7361 7821 0.492556 -0.091771 0.800919 0.3941670 -0.1821833 -0.5219627 0.7341638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7362 7397 -0.545662 -0.588843 -0.676743 0.6848846 -0.2937529 -0.4327048 0.5073547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7362 7822 0.186675 -0.655801 0.849929 -0.1818283 0.7127570 -0.4272627 0.5257019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7363 7396 0.043421 0.633613 -0.878870 -0.1489746 -0.1896819 -0.8771032 0.4153521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7363 7823 0.324186 0.839229 0.813978 0.2109447 0.1920626 0.5059534 0.8140181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7364 7024 -0.612117 -0.372968 -0.706021 -0.3239286 0.4287363 -0.7570241 0.3717122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7364 7395 -0.029752 -0.935483 0.179872 0.1676151 0.3652254 -0.0852684 0.9117263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7364 7824 0.599481 0.433895 0.790555 0.3141868 0.1054679 0.8833067 0.3315607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7366 7393 0.747972 -0.472849 0.366850 -0.8288219 -0.1110311 0.5347597 0.1214844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7366 7826 -0.515296 -0.834895 0.274163 -0.0000514 0.3647800 -0.8455025 0.3899501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7367 7392 -0.239326 -0.157905 -0.929656 0.4522135 -0.3197487 -0.6772230 0.4843890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7368 7391 -0.365931 0.857983 0.217526 0.6259568 -0.7527541 0.1747929 0.1048180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7369 7350 0.094069 -0.476215 -0.899021 0.9272037 -0.0639989 0.2247208 0.2927422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7369 7390 -0.104417 0.392806 0.932644 0.1347974 0.7903056 -0.5904402 0.0928827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7369 7829 -0.066731 -0.822251 0.527191 0.3792166 0.1258349 0.6949473 0.5978366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7370 7030 0.720043 -0.700205 -0.646161 -0.2315698 -0.1907481 0.3514721 0.8868247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7370 7389 -0.625130 -0.800877 0.448560 0.2426360 0.2015942 -0.9398151 0.1312823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7370 7830 -0.747737 0.766469 0.499283 -0.1540084 0.2500356 0.8979636 0.3277575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7371 7831 -0.844116 -0.562743 -0.036216 -0.0333453 -0.1378985 0.8317663 0.5366907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7372 7387 -0.785298 -0.342877 -0.656395 -0.2100153 0.2079190 0.1002499 0.9500596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7373 7033 -0.525146 -0.847938 -0.139431 -0.5181576 0.0574643 -0.5845890 0.6216641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7373 7833 0.814960 0.737734 -0.032096 -0.6062241 -0.0487597 0.0532584 0.7920090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7374 7385 -0.029562 0.080417 0.936445 0.4278345 0.0006645 -0.8995667 0.0879603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7374 7834 -0.846678 -0.547689 -0.037478 0.2205770 -0.2803962 -0.4767538 0.8033863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7375 7835 -0.495735 0.888719 0.042156 -0.7623245 -0.5014805 0.0046616 0.4090928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7376 7383 0.054246 -1.014743 -0.678057 -0.4940373 0.0480975 -0.5416056 0.6784373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7376 7836 0.135414 -0.550818 0.844005 -0.2202883 0.0111760 0.9736541 0.0578434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7377 7037 0.687119 -0.672188 -0.546939 0.0622109 0.2738611 0.6415657 0.7138091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7377 7837 -0.402847 0.820409 0.668774 -0.7406214 -0.1817047 0.2263402 0.6059980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7379 7039 -0.197995 -0.232103 -0.931622 0.2577332 0.0106375 0.1402757 0.9559201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7379 7839 0.290732 0.316562 1.127457 0.0247173 -0.6585845 -0.7471037 0.0865541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7380 7419 0.300158 -1.238556 0.188672 -0.3658761 -0.2741416 0.0702243 0.8865944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7380 7800 -0.561219 -0.341602 0.638176 -0.5626907 -0.0809599 0.7779008 0.2677594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7381 7378 1.010120 -0.116791 -0.274267 -0.0245905 -0.2888354 -0.6752026 0.6782852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7381 7418 -0.969502 0.036698 0.111725 0.4184992 0.2497407 0.8403744 0.2371894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7381 7801 0.269554 0.506333 0.953364 0.1288033 0.3859783 0.5923030 0.6954190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7382 7377 -0.471750 0.160730 -0.940796 -0.5981267 -0.1344828 0.7243475 0.3154037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7382 7417 0.326060 -0.036148 1.054562 0.4226888 0.5797606 -0.6493758 0.2520374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7383 7416 0.151852 0.496106 -0.927659 0.0104099 0.1064726 -0.7821810 0.6137981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7384 7375 -0.767444 0.129537 -0.680908 -0.7570305 0.4043769 0.5100585 0.0567842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7384 7804 -0.725189 -0.127396 0.684193 0.9030869 -0.2187359 -0.2472474 0.2746950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7386 7373 -0.331897 -0.888811 -0.007951 -0.1939532 -0.6182065 -0.7457048 0.1553295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7386 7806 -0.185022 -0.036222 0.985511 -0.0814083 0.1326256 -0.5594651 0.8141142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7388 7008 -0.174322 0.514669 -1.001662 0.1487915 0.6488832 -0.6863117 0.2928959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7388 7371 -0.605530 -0.708733 -0.468589 -0.5775672 -0.2737255 0.6842095 0.3512092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7388 7808 -0.022996 -0.525882 0.932962 -0.4378665 0.5419553 -0.3427892 0.6301213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7389 7410 0.255787 0.428618 1.023994 0.5549314 0.2169330 0.5304922 0.6029670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7389 7809 0.043068 -0.761927 0.191634 0.6531456 0.3823943 -0.6409826 0.1277369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7390 7409 -0.082457 -0.647845 -0.675583 -0.4072173 0.1126976 0.8398859 0.3406830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7391 7408 -0.510711 0.424874 -0.718413 0.3998324 0.1821458 0.7513608 0.4923555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7392 7407 0.482200 -0.896252 -0.289489 0.1399121 -0.5547672 0.2171675 0.7908832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7392 7812 -0.520182 -0.275741 0.840357 -0.0418255 -0.8039967 0.3250871 0.4961434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7393 7813 -0.758425 0.777235 0.189073 -0.0951851 0.0859631 -0.7163593 0.6858422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7394 7405 0.231811 -1.027735 -0.410849 0.2486798 -0.1643311 0.3400164 0.8919319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7394 7814 0.709926 -0.155021 0.621769 0.2834035 0.6856882 0.3219691 0.5880902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7395 7404 -0.064997 -0.979976 0.674877 0.1755809 -0.4035388 -0.6601724 0.6086873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7395 7815 -0.021390 0.605299 0.737711 -0.1223268 0.2272001 -0.7106198 0.6545501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7396 7016 0.455746 0.354108 -1.067491 0.0232000 0.0512444 0.9983439 0.0120552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7396 7403 -0.806071 -0.281947 -0.355999 0.2412861 -0.1409327 0.0073492 0.9601380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7396 7816 -0.476892 -0.345675 1.006292 -0.1021594 -0.5259017 -0.7935127 0.2886668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7397 7402 0.409257 -0.284817 0.768982 -0.2774952 0.6733763 0.2864932 0.6224809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7397 7817 0.209560 0.847821 0.272487 -0.5592607 0.4263948 0.6529906 0.2811017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7398 7361 -0.147877 1.154008 0.247492 0.1682862 -0.3187352 -0.1535478 0.9200602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7398 7401 0.238771 -0.933624 -0.310507 0.1308748 0.5801612 -0.7768453 0.2068723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7398 7818 -0.472097 -0.153228 0.908889 -0.2269748 0.1839374 0.9136872 0.2825334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7399 7819 -0.363544 -0.475199 0.909537 0.2377829 0.2825003 0.0610470 0.9273220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7400 7439 0.073875 -0.931905 0.563840 0.0354725 -0.1559526 -0.9714356 0.1753093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7401 7438 0.002653 0.553436 0.954533 -0.2883177 0.7573912 -0.4957567 0.3121808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7401 7781 -0.070283 -0.893637 0.580074 0.1172660 0.2219688 0.9162211 0.3122779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7402 7437 -0.759437 -0.575170 -0.044938 -0.1138833 -0.3472647 -0.4354926 0.8226688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7402 7782 -0.326677 0.298728 0.997452 -0.2555704 -0.0537753 0.6109769 0.7473281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7403 7436 -0.737095 -0.474887 0.080944 -0.0440594 -0.1403713 -0.5990191 0.7871028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7403 7783 -0.062093 0.540757 0.933417 0.5389237 -0.3402855 -0.7426583 0.2054886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7404 7784 -0.369618 0.334110 0.778355 -0.6256754 -0.1349216 0.3039659 0.7056424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7405 7434 -0.369808 -0.860346 -0.047420 -0.3791702 -0.2107048 -0.6385323 0.6356964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7406 7433 0.704518 -0.739418 0.426033 0.3280831 -0.3143048 0.3054210 0.8368345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7406 7786 -0.658101 -0.310609 0.428741 0.3634301 -0.5742242 -0.1750394 0.7124229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7407 7432 -0.265599 -0.862594 -0.008413 -0.0660680 -0.3351042 0.8297604 0.4414043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7408 7431 0.340752 -0.198796 -0.673290 0.3487796 0.7993214 -0.3294408 0.3618105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7409 7430 0.153554 0.776015 -0.696844 -0.1871691 -0.6550579 -0.5039263 0.5309663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7409 7789 -0.826001 0.439353 0.280513 0.1489103 0.0212248 -0.8120819 0.5638247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7410 7429 0.652747 0.642565 0.373456 -0.1009843 0.5951374 0.7956822 0.0500336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7410 7790 -0.599708 0.279512 0.534473 -0.7442588 0.0323596 -0.0835431 0.6618552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7411 7388 -0.741539 0.549649 -0.705610 -0.5584537 -0.1399342 -0.7786601 0.2494720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7412 7387 0.067848 0.750182 0.139773 -0.2255789 0.3887309 0.6199674 0.6431508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7412 7427 -0.060388 -0.838404 -0.112886 -0.0824762 -0.3649010 -0.1570013 0.9139997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7412 7792 -0.003410 -0.029206 1.018304 0.0465052 0.5661472 -0.4408921 0.6949308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7413 7386 0.212713 -0.581341 0.752631 -0.4351227 0.5063395 0.0293983 0.7439249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7413 7793 0.569499 0.608594 0.337749 -0.4457226 0.2395418 -0.5584079 0.6573673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7414 7385 0.904241 -0.247743 0.264375 0.0588161 -0.4803183 -0.2627491 0.8347442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7414 7425 -0.840457 0.224648 -0.508610 -0.0178124 0.4377143 -0.5685295 0.6963211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7414 7794 -0.222828 0.316028 0.926392 -0.2992794 -0.2235586 -0.6615032 0.6502822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7415 7384 -0.892322 -0.656777 -0.196896 -0.7072613 0.0926560 0.0294984 0.7002329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7415 7424 0.801399 0.550443 0.143136 -0.0063837 -0.4253056 0.1244439 0.8964308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7415 7795 -0.762792 0.648319 0.477764 -0.2718477 -0.5486689 0.7566702 0.2291536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7416 6996 -0.365802 -0.960875 -0.244962 0.1093409 0.5260025 0.8077115 0.2428334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7417 6997 -0.228979 0.450800 -0.784950 -0.0607914 -0.1046159 -0.6485417 0.7515009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7417 7422 -0.940761 -0.178166 -0.024924 0.8222880 -0.0361901 0.0202041 0.5675601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7417 7797 0.132946 -0.500209 0.863615 0.5259789 -0.3044812 0.7933255 0.0356653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7418 7798 0.591412 0.094670 0.788458 -0.2718020 0.0859025 0.7500369 0.5968158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7419 7799 -0.416838 -0.814506 0.316134 0.9608756 -0.1306389 -0.0482827 0.2394167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7420 7760 0.304953 0.111498 0.694745 0.0403012 -0.4234314 0.4415569 0.7900058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7421 7458 -0.571352 -0.345792 0.565557 0.7282391 0.3433543 0.0837495 0.5871641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7421 7761 0.702917 0.101223 0.675666 0.0793914 0.4364365 -0.1953295 0.8746808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7422 7457 -0.995826 0.033079 -0.007790 -0.9363233 0.2660635 -0.0679404 0.2188447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7422 7762 0.147289 1.016940 -0.043093 0.1548094 -0.9587497 -0.2234410 0.0831095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7423 7416 -0.413192 0.964087 0.066608 -0.1536572 -0.5597474 -0.8141801 0.0135298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7423 7456 0.299270 -0.897774 0.057588 0.0094557 0.1528248 -0.6130220 0.7750866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7423 7763 -0.209157 -0.093764 1.154661 -0.1746095 0.1243819 0.4383573 0.8728594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7424 7455 0.874493 0.539824 -0.524107 -0.1055329 -0.8878566 -0.4366051 0.0997471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7425 7454 -0.102470 -0.609791 -0.918594 0.7041375 0.1046449 -0.3599433 0.6030594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7425 7765 -0.761693 -0.780191 0.343101 0.6963081 -0.5302844 0.0491200 0.4811867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7426 7413 0.458502 0.826861 0.017405 -0.7782972 -0.1062603 -0.5429120 0.2969995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7426 7766 0.874328 -0.352676 0.179639 0.6503380 -0.0745970 0.3196086 0.6850884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7427 7452 0.114006 -0.932886 -0.347363 0.3687450 0.3823067 -0.4574413 0.7131733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7428 7411 -0.660804 -0.790658 0.546600 0.7949953 0.3636425 0.4144747 0.2528980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7428 7451 0.518448 0.675567 -0.679947 0.3521408 -0.0093639 0.2258180 0.9082486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7429 7450 -0.666284 0.011357 0.601299 0.2662183 -0.0275024 -0.0706291 0.9609282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7429 7769 0.382364 0.688625 0.624296 -0.4910429 0.1247079 0.2814796 0.8149197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7430 7770 0.354546 -0.189763 0.722364 0.0227468 0.1675404 -0.9159910 0.3638313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7431 7448 0.496201 0.344058 0.716237 -0.7945813 -0.1218920 0.5617201 0.1955847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7432 7447 -0.627743 0.530197 0.670577 0.2956794 0.2702631 -0.4172362 0.8157484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7432 7772 -0.182756 -0.950066 0.472805 0.3602103 0.6160768 -0.7003101 0.0162406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7433 7446 0.295242 -0.760652 0.414618 -0.4407699 0.0157518 0.8540742 0.2757371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7433 7773 -0.041215 0.588136 0.886314 -0.1357907 0.4635789 0.0861417 0.8713410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7434 7445 0.517793 -0.456005 -0.745326 -0.6944542 -0.5515930 -0.4378294 0.1475938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7434 7774 0.600348 0.770101 0.174895 -0.1324885 0.4554764 0.2082128 0.8553569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7435 6975 0.367872 0.815195 -0.275055 0.2959982 -0.5965725 -0.4140903 0.6204962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7435 7404 0.290106 -0.183478 0.830885 -0.5277966 -0.3153548 0.7640036 0.1956543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7435 7444 -0.355406 0.255097 -0.928517 0.6016648 -0.1039462 0.5454862 0.5741424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7436 7443 0.185530 -0.966880 0.018652 -0.4759514 0.3998429 -0.6566130 0.4271480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7437 7777 0.277475 0.049541 0.861822 -0.0419443 0.1429775 0.9643172 0.2188388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7438 7441 -0.651248 -0.567506 -0.323508 -0.0390724 -0.4316011 0.7468094 0.5044498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7438 7778 0.574096 -0.784302 0.282534 0.3232680 0.6134546 -0.5973836 0.4028698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7439 6979 0.216830 0.049762 -1.000410 -0.1016739 0.6072223 -0.4327857 0.6585135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7439 7779 -0.127771 -0.386357 1.067786 0.4518449 0.5126979 -0.7005812 0.2053364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7440 7479 0.642006 -0.621949 0.510778 -0.0105547 -0.1296236 -0.5743997 0.8081778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7440 7740 0.178218 0.858126 0.601689 -0.0386414 0.1613164 -0.8579823 0.4861586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7441 6941 0.732031 0.406267 -0.564210 0.6462707 0.1224844 -0.5838384 0.4758828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7441 7478 -0.361631 0.916532 0.251965 -0.3453922 -0.5860666 0.0680782 0.7297914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7441 7741 -0.705279 -0.319140 0.429784 0.0814779 0.4157487 -0.8983853 0.1158371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7442 7437 -0.661346 -0.734793 0.478446 -0.4704468 0.3494635 0.7789499 0.2231415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7442 7742 -0.701182 0.485693 0.315053 -0.4635964 -0.7518941 -0.4606812 0.0866396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7443 7476 0.700573 0.197311 0.597225 0.4441325 0.7114719 -0.4843600 0.2488965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7443 7743 0.198836 -0.954262 0.159980 0.0488745 -0.5691038 0.3200460 0.7558457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7444 7475 -0.726321 -0.138034 -0.588408 0.7084727 -0.1183957 -0.6863733 0.1137564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7444 7744 -0.480979 0.708122 0.390422 0.0475646 -0.6070219 -0.7797235 0.1459223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7445 7474 -0.708512 0.600876 0.516887 -0.0180955 0.3666029 -0.8273013 0.4252617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7445 7745 0.529735 0.564638 0.832404 0.6498342 -0.2316963 0.7238997 0.0012120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7446 7473 -1.049345 0.262822 -0.183227 0.4742023 -0.4133571 -0.4318793 0.6463346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7446 7746 -0.147270 -0.855113 0.614233 -0.6259718 -0.3008179 0.4269651 0.5791102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7447 7472 -0.821134 -0.342001 -0.112109 0.6090220 0.3028290 0.5488557 0.4859467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7448 7471 -0.392643 -0.596620 -0.598035 -0.0965184 -0.8092677 0.4131009 0.4063467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7448 7748 -0.710578 -0.186174 0.670326 -0.1898914 -0.3350721 0.8043823 0.4523682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7449 7430 0.730964 -0.312093 0.914399 -0.4722616 -0.4667001 -0.0738542 0.7441140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7449 7470 -0.544261 0.190429 -0.670619 -0.7958678 0.1429000 0.3486522 0.4739363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7449 7749 -0.360528 0.742988 0.531291 -0.5791352 -0.2262821 -0.1837298 0.7613423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7450 7469 -0.863075 0.235326 0.533627 0.2370828 0.2642224 0.2009776 0.9130094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7451 7468 0.557475 -0.034949 -0.664920 0.3339448 0.3355181 0.8700346 0.1376528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7451 7751 0.902266 0.118701 0.446717 0.1577654 0.2162876 0.8562829 0.4417119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7452 7467 0.497444 -0.329663 0.809362 -0.1555351 -0.0074339 0.7306767 0.6647294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7452 7752 -0.524636 0.785342 0.496521 -0.3113182 -0.4464702 -0.2739694 0.7928973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7453 7466 -1.065567 -0.129830 0.423359 0.5402400 -0.3144804 0.7697502 0.1293348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7453 7753 0.208251 -0.845174 0.511822 0.1664036 0.9243282 -0.1305226 0.3176337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7454 7465 0.753940 -0.733151 0.238225 0.0101813 -0.4850628 0.7269638 0.4859362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7454 7754 -0.610996 -0.184382 0.933717 -0.2558034 -0.0705969 0.9134324 0.3085804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7455 6955 -0.127364 -0.969262 -0.020049 -0.4839635 -0.0086322 -0.8725432 0.0661301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7455 7755 0.107526 0.935436 -0.040783 -0.8881564 -0.0322074 -0.4203082 0.1829806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7456 7463 0.792302 0.125042 0.182530 0.6175346 -0.1518242 -0.5050009 0.5835877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7456 7756 -0.387348 -0.301073 1.172163 -0.2073896 0.4215082 -0.1229882 0.8741821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7457 7462 -0.674120 0.453560 -0.487703 -0.0519896 -0.0187312 0.2392140 0.9693931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7457 7757 -0.430701 -0.854046 0.185616 0.5943038 -0.0985950 0.3585448 0.7131113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7458 6958 -0.379852 -0.998113 -0.127795 0.1236217 0.2191233 0.7590196 0.6004931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7459 6959 -0.546672 0.159778 -0.544084 0.5343289 -0.0882686 0.7824946 0.3072515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7459 7420 -0.587895 0.214416 0.684850 0.4129617 0.0546497 0.1459659 0.8973127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7460 7499 0.335809 -0.961146 -0.061375 0.3669452 -0.7081453 -0.2513639 0.5483591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7460 7720 -0.446496 -0.291226 0.826650 -0.4116035 0.0745044 0.1562380 0.8947745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7461 7458 0.535374 -0.001132 -0.881429 0.8685487 0.2266723 -0.0716224 0.4348712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7461 7498 -0.603866 -0.075053 0.765762 0.4188315 0.1402771 -0.8701241 0.2186015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7461 7721 0.766321 -0.479111 0.387292 0.2479960 0.0998188 0.9122358 0.3104192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7462 7497 -0.761627 0.733451 -0.290476 -0.2099289 -0.4161035 0.6399888 0.6109027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7462 7722 -0.716306 -0.645965 0.300334 0.2985263 -0.5407760 0.6770545 0.4000507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7463 6923 0.127258 -0.840847 -0.363892 -0.1055034 0.0870762 -0.2590682 0.9561226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7463 7723 -0.260728 0.716225 0.486356 -0.0121305 0.1005741 -0.4286749 0.8977614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7464 7455 0.691813 -0.586883 0.163374 0.9243835 -0.3407464 -0.1591673 0.0638184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7464 7495 -0.757956 0.360110 -0.179829 0.5936268 0.5369268 0.0056685 0.5994036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7464 7724 -0.640091 -0.904485 0.168394 0.8288481 -0.4378721 0.2759020 0.2125016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7466 7493 0.865484 0.508404 -0.372569 0.3070110 0.1641296 0.6405928 0.6844315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7467 7492 -0.591486 -0.664857 0.650295 0.0412818 0.2540675 0.0336447 0.9657192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7467 7727 0.513883 0.232076 0.678316 0.5225521 0.5626823 0.5940607 0.2396243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7468 7491 -0.828945 -0.622012 -0.214750 0.2941602 -0.0506684 -0.0544199 0.9528594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7468 7728 -0.320009 0.564320 0.898525 0.2877944 0.3210439 0.7892120 0.4373209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7469 7729 0.705023 0.650839 0.289229 -0.0635195 -0.9077309 -0.3090754 0.2765182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7470 6930 0.646545 0.527022 -0.572850 -0.0356954 -0.1464503 -0.4729138 0.8681191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7470 7489 0.022887 0.519744 0.791409 0.6110216 0.5711703 -0.4809340 0.2629059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7470 7730 -0.643754 -0.624570 0.375712 -0.1727511 -0.0495010 0.1648565 0.9698088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7471 7488 -0.432078 0.049721 0.968194 -0.3645712 0.7125785 -0.0629766 0.5961155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7471 7731 0.826116 -0.525350 0.344768 0.2375394 -0.2333662 0.5829793 0.7411143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7472 7487 -0.721852 0.133748 -0.880636 0.5982837 -0.2898069 -0.7394125 0.1064789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7472 7732 -0.144380 1.036880 0.427981 -0.7064910 0.3794757 -0.0764127 0.5924777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7473 7486 -0.539566 -0.467343 0.749669 -0.4099302 0.3633426 0.6922315 0.4698457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7474 7734 -0.856795 -0.161247 0.474058 0.4519920 -0.3700907 -0.6099054 0.5354918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7475 6935 0.491138 0.646013 -0.251210 0.6581809 -0.6647948 0.0990345 0.3391724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7475 7735 -0.861667 -0.490443 0.337008 -0.2590186 -0.3128518 0.1827549 0.8953400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7476 7483 -0.606221 0.513359 -0.496536 0.3759907 -0.3454703 -0.2825301 0.8120702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7477 6937 -0.260706 0.711684 -0.329300 0.5441887 -0.2877941 0.1832735 0.7664490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7477 7482 0.413937 0.392477 0.943778 0.6375735 -0.3422209 -0.0479330 0.6885400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7477 7737 0.538114 -0.938285 0.347111 0.7348738 0.4201873 0.4853097 0.2188094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7480 6900 -0.581766 -0.701034 -0.291668 -0.3507343 -0.7714943 -0.4557338 0.2721924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7480 7519 -0.565308 0.399924 0.792982 0.3321479 0.1823067 0.0075460 0.9254108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7480 7700 0.615819 0.705291 0.187632 -0.2196224 -0.7144488 -0.5097061 0.4260617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7481 7478 -0.465654 0.958413 0.122868 0.1186863 0.3720108 -0.7139454 0.5812086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7481 7518 0.263324 -0.791114 0.003712 0.2754444 0.1535020 -0.5499536 0.7733813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7482 7517 0.511182 0.688384 -0.525508 -0.4513872 -0.2572688 -0.7980651 0.3052122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7482 7702 0.766416 -0.173478 0.643322 0.8041764 -0.2056004 0.5559134 0.0445982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7483 7516 -1.064600 -0.035419 0.070758 0.2720218 -0.2202063 0.2621118 0.8993391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7483 7703 -0.076915 0.489870 0.838098 -0.0588325 0.6439897 0.7605225 0.0584933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7484 7475 0.992876 -0.404584 0.205012 -0.5033172 -0.2803312 0.8075689 0.1261691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7484 7515 -0.924770 0.103847 -0.197187 -0.0427937 0.2183143 -0.8491792 0.4789596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7485 7474 -0.494123 0.238914 -1.017801 -0.5769508 -0.2924282 0.3929184 0.6536273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7485 7514 0.431802 -0.135625 0.688164 -0.3725805 -0.0687520 0.6098231 0.6961126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7485 7705 -0.732568 -0.527564 0.313440 -0.5589297 -0.0380965 0.6906981 0.4572553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7486 7513 -0.692161 0.866327 0.058050 -0.1128104 -0.5596534 0.7456196 0.3436761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7487 6907 0.619899 0.603995 -0.656161 0.5835448 0.2026095 -0.0774988 0.7825720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7487 7512 0.930157 -0.660162 0.477562 -0.1508169 -0.0592993 0.9834174 0.0814129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7487 7707 -0.726450 -0.655471 0.546716 0.5571233 0.3909353 -0.6523722 0.3334574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7488 7511 -0.862211 -0.373240 -0.524241 -0.3492561 -0.3255025 0.5611647 0.6761379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7488 7708 -0.080892 -0.882769 0.500121 0.0301841 -0.4202062 -0.0723736 0.9040341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7489 6909 0.449701 0.455784 -0.425914 0.0958302 0.5168995 -0.7416342 0.4166655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7489 7510 -0.360192 -0.424165 -0.792260 0.4238970 -0.4897858 0.6577319 0.3844607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7489 7709 -0.436766 -0.708176 0.583339 -0.1505439 -0.1847447 0.4959272 0.8350222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7490 7469 0.451597 0.769283 -0.535067 0.8053097 0.3069897 0.3311878 0.3841202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7490 7509 -0.321012 -0.601117 0.393243 0.3336192 0.6296457 0.1336526 0.6887535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7490 7710 0.447697 0.143790 0.726589 -0.3913431 0.2753444 -0.5358227 0.6956509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7491 6911 0.345486 -0.877471 -0.414121 -0.7546934 -0.1530015 0.4371638 0.4646679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7491 7711 -0.274187 0.998210 0.321722 0.1486747 0.3210017 0.8728363 0.3361704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7492 7507 -0.776305 -0.427473 0.251754 0.0375908 -0.4977985 0.6014770 0.6237059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7493 7506 0.568844 -0.605532 -0.098323 -0.1292698 0.3223700 -0.8935806 0.2843951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7493 7713 0.633707 0.292117 0.568520 -0.1211536 -0.0569715 0.5965140 0.7913578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7494 7465 0.221798 0.809310 0.226497 0.1396130 -0.1079296 0.1391619 0.9744195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7494 7714 0.371997 -0.322627 0.825237 -0.4575235 -0.1344896 0.8285523 0.2934040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7495 7715 -0.844949 -0.353059 -0.077907 0.5708679 0.0269201 -0.7354865 0.3639297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7496 7503 0.195911 0.732468 -0.628877 -0.3737257 -0.0742603 -0.8702140 0.3123174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7496 7716 -0.218159 0.603392 0.929552 -0.1612273 0.3253438 -0.4767809 0.8005230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7497 7502 0.836842 0.706352 0.070799 -0.2113857 0.4400820 -0.8665188 0.1038703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7498 7501 -0.302699 -0.569670 0.953960 -0.4033325 -0.1012997 0.6938924 0.5878559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7498 7718 -0.738609 0.767986 -0.024056 -0.2790507 -0.2786294 -0.4969529 0.7730034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7500 7539 0.733450 0.900870 -0.306866 0.7946869 0.1342199 -0.5810704 0.1132032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7500 7680 -0.467126 0.435498 0.719797 0.0237506 -0.0345815 -0.4065381 0.9126701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7501 7681 0.534751 0.054412 0.768628 0.7762976 -0.1200396 0.6114834 0.0950819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7503 7536 -0.594309 -0.530433 -0.145575 0.0782632 -0.8220775 0.4765048 0.3016731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7503 7683 0.262528 -0.532922 0.750266 0.0756049 -0.3270240 -0.7105484 0.6184337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7504 7495 -0.207581 0.765496 -0.789744 -0.6559259 0.7195686 0.0317680 0.2257720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7504 7535 0.245246 -0.568162 0.643389 -0.1541834 0.7834821 -0.1245533 0.5889565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7504 7684 0.716316 0.659357 0.070285 0.3510404 0.5932510 0.6738490 0.2659914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7505 7494 -0.519109 0.890812 -0.071332 0.0636551 -0.6225956 0.3204399 0.7110844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7505 7685 -0.582013 -0.326704 0.539509 0.3493547 0.4693980 -0.2445819 0.7731730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7507 6887 -0.843658 0.604978 -0.222454 -0.6134398 0.4310642 -0.6525299 0.1099087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7507 7532 -0.052945 0.515237 1.085220 0.0189969 0.2295096 0.3914340 0.8909230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7508 7491 -0.169220 -0.806461 -0.406386 0.4055891 -0.1955854 -0.8736383 0.1843907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7508 7531 0.261475 1.027629 0.553931 -0.0123751 0.4491603 0.6124871 0.6503548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7508 7688 -0.122206 -0.433809 1.069996 0.1905753 0.2705302 -0.8408711 0.4282876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7509 7530 -1.164193 -0.500316 0.042784 0.1020883 0.4508980 0.8143288 0.3509096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7510 7529 -0.520775 0.701946 0.141286 -0.3788002 0.6885676 0.3645523 0.4994865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7511 6891 0.741523 0.563411 -0.320341 -0.1734830 -0.3085735 -0.5889823 0.7264888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7511 7528 -0.439545 0.783856 0.417764 -0.1073537 -0.5363787 0.8072308 0.2217015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7511 7691 -0.844132 -0.620922 0.113426 0.3277514 0.0990682 -0.0707619 0.9368870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7512 6892 -0.384437 -0.531105 -0.562446 -0.5278432 0.5783246 -0.2542848 0.5676808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7512 7692 0.460612 0.483469 0.780848 -0.7734405 0.2846629 -0.5110554 0.2440886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7513 7526 0.999241 0.202795 -0.110180 0.2698033 0.0742568 0.8389027 0.4668344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7513 7693 0.263684 -0.039690 0.907486 -0.2471751 -0.6444767 0.5928667 0.4148052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7514 7525 -0.392861 -0.780840 0.321818 -0.8522811 -0.4346057 0.0951682 0.2750960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7514 7694 -0.743377 0.595880 0.554452 -0.2674307 0.1108919 -0.0444123 0.9561440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7515 7524 0.387388 -0.676318 -0.337062 -0.3309892 -0.5361054 0.4041333 0.6631089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7515 7695 -0.128963 -0.582858 0.803586 0.3594415 -0.3483365 -0.6687066 0.5498135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7516 7523 -0.736920 0.629822 0.383017 0.3206042 0.8390225 0.4374477 0.0435166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7516 7696 0.486647 0.761761 0.333560 -0.0745730 0.2856911 -0.7014839 0.6486445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7517 7522 -0.822487 -0.299550 0.642529 -0.3836868 -0.2146622 -0.5543006 0.7067216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7517 7697 0.194084 0.780523 0.607207 -0.0049111 -0.5071670 -0.8612734 0.0310768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7518 7521 0.812145 -0.002914 0.673693 -0.0354624 0.1553536 -0.9872217 0.0010072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7520 7559 -0.236084 -0.227658 -0.801505 0.5739393 -0.4198807 -0.0156123 0.7028870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7520 7660 0.489005 -0.786183 0.246245 -0.1925061 -0.0918617 -0.9649499 0.1528873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7521 7558 -0.842779 -0.461809 0.485911 0.0038172 0.5032849 -0.2456452 0.8284613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7522 7557 0.308691 -1.057250 -0.041924 0.2499243 0.5565614 0.7499151 0.2557432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7522 7662 0.216589 0.099635 0.936817 0.5763729 0.3481062 0.7000443 0.2378117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7523 7556 1.019702 -0.075547 -0.233397 -0.2371925 -0.2798840 0.7132890 0.5971796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7523 7663 -0.020665 1.208858 0.368946 0.0271232 0.2058325 0.9320251 0.2970296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7524 7664 -0.359049 -0.858377 0.285299 0.5528832 0.5873319 -0.0952624 0.5833408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7525 6865 -0.190611 0.914815 -0.242253 -0.3088694 -0.4463681 0.8380116 0.0556040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7525 7554 -0.972407 -0.279487 -0.329319 0.3622178 0.4080641 -0.1978729 0.8143269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7525 7665 0.063609 -1.134075 0.083043 0.8757965 -0.3125489 -0.1488212 0.3363718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7526 7553 -0.265364 -0.797638 0.461288 -0.2108903 0.3375215 -0.8088081 0.4329364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7526 7666 -0.008255 0.283354 0.829157 0.0559073 -0.2302996 -0.3362350 0.9114727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7527 7512 -0.175944 -0.375687 1.059003 -0.4812378 -0.4207709 -0.5415841 0.5459383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7527 7552 0.239264 0.192655 -1.088162 -0.0902582 0.7684848 0.0392245 0.6322547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7528 7551 0.877693 -0.554365 -0.363944 -0.6698566 0.5032712 -0.2549969 0.4826871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7528 7668 0.539679 0.230366 1.001090 -0.5112441 0.1028450 0.1897203 0.8319006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7529 7550 0.157934 0.836370 0.393934 -0.0616861 -0.8471882 0.4476339 0.2794476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7530 7549 0.599232 0.426128 -0.891927 -0.4693314 -0.3392210 -0.8152612 0.0025185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7531 7548 0.316882 0.134405 0.955465 -0.7427923 -0.5727741 0.3455354 0.0281912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7532 7547 -0.157275 0.478886 0.860133 -0.2789251 0.3422682 -0.4679171 0.7655762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7533 7506 0.027323 0.784529 0.726264 0.2139521 0.6086131 -0.7638164 0.0199747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7533 7546 0.078004 -0.659619 -0.716061 -0.0333077 0.0154755 -0.8992156 0.4359614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7533 7673 0.144512 -0.870765 0.653493 -0.2930187 0.1536391 0.9243215 0.1901706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7534 6874 0.008098 0.995288 -0.195556 -0.0851519 -0.6950085 0.4532860 0.5515833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7534 7545 -0.698918 0.118849 0.805080 0.3387466 -0.5212724 -0.3079640 0.7201972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7534 7674 0.179798 -0.971065 0.201567 0.7674412 -0.3773612 -0.4003987 0.3291100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7535 7544 -0.458488 -0.758397 0.140374 -0.2227542 -0.5947245 0.4745024 0.6095333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7535 7675 -0.864797 0.570339 0.438329 -0.5153956 0.5198043 0.4012989 0.5505724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7536 7676 0.108459 -0.936072 0.040043 0.5613052 0.5657007 -0.0463741 0.6023028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7537 7502 -0.482101 -0.202856 -1.016437 0.4637139 0.4132444 -0.7803646 0.0723152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7537 7542 0.422791 0.114036 0.902229 -0.0733654 -0.4637577 -0.7910744 0.3921066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7537 7677 -0.688762 0.586147 0.254513 0.1518522 -0.8457374 -0.4183950 0.2943039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7538 7541 -0.066914 0.854451 0.434180 0.1451730 0.4374474 -0.0381981 0.8866259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7538 7678 0.798821 -0.315574 0.510617 0.4236741 0.2479871 0.3617727 0.7925422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7539 7679 -0.697381 -0.729516 0.270011 0.2324908 -0.2036069 -0.0730245 0.9482403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7540 6840 -0.077521 0.967992 -0.084984 -0.7245691 -0.3782563 0.5471674 0.1803595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7540 7640 0.081808 -0.955967 -0.095705 0.8014531 0.3704544 -0.2027151 0.4234891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7541 7641 -0.062903 -0.051297 1.089443 0.3396653 0.2092239 0.6447259 0.6520593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7542 7577 -0.121796 0.724380 0.599710 -0.5974593 0.1881220 -0.3292984 0.7065516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7542 7642 0.300755 -0.361891 0.749437 0.2500774 0.2649334 0.5734810 0.7337515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7543 6843 -0.728088 -0.398252 -0.549774 0.0155804 0.0811599 0.9965687 0.0046096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7543 7536 -0.587766 0.185219 0.651704 -0.8036045 0.4699579 -0.2576440 0.2588029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7543 7576 0.687675 -0.435736 -0.480665 0.0515969 -0.4834039 -0.8721565 0.0547860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7543 7643 0.862341 0.274393 0.656987 -0.8594879 0.2867292 -0.3934983 0.1556468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7544 7575 -0.639008 -0.390974 0.723474 0.2388871 0.2025766 -0.7473562 0.5859645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7545 7574 0.384191 0.679751 0.833745 0.2034452 0.8628005 -0.2499062 0.3895283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7545 7645 0.749928 -0.571771 0.312004 -0.7338711 -0.1742149 -0.6029799 0.2598029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7546 7573 0.491364 0.662876 -0.781825 0.5143353 0.2586483 0.5408240 0.6132452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7546 7646 0.310802 0.578890 0.531042 0.2918527 -0.6964099 -0.6524833 0.0640377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7547 7572 -0.583159 -0.618070 0.570162 0.8503650 0.0218204 0.0202690 0.5253498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7547 7647 0.599208 -0.712495 0.187074 0.2945151 0.3719626 0.8745899 0.0999858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7548 7571 -0.107111 0.005317 -1.062698 0.5343153 0.7460944 -0.2044539 0.3406596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7549 7570 -0.669392 -0.653923 0.337984 -0.3032733 0.2255863 -0.1654760 0.9109083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7549 7649 0.227508 0.354936 0.948928 0.3140078 0.1890251 -0.0594353 0.9285128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7550 7569 0.683882 0.075806 -0.848417 0.1723363 0.3768118 0.0533443 0.9085524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7552 6852 0.416641 -0.452265 -0.768136 -0.4575737 0.2149088 0.6167741 0.6033492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7552 7652 -0.479144 0.620942 0.597808 0.5554599 -0.2685086 -0.6945777 0.3700396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7553 7566 0.919701 -0.107712 0.198946 0.5203106 -0.0530131 -0.7772319 0.3498243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7553 7653 -0.287942 -0.754637 0.653611 0.4153947 -0.4282914 0.6935592 0.4037194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7554 7565 -0.061438 -0.818774 -0.591745 0.6768048 0.1105106 -0.1187700 0.7180643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7554 7654 0.180317 -0.459337 0.795781 -0.5768700 -0.0738817 -0.8127002 0.0357890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7555 7524 0.970131 0.217912 0.380162 -0.7181981 -0.0333846 -0.2289496 0.6562462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7555 7564 -0.712585 -0.248674 -0.624259 0.4161407 0.1567121 -0.8179049 0.3651026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7555 7655 -0.661876 0.392451 0.715860 0.5151126 -0.3877123 -0.7596784 0.0850118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7556 7563 -0.198401 -0.578031 -0.980001 0.6446295 0.1105124 0.6290038 0.4202309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7556 7656 0.850416 -0.248643 0.195638 -0.7445013 0.5934639 -0.2994426 0.0620684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7557 7657 0.272994 0.803980 0.398249 -0.3402588 0.0007943 -0.2115403 0.9162281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7558 6858 0.679770 -0.289681 -0.770762 0.6419395 -0.2611188 -0.6770579 0.2476352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7558 7658 -0.558146 0.237517 0.640137 0.1878284 0.5356597 -0.7443114 0.3518376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7559 7659 0.940549 -0.221317 0.461016 0.5613680 -0.0884346 0.5527072 0.6095573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7560 7599 0.918117 -0.041476 0.354344 -0.1611354 -0.0234429 -0.0628022 0.9846531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7560 7620 -0.315819 -0.498405 0.795472 0.1899267 -0.7205725 0.4920089 0.4501449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7561 7558 0.082732 -0.484240 0.915125 0.1913286 -0.3273039 -0.6659013 0.6425270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7561 7598 0.016746 0.559378 -0.885697 -0.0454250 -0.6259795 -0.3047300 0.7163978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7561 7621 -0.295411 0.804503 0.461060 0.0140688 -0.0761139 -0.7638721 0.6407091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7562 7557 -0.032307 0.947256 -0.250836 0.5126023 0.6890100 0.4644311 0.2163512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7562 7597 -0.064959 -0.881567 0.266698 -0.4033741 0.5368547 -0.0800650 0.7366587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7562 7622 0.749463 0.169223 0.600188 0.6299916 0.4743537 0.5579351 0.2584715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7563 7596 -1.067603 -0.056165 -0.017911 0.1074099 0.3437130 0.2819270 0.8892928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7563 7623 -0.123332 0.087988 1.056913 -0.1867292 0.6092779 0.6664953 0.3869065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7564 6824 0.381557 0.719639 -0.314856 0.4832010 0.0157538 -0.7794249 0.3984537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7564 7595 0.736902 -0.423034 0.550989 0.6934347 -0.6189624 -0.0434073 0.3662645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7564 7624 -0.696446 -0.612568 0.282062 -0.6064151 -0.6456602 0.0996274 0.4532749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7565 7625 0.015315 0.835105 0.525390 0.2004326 -0.1551623 -0.9672296 0.0147760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7566 7593 -0.235354 0.586111 -0.791142 -0.1313850 0.7456330 0.1820832 0.6273875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7566 7626 -0.029635 0.547922 0.709482 -0.7311092 -0.4069673 -0.3983156 0.3757681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7567 6827 -0.393348 -0.629154 -0.374723 0.0203149 -0.1448006 -0.9014130 0.4075225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7567 7552 0.841461 0.117326 -0.923548 -0.0106904 -0.5557461 -0.7904085 0.2574615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7567 7627 0.431365 0.591061 0.544634 -0.0476157 -0.1034348 -0.0862413 0.9897456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7568 7551 0.197418 -0.145760 1.009230 0.3970100 0.8191939 -0.2607013 0.3214641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7568 7591 -0.226042 0.108255 -1.115903 0.2763921 0.7290778 -0.5997191 0.1799720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7568 7628 -0.729485 -0.583734 -0.172276 0.9284025 -0.0341129 0.0328794 0.3685432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7569 7590 1.056248 -0.003792 -0.133326 -0.3129907 0.2407302 -0.0846385 0.9148345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7570 6830 0.468648 0.217814 -0.902203 -0.1204171 0.1422945 0.9661498 0.1783440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7570 7589 -0.570510 -0.951216 -0.289613 -0.2228770 -0.2593345 -0.8152436 0.4673856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7571 7588 0.438495 -0.290170 0.672691 0.3902231 -0.7186363 -0.5369289 0.2073526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7571 7631 -0.745931 -0.074825 0.343548 -0.0341144 -0.6728964 0.4790471 0.5626372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7572 6832 -0.861867 -0.338563 -0.560870 -0.3033779 -0.0578132 -0.1584583 0.9378222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7572 7587 -0.718003 0.752122 0.156368 -0.6394988 0.5451921 -0.0201548 0.5416646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7572 7632 0.601009 0.666772 0.661815 -0.3827183 -0.0945327 0.1205335 0.9110774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7573 7633 0.850326 0.407308 0.423194 -0.4322841 -0.0748277 -0.8673755 0.2349277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7574 6834 0.689212 -0.061455 -0.651860 0.6039202 -0.2673725 -0.2734570 0.6992951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7574 7585 -0.624007 0.601503 -0.656897 -0.0457501 -0.0782212 0.5132969 0.8534135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7574 7634 -0.682024 0.031664 0.751717 0.3097712 0.4938362 -0.8106657 0.0546688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7576 7583 -0.431527 -0.348685 -0.696457 0.2177233 -0.3910059 -0.7888913 0.4211430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7576 7636 -0.862799 0.495112 0.398064 -0.0339527 -0.3862860 -0.9201281 0.0547228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7577 7582 -0.724204 -0.435634 0.826482 0.6811973 0.0261536 0.0351862 0.7307860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7577 7637 0.528361 -0.808201 0.160965 0.4020961 -0.2757040 0.8385374 0.2432304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7578 7541 0.758570 -0.627072 -0.154234 0.4067288 -0.4962939 0.1286206 0.7561222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7578 7638 -0.694348 -0.796733 0.080650 0.1457647 -0.8213313 0.5508690 0.0266627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7579 7639 -0.614485 -0.811230 0.279071 -0.5731432 -0.5405802 0.2632037 0.5567797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7580 7600 -0.826202 -0.362818 0.697843 -0.0340448 -0.3888286 0.4634100 0.7955529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7581 7601 0.324633 0.665946 0.757345 0.0349839 0.1995813 -0.8601026 0.4681526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7582 7602 0.514291 0.319833 0.834927 -0.0474884 0.5102075 -0.6604954 0.5487978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7583 7603 -0.001369 -0.288403 0.985532 -0.2998920 -0.3281019 -0.8271531 0.3438482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7584 7575 0.666778 -0.128682 -0.590828 0.0512595 0.0605314 -0.7969068 0.5988722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7584 7604 0.813447 0.539440 0.496452 -0.4563650 0.4736787 0.7324325 0.1757902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7585 7605 -0.129388 0.474477 0.786420 -0.3250222 0.0327097 0.8715943 0.3655325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7586 7573 1.009837 0.310900 0.187025 -0.1844188 -0.7704851 -0.5319032 0.2990341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7586 7606 -0.421823 0.482074 0.836008 -0.3857581 -0.5676045 0.7060255 0.1747680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7587 7607 -0.389068 -0.855725 0.364044 0.5839559 0.3520074 -0.5932328 0.4279732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7588 7608 0.534324 0.664701 0.365583 0.6655536 0.0077277 0.5897907 0.4573026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7589 7609 0.643698 0.034989 0.460675 0.3767990 -0.0971459 0.5654707 0.7272057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7590 7610 -0.188616 -0.704211 0.547536 0.5771587 0.0706177 0.7058243 0.4046147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7591 7611 0.336206 -0.596226 0.742887 0.5301959 0.6385771 0.1063257 0.5475459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7592 7567 0.205755 0.272654 -0.839051 -0.0392070 0.2234975 0.2618499 0.9380545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7594 7565 0.482108 0.561883 0.762556 0.6308587 -0.4576883 -0.1558438 0.6068373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7594 7614 -0.902660 -0.119834 0.521474 -0.1844913 -0.7585075 -0.0072136 0.6249618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7595 7615 0.569845 0.773841 0.523314 0.2302421 0.2392514 0.3594675 0.8720840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7597 7617 -0.309714 -0.385590 0.761549 0.2621536 -0.2053340 0.8556494 0.3962039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7598 7618 0.187912 0.853695 0.590930 0.2634335 0.5128190 -0.1193976 0.8083092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7601 7638 0.437921 -0.878093 -0.148969 -0.0119095 -0.7070281 0.6547732 0.2669110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7602 7637 0.249845 0.813279 0.452602 0.5603524 -0.1061901 -0.8117058 0.1259465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7603 7636 0.155993 -0.735056 0.658772 0.4454812 0.1731763 0.5866456 0.6537610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7604 7635 0.353091 -0.847175 -0.496373 0.7086770 -0.2385625 -0.1197204 0.6530941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7605 7634 -0.803480 0.581160 0.237793 -0.3259899 0.1178413 -0.2382083 0.9072490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7607 7632 0.084462 1.111113 0.242531 0.2364859 -0.4522931 0.7862282 0.3483541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7609 7630 0.300535 0.840016 0.173522 0.5131500 0.2060773 -0.4145071 0.7227676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7610 7629 -0.316932 0.187417 -0.937465 0.2111664 0.6395825 0.6083558 0.4198169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7611 7628 -0.593481 -0.754415 -0.231148 -0.6368556 0.4658003 0.3259329 0.5207809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7612 7592 -0.506053 -0.738595 -0.186595 -0.3583604 -0.7890380 -0.3272260 0.3767227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7612 7627 0.589370 -0.476720 0.732166 -0.5221166 -0.6118513 -0.3222248 0.4992028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7613 7593 0.807691 -0.110966 -0.698636 -0.6990047 0.4367796 0.5493140 0.1373686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7614 7625 0.817184 0.351542 -0.533180 0.2094127 -0.1141214 0.6691590 0.7038102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7615 7624 -0.373335 1.004472 -0.257610 -0.5636809 0.4574003 0.5691927 0.3860938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7616 7596 -0.252433 0.429040 -0.818112 0.3125695 0.1102023 -0.8899161 0.3133770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7616 7623 -1.011713 -0.324209 0.062227 0.7244579 0.3064839 -0.3283836 0.5228695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7618 7621 0.814077 0.389770 0.976843 -0.3847974 -0.2082887 -0.5422352 0.7173059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7619 7599 -0.762652 0.440587 -0.584587 -0.4157307 0.7328818 -0.4202933 0.3367578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7620 7659 0.152978 0.789913 0.466745 0.5782580 -0.3888118 0.6904962 0.1940569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7621 7658 0.675013 0.241590 0.643412 0.3862036 0.7324675 -0.4912827 0.2701470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7622 7617 -0.608142 0.637040 -0.346666 -0.3214386 -0.1256390 -0.1892527 0.9192799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7622 7657 0.730761 -0.749031 0.154013 -0.1940289 0.1592484 -0.3371623 0.9073667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7623 7656 -0.781192 -0.692055 0.492235 -0.6809751 -0.6259636 -0.3026081 0.2299366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7624 7655 -0.054296 -0.010552 1.000472 0.7694725 0.3908227 -0.5022855 0.0536566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7625 7654 0.200332 -0.914827 -0.499680 0.6254482 -0.5700333 -0.1511986 0.5108969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7626 7613 -0.602021 -0.568402 0.871177 0.1588916 0.8258784 -0.1745483 0.5120656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7626 7653 0.428266 0.542990 -0.762128 -0.0579704 0.2519643 -0.4484089 0.8556184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7627 7652 0.473842 0.095368 -0.632162 -0.4077640 0.7093471 0.2124356 0.5342530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7628 7651 0.272436 0.697214 -0.632221 -0.1883064 -0.2466849 0.9259463 0.2151991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7629 7569 -0.534261 -0.331208 -0.697948 0.2283041 0.2523585 0.8791082 0.3337081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7630 7649 -0.100909 0.543534 -0.749094 0.0346388 0.4918517 0.1843115 0.8502419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7631 7608 0.092187 -0.882124 -0.228301 -0.2550323 -0.3091426 0.1225955 0.9079426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7632 7647 0.471026 -0.415150 -0.841887 0.2492679 0.7846268 0.5109027 0.2473959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7633 7646 0.093870 -1.044192 -0.007479 0.6753641 -0.2676317 -0.6860919 0.0391723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7634 7645 -0.876378 -0.006125 0.106781 0.9016431 -0.0852439 0.1439095 0.3988273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7635 7644 0.683197 -0.593515 0.479768 -0.3745418 -0.0141512 0.8686037 0.3241078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7636 7643 -0.712620 0.372388 0.913426 -0.7987742 0.4695546 -0.3496052 0.1387602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7637 7642 -0.920088 -0.438807 -0.066735 -0.0103494 -0.0032212 -0.0017809 0.9999397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7638 7641 -0.706010 -0.167004 0.837458 0.4358915 0.3678305 -0.3349838 0.7499901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7640 7679 1.010016 0.519117 0.043370 -0.1111981 0.0766875 -0.7409998 0.6577791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7641 7678 -0.907474 -0.221158 0.104658 -0.3649649 -0.1150162 -0.1885654 0.9044418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7642 7677 -0.804575 -0.499617 -0.085981 0.1251572 -0.5232762 -0.4136792 0.7344299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7643 7676 -0.239665 -0.418032 -0.884856 0.4353166 0.6079835 0.1230372 0.6524703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7644 7544 0.143633 0.120648 -1.133835 0.3598362 -0.0363358 0.9282216 0.0871907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7645 7674 -0.845007 0.424774 -0.566523 0.5748032 0.7509919 0.2995431 0.1260408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7646 7673 0.517187 1.003090 -0.305066 -0.7867931 0.5171986 0.1389479 0.3068479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7647 7672 -0.482605 -0.791746 0.065921 -0.4178681 -0.3811654 0.7124080 0.4154203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7648 7548 0.401080 0.448191 -0.837848 -0.4655590 0.1181602 -0.3797548 0.7906195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7648 7631 -0.785563 -0.710739 -0.262352 -0.0700177 -0.3396542 -0.5593333 0.7529135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7649 7670 0.657050 0.341566 -0.510943 -0.0905335 0.2077702 -0.0822878 0.9704967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7650 7629 0.794320 -0.621921 -0.248963 0.0361924 0.3715170 -0.9186957 0.1290873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7650 7669 -0.939710 0.405755 0.115039 -0.1937671 -0.3907730 0.8984641 0.0501298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7651 7551 -0.665948 0.720475 -0.502530 0.0663103 -0.4121836 0.5337128 0.7354307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7651 7668 0.338019 -0.512926 -0.964204 0.4493859 -0.6455894 0.5676947 0.2428773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7652 7667 0.559662 0.002044 0.779911 -0.1229938 -0.6765070 0.2895979 0.6658407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7653 7666 0.129098 1.034089 -0.454435 0.0711474 -0.0823297 -0.3227587 0.9402057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7654 7665 0.527135 -0.822404 0.443536 -0.5469531 -0.3385336 -0.1716261 0.7461781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7657 7662 0.939324 -0.389951 0.497213 0.3356390 -0.3167868 0.2372351 0.8548170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7658 7661 -0.754437 -0.108707 -0.365496 0.2109700 -0.3107245 0.9267751 0.0054697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7660 7699 0.031367 -0.293267 0.964782 -0.9303130 -0.0322835 0.1888660 0.3127381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7661 7521 -0.414235 -0.688477 -0.676227 -0.2111229 0.0377059 0.2739711 0.9375208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7661 7698 0.531263 0.490406 -0.745494 -0.3337949 0.0743068 0.3210691 0.8831614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7662 7697 0.976722 -0.733673 0.015361 -0.0236132 0.7403117 0.5702801 0.3551924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7663 7696 0.701413 0.893720 0.001178 0.4124262 0.6751159 -0.0122153 0.6115341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7664 7655 0.271121 -1.004171 -0.387054 0.7755472 -0.1167787 -0.4177529 0.4586630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7664 7695 -0.089234 0.800604 0.335156 0.4630549 -0.5330127 -0.6581203 0.2614486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7665 7694 0.501767 -0.057476 -0.824997 -0.1747334 0.5195253 -0.6369694 0.5420624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7666 7693 -0.383168 0.942416 -0.516706 -0.7445934 -0.0910967 0.4995606 0.4332680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7667 7527 -0.789548 0.106145 -0.701589 0.7093016 0.1478548 0.3083346 0.6164089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7667 7692 0.555423 -0.692102 -0.518119 -0.6390442 0.6181959 -0.4472129 0.0972466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7669 7529 -0.273268 -0.568293 -0.711603 -0.4910540 0.4363064 0.4422330 0.6106821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7669 7690 0.768422 -0.674314 0.180709 0.0470294 0.0944931 -0.0645695 0.9923155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7670 7530 0.389286 -0.640589 -0.445706 0.1432408 0.5100390 0.8147751 0.2355501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7670 7689 0.878396 0.692452 0.005431 0.4221151 -0.2270953 -0.8016501 0.3572165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7671 7531 -0.708772 0.207197 -0.687147 0.4054722 0.2304025 -0.8360409 0.2890373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7671 7688 0.529367 0.850440 -0.114067 0.1170797 0.5089215 0.2848492 0.8038360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7672 7532 -0.903968 0.129435 -0.547112 -0.5211278 0.6878763 -0.3852690 0.3268330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7672 7687 -0.578017 -0.074934 0.920752 -0.1470907 0.3276230 -0.0774618 0.9300684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7674 7685 0.372984 -0.775278 0.214673 -0.3202385 0.5250070 0.7861795 0.0611292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7675 7644 0.049336 0.243202 -0.762146 -0.6000672 0.1702466 0.6408072 0.4475507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7677 7682 0.097557 -0.887613 0.559847 -0.6047136 0.1056081 -0.7826322 0.1032236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7678 7681 -0.722138 -0.789221 0.262472 -0.1419100 -0.5416116 0.2617349 0.7861382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7680 7719 0.322258 -0.689200 0.327831 -0.4484214 -0.7347050 -0.0399150 0.5074778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7681 7718 -0.405892 -0.434648 0.910558 0.1366495 0.6020089 0.4283755 0.6598535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7682 7717 0.891322 0.655847 0.157329 0.5969646 -0.7249487 0.2978202 0.1714230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7683 7676 0.794639 -0.452992 0.277651 -0.3183154 -0.3137343 -0.8885051 0.1039457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7684 7715 0.488741 -0.751498 0.123197 0.1185045 0.0377009 0.8310565 0.5421074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7686 7673 -0.086975 -0.012507 -1.062494 -0.2866519 -0.0268179 0.6576865 0.6961034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7686 7713 0.149229 0.222492 0.965328 0.1319619 -0.4612814 -0.3228089 0.8158431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7687 7507 -0.359447 0.366736 -0.816301 -0.6450327 0.2358335 -0.4782933 0.5473124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7687 7712 -0.978215 -0.246360 0.207657 0.7308284 0.2908594 -0.1962121 0.5854839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7688 7711 0.909730 0.569301 0.269862 0.3448739 -0.3216402 0.8600899 0.1945635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7689 7509 0.580038 0.258377 -0.663561 -0.4734629 0.3338847 0.7883115 0.2071688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7690 7510 0.032200 -0.575845 -0.788554 -0.0065198 -0.2295240 0.1553770 0.9607987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7690 7709 0.843442 -0.340023 0.328514 -0.3224637 0.4070578 -0.0955112 0.8492342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7691 7668 -0.558857 0.670819 -0.257835 0.3649960 0.6764937 -0.6134804 0.1810415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7691 7708 0.547129 -0.715109 0.284700 0.0230330 -0.2998315 -0.6530329 0.6950673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7693 7706 0.711802 0.034262 0.776195 0.9673304 -0.2146100 -0.0651191 0.1182117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7694 7705 0.356607 0.977675 0.101170 0.1222803 -0.0659702 0.2022026 0.9694378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7695 7704 -0.851093 0.156644 0.672945 -0.5654175 0.6661938 -0.2482230 0.4181797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7696 7703 0.601687 0.846797 0.086559 0.4833826 -0.6490964 -0.5871700 0.0156999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7697 7702 -0.932551 -0.487098 -0.103030 0.4115334 -0.1620692 0.8957549 0.0446866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7698 7518 -0.485587 0.051170 -0.997671 -0.0166836 -0.2711947 0.9601846 0.0649669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7698 7701 0.752984 0.436883 -0.462277 0.0901184 -0.4486091 -0.8739486 0.1638363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7699 7519 0.055811 0.883190 -0.378175 0.4014760 -0.2677186 -0.7768962 0.4044453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7700 7739 -1.108623 -0.223266 -0.346335 0.1022653 -0.5095890 -0.6658989 0.5352004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7701 7481 0.378129 -0.985295 -0.353864 -0.8075940 0.2508248 0.3298897 0.4195852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7701 7738 -0.945779 -0.480038 -0.345210 0.1962538 0.4098827 0.8905934 0.0179979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7704 7484 0.581594 0.717446 -0.043784 0.6912362 0.1335188 -0.6631678 0.2541135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7704 7735 -0.143197 -0.063386 -0.963940 -0.3686237 -0.5130933 0.1942991 0.7503997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7705 7734 0.665554 0.794597 0.029752 0.2004650 -0.6002435 -0.7056613 0.3186906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7706 7486 -0.507657 -0.741242 -0.217741 -0.5712708 0.4965052 0.6267805 0.1851445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7706 7733 0.408421 -0.036589 -0.828250 0.1893924 0.8525544 0.2052973 0.4417402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7707 7692 -0.459924 0.910297 0.084378 -0.1348287 0.6544208 -0.5956330 0.4458430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7707 7732 0.517080 -0.927433 -0.005446 -0.1060203 0.1930765 0.2599908 0.9401521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7708 7731 0.811283 0.519056 -0.367330 0.3174320 -0.6541756 0.4979498 0.4725857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7710 7689 0.550367 -0.690621 -0.130787 0.1874361 0.4096732 -0.3954961 0.8003864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7710 7729 -0.470704 0.883437 0.180709 0.7177336 0.3010488 -0.0722746 0.6237023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7711 7728 -0.187893 -0.984504 0.333562 0.3347933 0.0796945 -0.2438251 0.9067037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7712 7492 0.216889 -0.885318 -0.038698 -0.1088966 0.7414244 0.6613524 0.0323181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7712 7727 -0.972799 -0.442860 0.109207 -0.1312223 -0.6677711 0.0078539 0.7326669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7714 7685 -0.526364 1.071187 0.148173 -0.7095199 -0.3326964 0.1207873 0.6093480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7714 7725 0.472594 -0.837356 -0.134116 -0.5208649 0.3455717 0.7760579 0.0837504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7715 7724 -0.770317 -0.171014 0.321732 -0.0383974 -0.4934285 -0.7702166 0.4022689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7716 7683 -0.536308 0.624982 -0.412521 -0.0301816 0.3903475 0.9194255 0.0370751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7716 7723 0.617883 -0.715320 0.119064 0.2120998 0.0611828 0.1677428 0.9607980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7717 7722 -0.446440 -0.877088 -0.408128 0.6247439 0.3193530 -0.1677924 0.6924987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7718 7721 -0.713156 0.533591 -0.379045 0.5339358 0.0930624 -0.3678665 0.7555966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7719 7499 -0.506113 0.964326 -0.130049 -0.8765020 0.1931426 -0.4243601 0.1198276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7720 7759 -0.035040 0.565379 0.841924 0.6231185 -0.3157967 0.0790148 0.7111627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7722 7757 -0.311084 -0.695178 0.696986 -0.0341875 0.0079135 -0.7148885 0.6983574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7723 7756 0.264234 -0.523776 0.620254 -0.8569966 -0.2159492 0.2812247 0.3739458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7725 7465 -0.306699 -0.846592 -0.289545 -0.4242345 0.0533863 0.3429214 0.8364089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7726 7466 -0.090715 0.720537 -0.477948 0.4512429 0.1123019 -0.3989072 0.7903425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7726 7753 -0.923680 -0.215529 0.267709 -0.2338030 -0.0919682 0.4986333 0.8296040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7727 7752 0.142911 -0.462749 0.626474 -0.1900816 0.3649796 0.6287730 0.6597753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7730 7709 0.201467 0.125981 1.060486 0.7170124 0.2300609 -0.4126185 0.5125536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7730 7749 -0.405316 -0.140107 -1.056415 0.4302313 0.2875126 -0.6068190 0.6033309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7731 7748 -0.567473 -0.293905 -0.715124 0.4058608 0.0997148 -0.4393800 0.7951599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7732 7747 0.350129 -1.025754 -0.163928 0.2421043 -0.4795544 0.6348966 0.5552651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7734 7745 -1.159010 -0.012805 -0.021776 -0.3421873 -0.3943728 0.4858388 0.7009555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7735 7744 -0.861411 0.567127 -0.083771 0.3926279 -0.4041232 0.0378590 0.8252845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7736 7703 0.403693 -0.241178 -0.709681 0.2090218 0.3154069 -0.5589811 0.7378133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7736 7743 -0.313566 0.397378 0.767189 -0.2546167 0.3823537 0.4808311 0.7468450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7737 7702 0.738550 0.796158 0.046352 0.0293917 0.2720290 0.9421835 0.1934596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7737 7742 -0.748166 -0.605518 0.141513 -0.4650271 -0.6196307 -0.6304499 0.0483786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7738 7741 0.663984 -0.062548 -0.720616 -0.5715702 0.2223166 -0.6073924 0.5049330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7739 7479 0.637664 -0.198931 -0.588805 -0.4127602 0.2302524 0.5577462 0.6822991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7740 7779 -0.129980 -0.491312 -0.787333 0.7610888 0.5123432 -0.3522557 0.1848358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7741 7778 -0.080675 0.932366 0.616960 0.1972575 0.5100087 -0.3905913 0.7405532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7743 7776 -0.746856 0.246896 0.672944 -0.0232208 0.6643791 -0.7189698 0.2028390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7745 7774 -0.361105 0.465077 0.879659 0.4553071 0.1283395 -0.2186102 0.8534835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7746 7733 -0.337963 0.348483 0.955481 0.8434597 -0.4910482 -0.1286193 0.1757964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7746 7773 0.200419 -0.312084 -0.944726 -0.6578117 -0.2104831 0.5033471 0.5192516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7747 7447 -0.562237 -0.575815 -0.358313 -0.4279975 -0.0561256 -0.9011925 0.0389898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7747 7772 -0.565857 -0.142199 0.835389 -0.2456621 0.5198121 0.6901342 0.4395000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7748 7771 0.466439 -0.955885 -0.147185 -0.5021497 0.2009686 -0.3194673 0.7780733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7750 7450 -0.556098 0.354006 -0.643326 0.7281676 0.3353868 0.5973265 0.0221061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7750 7729 0.471761 -0.430449 -0.655503 0.7480760 0.4969656 -0.1540170 0.4119300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7750 7769 -0.553529 0.444310 0.721556 0.4284118 -0.4194600 0.7063140 0.3763471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7751 7728 -0.576552 -0.922711 -0.363646 0.2934071 0.1669131 0.9380304 0.0784304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7751 7768 0.383152 0.762781 0.307997 0.1820483 -0.5920910 -0.3705993 0.6920570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7752 7767 -0.942448 0.000191 0.375534 -0.4476850 -0.1184057 -0.8169080 0.3438307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7753 7766 -0.558756 0.642913 0.609379 0.1153382 -0.7886474 0.5797057 0.1693331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7754 7765 1.019635 -0.080371 0.031635 0.1715771 -0.3368007 -0.4756719 0.7942687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7755 7724 -0.141724 -0.398893 -0.820770 0.5941718 -0.1040901 0.7934723 0.0807886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7755 7764 0.322715 0.313563 0.985165 0.5325128 -0.0580002 -0.6538613 0.5343515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7756 7763 -0.379856 -0.147618 -0.879896 -0.4841769 -0.5088045 0.6884184 0.1810270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7758 7458 -0.744851 -0.529224 -0.446618 0.3759098 0.2078507 -0.0917944 0.8983672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7758 7721 -0.684085 0.434992 0.352232 -0.0438617 0.6118770 0.7536595 0.2359662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7758 7761 0.883933 -0.574190 -0.345614 -0.2589002 0.2429561 -0.4241554 0.8330877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7759 7459 0.155845 -0.518883 -0.826224 -0.4737414 -0.4969376 -0.4117319 0.5992487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7760 7799 0.685318 0.583456 -0.073712 0.4951174 0.1958758 -0.7417107 0.4078684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7761 7798 0.956119 0.558819 0.139938 -0.2774522 0.2183007 -0.6360694 0.6861346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7762 7757 0.904888 0.560005 0.063877 0.3390861 -0.6372142 -0.4832189 0.4954576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7762 7797 -0.776414 -0.456381 -0.003001 -0.4826020 -0.6444413 0.2517683 0.5370321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7763 7796 0.451226 0.711425 0.215609 -0.0893457 0.0018170 -0.8893897 0.4483303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7764 7424 -0.605551 -0.704736 -0.731792 -0.1679072 -0.1877320 -0.4287309 0.8676138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7764 7795 -0.728167 0.670551 0.217285 -0.3786093 -0.3641495 0.4067326 0.7474080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7765 7794 0.487222 0.484231 -0.735557 -0.5839093 0.0031597 0.1239035 0.8023016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7766 7793 0.849443 -0.232640 -0.532970 0.1034960 0.5330486 0.2478288 0.8023271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7767 7427 -0.603721 -0.189984 -0.590184 -0.6788644 0.0731186 -0.6670972 0.2979567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7767 7792 0.509217 -0.598691 -0.336751 -0.1663175 -0.2730519 0.9329716 0.1653636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7768 7428 -0.672846 -0.278727 -0.388676 -0.7987144 -0.0402567 -0.4110388 0.4375863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7768 7791 -0.283709 1.081674 -0.030593 -0.7613751 0.4718522 -0.1122883 0.4301800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7769 7790 0.726160 0.030544 -0.279148 -0.2363615 -0.6707591 0.6782644 0.1848588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7770 7749 0.403221 -1.055223 0.457481 -0.3771302 -0.1844720 0.8574712 0.2974661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7770 7789 -0.331115 1.038335 -0.463322 -0.6754436 -0.1901529 0.3625567 0.6133273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7771 7788 0.908883 0.073431 -0.306550 0.0822342 0.3354252 0.4378893 0.8300485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7772 7787 -0.546194 0.910192 0.061487 -0.1853062 0.1558974 -0.5503391 0.7990522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7773 7786 0.268298 0.833019 -0.338129 0.1378499 -0.7227671 -0.4179913 0.5328117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7775 7435 0.773922 -0.114460 -0.689066 -0.4593000 0.1834687 -0.1973337 0.8464291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7775 7744 -0.757004 -0.304489 -0.593455 0.2150653 -0.2819196 -0.8301141 0.4303242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7775 7784 0.744963 0.272266 0.587413 0.1994653 0.2622310 -0.8352024 0.4403244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7776 7436 -0.200970 0.435905 -0.755088 -0.1631133 0.2252675 -0.9466912 0.1625556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7777 7742 -0.396395 0.926215 -0.307972 -0.3589492 -0.6793780 -0.1539212 0.6212159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7777 7782 0.300491 -0.828590 0.437926 -0.0130702 -0.1694134 -0.0971425 0.9806588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7780 7400 -0.515104 -1.052808 -0.008484 -0.4088075 -0.5390241 -0.5534038 0.4858741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7780 7819 0.669859 -0.475200 0.133457 -0.4903533 0.2899948 -0.5457449 0.6145073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7781 7778 0.475895 0.013361 1.076895 -0.3391201 -0.2033206 -0.1102244 0.9118711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7781 7818 -0.304536 0.041422 -0.901777 0.4641486 -0.7504272 -0.4404508 0.1656145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7782 7817 0.528489 -0.574077 -0.167351 -0.2037130 0.3738274 -0.4133333 0.8049284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7783 7776 0.438453 0.582306 0.650979 -0.0486741 -0.4615878 -0.8078402 0.3632655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7783 7816 -0.583332 -0.387221 -0.601930 0.0831387 -0.5723820 0.5351443 0.6157008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7784 7815 -1.100369 0.304700 0.212723 0.1566517 0.3759234 0.0126862 0.9132256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7785 7405 0.139651 0.391173 -0.965900 -0.3642404 0.3869414 -0.8466536 0.0279817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7785 7774 0.746897 0.687789 0.310517 0.3116791 -0.1969275 0.6749014 0.6392057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7785 7814 -0.520306 -0.812401 -0.271581 -0.2696798 0.1527413 0.9346512 0.1742702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7787 7407 -0.154529 0.813359 -0.671023 0.5440188 -0.5269450 0.5447093 0.3600893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7787 7812 -1.014098 -0.159673 0.009163 0.3937046 -0.8048220 0.4430919 0.0304592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7788 7408 0.873157 0.291090 -0.442234 0.1488681 0.5365225 -0.8048827 0.2052943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7788 7811 0.252014 -0.916657 0.122586 0.5854422 -0.2192276 0.1901585 0.7569917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7789 7810 0.374855 0.264775 0.639217 0.2461499 -0.0773097 -0.8705046 0.4191124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7790 7809 -0.751040 0.566893 -0.407339 -0.5927028 -0.0568673 0.7410501 0.3103454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7791 7411 -0.063607 0.756896 -0.264516 0.8816620 -0.2016462 0.2267690 0.3613678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7791 7808 -0.864787 0.043756 0.443834 -0.0329084 0.9472332 -0.2739590 0.1631340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7792 7807 -0.904644 0.672385 -0.296662 -0.5586894 -0.7974602 0.2140843 0.0780472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7793 7806 0.700663 -0.520448 0.385536 -0.2416766 -0.1363038 -0.0455711 0.9596546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7794 7805 0.447027 0.812819 0.447316 -0.0820938 0.6393501 0.1957405 0.7390384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7795 7804 0.389305 0.195417 0.773291 0.1176644 0.1195380 -0.9655090 0.1991436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7796 7416 -0.522998 0.397895 -0.875386 0.0736924 -0.2810428 -0.7549025 0.5879682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7797 7802 -0.548662 -0.369037 0.610879 0.8346045 -0.3771568 0.3978850 0.0536243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7798 7801 -0.497540 0.717968 0.552593 0.2040621 0.2448271 -0.9446635 0.0776485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7800 7839 0.358970 -0.624192 0.618515 -0.2302691 0.4750369 0.5353991 0.6592905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7801 7838 0.145049 -0.956906 0.381870 -0.6729316 -0.0558687 0.6101068 0.4145014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7802 7382 -0.734825 0.749838 -0.304837 0.0380768 -0.5968942 0.6633417 0.4497168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7802 7837 0.570652 0.362875 -0.693112 0.1691437 0.3300113 0.3570265 0.8573301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7803 7383 -0.427910 0.712523 -0.463597 0.5042148 -0.6466072 0.0617872 0.5690773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7803 7796 0.231277 0.441724 0.945736 0.5759247 -0.3677625 0.4150976 0.6006292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7803 7836 -0.144413 -0.433204 -1.031791 0.6238258 0.5362083 0.0970245 0.5602753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7804 7835 -0.517453 -0.459702 0.681300 -0.5675977 -0.5856326 -0.4206809 0.3973598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7805 7385 1.012388 0.409364 -0.206286 0.3401278 -0.6509359 0.4339788 0.5217834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7806 7833 0.714615 -0.500788 0.011806 -0.0391059 -0.2270372 -0.7873361 0.5718624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7807 7387 0.202508 0.852697 -0.127076 0.5448986 0.1035898 0.4211743 0.7176119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7807 7832 0.811954 -0.212668 0.529127 0.6320385 0.1692968 0.6237320 0.4275796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7809 7830 0.730498 0.111844 0.648506 -0.2540361 -0.1400622 0.6646477 0.6885432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7810 7390 -0.603590 -0.586157 -0.631841 -0.2581248 0.2509225 0.6725112 0.6466361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7810 7829 -0.761764 0.376575 0.512678 0.1468522 0.4594953 -0.5223336 0.7031829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7811 7828 0.441552 -0.188737 0.959716 -0.5017927 -0.3594991 0.3443257 0.7073926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7812 7827 0.716486 0.774933 -0.170387 -0.7173867 0.6262543 -0.1418231 0.2702743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7813 7786 -0.544131 0.242447 -0.748402 0.4622624 0.2350451 -0.8334291 0.1909532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7813 7826 0.199120 -0.325454 0.949289 0.3495559 -0.8820357 0.0937652 0.3017148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7814 7825 0.417853 0.871078 -0.357809 -0.5958639 -0.1705916 -0.0000115 0.7847577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7815 7824 -0.705305 0.431989 -0.605711 0.3221208 0.2118139 -0.8631808 0.3260244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7816 7823 -0.564022 0.525147 0.383243 -0.2621966 -0.0544427 -0.0336554 0.9628895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7817 7822 0.839142 -0.082896 0.618174 0.1598389 0.8338429 -0.4263383 0.3120788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7818 7821 0.411179 -0.562507 0.738214 -0.0728637 0.6910974 0.5388852 0.4761072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7820 7859 -0.735724 0.093619 0.746351 0.1417607 0.0272151 -0.7541517 0.6406391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7821 7858 -1.047773 0.129066 -0.195759 -0.3006784 0.0841977 0.9400161 0.1373789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7822 7857 -1.173564 0.116320 0.275041 0.8122346 -0.4482986 0.3731718 0.0067919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7823 7856 -0.722685 0.236622 0.752478 0.6291295 0.3090711 0.5259430 0.4817210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7825 7365 0.445632 0.685687 -0.625208 0.3562503 -0.1719996 0.3870750 0.8328714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7825 7854 0.743109 0.728168 0.550364 0.6112261 -0.4739210 -0.0648332 0.6305539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7826 7853 0.504574 -0.572854 -0.805565 0.3885050 -0.6196028 0.6792233 0.0617410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7827 7367 -0.834825 0.565411 -0.161009 -0.2022358 -0.2479587 0.9423124 0.0983083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7827 7852 -0.607030 -0.346307 0.601761 0.9443585 -0.1801160 0.1488147 0.2315156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7828 7368 -0.743370 0.272380 -0.745884 -0.2277632 0.7267982 0.0674223 0.6444707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7828 7851 -0.138375 -0.941551 -0.269246 0.2927413 0.1652264 0.2110177 0.9178640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7829 7850 -0.837259 -0.662200 -0.569529 -0.6445642 -0.6541177 -0.1931252 0.3454993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7830 7849 0.162062 -1.003922 0.011513 0.3303045 0.5715222 0.6229552 0.4197478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7831 7808 -1.041583 0.014562 -0.596246 -0.9549015 -0.1367016 0.1734455 0.1984752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7831 7848 1.016962 -0.143797 0.445318 -0.0534255 -0.2233486 -0.3422989 0.9110942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7832 7372 0.663136 -0.697216 -0.168518 0.0308520 -0.3173313 -0.2513721 0.9138715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7832 7847 0.064553 0.111331 0.951008 0.4944129 0.0297610 -0.7099600 0.5006266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7833 7846 0.193815 0.894609 -0.403803 0.2397307 0.4710226 -0.3961556 0.7508180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7834 7805 -0.264611 0.617843 0.785600 -0.4684240 -0.6960819 0.5435864 0.0237242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7835 7844 0.662409 -0.735057 -0.543931 0.2612706 -0.2551246 0.7914172 0.4902121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7836 7843 -0.148285 -0.854862 0.570764 -0.7908274 0.1884223 0.0508048 0.5800930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7838 7378 0.455816 0.994513 -0.099764 0.4058082 -0.3761292 0.6795856 0.4816740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7838 7841 -0.750234 0.344783 -0.297521 0.0079362 -0.3741105 -0.3295538 0.8668175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7840 7879 0.316513 0.445604 -0.773107 -0.3365013 0.8915921 0.3028773 0.0097879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7841 7341 -0.267530 0.994001 -0.220539 -0.0853667 -0.0305736 0.1099062 0.9897972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7841 7878 -0.997826 -0.381381 0.173131 -0.4525684 0.6991795 -0.2630185 0.4869816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7842 7837 0.684275 -0.500740 0.789202 -0.3750844 -0.0250389 0.9261597 0.0302161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7842 7877 -0.713621 0.367375 -0.595827 -0.5705267 -0.4890382 0.4971116 0.4338444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7843 7876 0.022887 -0.229705 -0.934614 -0.2512952 -0.9427119 0.0814594 0.2037383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7844 7344 -0.134120 0.301424 -1.025130 -0.0403498 0.3907231 -0.7324215 0.5561169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7844 7875 -1.036166 -0.080303 0.071195 0.2940745 0.3912662 -0.7062459 0.5115151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7845 7834 0.316636 -0.394407 0.883526 0.0770815 -0.0407264 -0.8904081 0.4467362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7846 7873 0.188224 0.666392 -0.702407 0.2218243 -0.5361957 -0.5240134 0.6234566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7847 7872 -0.836845 0.487976 0.347638 -0.7581833 -0.4380321 0.4070168 0.2600448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7848 7871 0.628306 0.609293 0.112753 0.6531946 -0.6195332 -0.2746035 0.3377992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7849 7870 -1.065325 -0.002208 -0.370137 0.2216403 -0.1126915 -0.8616086 0.4425006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7850 7350 -0.579766 0.700743 -0.240624 0.7947578 0.1645563 -0.4799206 0.3331027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7850 7869 -0.805555 -0.489916 -0.072872 0.5060880 -0.4419157 0.5996179 0.4347918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7851 7868 -0.260072 -0.798201 0.396176 -0.1287574 0.2269658 -0.0224943 0.9650917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7852 7867 -0.384982 0.670171 -0.445615 0.2241662 0.4478837 0.5120141 0.6978476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7853 7353 -0.052032 0.865310 -0.638304 -0.6347049 0.1672725 -0.7470812 0.1050685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7853 7866 -0.695429 0.444580 0.673859 0.5623407 -0.0665675 0.7013319 0.4329842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7854 7865 0.312477 0.406710 -0.755096 0.0337313 0.0460239 0.6986004 0.7132331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7855 7355 -0.732377 -0.311640 -0.681855 0.1218224 0.4703508 0.8543581 0.1843952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7855 7824 -0.306422 -0.373350 0.925123 0.1460900 0.2664054 0.5795454 0.7561832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7855 7864 0.375870 0.488579 -0.657038 0.0575560 0.7329104 0.3799523 0.5613964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7856 7863 0.125654 0.519833 -0.856456 0.4354702 0.1863114 0.8801695 0.0309082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7857 7357 -0.851419 -0.618842 -0.198256 -0.6714965 0.0553518 0.0631868 0.7362310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7858 7358 -0.064688 0.786060 -0.495161 0.0384447 0.9519820 -0.2158318 0.2137027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7858 7861 0.729121 0.422457 0.555458 0.2912978 0.3986916 -0.7812701 0.3818477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7861 7898 -0.913821 0.409133 -0.372396 -0.2327534 0.7261257 0.5099773 0.3981088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7862 7857 -0.165072 -1.015020 -0.019441 0.2324714 -0.8407770 0.1926875 0.4493580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7862 7897 0.255121 0.894373 0.190750 -0.6930780 -0.0453802 0.6250934 0.3561485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7863 7896 -0.806942 -0.648912 -0.034901 -0.2766845 0.4720407 -0.7742795 0.3179850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7864 7895 0.612563 -0.288923 0.663442 -0.1265193 -0.6331559 0.1472787 0.7492767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7865 7325 -0.431058 0.533885 -0.551035 0.3298615 0.1867532 -0.7443281 0.5498093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7865 7894 0.139040 -0.534279 -0.584575 0.3528947 -0.1486577 -0.7766692 0.5001511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7866 7326 -0.062261 -0.768370 -0.796545 -0.0653082 -0.1815229 -0.2587548 0.9464831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7866 7893 0.831514 0.270428 -0.490186 0.2903309 0.3378194 0.8253449 0.3469753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7868 7891 -0.229315 -0.988127 -0.196522 0.4632214 -0.0645782 -0.8816398 0.0629825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7869 7890 0.000426 1.128522 0.262365 0.1275649 -0.2577597 -0.2393427 0.9273630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7870 7330 0.689582 0.314954 -0.332493 -0.3395271 -0.2718897 -0.1325751 0.8906297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7870 7889 0.563638 -0.717882 0.142050 0.4386516 -0.7046103 -0.3460138 0.4374740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7871 7888 -0.413985 -0.372845 -0.610275 0.2323553 -0.7747808 -0.1121585 0.5771882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7872 7887 0.087479 -0.740657 0.455792 0.1638330 -0.0993490 0.6542080 0.7316422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7874 7885 -0.283693 0.268422 0.946752 0.5204450 -0.0640274 -0.7707686 0.3618745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7876 7883 -0.489896 0.068915 1.164264 0.5743525 0.5469010 -0.0687353 0.6052223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7877 7882 0.265808 0.695578 0.675815 0.1278269 -0.1623165 0.9253065 0.3179962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7878 7881 0.300488 -0.018921 -1.117831 -0.1896082 0.8700345 -0.4109226 0.1955282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7879 7339 0.925439 -0.471024 -0.195215 -0.8410043 -0.4893607 0.1919844 0.1279836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7880 7919 0.504159 0.921104 -0.471928 -0.2347887 -0.2322299 0.5223986 0.7861572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7882 7917 0.164118 -0.899667 0.539319 0.6657530 -0.5308015 -0.4436915 0.2795721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7883 7916 -0.738460 0.305292 -0.504597 0.4463694 0.0810651 0.6089451 0.6506679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7884 7304 0.831160 0.571857 -0.345136 -0.4628942 0.5099261 0.7171251 0.1069389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7884 7875 0.234215 -0.842264 -0.708015 -0.6257204 -0.3976265 0.5418567 0.3959273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7884 7915 -0.290724 0.556986 0.704452 -0.5235261 0.0890997 0.8393371 0.1161673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7885 7305 -0.528962 -0.512961 -0.487271 0.1179542 0.3344996 0.8829961 0.3074325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7885 7914 -0.714200 0.308569 0.452842 0.3426837 0.2131273 0.7760898 0.4845918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7886 7873 -0.368185 -0.117536 0.892879 -0.1174642 -0.5896841 -0.7241368 0.3377880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7886 7913 0.499609 0.074068 -0.793266 -0.9374235 -0.2401100 -0.0502566 0.2471006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7887 7307 -0.199813 -0.884016 -0.299090 -0.3526188 0.6251833 0.1806124 0.6724470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7889 7910 0.789401 -0.431952 -0.505864 0.1768279 0.4802723 -0.3651178 0.7776628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7890 7909 -0.169354 1.163842 -0.100993 0.7277178 0.1133356 0.3453637 0.5816406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7892 7867 -0.463432 -0.294464 0.810267 -0.5975039 0.0641140 0.4975498 0.6255579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7893 7906 -0.434105 -0.776823 0.430388 0.3264297 0.0466264 0.5335487 0.7788424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7894 7314 -0.305975 -0.826768 -0.217625 0.1041517 0.4546276 0.5401890 0.7004727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7895 7904 0.429870 -0.511378 -0.401415 -0.6230176 0.3813902 0.3376536 0.5936166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7896 7316 -0.110398 0.868624 -0.722495 -0.1372001 0.1303204 -0.2472992 0.9502820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7896 7903 0.914859 0.201775 0.025695 0.1560974 0.4507342 -0.7277338 0.4928243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7897 7902 0.460531 -0.805797 0.253483 -0.0060339 0.1110713 -0.9797604 0.1664218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7898 7901 0.691321 0.655812 0.020202 -0.7453213 -0.5145554 0.1108370 0.4091993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7899 7860 0.387530 0.459381 0.775768 -0.6856233 0.1574976 0.0223647 0.7103626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7900 7939 0.926609 -0.435552 0.169812 0.2593526 0.8601457 0.1871725 0.3973060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7901 7938 0.825814 0.370123 -0.047619 0.0135384 0.1632719 0.3295302 0.9298220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7903 7936 -0.489288 0.853938 -0.119619 0.4978893 -0.0433602 -0.4353189 0.7488148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7904 7935 0.787132 -0.260954 -0.406304 0.5644985 -0.0240479 0.7427592 0.3592658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7905 7894 -0.443561 0.327247 -0.727342 0.7534643 -0.5927152 -0.0474870 0.2805802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7906 7933 -0.571169 0.357998 0.585328 -0.1671645 0.7795619 0.1567910 0.5828858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7907 7892 0.535553 -0.689650 -0.382912 0.4625166 0.8511778 0.1329282 0.2095349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7907 7932 -0.388539 0.715199 0.441880 0.0565387 -0.0629857 0.4868819 0.8693574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7908 7891 0.543245 0.551922 -0.754349 0.2285138 0.1478550 0.9275216 0.2561717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7909 7930 0.430407 0.038289 -0.897106 -0.6794618 -0.3087918 -0.3400547 0.5721382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7910 7929 0.792813 0.407090 0.582631 -0.3376853 0.3369527 0.8678425 0.1388559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7911 7888 0.086882 -0.765251 -0.740079 -0.0706740 -0.0614982 -0.9787520 0.1823944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7911 7928 -0.257843 0.966793 0.484685 0.4717555 -0.0649175 0.8674257 0.1442397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7912 7887 0.485595 -0.470121 0.924902 -0.3702723 -0.6558755 -0.3323078 0.5677123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7912 7927 -0.260166 0.369819 -0.883862 -0.6907265 0.5888584 -0.2475614 0.3389041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7913 7293 -0.756311 0.536383 -0.115030 0.7274610 -0.4098190 0.5442074 0.0817754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7913 7926 0.392673 0.489079 0.825558 0.7604532 0.5935815 0.2576208 0.0548046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7914 7925 0.741444 0.561133 -0.340961 0.0421740 0.6076969 0.4255047 0.6692321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7915 7295 -0.015232 -0.892933 -0.671712 0.2371456 0.3482027 0.8119341 0.4040789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7915 7924 -0.466662 -0.326317 0.655026 -0.6808086 0.3056351 -0.2003353 0.6347855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7916 7296 -0.389656 -1.064718 -0.240544 -0.5538119 0.4705197 -0.5906571 0.3507532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7916 7923 -0.075069 0.212440 -1.050686 0.5621169 0.8179447 0.0944687 0.0778900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7917 7922 0.488040 0.370108 -0.694980 -0.3762801 -0.3602134 -0.6551839 0.5471688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7918 7881 0.061392 0.647478 -0.911099 0.3282670 -0.0116072 -0.8562442 0.3986878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7918 7921 0.429637 -0.731154 0.859214 -0.4170489 -0.6850048 0.5240464 0.2867298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7920 7959 -1.016626 0.013096 -0.542309 0.6135664 -0.4681090 -0.5172567 0.3699401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7921 7958 -0.658939 -0.846373 -0.209457 0.3900751 0.3113645 -0.3395428 0.7972479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7923 7263 -0.816286 -0.643874 0.023188 -0.3373296 0.7458771 -0.0573755 0.5714755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7923 7956 0.102248 -0.389467 0.883586 -0.5865092 0.0342793 -0.7614153 0.2740049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7924 7955 -0.167503 -0.618282 -0.778647 0.4209625 -0.4904003 0.3374600 0.6844113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7926 7953 0.706159 0.541243 -0.238858 -0.4196472 0.8755946 0.1241525 0.2044910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7927 7267 0.563460 0.557493 -0.500858 0.0148471 0.1414155 0.9404119 0.3088796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7927 7952 -0.611221 0.693237 0.131673 -0.3157210 -0.1837173 0.5039293 0.7827027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7928 7951 0.666630 -0.816161 0.411673 -0.0417459 0.0948977 0.0801899 0.9913734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7929 7950 -0.869630 -0.480922 0.096629 -0.6495274 0.2145017 -0.2277207 0.6929982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7930 7949 -0.559798 0.740709 0.297545 0.4667224 0.5930864 0.6498389 0.0901560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7931 7908 0.748902 0.304422 -0.262737 -0.3077063 -0.2735902 0.1913542 0.8909819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7931 7948 -0.752260 -0.339753 0.503127 -0.5380596 0.6439629 -0.2565026 0.4795936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7932 7947 0.263458 0.845658 0.535400 0.1365374 0.6108562 -0.2426177 0.7411808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7934 7274 0.327156 -0.722738 -0.361304 -0.5456603 -0.0348585 -0.4087103 0.7307501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7934 7905 -0.127998 0.572244 -0.663650 -0.1592036 0.0463357 -0.6488993 0.7425880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7934 7945 0.021890 -0.364962 1.029610 0.2955237 -0.2650713 -0.8975166 0.1920076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7935 7944 -0.601677 -0.618632 0.670499 -0.4895379 -0.6755483 -0.4027640 0.3765214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7936 7943 -0.945944 -0.523957 -0.263023 -0.8954236 -0.2281468 -0.1897788 0.3318880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7937 7902 0.293613 0.881820 0.157631 0.6641873 -0.1780425 0.6809493 0.2519209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7938 7278 0.512848 0.363315 -0.819277 -0.0647693 0.6657451 -0.7142119 0.2061304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7938 7941 0.880317 -0.251956 0.140236 0.4660649 -0.5238151 -0.4954332 0.5127838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7941 7978 0.332057 0.333877 -0.867862 0.1236035 -0.4977221 -0.7755285 0.3681718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7942 7242 0.828000 0.708685 0.052569 0.1019544 -0.3239381 -0.1858045 0.9220337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7942 7937 -0.730888 0.706934 -0.526930 0.2348130 -0.8748949 0.3726594 0.2013620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7942 7977 0.660490 -0.506162 0.473211 0.2194694 -0.3870520 0.3857060 0.8082418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7943 7976 -0.943197 -0.047798 -0.355443 0.1274600 0.9626915 -0.1307240 0.1997253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7944 7975 0.747758 -0.563054 -0.727510 0.2916628 -0.4953987 0.6161726 0.5383719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7945 7245 0.427356 0.597979 -0.675922 0.7463452 0.1434493 -0.6283256 0.1661270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7945 7974 -0.245514 0.850343 0.426291 -0.2042774 0.3014635 -0.1224209 0.9232571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7946 7933 -0.466636 0.238502 -0.992868 0.5346516 -0.4147497 -0.7306213 0.0912303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7946 7973 0.449774 -0.177127 0.812511 -0.5096524 0.5654500 0.5911449 0.2665867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7947 7972 -0.665285 0.669800 -0.018218 -0.0506707 0.6682968 -0.3529475 0.6528705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7948 7248 0.509360 0.835891 -0.160620 0.5539953 0.2379788 -0.1488026 0.7837813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7948 7971 0.171411 -0.060082 -1.004404 -0.6016816 -0.6472676 0.3781499 0.2757293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7949 7249 0.029920 -0.642125 -0.928775 0.5031252 -0.0314375 -0.5113935 0.6959551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7949 7970 0.866814 -0.403936 -0.034710 -0.0666916 0.7644281 0.6253104 0.1420873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7951 7968 0.513877 -1.111926 -0.026050 -0.4865256 0.4786649 -0.6129475 0.3980805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7952 7252 0.588232 0.297860 -0.466886 0.5077071 -0.4166341 -0.5516771 0.5141031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7952 7967 0.391386 0.549868 0.671598 0.6808736 0.1398131 -0.5204566 0.4959722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7953 7966 -0.410303 -0.299599 0.549555 -0.4601190 0.4777983 0.7483291 0.0017031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7954 7925 0.785108 -0.495276 0.253917 0.3857770 -0.3565392 -0.8509143 0.0009059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7954 7965 -0.924275 0.493912 -0.295804 -0.7512517 0.3395309 0.0483168 0.5639195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7955 7964 -0.786174 -0.200292 0.725251 0.1909018 -0.0122707 0.7808344 0.5947298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7956 7256 0.455366 0.306967 -0.800431 -0.1673532 -0.4736649 0.7135393 0.4883607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7956 7963 1.006448 -0.095849 0.390727 0.6366257 -0.0470232 -0.7664211 0.0713814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7957 7257 0.954389 -0.085680 -0.525544 0.2387881 -0.6414643 -0.4732845 0.5545319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7957 7922 -0.621574 -0.081015 -0.858931 0.3588107 -0.0332670 -0.9029829 0.2340298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7957 7962 0.656814 0.090619 0.851035 0.0916136 -0.8590473 -0.0020090 0.5036275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7960 7999 0.394874 0.740690 -0.577818 -0.6476637 -0.2875529 0.6738939 0.2090745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7961 7998 0.398588 0.526224 0.495168 -0.3086110 0.0489040 0.1128290 0.9432058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7962 7997 0.403176 -0.125561 -0.947735 0.3974496 0.3195929 0.1897018 0.8389919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7964 7224 -0.572831 0.079174 -0.897756 -0.0797452 0.4271100 -0.2389808 0.8683927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7964 7995 0.169253 1.030006 0.328646 -0.6710272 -0.0882176 -0.6418515 0.3605092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7965 7994 -0.747087 0.821374 0.123827 0.1802018 -0.2673575 0.8548974 0.4064451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7966 7993 0.137565 1.082341 0.047781 0.5088276 -0.0483907 -0.6804687 0.5250858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7968 7991 0.660627 0.113864 0.623882 0.3101354 -0.3660255 0.4391483 0.7595987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7969 7950 -0.595386 0.493369 0.586956 -0.2359954 -0.2748174 0.4650487 0.8077817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7969 7990 0.558305 -0.629712 -0.692074 0.4285218 0.5580048 0.6228259 0.3421806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7970 7230 0.419354 -0.902970 -0.392198 0.0443194 -0.0212586 -0.8447252 0.5329383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7970 7989 -1.083277 -0.262287 -0.112227 -0.3323312 0.6879357 0.6113102 0.2063983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7974 7985 -0.593194 0.526610 0.599249 -0.2830245 -0.4177049 0.6243655 0.5963116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7975 7984 -1.036546 -0.513320 0.422002 -0.0634115 -0.3685976 0.7030945 0.6047917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7977 7982 0.232011 -0.808304 0.547309 0.5550562 0.1328494 -0.7870657 0.2340753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7978 7981 -0.531755 -0.667585 -0.364453 -0.8476990 -0.0770418 0.2517874 0.4605149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7979 7940 -0.160071 -1.087295 0.628392 0.5695255 -0.4621915 -0.2300432 0.6396092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7982 7202 0.567182 0.638460 -0.732748 -0.7462430 -0.3412603 0.5711771 0.0204810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7983 7203 0.315554 0.396098 -0.868618 0.1961561 -0.3751750 -0.8098598 0.4060709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7983 7976 -0.833808 -0.038628 -0.486054 -0.5019699 -0.0809194 0.0429974 0.8600171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7985 7205 0.733566 -0.037844 -0.726413 -0.1313442 -0.5835091 0.6047113 0.5259183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7988 7971 -0.057684 1.122703 0.281402 0.4687290 0.3775549 -0.7934094 0.0908120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7990 7210 0.322549 -1.035351 -0.772072 0.5027087 0.2509827 -0.8174518 0.1267443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7991 7211 0.408799 0.311063 -0.875217 -0.2537451 0.4376733 -0.6998781 0.5042085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7992 7967 -0.507240 -0.601997 0.790783 -0.0742520 0.4192911 -0.8446672 0.3243748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7994 7214 -0.106579 -0.528841 -0.733066 0.3211131 -0.3414351 -0.0331974 0.8827266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7995 7215 -0.987409 -0.388042 -0.249638 -0.3450530 -0.7417828 -0.4777004 0.3201547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7996 7963 0.356421 -0.903988 -0.185193 0.4530700 0.1144297 -0.1805541 0.8654673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 diff --git a/examples/module/pgo/data/sphere_bignoise_vertex3.g2o b/examples/module/pgo/data/sphere_bignoise_vertex3.g2o new file mode 100644 index 0000000..c09e6f4 --- /dev/null +++ b/examples/module/pgo/data/sphere_bignoise_vertex3.g2o @@ -0,0 +1,10847 @@ +VERTEX_SE3:QUAT 0 18.7381 2.74428e-07 98.2287 0 0 0 1 +VERTEX_SE3:QUAT 1 19.0477 2.34636 98.2319 -0.139007 0.0806488 0.14657 0.976059 +VERTEX_SE3:QUAT 2 18.2645 4.24943 97.2057 -0.245499 0.0604028 0.303424 0.918703 +VERTEX_SE3:QUAT 3 16.9553 5.93643 96.0247 -0.224044 0.00405132 0.325757 0.918515 +VERTEX_SE3:QUAT 4 15.7039 7.47018 94.95 -0.296035 -0.0489643 0.352924 0.886234 +VERTEX_SE3:QUAT 5 14.2759 8.79177 93.4729 -0.156498 -0.0138016 0.35213 0.922671 +VERTEX_SE3:QUAT 6 12.6991 10.4151 92.7022 -0.164088 0.0122952 0.161119 0.973121 +VERTEX_SE3:QUAT 7 12.1447 12.8053 91.7945 -0.0100862 0.157459 0.137556 0.977846 +VERTEX_SE3:QUAT 8 11.8024 15.1529 91.5687 0.0965312 0.335796 0.0607819 0.935002 +VERTEX_SE3:QUAT 9 11.7867 17.5693 91.8963 0.182987 0.334248 0.0669127 0.922126 +VERTEX_SE3:QUAT 10 12.0189 19.932 92.7783 0.0521664 0.36274 0.200284 0.908617 +VERTEX_SE3:QUAT 11 11.0925 22.272 93.3787 0.244176 0.264528 0.15573 0.919865 +VERTEX_SE3:QUAT 12 10.7607 24.6552 94.8896 0.148465 0.364814 0.221324 0.892123 +VERTEX_SE3:QUAT 13 10.1342 26.6638 96.0291 0.460439 0.473436 0.272905 0.699556 +VERTEX_SE3:QUAT 14 10.6361 27.8577 98.6647 0.462937 0.526742 0.233797 0.673477 +VERTEX_SE3:QUAT 15 10.4438 28.8014 101.027 0.392959 0.494508 0.228972 0.740687 +VERTEX_SE3:QUAT 16 10.4263 30.0006 103.271 0.460691 0.527295 0.145698 0.698925 +VERTEX_SE3:QUAT 17 11.4717 31.2296 105.381 0.505254 0.452375 0.32824 0.657521 +VERTEX_SE3:QUAT 18 11.7559 32.3797 108.197 0.449705 0.347531 0.35294 0.74325 +VERTEX_SE3:QUAT 19 11.087 33.6087 110.383 0.441643 0.292346 0.258036 0.808024 +VERTEX_SE3:QUAT 20 10.6158 35.1103 113.082 0.620818 0.239288 0.26559 0.697702 +VERTEX_SE3:QUAT 21 10.3524 35.4769 116.103 0.58053 0.273608 0.266106 0.719243 +VERTEX_SE3:QUAT 22 10.3485 35.9931 119.015 0.524267 0.279778 0.334297 0.731515 +VERTEX_SE3:QUAT 23 9.68216 36.7118 121.701 0.477631 0.288071 0.38625 0.734639 +VERTEX_SE3:QUAT 24 9.11976 37.8483 124.272 0.624912 0.299747 0.304355 0.653456 +VERTEX_SE3:QUAT 25 9.22631 37.7179 127.084 0.630101 0.0934945 0.181116 0.749285 +VERTEX_SE3:QUAT 26 8.72303 38.101 129.752 0.566918 0.0780591 0.285824 0.768645 +VERTEX_SE3:QUAT 27 7.70635 38.6374 132.233 0.687909 -0.0952818 0.361701 0.621992 +VERTEX_SE3:QUAT 28 5.93736 38.2599 134.515 0.631257 -0.125726 0.461316 0.610651 +VERTEX_SE3:QUAT 29 3.70252 37.5279 136.374 0.739805 -0.16538 0.387394 0.524656 +VERTEX_SE3:QUAT 30 2.08577 36.6128 138.233 0.712385 -0.0193524 0.415843 0.564984 +VERTEX_SE3:QUAT 31 0.63851 35.4922 140.955 0.648541 -0.132523 0.386185 0.642412 +VERTEX_SE3:QUAT 32 -1.46014 35.1985 142.846 0.593824 -0.287329 0.471992 0.584841 +VERTEX_SE3:QUAT 33 -4.00908 35.0041 144.392 0.577593 -0.371077 0.54973 0.475904 +VERTEX_SE3:QUAT 34 -6.69731 34.303 144.741 0.519894 -0.441358 0.599678 0.418688 +VERTEX_SE3:QUAT 35 -9.22776 33.7473 144.559 0.541721 -0.593466 0.522486 0.28521 +VERTEX_SE3:QUAT 36 -12.1911 33.4362 143.841 0.374436 -0.676438 0.557473 0.30241 +VERTEX_SE3:QUAT 37 -14.8441 33.6249 142.271 0.362823 -0.619327 0.642118 0.269219 +VERTEX_SE3:QUAT 38 -17.276 33.6987 140.036 0.35085 -0.707593 0.489455 0.369662 +VERTEX_SE3:QUAT 39 -19.3684 34.4221 138.991 0.30205 -0.714654 0.506231 0.376518 +VERTEX_SE3:QUAT 40 -21.6245 35.2909 137.509 0.218515 -0.715909 0.585025 0.312204 +VERTEX_SE3:QUAT 41 -23.7379 36.1132 135.567 0.359201 -0.76903 0.340186 0.404773 +VERTEX_SE3:QUAT 42 -26.1266 37.467 134.699 0.140353 -0.702352 0.293173 0.633287 +VERTEX_SE3:QUAT 43 -27.8492 39.7701 134.136 -0.0110356 -0.812083 0.362746 0.456962 +VERTEX_SE3:QUAT 44 -28.7622 41.7539 132.047 -0.147162 -0.82839 0.410754 0.351277 +VERTEX_SE3:QUAT 45 -28.8273 43.6624 129.733 -0.203699 -0.853759 0.401628 0.261337 +VERTEX_SE3:QUAT 46 -28.5946 45.2068 127.362 -0.312251 -0.814735 0.361729 0.328419 +VERTEX_SE3:QUAT 47 -27.7892 46.8389 125.093 -0.307218 -0.77686 0.386666 0.390634 +VERTEX_SE3:QUAT 48 -26.9947 48.6922 122.253 -0.454127 -0.692602 0.426911 0.363068 +VERTEX_SE3:QUAT 49 -26.0807 49.4068 119.017 -0.512984 -0.690637 0.399 0.317281 +VERTEX_SE3:QUAT 50 -24.8419 49.9391 116.306 -0.490213 -0.75862 0.379647 0.200136 +VERTEX_SE3:QUAT 51 -22.8301 50.6185 113.778 -0.445263 -0.781519 0.330615 0.285765 +VERTEX_SE3:QUAT 52 -21.2206 52.0923 111.194 -0.408853 -0.831959 0.345229 0.146632 +VERTEX_SE3:QUAT 53 -19.4488 53.3456 108.856 -0.342398 -0.70132 0.511585 0.359437 +VERTEX_SE3:QUAT 54 -19.0087 54.0285 105.637 -0.283341 -0.740309 0.341654 0.50491 +VERTEX_SE3:QUAT 55 -18.5807 55.8779 103.393 -0.275734 -0.717446 0.3135 0.557637 +VERTEX_SE3:QUAT 56 -18.0951 57.835 101.033 -0.403574 -0.693621 0.295399 0.518418 +VERTEX_SE3:QUAT 57 -17.3312 59.3829 98.3378 -0.583224 -0.615515 0.170418 0.501945 +VERTEX_SE3:QUAT 58 -15.6435 59.7423 95.5582 -0.615189 -0.637638 0.0715505 0.458084 +VERTEX_SE3:QUAT 59 -13.2997 60.3309 93.3135 -0.818345 -0.415329 0.113634 0.380659 +VERTEX_SE3:QUAT 60 -11.2997 59.1895 91.3429 -0.858437 -0.144525 0.245707 0.426411 +VERTEX_SE3:QUAT 61 -11.0408 57.2146 88.3854 -0.878567 -0.0812818 0.203078 0.424585 +VERTEX_SE3:QUAT 62 -11.1895 54.8902 85.6811 -0.809425 0.0147043 0.292493 0.508983 +VERTEX_SE3:QUAT 63 -12.2078 53.2296 82.9384 -0.868539 -0.00699396 0.161026 0.468681 +VERTEX_SE3:QUAT 64 -12.9247 51.1842 80.1736 -0.846335 -0.029176 0.248022 0.47048 +VERTEX_SE3:QUAT 65 -13.3455 49.3818 77.3256 -0.809744 0.0670697 0.286209 0.50784 +VERTEX_SE3:QUAT 66 -15.3112 47.5888 74.6811 -0.655998 0.276847 0.340164 0.614257 +VERTEX_SE3:QUAT 67 -18.3865 47.0965 72.9114 -0.754037 0.165067 0.221773 0.595817 +VERTEX_SE3:QUAT 68 -20.2474 46.4104 70.1158 -0.74063 -0.0265961 0.287511 0.60671 +VERTEX_SE3:QUAT 69 -21.3396 45.3961 66.9707 -0.671865 0.0369888 0.294322 0.678678 +VERTEX_SE3:QUAT 70 -23.2468 45.1578 63.7888 -0.649987 0.169827 0.440479 0.595528 +VERTEX_SE3:QUAT 71 -25.6762 44.1653 61.5741 -0.604131 0.200517 0.479127 0.604364 +VERTEX_SE3:QUAT 72 -28.5826 43.3443 59.7282 -0.541387 0.36032 0.486068 0.583788 +VERTEX_SE3:QUAT 73 -31.9703 43.1717 58.8719 -0.529255 0.403957 0.613655 0.424423 +VERTEX_SE3:QUAT 74 -35.1818 42.0134 59.2441 -0.521065 0.382576 0.611177 0.456717 +VERTEX_SE3:QUAT 75 -38.7462 40.9857 59.6932 -0.47101 0.377156 0.633654 0.484135 +VERTEX_SE3:QUAT 76 -42.0718 40.3578 59.5347 -0.534971 0.450385 0.677399 0.228232 +VERTEX_SE3:QUAT 77 -44.7708 38.7254 61.0747 -0.324258 0.714023 0.585312 0.206004 +VERTEX_SE3:QUAT 78 -47.127 38.9113 63.9284 -0.383793 0.615285 0.618824 0.301967 +VERTEX_SE3:QUAT 79 -50.3841 38.4245 66.3058 -0.277401 0.747088 0.568962 0.202954 +VERTEX_SE3:QUAT 80 -52.291 39.298 69.0961 -0.367854 0.680709 0.621177 0.124328 +VERTEX_SE3:QUAT 81 -54.5704 39.2599 71.7926 -0.254183 0.692967 0.674536 0.0137878 +VERTEX_SE3:QUAT 82 -55.7016 39.0618 75.2517 -0.219517 0.614424 0.755866 0.054431 +VERTEX_SE3:QUAT 83 -56.9522 38.4381 78.3477 0.256857 -0.634401 -0.722844 0.0951631 +VERTEX_SE3:QUAT 84 -57.6289 37.9638 81.9669 0.189647 -0.710957 -0.668239 0.109685 +VERTEX_SE3:QUAT 85 -58.3281 37.6535 85.5763 0.0702427 -0.786588 -0.607255 0.087104 +VERTEX_SE3:QUAT 86 -58.2816 38.4763 89.1213 -0.0824894 -0.820837 -0.557213 0.0945291 +VERTEX_SE3:QUAT 87 -57.1994 39.6079 92.4409 -0.0767657 -0.862736 -0.499764 0.00545862 +VERTEX_SE3:QUAT 88 -56.4012 41.3847 95.3846 0.149723 0.892229 0.425963 0.00809379 +VERTEX_SE3:QUAT 89 -55.0525 43.6407 98.1154 -0.331274 -0.861532 -0.338519 0.182823 +VERTEX_SE3:QUAT 90 -52.5661 45.3709 99.9387 -0.299659 -0.861108 -0.209899 0.353045 +VERTEX_SE3:QUAT 91 -49.7551 48.1635 100.678 -0.328151 -0.87805 -0.00608031 0.348295 +VERTEX_SE3:QUAT 92 -47.4975 51.4032 99.4374 -0.428261 -0.874321 0.00974707 0.228166 +VERTEX_SE3:QUAT 93 -44.2148 53.8838 98.5225 -0.408969 -0.894023 -0.0379945 0.178949 +VERTEX_SE3:QUAT 94 -41.3342 56.3878 98.3727 -0.576309 -0.790349 0.146025 0.147963 +VERTEX_SE3:QUAT 95 -37.75 57.2746 96.7377 -0.648981 -0.754048 0.071057 0.0720155 +VERTEX_SE3:QUAT 96 -33.9127 57.6475 96.0028 -0.750719 -0.653147 0.0512338 0.0848181 +VERTEX_SE3:QUAT 97 -30.1828 57.0741 95.358 -0.727435 -0.677005 0.0994413 0.0511346 +VERTEX_SE3:QUAT 98 -26.5463 56.7601 94.6816 -0.877932 -0.441349 0.184845 0.0166872 +VERTEX_SE3:QUAT 99 -23.7373 54.184 93.5183 0.842841 0.481898 -0.22068 0.0932357 +VERTEX_SE3:QUAT 100 -20.5141 52.0882 93.6591 0.855664 0.485835 -0.0725008 0.162934 +VERTEX_SE3:QUAT 101 -17.5234 50.1493 94.5959 0.934375 0.354087 -0.0347715 0.018897 +VERTEX_SE3:QUAT 102 -15.5292 47.068 94.8281 -0.86477 -0.48837 0.115468 0.0183275 +VERTEX_SE3:QUAT 103 -12.1543 44.8108 94.4037 0.920235 0.336101 -0.200497 0.00216307 +VERTEX_SE3:QUAT 104 -9.67951 41.4067 93.8208 -0.946493 -0.26993 0.176886 0.000742715 +VERTEX_SE3:QUAT 105 -8.04835 37.7823 93.6266 -0.923796 -0.358054 0.0883693 0.102901 +VERTEX_SE3:QUAT 106 -5.86369 34.6301 92.4712 -0.886039 -0.370514 -0.00307236 0.27865 +VERTEX_SE3:QUAT 107 -3.4315 31.8809 90.3463 -0.879533 -0.365888 0.194884 0.233596 +VERTEX_SE3:QUAT 108 -1.1319 29.2552 88.1278 -0.933496 -0.252515 0.202962 0.153714 +VERTEX_SE3:QUAT 109 0.511604 25.9611 86.537 -0.907545 -0.163197 0.338443 0.187578 +VERTEX_SE3:QUAT 110 1.01033 22.2133 84.7306 0.922998 -0.00118935 -0.384786 0.00368425 +VERTEX_SE3:QUAT 111 0.638777 18.6416 85.3265 0.89368 -0.264912 -0.36193 0.0128177 +VERTEX_SE3:QUAT 112 -1.08064 15.3594 86.3893 -0.88774 0.340269 0.293544 0.0998358 +VERTEX_SE3:QUAT 113 -3.32504 12.2864 86.5753 0.874714 -0.332075 -0.352282 0.0223463 +VERTEX_SE3:QUAT 114 -5.85645 9.31926 87.8638 0.794782 -0.450663 -0.399645 0.0742175 +VERTEX_SE3:QUAT 115 -8.71039 7.15611 90.3339 0.788036 -0.384639 -0.416804 0.239429 +VERTEX_SE3:QUAT 116 -10.3508 4.53809 93.1986 0.793018 -0.319676 -0.459375 0.240635 +VERTEX_SE3:QUAT 117 -11.4191 1.7633 96.2406 0.851448 -0.333774 -0.356865 0.190468 +VERTEX_SE3:QUAT 118 -13.1588 -1.16336 98.906 0.84866 -0.275879 -0.449258 0.042833 +VERTEX_SE3:QUAT 119 -14.8904 -4.47011 100.454 0.720573 -0.415429 -0.55491 0.0164083 +VERTEX_SE3:QUAT 120 -16.9116 -7.33555 102.328 0.714929 -0.316636 -0.616269 0.0939692 +VERTEX_SE3:QUAT 121 -18.2263 -10.6761 104.768 0.684023 -0.215148 -0.690528 0.0948393 +VERTEX_SE3:QUAT 122 -19.2577 -14.6426 107.188 0.732566 -0.191015 -0.603018 0.251454 +VERTEX_SE3:QUAT 123 -19.2948 -18.0412 109.759 0.773597 -0.0301225 -0.601299 0.197686 +VERTEX_SE3:QUAT 124 -18.5272 -22.271 111.361 0.734755 0.0801768 -0.649326 0.179116 +VERTEX_SE3:QUAT 125 -17.0396 -25.9531 112.132 0.702656 -0.0428757 -0.700842 0.115137 +VERTEX_SE3:QUAT 126 -16.8218 -30.043 113.286 0.605757 -0.146817 -0.732149 0.274702 +VERTEX_SE3:QUAT 127 -15.8321 -33.3557 115.512 0.652416 -0.357125 -0.634449 0.21045 +VERTEX_SE3:QUAT 128 -16.4583 -36.0894 118.676 0.665161 -0.337278 -0.653736 0.128191 +VERTEX_SE3:QUAT 129 -17.5108 -39.1472 121.51 0.688383 -0.437002 -0.54749 0.188184 +VERTEX_SE3:QUAT 130 -19.4601 -41.3794 124.716 0.742666 -0.393059 -0.467993 0.273742 +VERTEX_SE3:QUAT 131 -20.9927 -43.6834 127.893 0.66629 -0.511787 -0.462096 0.283899 +VERTEX_SE3:QUAT 132 -22.7616 -44.6799 131.72 0.570789 -0.668852 -0.42558 0.21382 +VERTEX_SE3:QUAT 133 -25.1742 -44.5693 135.665 0.432272 -0.79102 -0.42668 0.0732958 +VERTEX_SE3:QUAT 134 -27.9409 -43.2101 138.824 0.370573 -0.738184 -0.53633 0.173525 +VERTEX_SE3:QUAT 135 -29.5428 -42.7161 142.995 0.219873 -0.77002 -0.585781 0.124839 +VERTEX_SE3:QUAT 136 -30.2901 -41.5048 147.412 0.061701 -0.825258 -0.483474 0.285297 +VERTEX_SE3:QUAT 137 -29.407 -39.2058 151.026 -0.0652144 -0.85188 -0.363868 0.371009 +VERTEX_SE3:QUAT 138 -27.9718 -36.1173 153.201 0.00274577 -0.86258 -0.21729 0.456874 +VERTEX_SE3:QUAT 139 -26.9946 -32.1664 154.748 -0.12321 -0.919295 -0.144038 0.344918 +VERTEX_SE3:QUAT 140 -25.3102 -27.9913 155.218 -0.216933 -0.863017 -0.189954 0.414801 +VERTEX_SE3:QUAT 141 -23.0094 -24.3018 155.642 -0.216006 -0.862979 -0.209279 0.40597 +VERTEX_SE3:QUAT 142 -20.2448 -20.7473 156.268 -0.0630262 -0.826652 -0.227391 0.51085 +VERTEX_SE3:QUAT 143 -18.5828 -16.655 157.731 -0.089603 -0.76844 -0.348859 0.528932 +VERTEX_SE3:QUAT 144 -16.0768 -13.3036 159.439 -0.294598 -0.718933 -0.325337 0.538983 +VERTEX_SE3:QUAT 145 -12.2133 -10.6451 159.597 -0.172443 -0.703888 -0.301673 0.619515 +VERTEX_SE3:QUAT 146 -9.36881 -7.28424 160.303 -0.0523001 -0.7516 -0.308775 0.580535 +VERTEX_SE3:QUAT 147 -7.24752 -3.48775 161.998 -0.181259 -0.733787 -0.280253 0.591744 +VERTEX_SE3:QUAT 148 -4.54447 0.163443 162.278 -0.198269 -0.710865 -0.32878 0.589291 +VERTEX_SE3:QUAT 149 -1.56717 3.47152 163.21 -0.173627 -0.600075 -0.231118 0.745888 +VERTEX_SE3:QUAT 150 1.09707 7.40551 163.224 -0.259768 -0.583516 -0.19348 0.744712 +VERTEX_SE3:QUAT 151 3.55028 10.739 162.034 -0.228015 -0.670908 -0.252381 0.658935 +VERTEX_SE3:QUAT 152 6.35103 14.135 161.891 -0.235274 -0.740282 -0.168645 0.606784 +VERTEX_SE3:QUAT 153 9.1223 18.3467 161.726 -0.215113 -0.782896 -0.0780359 0.578542 +VERTEX_SE3:QUAT 154 11.4663 22.1808 160.99 -0.331087 -0.69614 -0.0561227 0.634524 +VERTEX_SE3:QUAT 155 14.1868 25.9607 159.201 -0.333399 -0.781698 0.0270139 0.526369 +VERTEX_SE3:QUAT 156 16.3005 29.5925 157.141 -0.475592 -0.729758 0.0107512 0.49107 +VERTEX_SE3:QUAT 157 19.4049 32.0698 154.384 -0.312573 -0.734562 0.0482193 0.600326 +VERTEX_SE3:QUAT 158 21.1435 36.0079 152.309 -0.319224 -0.621377 0.0548799 0.713425 +VERTEX_SE3:QUAT 159 22.8534 39.374 149.496 -0.224462 -0.600509 0.106132 0.760093 +VERTEX_SE3:QUAT 160 23.157 43.4321 146.991 -0.253274 -0.464025 0.195019 0.826136 +VERTEX_SE3:QUAT 161 22.781 46.8178 143.99 -0.0601156 -0.455869 0.101065 0.882244 +VERTEX_SE3:QUAT 162 21.9774 51.2398 142.857 -0.116385 -0.485144 0.125129 0.857573 +VERTEX_SE3:QUAT 163 21.3788 55.4322 141.256 -0.0444539 -0.650323 0.180094 0.736661 +VERTEX_SE3:QUAT 164 20.2761 59.8915 139.972 -0.135634 -0.641052 0.21139 0.725238 +VERTEX_SE3:QUAT 165 19.5597 64.1611 137.359 0.0191262 -0.696793 0.312999 0.645093 +VERTEX_SE3:QUAT 166 17.5537 67.9284 135.206 -0.0572675 -0.604464 0.412026 0.679395 +VERTEX_SE3:QUAT 167 15.2138 71.266 132.092 -0.0652571 -0.696224 0.364599 0.614883 +VERTEX_SE3:QUAT 168 13.5679 74.6481 128.925 -0.163887 -0.618141 0.342162 0.688454 +VERTEX_SE3:QUAT 169 12.3373 78.049 125.58 -0.100232 -0.553701 0.531471 0.633172 +VERTEX_SE3:QUAT 170 9.41774 79.8376 122.159 -0.230804 -0.500873 0.572085 0.607104 +VERTEX_SE3:QUAT 171 7.45255 80.7947 117.553 -0.177647 -0.48383 0.591049 0.620493 +VERTEX_SE3:QUAT 172 4.62935 81.7077 113.6 -0.183631 -0.624966 0.546639 0.526197 +VERTEX_SE3:QUAT 173 2.70018 82.9692 109.044 -0.224824 -0.630301 0.613555 0.419196 +VERTEX_SE3:QUAT 174 2.09042 83.82 104.337 -0.157399 -0.569151 0.67557 0.441472 +VERTEX_SE3:QUAT 175 0.470415 83.8496 99.8595 -0.191831 -0.614445 0.681475 0.34821 +VERTEX_SE3:QUAT 176 -0.666318 83.9174 94.7094 -0.219808 -0.657132 0.66673 0.274469 +VERTEX_SE3:QUAT 177 -1.10594 84.0942 89.7615 -0.166729 -0.710886 0.61858 0.290175 +VERTEX_SE3:QUAT 178 -1.70281 84.615 84.4608 -0.358677 -0.650135 0.606141 0.285075 +VERTEX_SE3:QUAT 179 -0.954874 84.6855 79.4433 -0.482974 -0.589504 0.603217 0.235265 +VERTEX_SE3:QUAT 180 0.77216 83.6482 74.8286 -0.537672 -0.525366 0.600027 0.273619 +VERTEX_SE3:QUAT 181 2.35057 82.1891 70.0265 -0.485729 -0.524389 0.682393 0.153047 +VERTEX_SE3:QUAT 182 3.61284 80.0336 65.8753 -0.535744 -0.268529 0.760571 0.249804 +VERTEX_SE3:QUAT 183 3.24719 76.2509 62.4038 -0.659628 -0.273236 0.668779 0.207288 +VERTEX_SE3:QUAT 184 3.62833 72.1705 58.8407 -0.679312 -0.248873 0.668611 0.171919 +VERTEX_SE3:QUAT 185 3.93266 67.8215 56.0089 0.775707 0.124058 -0.616706 0.0506172 +VERTEX_SE3:QUAT 186 5.12678 62.4428 55.4787 0.755359 0.0689093 -0.59586 0.263885 +VERTEX_SE3:QUAT 187 7.21504 58.1217 57.2149 0.804979 -0.102357 -0.484463 0.326845 +VERTEX_SE3:QUAT 188 7.95676 54.4301 60.5207 0.772677 -0.31258 -0.473451 0.284794 +VERTEX_SE3:QUAT 189 6.8024 51.1548 64.424 0.821733 -0.252141 -0.371722 0.350717 +VERTEX_SE3:QUAT 190 6.10029 48.1446 68.5344 0.665628 -0.346435 -0.403747 0.523365 +VERTEX_SE3:QUAT 191 5.83942 47.4664 73.5785 0.696926 -0.376088 -0.417186 0.445879 +VERTEX_SE3:QUAT 192 5.25092 45.7754 78.5465 0.67092 -0.482754 -0.334544 0.452653 +VERTEX_SE3:QUAT 193 3.32542 45.2443 83.2791 0.561594 -0.517471 -0.211212 0.610103 +VERTEX_SE3:QUAT 194 1.22526 47.0364 87.8659 0.646912 -0.428695 -0.0536355 0.62837 +VERTEX_SE3:QUAT 195 -1.77943 47.8566 92.2898 0.512358 -0.514868 0.00518581 0.687294 +VERTEX_SE3:QUAT 196 -4.46327 50.5009 95.7982 0.646308 -0.552749 0.0540946 0.523286 +VERTEX_SE3:QUAT 197 -8.52098 51.6604 99.1163 0.566509 -0.57276 0.192509 0.560315 +VERTEX_SE3:QUAT 198 -13.1904 53.2228 101.537 0.56456 -0.57372 0.173897 0.567343 +VERTEX_SE3:QUAT 199 -17.744 54.8627 103.564 0.474057 -0.667881 0.137179 0.557124 +VERTEX_SE3:QUAT 200 -21.8578 57.6585 105.332 0.420709 -0.733046 0.38492 0.370788 +VERTEX_SE3:QUAT 201 -26.5163 59.1355 103.739 0.380639 -0.79561 0.434556 0.182426 +VERTEX_SE3:QUAT 202 -30.6284 61.0431 100.543 0.485049 -0.78234 0.344293 0.184753 +VERTEX_SE3:QUAT 203 -35.3001 62.3366 98.4678 0.324899 -0.825841 0.448364 0.10676 +VERTEX_SE3:QUAT 204 -38.6787 64.4549 94.6953 0.37206 -0.794417 0.479243 0.0282596 +VERTEX_SE3:QUAT 205 -41.7874 66.127 90.6393 0.305968 -0.772148 0.556048 0.031327 +VERTEX_SE3:QUAT 206 -44.4167 67.3923 86.0639 -0.283074 0.8184 -0.494742 0.0729492 +VERTEX_SE3:QUAT 207 -46.2973 69.3313 81.7704 -0.329322 0.802737 -0.472957 0.153204 +VERTEX_SE3:QUAT 208 -48.2866 71.3606 76.9124 -0.16356 0.876557 -0.375814 0.252309 +VERTEX_SE3:QUAT 209 -48.5597 75.2445 72.7996 -0.0600141 0.865125 -0.360814 0.343176 +VERTEX_SE3:QUAT 210 -47.7393 79.2686 69.1294 -0.0210274 0.917819 -0.239338 0.316044 +VERTEX_SE3:QUAT 211 -47.0144 84.5754 67.0484 0.0955683 0.954966 -0.18141 0.21447 +VERTEX_SE3:QUAT 212 -44.8477 89.4779 65.2717 0.230696 0.858052 -0.424398 0.174392 +VERTEX_SE3:QUAT 213 -41.5347 92.4333 61.8949 0.100014 0.804249 -0.487989 0.32411 +VERTEX_SE3:QUAT 214 -38.907 95.0776 57.9934 0.198746 0.891821 -0.301099 0.272936 +VERTEX_SE3:QUAT 215 -35.9207 99.384 55.4668 0.206385 0.919675 -0.288104 0.169113 +VERTEX_SE3:QUAT 216 -33.1168 103.772 52.9178 0.266208 0.870822 -0.388266 0.141608 +VERTEX_SE3:QUAT 217 -30.1496 107.047 49.732 0.25892 0.847839 -0.331752 0.3226 +VERTEX_SE3:QUAT 218 -26.0057 110.591 47.7198 0.351206 0.839941 -0.263311 0.319094 +VERTEX_SE3:QUAT 219 -21.7648 113.778 46.7849 0.452059 0.789287 -0.200993 0.363692 +VERTEX_SE3:QUAT 220 -17.0481 116.512 47.0136 0.522812 0.758171 -0.201375 0.333606 +VERTEX_SE3:QUAT 221 -11.6828 118.527 47.296 0.537439 0.75437 -0.228914 0.299472 +VERTEX_SE3:QUAT 222 -6.26259 120.436 47.1096 0.672581 0.558107 -0.236448 0.424552 +VERTEX_SE3:QUAT 223 -1.08799 120.274 49.0543 0.772944 0.526258 -0.150171 0.321026 +VERTEX_SE3:QUAT 224 4.02071 118.717 50.9086 0.76894 0.495039 -0.183034 0.360785 +VERTEX_SE3:QUAT 225 9.52002 117.292 53.0745 0.822694 0.459758 -0.187218 0.277033 +VERTEX_SE3:QUAT 226 14.5344 114.549 54.8292 0.795356 0.468105 -0.291692 0.2514 +VERTEX_SE3:QUAT 227 19.3377 112.071 55.6393 0.693766 0.516677 -0.250313 0.43483 +VERTEX_SE3:QUAT 228 24.9992 111.49 58.0519 0.749643 0.541834 -0.162145 0.343744 +VERTEX_SE3:QUAT 229 30.1609 110.676 60.4069 0.795504 0.499512 -0.0621977 0.337333 +VERTEX_SE3:QUAT 230 34.4216 108.903 63.504 0.859524 0.458765 -0.121649 0.189617 +VERTEX_SE3:QUAT 231 39.3893 105.803 64.5753 0.913736 0.332767 -0.185581 0.141109 +VERTEX_SE3:QUAT 232 43.2264 100.909 65.1719 0.908259 0.288987 -0.235663 0.189778 +VERTEX_SE3:QUAT 233 46.9751 96.573 66.5703 0.905771 0.265813 -0.292016 0.153782 +VERTEX_SE3:QUAT 234 49.8925 91.9798 67.4065 0.899814 0.272666 -0.339712 0.0241829 +VERTEX_SE3:QUAT 235 53.0407 86.9812 66.7774 0.895227 0.200067 -0.386438 0.0959538 +VERTEX_SE3:QUAT 236 55.7542 82.0189 67.1334 -0.909334 -0.151151 0.36694 0.124983 +VERTEX_SE3:QUAT 237 56.6053 76.5852 65.3127 -0.901163 0.0259279 0.280461 0.329506 +VERTEX_SE3:QUAT 238 55.0854 71.7522 62.2106 -0.841628 0.222103 0.275878 0.407705 +VERTEX_SE3:QUAT 239 51.3011 68.6086 59.0273 -0.795462 0.294868 0.304815 0.432876 +VERTEX_SE3:QUAT 240 46.8305 66.0272 56.242 -0.774949 0.420926 0.201906 0.426039 +VERTEX_SE3:QUAT 241 42.0872 64.3377 53.4453 -0.84723 0.335067 0.279545 0.302961 +VERTEX_SE3:QUAT 242 37.5006 60.6987 51.6057 -0.857979 0.436984 0.192432 0.18944 +VERTEX_SE3:QUAT 243 32.6139 57.4956 50.9806 -0.749578 0.573038 0.243449 0.224704 +VERTEX_SE3:QUAT 244 27.0824 56.473 50.7988 -0.640001 0.622434 0.313037 0.32401 +VERTEX_SE3:QUAT 245 20.8202 56.5566 50.6694 -0.580995 0.695989 0.279761 0.315878 +VERTEX_SE3:QUAT 246 15.2264 57.8163 50.8794 -0.478252 0.706375 0.475899 0.214078 +VERTEX_SE3:QUAT 247 10.2342 58.2725 53.8186 -0.455966 0.735003 0.448971 0.224255 +VERTEX_SE3:QUAT 248 5.03902 58.9835 56.8534 -0.323221 0.739352 0.476689 0.348788 +VERTEX_SE3:QUAT 249 0.562408 61.0381 60.2965 -0.456044 0.791882 0.379765 0.143965 +VERTEX_SE3:QUAT 250 -4.81045 62.783 63.5527 -0.564742 0.701663 0.427432 0.0777016 +VERTEX_SE3:QUAT 251 -9.84923 63.1621 66.6476 -0.552112 0.754524 0.336792 0.111522 +VERTEX_SE3:QUAT 252 -15.5735 64.3409 69.0597 -0.537734 0.778054 0.315071 0.0787704 +VERTEX_SE3:QUAT 253 -20.8989 65.9557 71.699 0.510365 -0.749223 -0.422065 0.00735605 +VERTEX_SE3:QUAT 254 -25.488 67.0151 75.7972 0.468846 -0.811125 -0.322255 0.135693 +VERTEX_SE3:QUAT 255 -29.6655 69.5583 79.8884 0.519457 -0.823528 -0.210952 0.0864043 +VERTEX_SE3:QUAT 256 -34.4547 72.1184 82.4559 0.565636 -0.793209 -0.21599 0.0649919 +VERTEX_SE3:QUAT 257 -39.9383 74.1402 85.145 0.549754 -0.800223 -0.239319 0.0118351 +VERTEX_SE3:QUAT 258 -45.1324 76.4844 87.2505 0.496491 -0.802581 -0.330651 0.00558595 +VERTEX_SE3:QUAT 259 -49.7875 78.5393 90.7615 0.452081 -0.830193 -0.316378 0.0794176 +VERTEX_SE3:QUAT 260 -53.7076 81.5115 94.951 0.395767 -0.871589 -0.257304 0.132274 +VERTEX_SE3:QUAT 261 -56.9922 85.0714 98.2448 0.337119 -0.908812 -0.122194 0.213261 +VERTEX_SE3:QUAT 262 -60.19 89.6828 100.344 0.220306 -0.84672 -0.343189 0.341688 +VERTEX_SE3:QUAT 263 -60.6257 94.1336 104.49 0.115168 -0.875918 -0.322623 0.339734 +VERTEX_SE3:QUAT 264 -60.3548 98.8609 108.477 -0.00287373 -0.917431 -0.148999 0.368932 +VERTEX_SE3:QUAT 265 -59.7119 104.905 110.113 -0.287347 -0.844403 -0.1209 0.435659 +VERTEX_SE3:QUAT 266 -55.775 109.581 109.603 -0.367079 -0.880454 -0.0130293 0.299807 +VERTEX_SE3:QUAT 267 -51.3804 114.098 108.489 -0.495768 -0.808519 0.041252 0.314338 +VERTEX_SE3:QUAT 268 -46.8051 116.986 106.027 -0.471296 -0.8528 -0.0879703 0.207061 +VERTEX_SE3:QUAT 269 -41.3161 120.298 105.972 -0.573029 -0.759628 -0.23118 0.202876 +VERTEX_SE3:QUAT 270 -34.8752 121.882 106.493 -0.695531 -0.550058 -0.237829 0.396372 +VERTEX_SE3:QUAT 271 -29.1062 121.146 104.508 -0.771641 -0.474787 -0.22605 0.357839 +VERTEX_SE3:QUAT 272 -23.7211 119.545 102.106 -0.734269 -0.570712 0.000914804 0.367609 +VERTEX_SE3:QUAT 273 -18.2637 119.031 98.7272 -0.783312 -0.449215 0.200083 0.380256 +VERTEX_SE3:QUAT 274 -14.9485 116.642 93.793 -0.816739 -0.301295 0.104252 0.480927 +VERTEX_SE3:QUAT 275 -12.6697 114.313 88.1663 -0.85657 -0.265606 0.113939 0.427502 +VERTEX_SE3:QUAT 276 -10.9848 110.75 83.4173 -0.767867 -0.266124 0.168735 0.557751 +VERTEX_SE3:QUAT 277 -9.55687 109.238 77.4379 -0.650119 -0.229229 0.207638 0.694036 +VERTEX_SE3:QUAT 278 -9.65354 109.421 70.8949 -0.690312 -0.165336 0.325761 0.62451 +VERTEX_SE3:QUAT 279 -10.8239 108.083 64.885 -0.730059 0.0792169 0.276981 0.619694 +VERTEX_SE3:QUAT 280 -13.7426 106.41 59.4058 -0.83174 0.0567073 0.190501 0.518365 +VERTEX_SE3:QUAT 281 -15.83 103.187 54.2898 -0.829756 0.0952387 0.247217 0.491242 +VERTEX_SE3:QUAT 282 -18.5637 100.113 49.4851 -0.867329 0.0513556 0.171732 0.464339 +VERTEX_SE3:QUAT 283 -20.2387 96.4437 44.4239 -0.859639 0.0862982 0.0571194 0.500311 +VERTEX_SE3:QUAT 284 -21.9923 93.4255 39.1036 -0.865838 0.263362 0.21107 0.369344 +VERTEX_SE3:QUAT 285 -26.4196 89.5575 35.6575 -0.714472 0.446282 0.399659 0.361433 +VERTEX_SE3:QUAT 286 -32.0645 87.5871 34.9693 -0.67774 0.523009 0.494859 0.149145 +VERTEX_SE3:QUAT 287 -37.9532 84.9478 37.537 -0.624687 0.458904 0.576435 0.258643 +VERTEX_SE3:QUAT 288 -43.2471 82.266 39.092 -0.472257 0.529757 0.65639 0.255894 +VERTEX_SE3:QUAT 289 -48.2546 80.4473 42.3945 -0.376636 0.537666 0.721405 0.220535 +VERTEX_SE3:QUAT 290 -53.0023 78.2756 46.5296 0.172842 -0.658131 -0.730626 0.0563521 +VERTEX_SE3:QUAT 291 -53.54 77.6876 52.8771 0.0984959 -0.550474 -0.82768 0.0471452 +VERTEX_SE3:QUAT 292 -53.2453 75.0041 58.7286 0.173403 -0.536699 -0.780772 0.26885 +VERTEX_SE3:QUAT 293 -50.9717 73.3238 64.5233 0.325197 -0.628075 -0.620596 0.338568 +VERTEX_SE3:QUAT 294 -50.2957 73.4567 71.0969 0.230175 -0.720205 -0.448051 0.477048 +VERTEX_SE3:QUAT 295 -49.4751 76.9081 76.7433 0.29835 -0.777664 -0.42945 0.348997 +VERTEX_SE3:QUAT 296 -50.3955 80.0018 82.7659 0.333991 -0.822644 -0.305124 0.344392 +VERTEX_SE3:QUAT 297 -52.371 84.2078 87.272 0.218142 -0.795146 -0.425385 0.3731 +VERTEX_SE3:QUAT 298 -51.9831 87.658 92.8324 0.151161 -0.738411 -0.412066 0.511958 +VERTEX_SE3:QUAT 299 -50.2502 92.182 97.7178 0.152425 -0.749247 -0.356524 0.536923 +VERTEX_SE3:QUAT 300 -48.7838 97.172 102.08 0.202693 -0.817138 -0.236955 0.484824 +VERTEX_SE3:QUAT 301 -49.2255 102.835 105.823 0.214193 -0.860086 -0.340149 0.314122 +VERTEX_SE3:QUAT 302 -50.0912 107.653 110.621 0.325448 -0.85537 -0.373913 0.150384 +VERTEX_SE3:QUAT 303 -53.3193 111.614 115.831 0.14486 -0.933594 -0.27765 0.174148 +VERTEX_SE3:QUAT 304 -54.4022 117.035 119.65 0.0686784 -0.937483 -0.288395 0.182312 +VERTEX_SE3:QUAT 305 -54.0262 122.328 123.192 -0.00300877 -0.935684 -0.277739 0.217593 +VERTEX_SE3:QUAT 306 -52.716 128.084 126.872 0.0953339 -0.855475 -0.405432 0.307731 +VERTEX_SE3:QUAT 307 -51.7097 132.171 131.599 0.0815588 -0.87926 -0.30906 0.353174 +VERTEX_SE3:QUAT 308 -51.0044 137.546 135.547 0.0115202 -0.874871 -0.272459 0.400292 +VERTEX_SE3:QUAT 309 -49.4231 143.505 138.659 -0.00532968 -0.904279 -0.176233 0.388835 +VERTEX_SE3:QUAT 310 -48.0924 149.499 140.636 0.00614735 -0.849997 0.00217517 0.526747 +VERTEX_SE3:QUAT 311 -47.8575 156.21 140.291 0.0180183 -0.858827 0.11104 0.499762 +VERTEX_SE3:QUAT 312 -48.3942 163.025 138.706 0.0875457 -0.892037 -0.0146182 0.443162 +VERTEX_SE3:QUAT 313 -49.3053 169.791 139.232 0.0795753 -0.925912 -0.0505395 0.365787 +VERTEX_SE3:QUAT 314 -49.4155 176.47 140.207 0.0907651 -0.912799 0.0327189 0.396849 +VERTEX_SE3:QUAT 315 -50.5559 183.422 139.946 0.0917511 -0.919056 0.013127 0.383073 +VERTEX_SE3:QUAT 316 -51.5967 190.568 140.017 0.0973551 -0.932642 0.120626 0.325807 +VERTEX_SE3:QUAT 317 -53.0154 197.017 138.765 0.0926821 -0.927336 0.230018 0.280267 +VERTEX_SE3:QUAT 318 -54.9828 202.884 136.476 0.0211752 -0.934548 0.231341 0.269541 +VERTEX_SE3:QUAT 319 -55.8143 209.288 133.748 -0.0188053 -0.919219 0.24797 0.305276 +VERTEX_SE3:QUAT 320 -56.573 215.083 130.127 -0.231317 -0.866843 0.3447 0.276148 +VERTEX_SE3:QUAT 321 -54.8395 219.383 124.733 -0.221679 -0.902927 0.305946 0.204884 +VERTEX_SE3:QUAT 322 -52.1631 224.018 120.296 -0.137806 -0.928015 0.293403 0.183606 +VERTEX_SE3:QUAT 323 -50.5617 229.315 116.251 -0.140308 -0.95833 0.205972 0.139615 +VERTEX_SE3:QUAT 324 -48.6067 235.259 113.368 -0.247632 -0.914531 0.319845 0.00330313 +VERTEX_SE3:QUAT 325 -45.1847 239.672 109.333 0.154687 0.800688 -0.578158 0.0265232 +VERTEX_SE3:QUAT 326 -42.9001 241.983 103.092 0.0673251 0.782576 -0.61736 0.0436824 +VERTEX_SE3:QUAT 327 -41.4462 243.671 96.2625 -0.0970422 -0.743177 0.661286 0.0311708 +VERTEX_SE3:QUAT 328 -40.6052 244.112 88.9493 0.166967 0.826265 -0.536723 0.0365644 +VERTEX_SE3:QUAT 329 -37.9918 246.841 83.1827 0.19023 0.891999 -0.394343 0.112448 +VERTEX_SE3:QUAT 330 -34.703 251.073 78.8135 0.263634 0.89582 -0.283849 0.217793 +VERTEX_SE3:QUAT 331 -30.0486 255.858 76.0749 0.363187 0.840197 -0.235485 0.326665 +VERTEX_SE3:QUAT 332 -24.1993 260.042 74.8741 0.317468 0.850095 -0.320915 0.271231 +VERTEX_SE3:QUAT 333 -18.9955 263.833 71.9274 0.374012 0.782326 -0.401546 0.29469 +VERTEX_SE3:QUAT 334 -13.0261 266.118 69.5035 0.374476 0.787734 -0.263391 0.412151 +VERTEX_SE3:QUAT 335 -7.14413 270.072 68.6078 0.320539 0.839381 -0.295452 0.324656 +VERTEX_SE3:QUAT 336 -1.20876 274.307 66.809 0.541019 0.664639 -0.402774 0.321446 +VERTEX_SE3:QUAT 337 6.09135 274.775 65.9609 0.726593 0.391867 -0.502523 0.256852 +VERTEX_SE3:QUAT 338 11.7259 270.54 66.3683 0.744277 0.398281 -0.459093 0.276871 +VERTEX_SE3:QUAT 339 17.5187 266.69 66.8703 0.911004 0.197884 -0.290585 0.215576 +VERTEX_SE3:QUAT 340 20.7584 260.602 69.4683 0.924662 0.239348 -0.197706 0.220511 +VERTEX_SE3:QUAT 341 24.3238 255.153 71.9507 0.894026 0.17291 -0.203654 0.359645 +VERTEX_SE3:QUAT 342 27.5523 250.011 76.3634 0.87388 0.00175915 -0.170026 0.455436 +VERTEX_SE3:QUAT 343 28.1503 245.801 82.6266 0.873147 -0.0395772 -0.100745 0.475288 +VERTEX_SE3:QUAT 344 28.0387 241.758 88.8158 0.889663 -0.173165 0.0361635 0.420958 +VERTEX_SE3:QUAT 345 25.3334 237.692 94.103 0.892669 -0.142959 0.0275423 0.426552 +VERTEX_SE3:QUAT 346 23.113 233.561 99.2296 0.901536 -0.0914371 0.0891179 0.413438 +VERTEX_SE3:QUAT 347 20.8361 229.121 104.408 0.823789 -0.101082 0.155077 0.535822 +VERTEX_SE3:QUAT 348 18.5126 226.209 110.43 0.795738 -0.140615 -0.0440512 0.587441 +VERTEX_SE3:QUAT 349 16.9923 224.555 117.506 0.743012 -0.281979 0.196723 0.574213 +VERTEX_SE3:QUAT 350 11.8648 223.257 122.626 0.820328 -0.430257 0.161129 0.340555 +VERTEX_SE3:QUAT 351 5.77847 220.65 125.275 0.726264 -0.486185 0.336902 0.35023 +VERTEX_SE3:QUAT 352 -1.3838 219.015 126.604 0.715445 -0.567018 0.35485 0.201769 +VERTEX_SE3:QUAT 353 -8.33111 217.359 125.688 0.672824 -0.433182 0.537824 0.265342 +VERTEX_SE3:QUAT 354 -15.0753 213.702 124.641 0.679819 -0.580045 0.444684 0.0604159 +VERTEX_SE3:QUAT 355 -21.403 211.418 121.109 0.660168 -0.616523 0.429013 0.00502434 +VERTEX_SE3:QUAT 356 -27.6535 210.109 117.138 -0.694894 0.66158 -0.268742 0.0849248 +VERTEX_SE3:QUAT 357 -34.2839 209.84 113.598 0.849125 -0.497596 0.175607 0.0233886 +VERTEX_SE3:QUAT 358 -40.8241 206.499 112.778 0.875872 -0.449119 0.124416 0.125148 +VERTEX_SE3:QUAT 359 -47.2131 202.467 113.484 0.840434 -0.526384 0.126299 0.0252692 +VERTEX_SE3:QUAT 360 -53.9107 199.438 112.472 -0.766625 0.634693 -0.0725375 0.0647223 +VERTEX_SE3:QUAT 361 -60.944 198.303 111.435 -0.762407 0.646981 -0.00392464 0.0116482 +VERTEX_SE3:QUAT 362 -68.2561 197.526 111.467 -0.763173 0.637657 -0.0144504 0.103687 +VERTEX_SE3:QUAT 363 -75.3754 196.915 109.94 0.701874 -0.710082 0.046865 0.0309925 +VERTEX_SE3:QUAT 364 -82.9353 197.488 109.816 -0.656073 0.713979 -0.231521 0.0787442 +VERTEX_SE3:QUAT 365 -89.6604 198.261 106.603 -0.620718 0.743896 -0.114574 0.219548 +VERTEX_SE3:QUAT 366 -96.4248 200.091 103.412 -0.327352 0.836811 -0.0122289 0.438677 +VERTEX_SE3:QUAT 367 -100.438 206.275 101.312 -0.225012 0.883093 -0.0289303 0.410707 +VERTEX_SE3:QUAT 368 -103.216 213.298 99.8551 -0.249602 0.856569 -0.177505 0.415307 +VERTEX_SE3:QUAT 369 -104.737 219.884 96.4073 -0.282551 0.905847 -0.131108 0.287083 +VERTEX_SE3:QUAT 370 -108.05 226.27 93.4043 -0.342517 0.854393 -0.019081 0.390296 +VERTEX_SE3:QUAT 371 -112.242 232.28 91.5317 -0.352223 0.794782 -0.132168 0.476227 +VERTEX_SE3:QUAT 372 -115.916 238.165 88.0954 -0.258255 0.834754 -0.12819 0.469103 +VERTEX_SE3:QUAT 373 -118.31 244.892 84.8217 -0.187599 0.89525 -0.0924971 0.393419 +VERTEX_SE3:QUAT 374 -120.399 252.124 82.8615 -0.0292002 0.869674 0.0126143 0.492601 +VERTEX_SE3:QUAT 375 -121.085 259.539 82.9893 -0.0934048 0.86522 -0.225077 0.43819 +VERTEX_SE3:QUAT 376 -120.292 266.557 79.6239 0.0247895 0.879743 -0.034418 0.473553 +VERTEX_SE3:QUAT 377 -119.522 274.387 79.6216 0.11964 0.92432 0.0799653 0.353448 +VERTEX_SE3:QUAT 378 -117.904 281.489 82.1991 0.321739 0.872131 0.172176 0.325926 +VERTEX_SE3:QUAT 379 -114.264 286.651 86.6898 0.335047 0.847465 0.234572 0.338412 +VERTEX_SE3:QUAT 380 -110.586 291.536 91.8396 0.447678 0.757838 0.0919119 0.465637 +VERTEX_SE3:QUAT 381 -106.174 295.771 96.3258 0.52193 0.730886 0.115539 0.424317 +VERTEX_SE3:QUAT 382 -101.05 298.637 101.523 0.433297 0.78774 0.0448662 0.435552 +VERTEX_SE3:QUAT 383 -95.5522 303.252 105.409 0.656565 0.679235 -0.0389859 0.325642 +VERTEX_SE3:QUAT 384 -88.3492 304.165 108.73 0.698422 0.61975 -0.0932316 0.345578 +VERTEX_SE3:QUAT 385 -81.1205 303.866 111.584 0.690147 0.574231 -0.165373 0.408175 +VERTEX_SE3:QUAT 386 -74.3643 303.618 114.814 0.827694 0.416798 -0.169054 0.335593 +VERTEX_SE3:QUAT 387 -68.2219 300.012 118.561 0.847602 0.194818 -0.0744971 0.487921 +VERTEX_SE3:QUAT 388 -65.4919 296.182 125.011 0.859913 0.233885 0.102361 0.442007 +VERTEX_SE3:QUAT 389 -63.6075 292.163 131.052 0.836779 0.216045 0.213279 0.455674 +VERTEX_SE3:QUAT 390 -62.7336 288.012 138.078 0.830771 0.175285 0.229907 0.475644 +VERTEX_SE3:QUAT 391 -62.6084 283.85 144.802 0.861929 0.0240591 0.287272 0.417102 +VERTEX_SE3:QUAT 392 -64.4404 278.567 150.085 0.824891 -0.0224776 0.31303 0.470172 +VERTEX_SE3:QUAT 393 -67.4343 274.142 155.87 0.813704 -0.120297 0.433142 0.368515 +VERTEX_SE3:QUAT 394 -71.5562 268.431 159.821 0.786897 -0.076528 0.31643 0.524222 +VERTEX_SE3:QUAT 395 -75.4094 264.88 165.813 0.673098 -0.276093 0.241115 0.64232 +VERTEX_SE3:QUAT 396 -80.9368 264.868 171.449 0.728854 -0.241373 0.19983 0.608752 +VERTEX_SE3:QUAT 397 -85.68 263.721 177.409 0.787138 -0.269035 0.2394 0.500721 +VERTEX_SE3:QUAT 398 -91.3072 260.683 182.932 0.721541 -0.39126 0.184584 0.540576 +VERTEX_SE3:QUAT 399 -97.7894 259.75 187.669 0.812274 -0.279437 0.227925 0.458449 +VERTEX_SE3:QUAT 400 -103.682 256.634 192.143 0.846548 -0.275637 0.265558 0.369946 +VERTEX_SE3:QUAT 401 -109.478 252.096 195.84 0.740308 -0.317415 0.301692 0.510072 +VERTEX_SE3:QUAT 402 -115.864 249.782 199.666 0.803765 -0.244533 0.187504 0.508928 +VERTEX_SE3:QUAT 403 -120.861 246.948 205.695 0.794211 -0.254157 0.349548 0.427141 +VERTEX_SE3:QUAT 404 -126.668 243.13 209.425 0.825715 -0.344875 0.241011 0.375725 +VERTEX_SE3:QUAT 405 -132.859 239.112 212.63 0.78194 -0.447813 0.379375 0.210019 +VERTEX_SE3:QUAT 406 -139.53 235.184 212.524 0.790656 -0.534404 0.298259 0.017788 +VERTEX_SE3:QUAT 407 -146.714 231.943 210.482 -0.83317 0.452835 -0.292215 0.124006 +VERTEX_SE3:QUAT 408 -152.105 227.954 206.879 -0.839027 0.350971 -0.404139 0.0975923 +VERTEX_SE3:QUAT 409 -156.67 222.501 203.358 -0.844082 0.335491 -0.413526 0.062984 +VERTEX_SE3:QUAT 410 -161.032 216.589 200.579 -0.792447 0.309352 -0.440169 0.287367 +VERTEX_SE3:QUAT 411 -163.047 211.803 194.156 -0.737725 0.276011 -0.436824 0.43447 +VERTEX_SE3:QUAT 412 -163.303 208.029 187.077 -0.68227 0.404912 -0.339722 0.505117 +VERTEX_SE3:QUAT 413 -165.233 207.08 178.901 -0.677451 0.469689 -0.424037 0.375027 +VERTEX_SE3:QUAT 414 -167.849 204.984 171.523 -0.763655 0.442729 -0.219918 0.415281 +VERTEX_SE3:QUAT 415 -171.957 202.959 164.731 -0.728334 0.472668 -0.133905 0.477687 +VERTEX_SE3:QUAT 416 -176.962 202.366 158.3 -0.627012 0.643021 -0.121164 0.422728 +VERTEX_SE3:QUAT 417 -182.608 204.097 153.091 -0.517177 0.722523 -0.0085374 0.458711 +VERTEX_SE3:QUAT 418 -188.172 207.861 149.525 -0.397109 0.755761 0.0479076 0.518492 +VERTEX_SE3:QUAT 419 -193.326 213.651 146.827 -0.109803 0.894214 -0.0577305 0.430106 +VERTEX_SE3:QUAT 420 -194.123 221.989 145.649 0.0775132 0.885857 -0.0400537 0.45568 +VERTEX_SE3:QUAT 421 -192.224 230.167 145.672 0.00691967 0.877932 0.0978761 0.468624 +VERTEX_SE3:QUAT 422 -192.61 238.082 147.072 -0.0142967 0.871846 0.153481 0.464891 +VERTEX_SE3:QUAT 423 -193.925 245.941 149.224 0.0156912 0.816514 0.217867 0.534408 +VERTEX_SE3:QUAT 424 -195.945 253.401 152.51 0.238247 0.681515 0.222855 0.655066 +VERTEX_SE3:QUAT 425 -195.373 259.769 157.828 0.330659 0.686987 0.166222 0.625367 +VERTEX_SE3:QUAT 426 -193.244 265.255 163.352 0.326576 0.645827 0.224239 0.652666 +VERTEX_SE3:QUAT 427 -192.39 270.832 169.463 0.464506 0.692873 0.231688 0.500482 +VERTEX_SE3:QUAT 428 -188.889 274.339 175.862 0.291154 0.700682 0.110397 0.64194 +VERTEX_SE3:QUAT 429 -186.686 281.001 180.606 0.501768 0.663455 0.08758 0.548076 +VERTEX_SE3:QUAT 430 -181.961 284.997 186.238 0.538215 0.639865 0.124679 0.534184 +VERTEX_SE3:QUAT 431 -177.522 288.358 192.648 0.586834 0.661041 0.191757 0.426473 +VERTEX_SE3:QUAT 432 -172.425 290.067 199.167 0.577267 0.630277 0.373148 0.360935 +VERTEX_SE3:QUAT 433 -168.556 290.137 206.965 0.512888 0.664401 0.431507 0.330633 +VERTEX_SE3:QUAT 434 -165.286 290.728 214.778 0.469125 0.682463 0.507148 0.238677 +VERTEX_SE3:QUAT 435 -161.832 290.622 222.458 0.385074 0.823443 0.406977 0.0896018 +VERTEX_SE3:QUAT 436 -156.833 293.304 228.671 0.30734 0.820106 0.479858 0.0520065 +VERTEX_SE3:QUAT 437 -152.97 296.094 235.66 0.258132 0.873426 0.410361 0.0458088 +VERTEX_SE3:QUAT 438 -149.091 300.249 241.877 -0.267714 -0.860522 -0.425192 0.0839164 +VERTEX_SE3:QUAT 439 -144.626 304.571 247.66 -0.208251 -0.838156 -0.448531 0.230101 +VERTEX_SE3:QUAT 440 -139.747 308.512 253.086 -0.236056 -0.854916 -0.438595 0.145024 +VERTEX_SE3:QUAT 441 -134.92 312.506 258.343 -0.235584 -0.907101 -0.284257 0.202151 +VERTEX_SE3:QUAT 442 -130.196 318.448 261.376 -0.294267 -0.845677 -0.272561 0.352062 +VERTEX_SE3:QUAT 443 -123.961 324.018 263.193 -0.490917 -0.751171 -0.161766 0.410579 +VERTEX_SE3:QUAT 444 -116.472 327.936 261.775 -0.335738 -0.811953 -0.242761 0.411192 +VERTEX_SE3:QUAT 445 -109.78 333.331 262.528 -0.403099 -0.738653 -0.224618 0.491375 +VERTEX_SE3:QUAT 446 -102.69 337.839 261.693 -0.415097 -0.760611 -0.243247 0.435884 +VERTEX_SE3:QUAT 447 -95.65 342.072 261.073 -0.537887 -0.744066 -0.146211 0.368328 +VERTEX_SE3:QUAT 448 -87.6705 344.891 259.032 -0.490967 -0.698392 -0.241609 0.461331 +VERTEX_SE3:QUAT 449 -79.8326 348.007 257.697 -0.520836 -0.617079 -0.0775164 0.584751 +VERTEX_SE3:QUAT 450 -73.4434 351.375 252.785 -0.595462 -0.507792 0.0924737 0.615647 +VERTEX_SE3:QUAT 451 -69.4616 353.277 245.054 -0.728771 -0.420745 0.160069 0.515989 +VERTEX_SE3:QUAT 452 -65.8477 352.203 237.301 -0.79687 -0.457753 0.190366 0.345285 +VERTEX_SE3:QUAT 453 -61.4598 348.906 231.072 -0.796416 -0.46807 0.123457 0.362478 +VERTEX_SE3:QUAT 454 -56.1893 345.799 224.531 -0.760627 -0.5754 0.113947 0.278167 +VERTEX_SE3:QUAT 455 -49.8195 343.672 219.667 -0.807555 -0.395856 0.187585 0.394924 +VERTEX_SE3:QUAT 456 -45.7395 339.781 212.626 -0.798724 -0.402397 0.236608 0.37965 +VERTEX_SE3:QUAT 457 -42.0616 335.961 206.055 -0.931845 -0.194892 0.253054 0.172178 +VERTEX_SE3:QUAT 458 -39.5852 328.281 202.52 -0.970686 -0.137355 0.196776 0.0134737 +VERTEX_SE3:QUAT 459 -37.7056 319.737 202.294 0.926085 0.140896 -0.333623 0.105879 +VERTEX_SE3:QUAT 460 -35.1368 311.792 203.273 0.951962 -0.0449502 -0.287018 0.0967937 +VERTEX_SE3:QUAT 461 -36.0373 303.659 205.383 0.996549 -0.0501328 -0.0660874 0.00288383 +VERTEX_SE3:QUAT 462 -37.1755 294.507 205.735 0.966451 -0.252057 -0.0493798 0.000820549 +VERTEX_SE3:QUAT 463 -41.6587 287.137 206.132 0.894423 -0.400044 -0.168375 0.107801 +VERTEX_SE3:QUAT 464 -47.8936 281.561 209.227 -0.854447 0.505224 0.120809 0.00860531 +VERTEX_SE3:QUAT 465 -55.7358 277.676 210.416 -0.850705 0.516043 -0.036755 0.0930027 +VERTEX_SE3:QUAT 466 -63.5415 274.121 208.839 -0.743358 0.632566 -0.0852652 0.200023 +VERTEX_SE3:QUAT 467 -71.1737 273.511 205.591 -0.712622 0.683151 -0.124663 0.0996707 +VERTEX_SE3:QUAT 468 -79.3859 274.034 202.898 -0.701773 0.679252 -0.0800558 0.199308 +VERTEX_SE3:QUAT 469 -87.5669 274.259 199.506 -0.751006 0.621747 -0.0239521 0.221012 +VERTEX_SE3:QUAT 470 -96.047 273.503 196.341 -0.597345 0.798166 -0.0231359 0.0746695 +VERTEX_SE3:QUAT 471 -104.526 276.51 195.482 -0.481518 0.862467 -0.0984407 0.120831 +VERTEX_SE3:QUAT 472 -111.135 281.257 193.354 -0.550949 0.811431 -0.0650616 0.183853 +VERTEX_SE3:QUAT 473 -118.634 284.89 190.991 -0.452606 0.877953 0.0977279 0.121636 +VERTEX_SE3:QUAT 474 -125.534 290.155 192.037 -0.43576 0.878269 0.0937791 0.173098 +VERTEX_SE3:QUAT 475 -132.169 295.936 192.452 -0.601981 0.739537 0.157827 0.256506 +VERTEX_SE3:QUAT 476 -140.718 297.894 192.289 -0.498246 0.759062 0.275145 0.316024 +VERTEX_SE3:QUAT 477 -148.854 301.061 193.839 -0.51797 0.723695 0.339875 0.304069 +VERTEX_SE3:QUAT 478 -157.132 303.471 195.947 -0.362333 0.685179 0.456803 0.436549 +VERTEX_SE3:QUAT 479 -164.959 305.796 199.304 -0.371937 0.578121 0.559221 0.463369 +VERTEX_SE3:QUAT 480 -173.279 306.46 202.606 -0.137942 0.569481 0.692512 0.420822 +VERTEX_SE3:QUAT 481 -180.128 305.918 208.791 -0.0520122 0.66628 0.680162 0.301239 +VERTEX_SE3:QUAT 482 -183.949 306.162 216.355 -0.0732059 0.679011 0.694038 0.227808 +VERTEX_SE3:QUAT 483 -187.289 306.186 224.806 0.0625757 0.609948 0.736122 0.286657 +VERTEX_SE3:QUAT 484 -189.967 305.247 233.52 -0.143669 0.631682 0.75762 0.0796855 +VERTEX_SE3:QUAT 485 -192.566 303.294 242 -0.0826234 0.637164 0.752266 0.145913 +VERTEX_SE3:QUAT 486 -194.953 302.163 250.371 -0.0418905 0.644445 0.754791 0.115011 +VERTEX_SE3:QUAT 487 -196.016 300.449 258.969 -0.00831218 0.580664 0.803526 0.130794 +VERTEX_SE3:QUAT 488 -197.401 297.745 267.597 0.102409 0.521097 0.838437 0.12245 +VERTEX_SE3:QUAT 489 -197.734 293.826 275.346 -0.00311639 0.660462 0.745357 0.090685 +VERTEX_SE3:QUAT 490 -198.795 292.565 284.488 -0.0386512 -0.643143 -0.76169 0.0685641 +VERTEX_SE3:QUAT 491 -196.918 291.074 293.101 0.210711 0.546784 0.810269 0.0096009 +VERTEX_SE3:QUAT 492 -194.65 286.897 301.213 -0.371646 -0.486444 -0.787679 0.0693747 +VERTEX_SE3:QUAT 493 -189.745 282.188 307.475 -0.473342 -0.533408 -0.69265 0.107979 +VERTEX_SE3:QUAT 494 -183.598 277.745 313.331 -0.484455 -0.444245 -0.732688 0.176403 +VERTEX_SE3:QUAT 495 -176.917 272.742 317.166 -0.5638 -0.529346 -0.556719 0.303291 +VERTEX_SE3:QUAT 496 -168.231 270.269 318.851 -0.639348 -0.524795 -0.348632 0.440772 +VERTEX_SE3:QUAT 497 -159.206 269.76 316.708 -0.66864 -0.560775 -0.162813 0.460373 +VERTEX_SE3:QUAT 498 -151.118 269.759 312.364 -0.722598 -0.504854 -0.135506 0.452341 +VERTEX_SE3:QUAT 499 -143.685 268.659 307.567 -0.763246 -0.488594 -0.124092 0.404143 +VERTEX_SE3:QUAT 500 -135.835 266.505 302.678 -0.784682 -0.273877 0.0459432 0.554215 +VERTEX_SE3:QUAT 501 -132.84 264.007 294.114 -0.804075 -0.20888 0.00383141 0.556613 +VERTEX_SE3:QUAT 502 -130.157 261.384 285.54 -0.776853 0.0387859 0.00478652 0.628469 +VERTEX_SE3:QUAT 503 -131.37 259.738 276.543 -0.784152 0.136508 0.0861005 0.599214 +VERTEX_SE3:QUAT 504 -135.183 257.324 268.288 -0.808507 0.204774 -0.0701119 0.547237 +VERTEX_SE3:QUAT 505 -138.096 254.27 259.524 -0.834169 0.147112 0.0299185 0.530684 +VERTEX_SE3:QUAT 506 -140.732 250.946 251.645 -0.835958 0.0917627 0.0962366 0.532441 +VERTEX_SE3:QUAT 507 -143.469 247.452 243.899 -0.842184 0.227393 0.146018 0.466581 +VERTEX_SE3:QUAT 508 -148.657 243.098 237.446 -0.857023 0.231819 0.219778 0.404314 +VERTEX_SE3:QUAT 509 -154.397 237.851 231.825 -0.920075 0.00122318 0.156688 0.359038 +VERTEX_SE3:QUAT 510 -155.585 230.619 225.644 -0.937522 -0.0779057 0.211785 0.264822 +VERTEX_SE3:QUAT 511 -155.488 222.384 220.481 -0.860957 -0.230851 0.42558 0.156019 +VERTEX_SE3:QUAT 512 -153.521 214.215 216.698 -0.873954 -0.261775 0.408696 0.0254069 +VERTEX_SE3:QUAT 513 -149.638 205.859 214.625 -0.837697 -0.0887487 0.537773 0.0344573 +VERTEX_SE3:QUAT 514 -148.792 196.809 213.831 0.855012 0.0724982 -0.496358 0.131633 +VERTEX_SE3:QUAT 515 -146.478 187.754 215.62 0.784546 0.134793 -0.576473 0.184385 +VERTEX_SE3:QUAT 516 -142.139 179.411 217.518 0.702644 0.191004 -0.654633 0.203135 +VERTEX_SE3:QUAT 517 -137.286 171.881 218.043 0.750417 0.0593624 -0.613694 0.238181 +VERTEX_SE3:QUAT 518 -133.908 163.715 221.012 0.638287 0.163876 -0.644525 0.387715 +VERTEX_SE3:QUAT 519 -127.231 157.671 223.842 0.677949 0.262532 -0.647052 0.229751 +VERTEX_SE3:QUAT 520 -121.252 150.703 223.696 0.739283 0.202918 -0.631581 0.115714 +VERTEX_SE3:QUAT 521 -116.9 142.21 223.23 0.66143 0.26505 -0.687122 0.141849 +VERTEX_SE3:QUAT 522 -111.457 134.218 222.182 0.683169 0.340615 -0.635955 0.113236 +VERTEX_SE3:QUAT 523 -105.82 127.064 219.921 0.737435 0.343234 -0.558309 0.163312 +VERTEX_SE3:QUAT 524 -99.3042 120.349 218.881 0.705865 0.267105 -0.57213 0.321056 +VERTEX_SE3:QUAT 525 -92.4472 114.088 220.66 0.769158 0.114752 -0.576462 0.250837 +VERTEX_SE3:QUAT 526 -87.9959 106.422 223.579 0.745868 -0.191041 -0.600764 0.215096 +VERTEX_SE3:QUAT 527 -87.7641 98.9102 229.314 0.65538 -0.331972 -0.633538 0.242696 +VERTEX_SE3:QUAT 528 -88.9733 92.9279 236.813 -0.765542 0.30486 0.56652 0.00783997 +VERTEX_SE3:QUAT 529 -93.5687 85.3626 240.506 0.783513 -0.360347 -0.497254 0.0948519 +VERTEX_SE3:QUAT 530 -98.134 78.9423 245.821 0.690179 -0.353916 -0.619492 0.120938 +VERTEX_SE3:QUAT 531 -101.361 72.3081 251.946 0.791467 -0.283345 -0.523256 0.139638 +VERTEX_SE3:QUAT 532 -104.442 65.3849 257.348 0.634262 -0.412473 -0.652686 0.0397378 +VERTEX_SE3:QUAT 533 -108.946 59.7786 263.315 0.617833 -0.509554 -0.597801 0.035663 +VERTEX_SE3:QUAT 534 -114.163 55.617 269.746 0.502239 -0.555918 -0.600129 0.280279 +VERTEX_SE3:QUAT 535 -115.906 54.0955 279.231 0.487683 -0.505634 -0.69794 0.13921 +VERTEX_SE3:QUAT 536 -118.588 50.1846 287.387 0.545982 -0.398329 -0.68308 0.276838 +VERTEX_SE3:QUAT 537 -119.082 45.3539 296.028 0.38133 -0.390355 -0.734948 0.402569 +VERTEX_SE3:QUAT 538 -116.085 42.3138 304.582 0.282365 -0.383522 -0.834141 0.278189 +VERTEX_SE3:QUAT 539 -113.149 37.4331 312.446 0.432798 -0.311238 -0.781304 0.324626 +VERTEX_SE3:QUAT 540 -110.538 32.2593 319.914 0.431565 -0.219134 -0.736281 0.472887 +VERTEX_SE3:QUAT 541 -105.538 28.1081 326.784 0.445476 -0.334699 -0.645282 0.522627 +VERTEX_SE3:QUAT 542 -101.546 26.2741 335.669 0.394478 -0.199621 -0.651633 0.616371 +VERTEX_SE3:QUAT 543 -95.1854 25.2677 342.871 0.281742 -0.328219 -0.671147 0.602043 +VERTEX_SE3:QUAT 544 -89.0487 25.309 350.284 0.283483 -0.278451 -0.640588 0.657076 +VERTEX_SE3:QUAT 545 -82.7759 26.1397 357.487 0.399315 -0.360433 -0.511445 0.670119 +VERTEX_SE3:QUAT 546 -79.0808 28.5446 366.32 0.247381 -0.289731 -0.433598 0.81661 +VERTEX_SE3:QUAT 547 -73.9233 33.9917 372.456 0.263074 -0.287249 -0.184915 0.902267 +VERTEX_SE3:QUAT 548 -72.523 41.4258 377.534 0.180824 -0.308426 -0.071061 0.931196 +VERTEX_SE3:QUAT 549 -73.0429 50.5411 380.823 0.173726 -0.230929 -0.131829 0.948215 +VERTEX_SE3:QUAT 550 -71.4227 59.4124 384.348 0.228152 -0.358973 -0.099079 0.899594 +VERTEX_SE3:QUAT 551 -71.7816 68.1562 388.605 0.119403 -0.450019 -0.237346 0.85258 +VERTEX_SE3:QUAT 552 -69.0313 76.7944 392.149 0.463776 -0.348104 -0.241032 0.778228 +VERTEX_SE3:QUAT 553 -68.7128 81.5903 400.755 0.334554 -0.509161 -0.193501 0.769016 +VERTEX_SE3:QUAT 554 -69.2533 88.618 407.205 0.222083 -0.623025 -0.194803 0.724272 +VERTEX_SE3:QUAT 555 -68.8786 97.2826 412.6 0.202169 -0.59881 -0.169405 0.756212 +VERTEX_SE3:QUAT 556 -68.627 105.998 416.866 0.12913 -0.65931 -0.0942103 0.734684 +VERTEX_SE3:QUAT 557 -68.9184 114.944 419.47 0.137937 -0.432641 -0.0746238 0.887821 +VERTEX_SE3:QUAT 558 -68.7248 124.468 422.031 0.0999449 -0.559463 -0.0758568 0.819303 +VERTEX_SE3:QUAT 559 -68.5981 134.385 423.858 0.103268 -0.602853 -0.153135 0.776179 +VERTEX_SE3:QUAT 560 -67.2158 143.71 426.988 0.0750418 -0.494104 -0.182689 0.846673 +VERTEX_SE3:QUAT 561 -65.092 152.961 430.014 -0.0992014 -0.517015 0.0153653 0.85007 +VERTEX_SE3:QUAT 562 -64.6648 162.176 427.582 -0.062007 -0.452904 0.123018 0.880851 +VERTEX_SE3:QUAT 563 -66.4204 171.23 424.874 -0.00658674 -0.407585 0.242054 0.880478 +VERTEX_SE3:QUAT 564 -70.8767 179.468 421.959 0.0587039 -0.505418 0.458911 0.728359 +VERTEX_SE3:QUAT 565 -78.1813 185.023 417.884 -0.159679 -0.429209 0.463733 0.758442 +VERTEX_SE3:QUAT 566 -83.8366 190.027 410.853 -0.182718 -0.469643 0.603756 0.617679 +VERTEX_SE3:QUAT 567 -89.1615 191.37 403.163 -0.218575 -0.404189 0.697993 0.549238 +VERTEX_SE3:QUAT 568 -95.0589 190.362 395.089 -0.114753 -0.463907 0.68661 0.547895 +VERTEX_SE3:QUAT 569 -101.292 189.83 387.534 -0.135565 -0.379567 0.723938 0.559879 +VERTEX_SE3:QUAT 570 -108.102 188.427 380.42 -0.101823 -0.393314 0.837507 0.365402 +VERTEX_SE3:QUAT 571 -112.925 183.952 373.298 -0.142509 -0.314762 0.905404 0.246697 +VERTEX_SE3:QUAT 572 -115.761 176.861 366.782 -0.118307 -0.600848 0.757372 0.226653 +VERTEX_SE3:QUAT 573 -117.118 175.119 357.317 -0.241898 -0.589741 0.750982 0.172386 +VERTEX_SE3:QUAT 574 -116.381 172.478 347.977 -0.203841 -0.660384 0.722268 0.0259024 +VERTEX_SE3:QUAT 575 -113.747 171.061 338.341 0.239849 0.64312 -0.727061 0.0158667 +VERTEX_SE3:QUAT 576 -109.654 169.156 329.211 0.221556 0.555841 -0.79465 0.102395 +VERTEX_SE3:QUAT 577 -105.084 165.54 320.986 0.21087 0.60149 -0.761017 0.120814 +VERTEX_SE3:QUAT 578 -100.243 163.328 312.922 0.253313 0.660862 -0.697625 0.111416 +VERTEX_SE3:QUAT 579 -94.8119 162.196 304.656 0.393675 0.520188 -0.736201 0.18009 +VERTEX_SE3:QUAT 580 -87.4069 158.574 298.883 0.232267 0.454747 -0.850547 0.125807 +VERTEX_SE3:QUAT 581 -82.7771 153.04 291.979 0.379922 0.389652 -0.761149 0.352822 +VERTEX_SE3:QUAT 582 -74.2631 149.026 289.059 0.414893 0.491504 -0.689136 0.333735 +VERTEX_SE3:QUAT 583 -65.2968 145.872 285.472 0.505231 0.332966 -0.709091 0.362029 +VERTEX_SE3:QUAT 584 -56.4544 140.898 285.237 0.528063 0.301838 -0.646854 0.460025 +VERTEX_SE3:QUAT 585 -47.1349 137.078 286.924 0.632292 0.370808 -0.437094 0.521207 +VERTEX_SE3:QUAT 586 -38.0583 135.083 291.057 0.584806 0.262972 -0.311268 0.701398 +VERTEX_SE3:QUAT 587 -30.9986 136.305 297.893 0.61558 0.0211481 -0.122142 0.778264 +VERTEX_SE3:QUAT 588 -29.04 138.757 307.513 0.645193 -0.0743984 -0.153103 0.744816 +VERTEX_SE3:QUAT 589 -27.9858 139.989 317.315 0.511126 -0.220708 -0.120706 0.821869 +VERTEX_SE3:QUAT 590 -28.8399 144.979 325.823 0.577756 -0.317378 0.0505216 0.750278 +VERTEX_SE3:QUAT 591 -34.0017 148.268 334.369 0.598881 -0.502665 0.140947 0.607292 +VERTEX_SE3:QUAT 592 -42.0813 150.863 339.976 0.538147 -0.667636 0.212347 0.468581 +VERTEX_SE3:QUAT 593 -51.2765 154.371 341.809 0.381518 -0.810476 0.261687 0.359294 +VERTEX_SE3:QUAT 594 -59.0334 160.355 340.198 0.390956 -0.777714 0.342943 0.353136 +VERTEX_SE3:QUAT 595 -67.3181 165.574 336.925 0.306529 -0.780059 0.448852 0.309968 +VERTEX_SE3:QUAT 596 -74.4249 169.477 331.41 0.378483 -0.75067 0.417157 0.34529 +VERTEX_SE3:QUAT 597 -82.7953 173.327 326.994 0.462835 -0.62926 0.374394 0.499645 +VERTEX_SE3:QUAT 598 -92.5762 176.662 326.338 0.444177 -0.690167 0.441868 0.362119 +VERTEX_SE3:QUAT 599 -101.838 179.094 323.095 0.494828 -0.656516 0.417901 0.38664 +VERTEX_SE3:QUAT 600 -111.856 181.127 320.872 0.516095 -0.665499 0.376154 0.386349 +VERTEX_SE3:QUAT 601 -122.042 183.158 319.701 0.371968 -0.691904 0.545705 0.291744 +VERTEX_SE3:QUAT 602 -130.107 184.651 313.855 0.359022 -0.7575 0.540202 0.0740186 +VERTEX_SE3:QUAT 603 -135.843 186.383 305.831 0.104781 -0.781668 0.600736 0.130893 +VERTEX_SE3:QUAT 604 -137.925 189.423 296.333 -0.157916 0.870238 -0.465625 0.0306875 +VERTEX_SE3:QUAT 605 -139.78 194.906 287.754 -0.242018 0.885423 -0.294395 0.266055 +VERTEX_SE3:QUAT 606 -142.216 202.37 281.524 -0.178495 0.876481 -0.389001 0.22045 +VERTEX_SE3:QUAT 607 -143.182 209.595 273.961 -0.173321 0.880358 -0.35696 0.259824 +VERTEX_SE3:QUAT 608 -143.836 217.146 266.974 -0.142953 0.880833 -0.334095 0.303444 +VERTEX_SE3:QUAT 609 -143.977 225.162 260.176 -0.0971047 0.842216 -0.421297 0.322106 +VERTEX_SE3:QUAT 610 -142.566 231.968 252.527 0.00773835 0.807708 -0.469661 0.356324 +VERTEX_SE3:QUAT 611 -138.878 237.741 245.161 0.142099 0.889745 -0.282996 0.328747 +VERTEX_SE3:QUAT 612 -134.074 245.893 241.375 0.317595 0.875396 -0.202694 0.302871 +VERTEX_SE3:QUAT 613 -127.025 253.219 240.045 0.257416 0.91978 -0.208051 0.210846 +VERTEX_SE3:QUAT 614 -120.787 260.98 237.59 0.186833 0.870999 -0.168036 0.422159 +VERTEX_SE3:QUAT 615 -115.478 269.789 236.488 0.283829 0.879799 -0.136645 0.355981 +VERTEX_SE3:QUAT 616 -109.095 278.073 236.812 0.429543 0.86159 -0.0234314 0.269456 +VERTEX_SE3:QUAT 617 -100.733 284.12 239.344 0.513531 0.815712 -0.0519705 0.261151 +VERTEX_SE3:QUAT 618 -91.4838 288.575 241.829 0.559482 0.740609 0.0960618 0.359513 +VERTEX_SE3:QUAT 619 -83.3608 291.795 247.653 0.68891 0.639112 0.0709886 0.334515 +VERTEX_SE3:QUAT 620 -74.8184 291.456 253.351 0.797035 0.534875 0.0624878 0.273386 +VERTEX_SE3:QUAT 621 -66.3941 288.029 259.041 0.75728 0.635107 -0.0153942 0.151426 +VERTEX_SE3:QUAT 622 -56.4915 286.093 261.287 0.684326 0.703034 -0.0470787 0.187682 +VERTEX_SE3:QUAT 623 -46.2199 285.851 263.581 0.773144 0.595904 0.0323308 0.214714 +VERTEX_SE3:QUAT 624 -37.0593 283.208 267.293 0.798778 0.563986 0.134511 0.160563 +VERTEX_SE3:QUAT 625 -28.7302 279.205 271.54 0.846846 0.4887 0.123789 0.169412 +VERTEX_SE3:QUAT 626 -20.7697 273.977 276.148 -0.884984 -0.462772 -0.0358346 0.0368986 +VERTEX_SE3:QUAT 627 -12.6772 267.631 275.936 -0.93111 -0.363901 -0.010973 0.0221405 +VERTEX_SE3:QUAT 628 -6.43728 259.544 275.705 -0.953562 -0.233783 0.0828726 0.170874 +VERTEX_SE3:QUAT 629 -2.45433 250.479 271.84 -0.96043 -0.210267 0.175269 0.051403 +VERTEX_SE3:QUAT 630 1.19166 240.85 269.937 -0.952181 -0.092093 0.262555 0.126234 +VERTEX_SE3:QUAT 631 1.80347 230.678 267.38 -0.94174 -0.113404 0.305356 0.0838039 +VERTEX_SE3:QUAT 632 3.0284 220.532 265.178 0.964369 -0.129417 -0.228065 0.0350854 +VERTEX_SE3:QUAT 633 0.68004 210.709 266.722 0.993115 0.021578 -0.111324 0.0294037 +VERTEX_SE3:QUAT 634 0.997542 200.252 267.378 -0.945424 0.112115 0.257128 0.165798 +VERTEX_SE3:QUAT 635 -2.61175 190.404 264.928 -0.887358 0.27144 0.290305 0.233751 +VERTEX_SE3:QUAT 636 -9.22304 183.125 262.52 -0.758984 0.423866 0.299664 0.393043 +VERTEX_SE3:QUAT 637 -19.0793 179.35 259.271 -0.791208 0.464376 0.314457 0.243847 +VERTEX_SE3:QUAT 638 -28.8434 175.574 259.075 -0.705895 0.533488 0.30123 0.355478 +VERTEX_SE3:QUAT 639 -39.0446 174.044 257.42 -0.658906 0.525545 0.378049 0.383047 +VERTEX_SE3:QUAT 640 -49.2627 172.682 256.552 -0.498064 0.669535 0.358 0.418916 +VERTEX_SE3:QUAT 641 -59.3906 175.318 257.627 -0.600497 0.555584 0.288322 0.497594 +VERTEX_SE3:QUAT 642 -69.3706 176.651 255.32 -0.516042 0.480581 0.19958 0.680375 +VERTEX_SE3:QUAT 643 -77.9648 180.765 250.505 -0.462485 0.659019 0.285567 0.519858 +VERTEX_SE3:QUAT 644 -87.9466 185.034 250.052 -0.424729 0.643732 0.32778 0.545688 +VERTEX_SE3:QUAT 645 -97.6104 189.257 249.902 -0.19191 0.753698 0.317633 0.54242 +VERTEX_SE3:QUAT 646 -104.355 196.819 253.206 -0.181059 0.726379 0.354379 0.560362 +VERTEX_SE3:QUAT 647 -111.537 203.813 256.841 -0.102439 0.72878 0.544257 0.402704 +VERTEX_SE3:QUAT 648 -117.172 207.807 264.688 0.028954 0.816282 0.410487 0.405396 +VERTEX_SE3:QUAT 649 -119.999 215.251 272.408 0.0687296 0.802624 0.486093 0.338798 +VERTEX_SE3:QUAT 650 -122.049 220.765 281.58 0.135384 0.78924 0.41134 0.435397 +VERTEX_SE3:QUAT 651 -123.395 226.783 290.191 0.108691 0.669617 0.61156 0.407179 +VERTEX_SE3:QUAT 652 -127.038 228.881 300.621 0.319765 0.645553 0.589992 0.364582 +VERTEX_SE3:QUAT 653 -126.87 229.087 311.098 0.39235 0.687589 0.500233 0.350784 +VERTEX_SE3:QUAT 654 -124.607 230.439 321.465 0.437771 0.527439 0.661307 0.304692 +VERTEX_SE3:QUAT 655 -123.899 226.711 331.365 0.458932 0.548782 0.681763 0.153033 +VERTEX_SE3:QUAT 656 -120.797 222.717 340.84 0.526423 0.440962 0.719808 0.101527 +VERTEX_SE3:QUAT 657 -117.136 216.205 348.26 0.377742 0.509834 0.77213 0.0345653 +VERTEX_SE3:QUAT 658 -113.193 210.824 356.976 -0.399081 -0.468399 -0.787149 0.0416312 +VERTEX_SE3:QUAT 659 -108.218 204.345 363.968 -0.563651 -0.412758 -0.715156 0.0218943 +VERTEX_SE3:QUAT 660 -102.646 197.144 369.423 -0.672784 -0.389026 -0.622709 0.0908497 +VERTEX_SE3:QUAT 661 -95.5634 189.741 373.177 -0.651879 -0.380444 -0.605862 0.251489 +VERTEX_SE3:QUAT 662 -86.9889 183.449 373.97 -0.74554 -0.189582 -0.58837 0.249098 +VERTEX_SE3:QUAT 663 -80.6938 174.95 371.749 -0.735121 0.0489978 -0.482609 0.473587 +VERTEX_SE3:QUAT 664 -76.9575 169.492 363.176 -0.817702 0.100393 -0.366893 0.432058 +VERTEX_SE3:QUAT 665 -75.9292 163.237 354.077 -0.769692 0.0563359 -0.4822 0.414588 +VERTEX_SE3:QUAT 666 -73.2188 156.409 346.213 -0.814136 0.0468077 -0.376337 0.439729 +VERTEX_SE3:QUAT 667 -71.1781 149.571 337.302 -0.819313 0.119526 -0.33603 0.448914 +VERTEX_SE3:QUAT 668 -70.1593 143.568 328.037 -0.899583 0.329002 -0.196352 0.209654 +VERTEX_SE3:QUAT 669 -75.9838 136.421 322.718 -0.839833 0.25586 -0.367695 0.306622 +VERTEX_SE3:QUAT 670 -78.4651 129.452 314.808 -0.774051 0.273357 -0.477901 0.31262 +VERTEX_SE3:QUAT 671 -80.0011 122.891 306.549 -0.762261 0.395082 -0.355075 0.36985 +VERTEX_SE3:QUAT 672 -84.2272 118.772 297.201 -0.828639 0.362216 -0.339012 0.259283 +VERTEX_SE3:QUAT 673 -89.1786 112.849 289.441 -0.923265 0.306075 -0.093428 0.212536 +VERTEX_SE3:QUAT 674 -95.2548 105.569 284.75 -0.892849 0.229413 -0.187029 0.339428 +VERTEX_SE3:QUAT 675 -98.7721 98.3776 277.092 -0.892867 0.145774 -0.193444 0.379628 +VERTEX_SE3:QUAT 676 -100.92 91.713 269.241 -0.881687 0.183898 -0.198578 0.386492 +VERTEX_SE3:QUAT 677 -103.594 85.3198 260.768 -0.844048 0.255251 -0.19062 0.431386 +VERTEX_SE3:QUAT 678 -106.874 80.1346 251.65 -0.794756 0.239728 -0.311253 0.462618 +VERTEX_SE3:QUAT 679 -108.253 75.6089 241.71 -0.808525 0.398077 -0.297035 0.315583 +VERTEX_SE3:QUAT 680 -113.489 70.5972 233.376 -0.79911 0.358839 -0.281923 0.391378 +VERTEX_SE3:QUAT 681 -117.91 66.7649 224.398 -0.701201 0.455799 -0.219218 0.502501 +VERTEX_SE3:QUAT 682 -123.017 66.2227 214.721 -0.608061 0.556476 -0.184555 0.53529 +VERTEX_SE3:QUAT 683 -128.283 68.6466 205.742 -0.485899 0.539116 -0.167108 0.667332 +VERTEX_SE3:QUAT 684 -131.663 74.4294 197.142 -0.471828 0.508095 0.162565 0.701991 +VERTEX_SE3:QUAT 685 -139.797 79.8375 192.743 -0.367086 0.552458 0.328444 0.67243 +VERTEX_SE3:QUAT 686 -149.186 85.0857 191.962 -0.438678 0.588282 0.284428 0.616917 +VERTEX_SE3:QUAT 687 -158.797 90.0341 190.311 -0.324049 0.681761 0.294342 0.586138 +VERTEX_SE3:QUAT 688 -167.119 96.7397 190.964 -0.342207 0.632575 0.484654 0.49785 +VERTEX_SE3:QUAT 689 -177.091 99.5961 194.829 -0.253872 0.639299 0.624341 0.370194 +VERTEX_SE3:QUAT 690 -185.151 100.463 202.038 -0.120872 0.593774 0.753265 0.255761 +VERTEX_SE3:QUAT 691 -190.488 98.7288 211.588 0.150902 -0.648383 -0.74087 0.0891018 +VERTEX_SE3:QUAT 692 -190.514 97.123 223.013 0.205515 -0.641596 -0.737073 0.0533047 +VERTEX_SE3:QUAT 693 -191.808 95.4268 233.92 -0.0468734 0.662777 0.747319 0.00660202 +VERTEX_SE3:QUAT 694 -191.638 93.7523 245.1 0.0612101 -0.72883 -0.676665 0.0847653 +VERTEX_SE3:QUAT 695 -190.801 94.6992 256.274 -0.0244239 -0.78951 -0.590898 0.164064 +VERTEX_SE3:QUAT 696 -187.362 97.9988 266.748 -0.027051 -0.704177 -0.696011 0.137735 +VERTEX_SE3:QUAT 697 -183.949 98.5698 276.955 0.050382 0.693962 0.71713 0.0400427 +VERTEX_SE3:QUAT 698 -183.537 98.0032 288.023 0.0707831 0.686633 0.719725 0.0743013 +VERTEX_SE3:QUAT 699 -183.277 97.2341 298.754 0.112822 0.613907 0.778896 0.0609144 +VERTEX_SE3:QUAT 700 -182.062 94.533 309.271 0.241517 0.748197 0.617715 0.0172582 +VERTEX_SE3:QUAT 701 -177.845 95.7728 319.379 -0.200802 -0.702396 -0.646401 0.22019 +VERTEX_SE3:QUAT 702 -171.071 96.5111 327.803 -0.171715 -0.708326 -0.605959 0.318752 +VERTEX_SE3:QUAT 703 -163.637 98.8241 335.991 -0.321109 -0.632625 -0.553783 0.43589 +VERTEX_SE3:QUAT 704 -153.369 100.762 339.891 -0.19057 -0.694027 -0.500152 0.481516 +VERTEX_SE3:QUAT 705 -144.746 105.498 344.99 -0.166579 -0.636212 -0.462587 0.594558 +VERTEX_SE3:QUAT 706 -136.248 111.288 348.981 -0.369707 -0.702187 -0.241038 0.558704 +VERTEX_SE3:QUAT 707 -127.218 117.703 347.427 -0.301097 -0.727975 -0.178598 0.589487 +VERTEX_SE3:QUAT 708 -120.29 126.005 345.599 -0.455344 -0.578892 -0.214046 0.641662 +VERTEX_SE3:QUAT 709 -111.469 131.468 341.34 -0.504308 -0.541455 -0.299417 0.602369 +VERTEX_SE3:QUAT 710 -101.951 134.51 337.905 -0.585071 -0.529308 -0.377696 0.484635 +VERTEX_SE3:QUAT 711 -90.7862 134.436 335.579 -0.543888 -0.510059 -0.393585 0.537694 +VERTEX_SE3:QUAT 712 -79.8915 135.232 332.949 -0.581158 -0.388911 -0.458172 0.54871 +VERTEX_SE3:QUAT 713 -69.2345 134.009 329.069 -0.665326 -0.355492 -0.432371 0.493985 +VERTEX_SE3:QUAT 714 -59.647 131.162 324.694 -0.685611 -0.364689 -0.339263 0.530885 +VERTEX_SE3:QUAT 715 -50.4199 129.249 318.898 -0.664231 -0.405742 -0.357099 0.516383 +VERTEX_SE3:QUAT 716 -40.8641 127.24 314.452 -0.723952 -0.304257 -0.219477 0.578922 +VERTEX_SE3:QUAT 717 -33.5548 125.411 306.367 -0.635636 -0.335266 -0.292256 0.630991 +VERTEX_SE3:QUAT 718 -25.3981 125.505 299.396 -0.623218 -0.277405 -0.369594 0.630909 +VERTEX_SE3:QUAT 719 -16.83 125.02 292.445 -0.62189 -0.152015 -0.280577 0.715137 +VERTEX_SE3:QUAT 720 -10.3653 125.808 283.43 -0.632376 0.0425385 -0.253099 0.730911 +VERTEX_SE3:QUAT 721 -7.54693 126.736 272.636 -0.525325 -0.0551594 -0.358053 0.769928 +VERTEX_SE3:QUAT 722 -1.5287 129.256 263.965 -0.407264 0.0785639 -0.399494 0.817538 +VERTEX_SE3:QUAT 723 4.93201 133.629 255.449 -0.295956 -0.0448603 -0.349727 0.887744 +VERTEX_SE3:QUAT 724 11.6983 140.425 249.672 -0.255621 -0.1597 -0.305706 0.90316 +VERTEX_SE3:QUAT 725 18.1443 148.15 245.18 -0.148257 -0.086172 -0.222801 0.959663 +VERTEX_SE3:QUAT 726 22.4808 157.58 242.365 0.0098322 0.0301137 -0.186316 0.981979 +VERTEX_SE3:QUAT 727 26.0711 168.387 242.691 0.0133852 -0.0113001 -0.430252 0.902539 +VERTEX_SE3:QUAT 728 34.3625 175.979 242.793 -0.0478248 -0.0404124 -0.339877 0.938383 +VERTEX_SE3:QUAT 729 41.0422 185.239 241.947 0.0166897 0.00141921 -0.293563 0.955793 +VERTEX_SE3:QUAT 730 46.8814 194.929 242.399 0.0894324 0.10301 -0.0652525 0.9885 +VERTEX_SE3:QUAT 731 47.9722 205.804 244.211 0.104488 0.0904214 -0.237416 0.96153 +VERTEX_SE3:QUAT 732 52.7429 215.831 246.034 -0.0315442 0.159297 -0.214683 0.963089 +VERTEX_SE3:QUAT 733 56.4681 226.587 244.531 -0.163302 0.248641 -0.043357 0.953746 +VERTEX_SE3:QUAT 734 55.9327 237.225 241.041 -0.356529 0.136701 -0.0482995 0.922967 +VERTEX_SE3:QUAT 735 55.1325 245.542 233.593 -0.298906 0.059608 0.016244 0.952281 +VERTEX_SE3:QUAT 736 53.7642 254.848 227.188 -0.256332 -0.192508 0.130754 0.938157 +VERTEX_SE3:QUAT 737 51.577 263.854 220.927 -0.227979 -0.168174 0.186509 0.940722 +VERTEX_SE3:QUAT 738 47.7848 272.943 215.111 -0.205949 -0.122451 0.221014 0.94538 +VERTEX_SE3:QUAT 739 43.3325 281.667 210.213 -0.177156 0.022087 0.188461 0.965718 +VERTEX_SE3:QUAT 740 38.6195 291.006 206.378 -0.100837 -0.163318 0.217701 0.956956 +VERTEX_SE3:QUAT 741 33.6576 300.567 203.034 -0.0477424 -0.229763 0.0986851 0.967053 +VERTEX_SE3:QUAT 742 31.1561 311.341 201.043 -0.0910201 -0.38089 0.327798 0.859759 +VERTEX_SE3:QUAT 743 25.1551 319.588 196.209 -0.0592127 -0.175836 0.259013 0.947886 +VERTEX_SE3:QUAT 744 19.5844 329.087 193.861 -0.127119 -0.121748 0.423404 0.888677 +VERTEX_SE3:QUAT 745 11.0198 335.207 189.804 0.047095 0.0133682 0.44092 0.89621 +VERTEX_SE3:QUAT 746 1.81258 341.077 190.855 0.0146574 -0.0304987 0.526381 0.849575 +VERTEX_SE3:QUAT 747 -8.36881 345.382 190.752 0.170224 -0.0583252 0.562562 0.806936 +VERTEX_SE3:QUAT 748 -18.9931 348.431 192.87 0.196667 -0.00535487 0.706142 0.680189 +VERTEX_SE3:QUAT 749 -29.8199 346.966 195.711 0.214609 0.18904 0.736522 0.612978 +VERTEX_SE3:QUAT 750 -39.1113 343.88 201.939 0.02394 0.0325223 0.704251 0.708802 +VERTEX_SE3:QUAT 751 -50.2736 343.318 202.659 0.139664 0.118866 0.769514 0.611729 +VERTEX_SE3:QUAT 752 -60.1386 339.786 206.483 0.0295867 -0.0408918 0.832011 0.552458 +VERTEX_SE3:QUAT 753 -69.9226 334.645 205.778 0.152471 0.0717033 0.854682 0.49105 +VERTEX_SE3:QUAT 754 -79.0449 328.182 208.152 0.112634 0.0764187 0.937119 0.321374 +VERTEX_SE3:QUAT 755 -85.0578 318.766 210.344 0.0913936 0.083689 0.950599 0.284614 +VERTEX_SE3:QUAT 756 -90.7218 308.859 212.479 0.24236 0.10423 0.952304 0.153346 +VERTEX_SE3:QUAT 757 -92.9101 298.248 214.694 -0.330351 -0.0415486 -0.939409 0.0815645 +VERTEX_SE3:QUAT 758 -90.3001 286.778 214.247 -0.189846 0.0228744 -0.970825 0.144685 +VERTEX_SE3:QUAT 759 -86.3574 275.737 212.942 -0.246194 -0.0808441 -0.962511 0.080157 +VERTEX_SE3:QUAT 760 -83.4936 264.708 213.286 -0.285493 0.0317155 -0.955392 0.0686593 +VERTEX_SE3:QUAT 761 -81.9695 253.743 211.734 -0.218358 -0.0839172 -0.963968 0.126662 +VERTEX_SE3:QUAT 762 -78.2928 242.958 212.61 -0.206536 0.195446 -0.958557 0.0176551 +VERTEX_SE3:QUAT 763 -78.0543 232.654 208.096 -0.364298 0.0808213 -0.926695 0.0446206 +VERTEX_SE3:QUAT 764 -77.3373 221.548 205.659 -0.331191 0.0529781 -0.930632 0.146393 +VERTEX_SE3:QUAT 765 -74.2889 211.1 202.666 -0.256323 0.206518 -0.928783 0.170327 +VERTEX_SE3:QUAT 766 -71.867 201.535 196.949 -0.204847 0.392658 -0.850679 0.283201 +VERTEX_SE3:QUAT 767 -68.2394 196.017 187.984 -0.0636222 0.477596 -0.863209 0.150744 +VERTEX_SE3:QUAT 768 -65.4615 190.528 178.541 -0.142215 0.596183 -0.76365 0.202925 +VERTEX_SE3:QUAT 769 -63.3016 188.921 167.63 -0.149787 0.547453 -0.771942 0.286294 +VERTEX_SE3:QUAT 770 -59.6109 186.548 156.912 -0.114301 0.620093 -0.700911 0.333383 +VERTEX_SE3:QUAT 771 -55.2276 186.942 146.095 -0.0768907 0.607658 -0.681871 0.399865 +VERTEX_SE3:QUAT 772 -49.7192 188.212 136.232 -0.113615 0.552731 -0.784912 0.255917 +VERTEX_SE3:QUAT 773 -46.0718 185.71 125.819 -0.113801 0.525698 -0.792696 0.286923 +VERTEX_SE3:QUAT 774 -42.1574 183.166 115.322 -0.167814 0.431047 -0.797164 0.388028 +VERTEX_SE3:QUAT 775 -36.3039 180.302 106.222 -0.21603 0.525548 -0.718405 0.401278 +VERTEX_SE3:QUAT 776 -31.7974 179.155 95.6538 -0.134657 0.402834 -0.739103 0.522799 +VERTEX_SE3:QUAT 777 -23.9142 177.849 87.4017 -0.136508 0.501959 -0.607215 0.600577 +VERTEX_SE3:QUAT 778 -17.0407 181.013 78.8199 -0.137522 0.449233 -0.616728 0.631605 +VERTEX_SE3:QUAT 779 -9.33361 183.712 70.7986 -0.204615 0.496351 -0.529701 0.656647 +VERTEX_SE3:QUAT 780 -3.55041 188.328 61.814 -0.0445519 0.468635 -0.493645 0.73124 +VERTEX_SE3:QUAT 781 4.03059 194.488 55.922 -0.109026 0.524363 -0.393825 0.747033 +VERTEX_SE3:QUAT 782 9.4214 202.873 50.0737 0.0441895 0.571625 -0.330813 0.74957 +VERTEX_SE3:QUAT 783 15.3769 212.525 46.8807 -0.00611237 0.528836 -0.414588 0.740548 +VERTEX_SE3:QUAT 784 22.4314 220.388 42.4942 0.00528665 0.545812 -0.45474 0.703757 +VERTEX_SE3:QUAT 785 29.6129 227.508 37.4823 0.128404 0.637646 -0.355063 0.671453 +VERTEX_SE3:QUAT 786 36.9664 235.989 34.7518 -0.0528975 0.7117 -0.385654 0.58477 +VERTEX_SE3:QUAT 787 41.1281 244.401 28.0571 0.00551309 0.727407 -0.421563 0.541419 +VERTEX_SE3:QUAT 788 47.0159 252.232 21.1434 0.106913 0.72152 -0.37107 0.574705 +VERTEX_SE3:QUAT 789 54.0919 260.37 17.1867 0.0329169 0.767036 -0.375375 0.519294 +VERTEX_SE3:QUAT 790 59.5552 269.073 11.2277 0.230097 0.870898 -0.160665 0.403458 +VERTEX_SE3:QUAT 791 65.7252 278.798 10.5418 0.351921 0.80832 -0.20576 0.424774 +VERTEX_SE3:QUAT 792 74.4132 286.181 10.7725 0.498297 0.801364 -0.0637099 0.32474 +VERTEX_SE3:QUAT 793 84.2156 291.356 13.9034 0.474043 0.754373 -0.0527426 0.451023 +VERTEX_SE3:QUAT 794 93.1258 297.235 18.2453 0.615358 0.641268 -0.0836659 0.450676 +VERTEX_SE3:QUAT 795 102.822 299.295 24.1234 0.525049 0.601588 -0.12934 0.587951 +VERTEX_SE3:QUAT 796 111.48 304.103 30.0408 0.588176 0.504988 -0.0961574 0.624332 +VERTEX_SE3:QUAT 797 119.178 307.224 38.1038 0.44642 0.659288 -0.100989 0.596531 +VERTEX_SE3:QUAT 798 127.121 313.906 43.5296 0.637019 0.560219 0.0593524 0.526154 +VERTEX_SE3:QUAT 799 134.608 315.337 52.3437 0.645627 0.570631 0.0566852 0.504313 +VERTEX_SE3:QUAT 800 142.388 316.865 61.0412 0.665111 0.540096 0.0355318 0.514453 +VERTEX_SE3:QUAT 801 150.002 317.852 69.782 0.603348 0.528413 -0.188543 0.566748 +VERTEX_SE3:QUAT 802 159.649 319.73 76.054 0.605024 0.53083 0.0526564 0.591095 +VERTEX_SE3:QUAT 803 165.932 322.387 85.4019 0.640287 0.478684 0.162503 0.578349 +VERTEX_SE3:QUAT 804 170.228 323.659 96.2223 0.569077 0.484749 0.121076 0.653077 +VERTEX_SE3:QUAT 805 174.115 327.104 106.575 0.564403 0.466436 0.269413 0.625543 +VERTEX_SE3:QUAT 806 175.797 328.954 118.303 0.566917 0.565258 0.225299 0.555273 +VERTEX_SE3:QUAT 807 180.009 331.452 128.936 0.549829 0.530131 0.306562 0.568039 +VERTEX_SE3:QUAT 808 182.22 333.057 140.286 0.608583 0.458386 0.452935 0.462989 +VERTEX_SE3:QUAT 809 183.636 330.817 151.875 0.606685 0.266987 0.577581 0.476499 +VERTEX_SE3:QUAT 810 180.488 325.147 161.848 0.600468 0.324384 0.434436 0.587774 +VERTEX_SE3:QUAT 811 178.392 323.393 173.431 0.444165 0.301397 0.473201 0.69854 +VERTEX_SE3:QUAT 812 173.413 324.705 183.741 0.47077 0.218189 0.634262 0.573132 +VERTEX_SE3:QUAT 813 167.042 321.06 192.96 0.51048 0.189382 0.651017 0.528886 +VERTEX_SE3:QUAT 814 160.939 316.466 201.518 0.462872 -0.0640003 0.657577 0.59097 +VERTEX_SE3:QUAT 815 151.508 312.403 206.493 0.496633 -0.276347 0.723439 0.391949 +VERTEX_SE3:QUAT 816 141.563 305.999 205.764 0.600469 -0.325512 0.644773 0.343143 +VERTEX_SE3:QUAT 817 131.62 299.785 205.166 0.591222 -0.369337 0.677057 0.235881 +VERTEX_SE3:QUAT 818 122.505 292.772 201.894 0.527085 -0.377058 0.67415 0.354303 +VERTEX_SE3:QUAT 819 112.301 287.675 199.496 0.493637 -0.313302 0.738394 0.336064 +VERTEX_SE3:QUAT 820 103.115 280.865 197.185 0.371296 -0.485195 0.788087 0.0751279 +VERTEX_SE3:QUAT 821 97.8128 275.124 188.323 0.364268 -0.47873 0.792369 0.101377 +VERTEX_SE3:QUAT 822 92.4301 269.31 180.16 0.30644 -0.467791 0.816133 0.14558 +VERTEX_SE3:QUAT 823 86.751 263.586 171.69 0.331969 -0.514261 0.785505 0.0911837 +VERTEX_SE3:QUAT 824 81.9106 258.591 162.427 0.21787 -0.50486 0.81735 0.172011 +VERTEX_SE3:QUAT 825 76.7175 253.765 153.033 0.194638 -0.50733 0.833472 0.100281 +VERTEX_SE3:QUAT 826 73.2764 248.813 143.303 0.0361548 -0.560462 0.816745 0.1323 +VERTEX_SE3:QUAT 827 70.778 244.989 132.69 0.120117 -0.633158 0.749353 0.152165 +VERTEX_SE3:QUAT 828 67.0673 243.277 121.475 0.0822965 -0.54746 0.832128 0.0328408 +VERTEX_SE3:QUAT 829 65.735 238.483 110.722 -0.0464723 -0.63731 0.763667 0.0921348 +VERTEX_SE3:QUAT 830 65.2649 236.309 98.6775 -0.101492 -0.558624 0.822349 0.0371636 +VERTEX_SE3:QUAT 831 66.516 231.833 87.7963 0.127297 0.61594 -0.770098 0.106596 +VERTEX_SE3:QUAT 832 70.9854 229.453 77.0689 0.263499 0.488455 -0.800197 0.227299 +VERTEX_SE3:QUAT 833 79.2072 224.612 69.6742 0.19619 0.340355 -0.894501 0.213393 +VERTEX_SE3:QUAT 834 85.9208 216.526 63.8343 0.210902 0.236896 -0.89245 0.320831 +VERTEX_SE3:QUAT 835 94.0922 208.822 60.2133 0.188883 0.256596 -0.884987 0.339528 +VERTEX_SE3:QUAT 836 102.662 201.453 56.4908 0.0685796 0.228456 -0.862832 0.445674 +VERTEX_SE3:QUAT 837 112.599 196.279 52.5665 0.106367 0.263041 -0.864462 0.414972 +VERTEX_SE3:QUAT 838 122.161 191.083 48.505 0.203028 0.200329 -0.896824 0.338164 +VERTEX_SE3:QUAT 839 130.545 183.311 46.1679 0.209793 0.215543 -0.805472 0.510629 +VERTEX_SE3:QUAT 840 141.653 179.38 45.19 0.157612 0.0228299 -0.8812 0.445111 +VERTEX_SE3:QUAT 841 151.811 172.785 46.723 0.0482227 -0.0135032 -0.861666 0.504998 +VERTEX_SE3:QUAT 842 162.718 167.491 47.2852 0.0410376 0.0129621 -0.834106 0.549923 +VERTEX_SE3:QUAT 843 174.165 163.491 47.4518 0.0200249 -0.194873 -0.686805 0.699945 +VERTEX_SE3:QUAT 844 185.913 164.845 50.9817 0.0450578 -0.223029 -0.562412 0.794934 +VERTEX_SE3:QUAT 845 195.867 169.824 54.4414 0.0573607 -0.130798 -0.393712 0.908071 +VERTEX_SE3:QUAT 846 203.593 178.52 56.4272 0.0475206 -0.0656197 -0.406076 0.91024 +VERTEX_SE3:QUAT 847 211.97 187.162 58.1234 -0.188172 0.191568 -0.427366 0.863279 +VERTEX_SE3:QUAT 848 219.551 193.985 51.8728 -0.337173 0.399317 -0.322864 0.789062 +VERTEX_SE3:QUAT 849 222.048 201.207 42.7698 -0.254952 0.417596 -0.327339 0.80837 +VERTEX_SE3:QUAT 850 225.656 209.7 34.8937 -0.289642 0.267132 -0.194459 0.898295 +VERTEX_SE3:QUAT 851 227.239 218.79 27.849 -0.236315 0.223878 -0.0895349 0.941285 +VERTEX_SE3:QUAT 852 227.635 229.228 22.3773 -0.157907 0.200121 0.046464 0.965846 +VERTEX_SE3:QUAT 853 224.917 240.379 18.9811 -0.155671 0.188992 -0.0276332 0.969167 +VERTEX_SE3:QUAT 854 224.066 251.858 15.5044 -0.282273 0.169056 0.0458675 0.943206 +VERTEX_SE3:QUAT 855 221.084 262.062 9.69471 -0.287662 0.123646 0.0822186 0.946151 +VERTEX_SE3:QUAT 856 217.691 271.796 3.72159 -0.335924 0.138952 0.363196 0.857867 +VERTEX_SE3:QUAT 857 208.861 277.478 -1.97718 -0.379206 -0.0896405 0.476632 0.788029 +VERTEX_SE3:QUAT 858 200.293 280.188 -10.4185 -0.434674 -0.106181 0.499387 0.741887 +VERTEX_SE3:QUAT 859 192.138 281.002 -19.1948 -0.419483 -0.0956891 0.477724 0.765936 +VERTEX_SE3:QUAT 860 183.706 282.761 -27.9948 -0.498234 -0.0669413 0.469537 0.725822 +VERTEX_SE3:QUAT 861 176.077 282.994 -36.9193 -0.541518 -0.0628097 0.493098 0.677988 +VERTEX_SE3:QUAT 862 168.219 281.533 -46.5064 -0.593834 0.0849054 0.516135 0.611357 +VERTEX_SE3:QUAT 863 159.287 278.222 -53.7978 -0.584641 0.101193 0.560342 0.577903 +VERTEX_SE3:QUAT 864 149.933 273.915 -59.6215 -0.577042 0.25671 0.45236 0.629677 +VERTEX_SE3:QUAT 865 139.216 272.804 -64.7297 -0.532393 0.368841 0.542866 0.534612 +VERTEX_SE3:QUAT 866 127.508 270.354 -66.2619 -0.650408 0.359193 0.529637 0.409188 +VERTEX_SE3:QUAT 867 116.784 265.45 -67.4555 -0.702066 0.253567 0.500735 0.43826 +VERTEX_SE3:QUAT 868 107.161 259.422 -71.371 -0.799073 0.17337 0.494315 0.295089 +VERTEX_SE3:QUAT 869 99.93 250.433 -74.2258 -0.78166 0.236818 0.552877 0.165081 +VERTEX_SE3:QUAT 870 93.2513 240.862 -72.9262 -0.753659 0.252747 0.603418 0.0632773 +VERTEX_SE3:QUAT 871 87.6914 230.816 -69.9683 -0.813244 0.276911 0.504376 0.0869386 +VERTEX_SE3:QUAT 872 80.7985 221.059 -67.4827 -0.778598 0.235933 0.575375 0.0840555 +VERTEX_SE3:QUAT 873 74.9414 210.808 -65.0663 -0.735475 0.139254 0.651069 0.125673 +VERTEX_SE3:QUAT 874 70.377 199.692 -64.5607 0.713813 -0.172581 -0.678453 0.019701 +VERTEX_SE3:QUAT 875 67.6986 188.538 -60.7572 0.513985 -0.195618 -0.830142 0.0917427 +VERTEX_SE3:QUAT 876 67.4877 178.035 -55.1474 0.410663 -0.160002 -0.885035 0.149898 +VERTEX_SE3:QUAT 877 69.397 167.334 -49.3919 0.446724 -0.354433 -0.803858 0.169193 +VERTEX_SE3:QUAT 878 69.0108 159.637 -40.2063 0.504535 -0.454197 -0.733414 0.0353919 +VERTEX_SE3:QUAT 879 64.563 152.747 -31.5915 0.409335 -0.380905 -0.82864 0.0266968 +VERTEX_SE3:QUAT 880 61.6291 144.298 -23.4617 0.439923 -0.475283 -0.761702 0.019598 +VERTEX_SE3:QUAT 881 57.5369 137.859 -14.4931 0.379531 -0.56903 -0.728622 0.0356454 +VERTEX_SE3:QUAT 882 53.5276 133.905 -3.80258 0.165617 -0.665011 -0.725494 0.0631619 +VERTEX_SE3:QUAT 883 52.4612 132.901 8.35818 0.0294613 -0.694944 -0.691595 0.194631 +VERTEX_SE3:QUAT 884 56.1341 133.559 20.3761 0.0399592 -0.65383 -0.697198 0.291248 +VERTEX_SE3:QUAT 885 61.2566 134.362 31.3187 0.052967 -0.638345 -0.745302 0.185027 +VERTEX_SE3:QUAT 886 64.6113 133.076 43.0321 -0.0124865 -0.578873 -0.715864 0.390242 +VERTEX_SE3:QUAT 887 71.8095 133.089 52.4943 0.111207 -0.543634 -0.635555 0.53681 +VERTEX_SE3:QUAT 888 79.0683 135.819 61.7439 0.0151263 -0.551758 -0.61192 0.566469 +VERTEX_SE3:QUAT 889 87.509 139.503 69.5108 0.0631029 -0.706631 -0.364446 0.603217 +VERTEX_SE3:QUAT 890 91.8282 148.533 75.8074 0.0960363 -0.719131 -0.456333 0.515157 +VERTEX_SE3:QUAT 891 96.3859 155.736 84.5513 0.0753315 -0.768905 -0.436377 0.461178 +VERTEX_SE3:QUAT 892 100.164 163.602 93.3502 -0.017351 -0.840705 -0.490228 0.229327 +VERTEX_SE3:QUAT 893 104.11 169.991 102.644 -0.140446 -0.861505 -0.474625 0.113206 +VERTEX_SE3:QUAT 894 109.242 176.323 112.37 -0.103147 -0.84691 -0.495893 0.161847 +VERTEX_SE3:QUAT 895 114.084 182.034 121.84 -0.246448 -0.745874 -0.567851 0.245929 +VERTEX_SE3:QUAT 896 122.405 184.545 130.279 -0.508331 -0.6575 -0.529023 0.171545 +VERTEX_SE3:QUAT 897 132.871 182.928 136.287 -0.702682 -0.42888 -0.457704 0.335867 +VERTEX_SE3:QUAT 898 143.946 177.689 134.661 -0.675712 -0.242817 -0.666543 0.200433 +VERTEX_SE3:QUAT 899 150.964 168.211 134.454 -0.637305 -0.0885903 -0.702058 0.305136 +VERTEX_SE3:QUAT 900 157.734 158.53 130.575 -0.568167 -0.0411415 -0.77406 0.276268 +VERTEX_SE3:QUAT 901 163.75 148.467 126.687 -0.588507 0.0778087 -0.663406 0.455519 +VERTEX_SE3:QUAT 902 169.772 141.934 118.106 -0.594312 0.172553 -0.659663 0.426454 +VERTEX_SE3:QUAT 903 174.082 135.49 108.465 -0.731872 0.269119 -0.522513 0.344846 +VERTEX_SE3:QUAT 904 173.368 128.699 98.3846 -0.61482 0.338626 -0.547838 0.455194 +VERTEX_SE3:QUAT 905 173.756 124.885 86.7005 -0.705199 0.356172 -0.461605 0.403432 +VERTEX_SE3:QUAT 906 172.141 120.538 75.9011 -0.66163 0.299537 -0.443897 0.524861 +VERTEX_SE3:QUAT 907 172.469 117.734 64.1191 -0.520815 0.259385 -0.475651 0.659718 +VERTEX_SE3:QUAT 908 176.07 118.111 52.5481 -0.317425 0.403337 -0.488077 0.705933 +VERTEX_SE3:QUAT 909 180.942 122.805 42.3841 -0.364793 0.500881 -0.36268 0.696066 +VERTEX_SE3:QUAT 910 181.928 129.193 32.2899 -0.364778 0.595752 -0.379353 0.606719 +VERTEX_SE3:QUAT 911 182.112 134.895 21.695 -0.393849 0.534728 -0.402277 0.630176 +VERTEX_SE3:QUAT 912 183.196 140.172 10.9091 -0.383501 0.58954 -0.427767 0.56779 +VERTEX_SE3:QUAT 913 183.64 144.684 -0.540716 -0.420356 0.519848 -0.371135 0.644451 +VERTEX_SE3:QUAT 914 183.614 149.886 -11.5817 -0.407928 0.556874 -0.085025 0.71851 +VERTEX_SE3:QUAT 915 179.217 158.116 -19.1695 -0.236299 0.580495 -0.0490069 0.77768 +VERTEX_SE3:QUAT 916 176.41 169.129 -23.7707 -0.168123 0.767245 -0.0948089 0.611622 +VERTEX_SE3:QUAT 917 174.38 180.679 -27.7401 -0.0534951 0.733089 0.0686335 0.674543 +VERTEX_SE3:QUAT 918 172.118 192.913 -26.8475 -0.106205 0.675624 0.0680067 0.72638 +VERTEX_SE3:QUAT 919 168.671 204.91 -26.9183 0.10784 0.63601 -0.0909834 0.758673 +VERTEX_SE3:QUAT 920 171.752 216.499 -25.4969 0.0757472 0.709766 -0.128987 0.688372 +VERTEX_SE3:QUAT 921 175.026 228.412 -25.6957 0.262491 0.687087 -0.0526673 0.675453 +VERTEX_SE3:QUAT 922 180.421 238.754 -21.503 0.352363 0.594476 -0.0925258 0.716852 +VERTEX_SE3:QUAT 923 186.737 247.62 -15.917 0.43186 0.383455 0.03313 0.815697 +VERTEX_SE3:QUAT 924 189.261 255.137 -6.78438 0.447331 0.285636 0.20691 0.821886 +VERTEX_SE3:QUAT 925 187.297 261.358 3.86779 0.360548 0.255551 0.276894 0.853246 +VERTEX_SE3:QUAT 926 183.15 267.932 13.4685 0.526657 0.228795 0.393932 0.717706 +VERTEX_SE3:QUAT 927 178.262 269.045 24.71 0.704157 0.109188 0.451169 0.537296 +VERTEX_SE3:QUAT 928 173.612 263.826 34.9467 0.68216 -0.0279595 0.421599 0.596766 +VERTEX_SE3:QUAT 929 166.331 259.805 44.3143 0.604807 -0.0418128 0.48275 0.631991 +VERTEX_SE3:QUAT 930 157.932 257.036 52.9271 0.572868 -0.182618 0.573769 0.556114 +VERTEX_SE3:QUAT 931 147.091 252.797 57.3513 0.519307 -0.141416 0.763928 0.355999 +VERTEX_SE3:QUAT 932 138.738 243.932 58.458 0.560991 -0.142234 0.762017 0.290499 +VERTEX_SE3:QUAT 933 131.486 234.154 59.148 0.557172 0.0141408 0.75957 0.33528 +VERTEX_SE3:QUAT 934 125.374 224.252 63.5213 0.643006 0.0360635 0.729302 0.231 +VERTEX_SE3:QUAT 935 121.953 213.023 66.7317 0.534523 -0.159336 0.780834 0.281416 +VERTEX_SE3:QUAT 936 114.52 202.771 66.6878 0.540586 -0.0980839 0.756112 0.355586 +VERTEX_SE3:QUAT 937 106.587 193.296 68.8423 0.466404 -0.0833178 0.746756 0.466777 +VERTEX_SE3:QUAT 938 97.2642 185.97 71.9969 0.315228 -0.165287 0.875934 0.325655 +VERTEX_SE3:QUAT 939 89.2736 176.763 70.3939 0.28701 -0.178531 0.90701 0.251169 +VERTEX_SE3:QUAT 940 83.302 166.84 67.4663 0.252665 -0.308124 0.877327 0.267427 +VERTEX_SE3:QUAT 941 75.9107 158.611 62.0205 0.140014 -0.266679 0.934205 0.191153 +VERTEX_SE3:QUAT 942 70.9976 148.737 56.4214 0.0953446 -0.33393 0.934672 0.0760888 +VERTEX_SE3:QUAT 943 68.7803 139.302 49.0555 -0.00504438 -0.315623 0.941887 0.11492 +VERTEX_SE3:QUAT 944 66.5728 129.422 41.6381 0.0264199 -0.211928 0.974244 0.0723737 +VERTEX_SE3:QUAT 945 65.5894 118.591 36.68 0.00468169 -0.19178 0.981322 0.0143187 +VERTEX_SE3:QUAT 946 66.0371 107.168 31.7619 0.0654326 -0.216961 0.973515 0.0302383 +VERTEX_SE3:QUAT 947 65.4602 96.596 26.0385 -0.00847585 0.248944 -0.966695 0.0587869 +VERTEX_SE3:QUAT 948 67.6724 86.3114 19.9383 0.127647 0.26285 -0.938077 0.186087 +VERTEX_SE3:QUAT 949 73.4746 76.8893 14.3897 0.400065 0.212943 -0.879301 0.146397 +VERTEX_SE3:QUAT 950 79.2586 66.9849 11.9566 0.540629 0.19033 -0.802353 0.16651 +VERTEX_SE3:QUAT 951 85.3652 56.3758 11.1212 0.456782 0.000691632 -0.889223 0.0251459 +VERTEX_SE3:QUAT 952 86.2081 43.9826 11.9402 0.444786 0.0872118 -0.885225 0.104574 +VERTEX_SE3:QUAT 953 89.9401 32.3081 11.9952 0.482614 0.101289 -0.824352 0.277972 +VERTEX_SE3:QUAT 954 97.2202 22.6467 13.8819 0.492312 0.105352 -0.787769 0.354894 +VERTEX_SE3:QUAT 955 105.808 14.1546 17.3981 0.480017 0.00692851 -0.765341 0.428706 +VERTEX_SE3:QUAT 956 114.124 7.14162 22.5772 0.434131 0.0471867 -0.807986 0.395554 +VERTEX_SE3:QUAT 957 122.691 -0.615778 26.5169 0.500325 0.156585 -0.757711 0.388627 +VERTEX_SE3:QUAT 958 132.398 -7.85188 29.1408 0.42614 0.13776 -0.740485 0.501107 +VERTEX_SE3:QUAT 959 143.097 -12.8382 32.654 0.481762 0.0332998 -0.652229 0.584289 +VERTEX_SE3:QUAT 960 152.821 -16.3093 39.4822 0.456561 -0.0528863 -0.564054 0.686002 +VERTEX_SE3:QUAT 961 161.69 -16.342 48.0379 0.493878 0.0730813 -0.351616 0.791903 +VERTEX_SE3:QUAT 962 169.219 -12.3026 57.4554 0.456291 -0.0420067 -0.0903478 0.884235 +VERTEX_SE3:QUAT 963 170.298 -4.91694 67.5763 0.390903 -0.130547 -0.0331067 0.910525 +VERTEX_SE3:QUAT 964 168.85 4.02654 76.2783 0.33742 -0.290955 0.0732965 0.892256 +VERTEX_SE3:QUAT 965 164.179 13.8944 82.5351 0.185909 -0.281568 0.0483933 0.940115 +VERTEX_SE3:QUAT 966 161.001 25.6031 85.8004 0.0302784 -0.271195 -0.0151328 0.961929 +VERTEX_SE3:QUAT 967 160.453 38.0333 86.3805 0.0236064 -0.103623 0.0466427 0.993242 +VERTEX_SE3:QUAT 968 158.452 49.9667 86.3639 -0.0035755 -0.225093 0.180855 0.957398 +VERTEX_SE3:QUAT 969 153.627 61.1587 84.9344 -0.180349 -0.188302 0.34991 0.899766 +VERTEX_SE3:QUAT 970 146.145 68.9025 78.8696 -0.208251 -0.0745233 0.47824 0.84992 +VERTEX_SE3:QUAT 971 136.027 73.9991 73.6728 -0.275514 -0.0242904 0.540522 0.794568 +VERTEX_SE3:QUAT 972 125.614 76.7062 67.7887 -0.217709 -0.0701811 0.61923 0.751153 +VERTEX_SE3:QUAT 973 114.214 77.3957 62.6576 -0.14057 -0.0724578 0.665726 0.729245 +VERTEX_SE3:QUAT 974 102.325 77.4819 58.9667 -0.104126 0.0702401 0.721001 0.681456 +VERTEX_SE3:QUAT 975 89.7394 75.8723 58.5495 -0.179578 0.0441768 0.80681 0.561122 +VERTEX_SE3:QUAT 976 78.2679 70.8506 56.7467 -0.405586 0.0629367 0.805368 0.427692 +VERTEX_SE3:QUAT 977 69.05 62.4704 54.2538 -0.393738 0.052421 0.858719 0.323767 +VERTEX_SE3:QUAT 978 62.2883 52.5169 52.6624 -0.209862 0.238185 0.939099 0.1316 +VERTEX_SE3:QUAT 979 58.645 42.1611 57.8931 -0.252016 0.355773 0.88188 0.179445 +VERTEX_SE3:QUAT 980 53.2151 33.3316 65.0944 -0.16456 0.239833 0.948956 0.121998 +VERTEX_SE3:QUAT 981 50.1861 22.5985 70.2708 -0.0247149 0.209091 0.977243 0.0258313 +VERTEX_SE3:QUAT 982 50.6087 11.2718 74.8432 0.067778 -0.174983 -0.982183 0.0101646 +VERTEX_SE3:QUAT 983 51.3912 -0.507329 78.9495 0.0992356 -0.172894 -0.975963 0.0880726 +VERTEX_SE3:QUAT 984 53.6805 -11.7878 83.0262 -0.0264277 0.0348722 -0.993586 0.104267 +VERTEX_SE3:QUAT 985 57.2607 -23.6604 81.6643 0.0389885 0.0867054 -0.933394 0.34603 +VERTEX_SE3:QUAT 986 66.1318 -32.5471 80.3147 -0.0457476 -0.0212861 -0.897265 0.4386 +VERTEX_SE3:QUAT 987 76.4104 -39.6257 80.3555 -0.040167 0.140381 -0.840603 0.5216 +VERTEX_SE3:QUAT 988 87.3144 -44.0113 77.1048 0.046081 0.00102455 -0.893546 0.4466 +VERTEX_SE3:QUAT 989 97.7756 -50.8112 77.6541 0.152182 0.153119 -0.807707 0.548639 +VERTEX_SE3:QUAT 990 109.5 -54.4519 76.8152 0.223145 0.250077 -0.726983 0.599303 +VERTEX_SE3:QUAT 991 121.802 -55.6609 75.9633 0.268862 0.263423 -0.652957 0.657243 +VERTEX_SE3:QUAT 992 134.245 -54.839 76.488 0.351782 0.267273 -0.716574 0.539756 +VERTEX_SE3:QUAT 993 146.331 -57.4836 76.6326 0.37954 0.363006 -0.725768 0.444339 +VERTEX_SE3:QUAT 994 158.245 -61.6059 74.957 0.497042 0.498285 -0.591505 0.393425 +VERTEX_SE3:QUAT 995 170.637 -63.9543 73.1594 0.523905 0.427124 -0.511772 0.530261 +VERTEX_SE3:QUAT 996 182.743 -64.5928 75.2519 0.639199 0.416783 -0.561977 0.319216 +VERTEX_SE3:QUAT 997 194.094 -69.9123 75.0731 0.760932 0.0915563 -0.564537 0.306429 +VERTEX_SE3:QUAT 998 200.063 -79.644 80.0203 0.831394 -0.0011026 -0.48439 0.272305 +VERTEX_SE3:QUAT 999 202.924 -90.2024 86.7789 0.821043 0.0431034 -0.445274 0.354628 +VERTEX_SE3:QUAT 1000 207.255 -99.4522 94.1806 0.799328 -0.0935104 -0.410175 0.429054 +VERTEX_SE3:QUAT 1001 209.231 -106.75 104.046 0.779225 -0.120386 -0.328429 0.520048 +VERTEX_SE3:QUAT 1002 210.484 -111.565 115.334 0.851511 -0.189484 -0.174399 0.456739 +VERTEX_SE3:QUAT 1003 207.899 -117.356 126.172 0.756569 -0.36778 -0.20616 0.499839 +VERTEX_SE3:QUAT 1004 202.823 -120.157 137.776 0.617601 -0.343542 -0.341371 0.619689 +VERTEX_SE3:QUAT 1005 202.496 -119.38 150.05 0.616944 -0.4094 -0.238027 0.628581 +VERTEX_SE3:QUAT 1006 199.765 -117.186 162.121 0.576194 -0.463179 -0.0433221 0.672004 +VERTEX_SE3:QUAT 1007 193.421 -112.345 171.764 0.525652 -0.418754 0.00452502 0.740483 +VERTEX_SE3:QUAT 1008 187.499 -106.435 181.075 0.507924 -0.465032 0.175746 0.703471 +VERTEX_SE3:QUAT 1009 178.583 -100.865 187.111 0.411408 -0.445279 0.314969 0.730249 +VERTEX_SE3:QUAT 1010 168.098 -94.88 190.267 0.562484 -0.34986 0.415908 0.623082 +VERTEX_SE3:QUAT 1011 156.228 -94.5893 194.935 0.439873 -0.404172 0.571301 0.562825 +VERTEX_SE3:QUAT 1012 143.748 -95.0222 194.533 0.646155 -0.482002 0.453393 0.380253 +VERTEX_SE3:QUAT 1013 131.357 -97.1867 194.792 0.770773 -0.421479 0.448489 0.164688 +VERTEX_SE3:QUAT 1014 121.193 -104.271 192.533 0.781508 -0.309301 0.515438 0.167036 +VERTEX_SE3:QUAT 1015 112.595 -113.648 191.356 0.72293 -0.346743 0.562547 0.2017 +VERTEX_SE3:QUAT 1016 103.608 -121.703 189.358 0.616358 -0.413499 0.649542 0.164977 +VERTEX_SE3:QUAT 1017 94.4519 -128.922 184.677 -0.602868 0.618464 -0.502579 0.0383067 +VERTEX_SE3:QUAT 1018 86.0477 -131.233 176.133 -0.549055 0.559831 -0.603816 0.143295 +VERTEX_SE3:QUAT 1019 80.5562 -134.723 165.342 -0.496782 0.571954 -0.640454 0.126076 +VERTEX_SE3:QUAT 1020 75.7174 -137.865 154.357 -0.518567 0.580692 -0.621435 0.0877663 +VERTEX_SE3:QUAT 1021 70.0386 -140.958 144.018 -0.271596 0.681401 -0.66097 0.158262 +VERTEX_SE3:QUAT 1022 68.4442 -140.531 131.446 -0.0590408 0.691675 -0.656732 0.294623 +VERTEX_SE3:QUAT 1023 72.7301 -138.586 119.778 0.0206248 0.521613 -0.741785 0.421009 +VERTEX_SE3:QUAT 1024 81.1752 -139.464 110.329 -0.00152588 0.636674 -0.683593 0.356854 +VERTEX_SE3:QUAT 1025 87.7013 -137.762 100.042 -0.041582 0.681499 -0.647746 0.338018 +VERTEX_SE3:QUAT 1026 93.1357 -135.193 89.2232 0.0624766 0.665353 -0.578527 0.467663 +VERTEX_SE3:QUAT 1027 101.251 -130.913 80.9222 0.196472 0.607784 -0.399794 0.65739 +VERTEX_SE3:QUAT 1028 110.975 -122.873 78.8258 0.22467 0.530096 -0.349261 0.739283 +VERTEX_SE3:QUAT 1029 120.321 -114.568 79.3664 0.104297 0.520871 -0.26392 0.805085 +VERTEX_SE3:QUAT 1030 126.551 -103.794 78.5228 -0.102026 0.566143 -0.218229 0.78832 +VERTEX_SE3:QUAT 1031 129.011 -92.1819 73.8069 -0.273427 0.622235 -0.14062 0.719922 +VERTEX_SE3:QUAT 1032 126.958 -81.5809 67.2785 -0.281194 0.554324 -0.221719 0.751329 +VERTEX_SE3:QUAT 1033 126.853 -72.0152 59.7949 -0.28337 0.547695 -0.271391 0.738971 +VERTEX_SE3:QUAT 1034 127.474 -62.8047 51.1364 -0.310645 0.541159 -0.017939 0.781233 +VERTEX_SE3:QUAT 1035 123.002 -52.3659 45.3874 -0.285773 0.66277 0.131033 0.679632 +VERTEX_SE3:QUAT 1036 115.916 -42.2586 43.3016 -0.382902 0.587432 0.304628 0.644602 +VERTEX_SE3:QUAT 1037 105.558 -35.9175 42.3928 -0.267517 0.715409 0.207308 0.611268 +VERTEX_SE3:QUAT 1038 97.7425 -26.2872 42.7266 -0.364777 0.72117 0.386345 0.44451 +VERTEX_SE3:QUAT 1039 86.8432 -20.7489 46.2012 -0.130347 0.768619 0.369904 0.505378 +VERTEX_SE3:QUAT 1040 79.6822 -12.381 52.4984 -0.157741 0.723959 0.398904 0.540257 +VERTEX_SE3:QUAT 1041 71.9051 -4.6145 58.2642 -0.196343 0.757734 0.289007 0.551147 +VERTEX_SE3:QUAT 1042 64.3578 4.59965 61.2778 -0.266747 0.768373 0.399689 0.422726 +VERTEX_SE3:QUAT 1043 55.5967 11.1893 66.5898 -0.0962588 0.74929 0.464748 0.461853 +VERTEX_SE3:QUAT 1044 48.7793 17.9002 74.7541 -0.209931 0.57275 0.536622 0.583029 +VERTEX_SE3:QUAT 1045 37.8555 21.6848 80.3282 -0.114354 0.645446 0.56553 0.500499 +VERTEX_SE3:QUAT 1046 29.2366 25.3492 88.2041 -0.128811 0.641492 0.533307 0.536171 +VERTEX_SE3:QUAT 1047 20.2551 30.0755 95.3207 0.0937494 0.592476 0.459768 0.654826 +VERTEX_SE3:QUAT 1048 13.942 36.3846 104.441 0.377916 0.566241 0.372314 0.630819 +VERTEX_SE3:QUAT 1049 13.378 41.1952 115.991 0.35564 0.626896 0.412452 0.55714 +VERTEX_SE3:QUAT 1050 13.3472 45.5319 127.858 0.383235 0.591607 0.535388 0.465287 +VERTEX_SE3:QUAT 1051 12.8943 46.5352 140.195 0.436977 0.632661 0.459974 0.444089 +VERTEX_SE3:QUAT 1052 14.374 48.8385 152.542 0.546362 0.482341 0.464042 0.503488 +VERTEX_SE3:QUAT 1053 14.8072 47.8263 165.445 0.562559 0.523189 0.441319 0.463722 +VERTEX_SE3:QUAT 1054 16.7965 46.5802 177.713 0.650386 0.446355 0.565252 0.241362 +VERTEX_SE3:QUAT 1055 20.2585 39.7772 187.611 0.704226 0.444662 0.490889 0.255676 +VERTEX_SE3:QUAT 1056 24.7651 33.4054 197.01 0.640857 0.485751 0.551851 0.220924 +VERTEX_SE3:QUAT 1057 29.9161 27.3622 207.247 0.655277 0.362595 0.631996 0.199294 +VERTEX_SE3:QUAT 1058 32.4477 18.5481 216.143 0.76627 0.385911 0.459546 0.229609 +VERTEX_SE3:QUAT 1059 36.7956 10.2268 224.76 0.590122 0.477592 0.613498 0.217444 +VERTEX_SE3:QUAT 1060 40.5398 4.02653 234.89 0.50136 0.446295 0.738673 0.0618128 +VERTEX_SE3:QUAT 1061 44.9855 -3.97551 243.335 0.559108 0.318213 0.765065 0.028528 +VERTEX_SE3:QUAT 1062 49.1231 -14.401 249.365 -0.645457 -0.284592 -0.694103 0.143573 +VERTEX_SE3:QUAT 1063 56.2927 -24.6024 251.631 -0.574433 -0.243705 -0.769753 0.134595 +VERTEX_SE3:QUAT 1064 62.5306 -34.9592 253.568 -0.649421 -0.0844905 -0.746181 0.119699 +VERTEX_SE3:QUAT 1065 66.1233 -46.879 252.605 -0.613457 -0.0572267 -0.739789 0.270386 +VERTEX_SE3:QUAT 1066 72.2684 -57.3687 248.713 -0.753975 -0.101722 -0.564806 0.319638 +VERTEX_SE3:QUAT 1067 78.2976 -66.7861 243.374 -0.661247 -0.178395 -0.580029 0.441015 +VERTEX_SE3:QUAT 1068 87.3715 -73.3392 237.425 -0.517898 -0.0352512 -0.668983 0.531979 +VERTEX_SE3:QUAT 1069 96.4708 -78.0107 230.191 -0.401047 -0.0958348 -0.704001 0.578239 +VERTEX_SE3:QUAT 1070 107.93 -81.4244 225.37 -0.290356 -0.0610354 -0.619716 0.726582 +VERTEX_SE3:QUAT 1071 119.321 -80.1743 220.789 -0.284528 0.0710534 -0.609434 0.736604 +VERTEX_SE3:QUAT 1072 129.825 -78.4125 214.32 -0.20814 0.157008 -0.67643 0.688817 +VERTEX_SE3:QUAT 1073 140.644 -77.5363 208.091 -0.149938 -0.0730569 -0.738426 0.653383 +VERTEX_SE3:QUAT 1074 153.281 -78.3235 206.422 -0.0727792 -0.163868 -0.688606 0.702618 +VERTEX_SE3:QUAT 1075 165.646 -77.0253 207.949 -0.165525 -0.265895 -0.66151 0.6814 +VERTEX_SE3:QUAT 1076 178.265 -75.5077 209.072 -0.143661 -0.376235 -0.511715 0.758918 +VERTEX_SE3:QUAT 1077 189.454 -69.3636 210.115 -0.216985 -0.45009 -0.44172 0.745131 +VERTEX_SE3:QUAT 1078 199.907 -62.3889 210.43 -0.215432 -0.505785 -0.389843 0.738778 +VERTEX_SE3:QUAT 1079 210.015 -54.5498 210.955 -0.18547 -0.396895 -0.351306 0.827441 +VERTEX_SE3:QUAT 1080 218.896 -45.9631 209.823 -0.313156 -0.361045 -0.360151 0.801169 +VERTEX_SE3:QUAT 1081 228.427 -39.0628 206.142 -0.318526 -0.43998 -0.213563 0.812003 +VERTEX_SE3:QUAT 1082 235.989 -30.4213 201.247 -0.403429 -0.443067 -0.249 0.760878 +VERTEX_SE3:QUAT 1083 244.699 -23.7025 195.595 -0.311047 -0.453944 -0.259486 0.793632 +VERTEX_SE3:QUAT 1084 252.953 -15.4267 192.117 -0.364918 -0.517031 -0.185895 0.751636 +VERTEX_SE3:QUAT 1085 261.06 -7.34903 186.562 -0.453818 -0.450523 -0.185525 0.746095 +VERTEX_SE3:QUAT 1086 269.105 -1.1832 179.759 -0.393475 -0.400705 -0.250222 0.788671 +VERTEX_SE3:QUAT 1087 277.922 5.90414 173.913 -0.516194 -0.118568 -0.135477 0.837336 +VERTEX_SE3:QUAT 1088 282.155 11.193 163.421 -0.536985 -0.145563 0.0524003 0.829284 +VERTEX_SE3:QUAT 1089 281.898 16.496 151.939 -0.527458 -0.223278 0.090887 0.814662 +VERTEX_SE3:QUAT 1090 282.565 21.3036 140.384 -0.572854 -0.258777 0.067472 0.774803 +VERTEX_SE3:QUAT 1091 284.249 25.4351 128.808 -0.71921 -0.255518 0.118597 0.635124 +VERTEX_SE3:QUAT 1092 285.842 24.2302 116.684 -0.59368 -0.380254 0.283772 0.649942 +VERTEX_SE3:QUAT 1093 286.473 25.3563 104.035 -0.550354 -0.455961 0.216375 0.665126 +VERTEX_SE3:QUAT 1094 288.844 28.3325 92.3086 -0.598407 -0.434936 0.266174 0.617974 +VERTEX_SE3:QUAT 1095 290.723 28.981 79.9835 -0.490999 -0.44528 0.250652 0.705563 +VERTEX_SE3:QUAT 1096 291.659 32.7726 68.5386 -0.589588 -0.369702 0.309329 0.648091 +VERTEX_SE3:QUAT 1097 291.798 33.671 56.3069 -0.549671 -0.283577 0.453899 0.641421 +VERTEX_SE3:QUAT 1098 287.874 32.5856 44.5127 -0.594779 -0.226796 0.404269 0.656786 +VERTEX_SE3:QUAT 1099 284.185 31.33 32.243 -0.640725 -0.235134 0.436258 0.586398 +VERTEX_SE3:QUAT 1100 281.088 28.1534 20.844 -0.609518 -0.0808394 0.530385 0.583648 +VERTEX_SE3:QUAT 1101 274.37 23.8563 11.4657 -0.668721 0.157236 0.555463 0.468563 +VERTEX_SE3:QUAT 1102 264.946 17.001 6.42588 -0.56081 0.290842 0.533621 0.562274 +VERTEX_SE3:QUAT 1103 253.538 14.4722 3.44706 -0.50209 0.313453 0.631985 0.500249 +VERTEX_SE3:QUAT 1104 241.614 9.94253 2.79685 -0.515401 0.346455 0.67923 0.391123 +VERTEX_SE3:QUAT 1105 231.026 3.5794 4.17284 -0.564957 0.307591 0.687519 0.33694 +VERTEX_SE3:QUAT 1106 221.214 -3.93444 5.33699 -0.540757 0.381549 0.700734 0.266409 +VERTEX_SE3:QUAT 1107 211.707 -11.0709 9.30435 -0.43435 0.469605 0.768473 0.0161169 +VERTEX_SE3:QUAT 1108 206.94 -17.5956 18.4487 0.434876 -0.330601 -0.812871 0.202057 +VERTEX_SE3:QUAT 1109 207.734 -25.7153 27.9184 0.380325 -0.267291 -0.85733 0.221119 +VERTEX_SE3:QUAT 1110 210.287 -34.4607 36.0785 0.261998 -0.336451 -0.879011 0.213303 +VERTEX_SE3:QUAT 1111 213.212 -42.8004 44.978 0.345013 -0.24457 -0.861448 0.281175 +VERTEX_SE3:QUAT 1112 217.677 -51.5472 53.3942 0.283471 -0.269679 -0.892846 0.223034 +VERTEX_SE3:QUAT 1113 221.173 -60.5709 61.2598 0.217445 -0.371394 -0.841499 0.326594 +VERTEX_SE3:QUAT 1114 226.752 -66.6197 70.653 0.139805 -0.386625 -0.73362 0.541089 +VERTEX_SE3:QUAT 1115 235.581 -67.6066 79.4553 0.0896613 -0.384217 -0.632922 0.666144 +VERTEX_SE3:QUAT 1116 245.65 -64.3784 86.7627 -0.0881834 -0.15309 -0.523154 0.833725 +VERTEX_SE3:QUAT 1117 256.642 -58.3518 86.2929 -0.14876 -0.267355 -0.447381 0.840382 +VERTEX_SE3:QUAT 1118 266.972 -51.0061 85.7955 -0.159015 -0.374998 -0.399804 0.821126 +VERTEX_SE3:QUAT 1119 276.401 -42.8378 85.613 -0.176151 -0.465875 -0.332991 0.800655 +VERTEX_SE3:QUAT 1120 284.815 -33.5776 85.4345 -0.181054 -0.442173 -0.228807 0.848145 +VERTEX_SE3:QUAT 1121 291.014 -23.0226 83.3318 -0.355824 -0.422853 -0.11242 0.8258 +VERTEX_SE3:QUAT 1122 296.54 -14.1017 76.4344 -0.23355 -0.478213 0.0413628 0.84561 +VERTEX_SE3:QUAT 1123 298.384 -3.14584 70.2783 -0.191114 -0.576382 0.151853 0.779872 +VERTEX_SE3:QUAT 1124 298.048 7.56168 63.4498 -0.127577 -0.612312 0.199055 0.754437 +VERTEX_SE3:QUAT 1125 296.232 18.3727 57.2346 -0.132095 -0.656345 0.152294 0.727027 +VERTEX_SE3:QUAT 1126 295.747 29.7308 51.5195 -0.211702 -0.708677 0.288219 0.608184 +VERTEX_SE3:QUAT 1127 295.256 38.7582 42.4351 -0.198593 -0.680058 0.41757 0.568961 +VERTEX_SE3:QUAT 1128 292.934 44.8577 32.2278 -0.213183 -0.555584 0.614785 0.517609 +VERTEX_SE3:QUAT 1129 288.392 45.9389 20.86 -0.17929 -0.554907 0.662398 0.470279 +VERTEX_SE3:QUAT 1130 283.633 45.9743 9.63038 -0.149166 -0.540573 0.751426 0.347692 +VERTEX_SE3:QUAT 1131 279.572 43.4217 -2.11914 -0.278404 -0.397979 0.79215 0.369598 +VERTEX_SE3:QUAT 1132 275.724 37.7007 -12.4322 -0.241369 -0.323849 0.830173 0.384286 +VERTEX_SE3:QUAT 1133 270.73 31.2059 -21.6064 -0.28407 -0.326867 0.859863 0.270366 +VERTEX_SE3:QUAT 1134 267.929 22.7822 -30.4621 -0.257419 -0.13881 0.943537 0.15558 +VERTEX_SE3:QUAT 1135 266.136 11.3062 -34.7072 -0.327516 -0.254052 0.909334 0.036091 +VERTEX_SE3:QUAT 1136 267.749 0.513582 -40.5812 -0.455558 -0.114376 0.870717 0.145728 +VERTEX_SE3:QUAT 1137 266.023 -11.3631 -44.2382 0.468607 0.307829 -0.825284 0.0674901 +VERTEX_SE3:QUAT 1138 271.679 -21.4855 -49.136 0.554916 0.260273 -0.781635 0.115641 +VERTEX_SE3:QUAT 1139 278.227 -32.1232 -51.8384 0.710936 0.211534 -0.651071 0.161026 +VERTEX_SE3:QUAT 1140 284.286 -42.678 -51.7233 0.726866 0.175423 -0.638564 0.18201 +VERTEX_SE3:QUAT 1141 290.212 -53.7295 -50.0423 0.748848 0.195234 -0.627759 0.0838365 +VERTEX_SE3:QUAT 1142 294.53 -65.4406 -51.1296 0.684956 0.280585 -0.630425 0.23382 +VERTEX_SE3:QUAT 1143 303.329 -74.4789 -50.6734 0.726409 0.254575 -0.569431 0.288566 +VERTEX_SE3:QUAT 1144 312.175 -83.2892 -48.344 0.685418 0.100139 -0.632913 0.345827 +VERTEX_SE3:QUAT 1145 319.609 -92.2144 -43.4339 0.568672 0.165594 -0.657091 0.466285 +VERTEX_SE3:QUAT 1146 329.686 -98.0317 -38.8821 0.57752 0.142925 -0.661669 0.45633 +VERTEX_SE3:QUAT 1147 339.629 -104.461 -34.2589 0.582728 -0.213886 -0.55654 0.552217 +VERTEX_SE3:QUAT 1148 344.358 -107.454 -22.7093 0.520305 -0.151466 -0.582628 0.605711 +VERTEX_SE3:QUAT 1149 351.023 -109.564 -12.3967 0.548177 -0.347272 -0.481457 0.589154 +VERTEX_SE3:QUAT 1150 353.493 -109.692 0.160023 0.519745 -0.396066 -0.502222 0.566365 +VERTEX_SE3:QUAT 1151 355.516 -109.119 12.1875 0.435087 -0.447067 -0.475136 0.620546 +VERTEX_SE3:QUAT 1152 358.339 -106.263 24.2419 0.40638 -0.492393 -0.455152 0.620678 +VERTEX_SE3:QUAT 1153 360.269 -102.29 35.5821 0.439187 -0.463206 -0.355814 0.682606 +VERTEX_SE3:QUAT 1154 360.743 -97.2381 47.0092 0.389046 -0.313584 -0.408538 0.763809 +VERTEX_SE3:QUAT 1155 365.489 -92.2346 57.6207 0.449119 -0.193184 -0.373775 0.788203 +VERTEX_SE3:QUAT 1156 370.575 -87.0108 68.2957 0.595464 -0.213118 -0.327612 0.701908 +VERTEX_SE3:QUAT 1157 372.313 -85.2079 80.405 0.588412 -0.259681 -0.273009 0.715404 +VERTEX_SE3:QUAT 1158 372.555 -82.5595 92.5691 0.521815 -0.142806 -0.25516 0.801379 +VERTEX_SE3:QUAT 1159 375.287 -77.851 104.23 0.445881 -0.178843 -0.264882 0.836088 +VERTEX_SE3:QUAT 1160 378.201 -71.4236 114.737 0.431692 -0.11991 -0.318002 0.835546 +VERTEX_SE3:QUAT 1161 383.01 -65.4635 124.898 0.456605 -0.265968 -0.329676 0.78236 +VERTEX_SE3:QUAT 1162 385.881 -60.475 135.928 0.546279 -0.30481 -0.279848 0.728255 +VERTEX_SE3:QUAT 1163 386.643 -56.5622 147.606 0.589521 -0.0917643 -0.319398 0.736226 +VERTEX_SE3:QUAT 1164 390.88 -54.896 159.232 0.47757 -0.0211254 -0.367988 0.797537 +VERTEX_SE3:QUAT 1165 397.442 -51.0148 169.307 0.397686 -0.0187839 -0.285571 0.871747 +VERTEX_SE3:QUAT 1166 402.85 -43.9968 178.435 0.434924 0.082702 -0.202135 0.87358 +VERTEX_SE3:QUAT 1167 407.149 -36.8163 187.6 0.283272 0.0244852 -0.140149 0.948428 +VERTEX_SE3:QUAT 1168 409.941 -26.6264 194.286 0.303185 -0.0196552 -0.179618 0.935644 +VERTEX_SE3:QUAT 1169 413.113 -16.905 201.185 0.44705 0.0117337 -0.0245285 0.894096 +VERTEX_SE3:QUAT 1170 413.015 -9.36165 211.055 0.422364 0.0836047 0.0915891 0.897903 +VERTEX_SE3:QUAT 1171 411.096 -1.53817 220.416 0.329909 0.127868 0.243911 0.902949 +VERTEX_SE3:QUAT 1172 405.969 6.08691 228.717 0.198554 0.160537 0.45418 0.853536 +VERTEX_SE3:QUAT 1173 396.328 12.0174 235.048 0.257738 -0.0332766 0.436565 0.861321 +VERTEX_SE3:QUAT 1174 386.18 17.4481 239.579 0.163127 -0.0610765 0.590985 0.787652 +VERTEX_SE3:QUAT 1175 374.006 19.9904 241.619 0.265858 -0.0150582 0.627676 0.731516 +VERTEX_SE3:QUAT 1176 362.275 20.2143 246.203 0.225118 0.0192172 0.811511 0.53889 +VERTEX_SE3:QUAT 1177 351.644 14.2699 249.402 0.262923 0.029087 0.901221 0.343258 +VERTEX_SE3:QUAT 1178 344.219 4.27308 251.826 0.214703 0.118286 0.892636 0.378302 +VERTEX_SE3:QUAT 1179 336.902 -4.84629 256.382 0.0467319 -0.0269398 0.939782 0.33749 +VERTEX_SE3:QUAT 1180 329.622 -14.715 255.806 0.0111052 0.0417653 0.963613 0.263785 +VERTEX_SE3:QUAT 1181 323.781 -25.5985 256.722 0.0139365 -0.0465764 0.95385 0.296323 +VERTEX_SE3:QUAT 1182 317.308 -36.285 255.593 0.0788707 0.0676105 0.958263 0.266347 +VERTEX_SE3:QUAT 1183 311.596 -47.4378 257.425 0.118231 0.0176433 0.943253 0.309813 +VERTEX_SE3:QUAT 1184 304.845 -57.7469 258.581 0.131976 -0.0597089 0.977201 0.155224 +VERTEX_SE3:QUAT 1185 301.456 -69.5785 256.915 0.144052 -0.12846 0.980932 0.0227997 +VERTEX_SE3:QUAT 1186 301.283 -81.302 253.523 0.186589 0.135138 0.969089 0.0882545 +VERTEX_SE3:QUAT 1187 300.702 -93.2102 256.448 -0.0459647 -0.0275176 -0.99638 0.0660029 +VERTEX_SE3:QUAT 1188 303.066 -105.271 256.267 -0.0772184 -0.0923789 -0.981734 0.147316 +VERTEX_SE3:QUAT 1189 307.62 -116.633 257.773 -0.0753298 0.131982 -0.952617 0.26349 +VERTEX_SE3:QUAT 1190 314.317 -126.234 254.171 -0.0857733 0.0836875 -0.986582 0.110888 +VERTEX_SE3:QUAT 1191 317.088 -137.955 251.765 0.0175276 0.0315017 -0.967298 0.251067 +VERTEX_SE3:QUAT 1192 323.924 -148.639 251.024 0.0766455 -0.00466581 -0.99086 0.11091 +VERTEX_SE3:QUAT 1193 327.176 -160.446 251.534 0.0371278 0.0203352 -0.990675 0.129507 +VERTEX_SE3:QUAT 1194 331.012 -172.49 251.196 -0.00247383 -0.103249 0.994095 0.0332977 +VERTEX_SE3:QUAT 1195 331.095 -184.792 248.822 -0.132962 0.0988129 -0.978285 0.124563 +VERTEX_SE3:QUAT 1196 334.323 -196.366 245.683 -0.092987 0.0678571 -0.909038 0.400499 +VERTEX_SE3:QUAT 1197 343.807 -203.988 243.139 -0.197401 0.204216 -0.84913 0.445318 +VERTEX_SE3:QUAT 1198 352.592 -209.967 236.014 -0.232046 0.224545 -0.814363 0.482232 +VERTEX_SE3:QUAT 1199 361.364 -214.517 228.621 -0.251289 0.211427 -0.67812 0.6575 +VERTEX_SE3:QUAT 1200 371.13 -214.078 220.971 -0.259282 0.0894559 -0.68204 0.677932 +VERTEX_SE3:QUAT 1201 381.935 -214.175 214.565 -0.325793 0.104749 -0.547642 0.763528 +VERTEX_SE3:QUAT 1202 391.037 -211.517 206.565 -0.32744 0.307974 -0.407713 0.794799 +VERTEX_SE3:QUAT 1203 396.065 -205.469 197.169 -0.354035 0.327191 -0.377 0.79087 +VERTEX_SE3:QUAT 1204 400.219 -199.271 187.238 -0.389802 0.316623 -0.276261 0.819442 +VERTEX_SE3:QUAT 1205 402.426 -192.172 177.387 -0.249394 0.302995 -0.197015 0.898433 +VERTEX_SE3:QUAT 1206 403.619 -181.772 170.403 -0.210123 0.24488 -0.0641694 0.944333 +VERTEX_SE3:QUAT 1207 402.836 -170.441 165.245 -0.23989 0.234185 0.0171537 0.941975 +VERTEX_SE3:QUAT 1208 400.525 -159.603 160.124 -0.195382 0.169022 -0.0172524 0.965898 +VERTEX_SE3:QUAT 1209 398.909 -148.197 155.506 -0.00719501 0.220594 0.116172 0.968396 +VERTEX_SE3:QUAT 1210 395.365 -136.139 156.3 -0.184823 0.12592 0.198838 0.954174 +VERTEX_SE3:QUAT 1211 389.414 -126.125 153.007 -0.241215 0.0724145 0.217342 0.943045 +VERTEX_SE3:QUAT 1212 383.242 -116.913 147.939 -0.320822 0.0576701 0.397495 0.857756 +VERTEX_SE3:QUAT 1213 373.741 -111.557 142.005 -0.338445 0.202406 0.44748 0.802651 +VERTEX_SE3:QUAT 1214 362.836 -107.525 137.649 -0.36131 0.330184 0.470563 0.734169 +VERTEX_SE3:QUAT 1215 351.244 -104.284 135.396 -0.249481 0.316632 0.578951 0.708744 +VERTEX_SE3:QUAT 1216 339.168 -102.387 136.191 -0.290164 0.211646 0.647345 0.672277 +VERTEX_SE3:QUAT 1217 326.635 -103.051 135.028 -0.279974 0.24399 0.723733 0.581631 +VERTEX_SE3:QUAT 1218 314.722 -106.185 135.74 -0.327591 0.163435 0.739383 0.565053 +VERTEX_SE3:QUAT 1219 303.224 -110.739 134.42 -0.26816 0.136662 0.780879 0.547396 +VERTEX_SE3:QUAT 1220 292.229 -115.62 134.119 -0.0907123 0.0814145 0.883567 0.452164 +VERTEX_SE3:QUAT 1221 282.534 -123.26 134.899 -0.137046 0.117502 0.84505 0.503291 +VERTEX_SE3:QUAT 1222 272.246 -129.892 135.459 0.0444904 0.249451 0.881553 0.39832 +VERTEX_SE3:QUAT 1223 264.31 -137.141 141.094 0.0599258 0.22864 0.894116 0.380379 +VERTEX_SE3:QUAT 1224 256.958 -145.279 146.633 0.0333256 0.225604 0.940037 0.253619 +VERTEX_SE3:QUAT 1225 252.142 -155.201 151.958 -0.107641 0.105922 0.988516 0.00554935 +VERTEX_SE3:QUAT 1226 252.497 -167.525 154.698 0.186292 0.00370528 -0.964886 0.185141 +VERTEX_SE3:QUAT 1227 257.595 -178.748 155.848 0.17233 -0.0198771 -0.941907 0.287609 +VERTEX_SE3:QUAT 1228 264.808 -188.421 157.885 0.293867 -0.195861 -0.896029 0.269095 +VERTEX_SE3:QUAT 1229 269.758 -197.667 164.834 0.429298 -0.219788 -0.771319 0.415288 +VERTEX_SE3:QUAT 1230 275.411 -203.684 174.378 0.366819 -0.257225 -0.735778 0.507848 +VERTEX_SE3:QUAT 1231 282.706 -207.317 183.947 0.298199 -0.282595 -0.684115 0.602663 +VERTEX_SE3:QUAT 1232 290.885 -207.494 193.06 0.246669 -0.472703 -0.665274 0.522605 +VERTEX_SE3:QUAT 1233 296.94 -207.098 203.537 0.214899 -0.637098 -0.542504 0.503601 +VERTEX_SE3:QUAT 1234 300.854 -202.495 214.587 0.332179 -0.593286 -0.573992 0.456291 +VERTEX_SE3:QUAT 1235 302.644 -200.478 226.475 0.286507 -0.538248 -0.582265 0.537746 +VERTEX_SE3:QUAT 1236 306.949 -197.95 237.784 0.190086 -0.632746 -0.454795 0.597211 +VERTEX_SE3:QUAT 1237 311.087 -191.031 247.364 0.0443535 -0.53653 -0.474315 0.696558 +VERTEX_SE3:QUAT 1238 318.557 -183.773 253.948 0.166579 -0.553811 -0.418448 0.700318 +VERTEX_SE3:QUAT 1239 323.508 -175.658 262.036 0.200617 -0.559208 -0.445789 0.66956 +VERTEX_SE3:QUAT 1240 328.069 -168.695 270.833 0.224081 -0.453933 -0.481344 0.71557 +VERTEX_SE3:QUAT 1241 333.986 -162.515 279.937 0.0286015 -0.510888 -0.44236 0.736542 +VERTEX_SE3:QUAT 1242 341.83 -154.509 285.252 0.00385688 -0.474735 -0.423908 0.771307 +VERTEX_SE3:QUAT 1243 349.64 -146.083 289.769 -0.101438 -0.276634 -0.232114 0.926988 +VERTEX_SE3:QUAT 1244 355.397 -134.846 288.674 -0.175702 -0.38906 -0.270216 0.862986 +VERTEX_SE3:QUAT 1245 362.195 -124.786 286.673 -0.207258 -0.330584 -0.269548 0.880399 +VERTEX_SE3:QUAT 1246 368.832 -115.28 283.568 -0.3245 -0.407213 -0.208956 0.827777 +VERTEX_SE3:QUAT 1247 375.841 -106.711 278.07 -0.420632 -0.34159 -0.174087 0.82224 +VERTEX_SE3:QUAT 1248 382.312 -99.7932 270.462 -0.448555 -0.201494 -0.0966734 0.865363 +VERTEX_SE3:QUAT 1249 385.889 -92.7385 260.839 -0.510669 -0.291868 -0.134512 0.797456 +VERTEX_SE3:QUAT 1250 391.91 -87.5198 251.504 -0.465422 -0.150141 -0.18865 0.851617 +VERTEX_SE3:QUAT 1251 396.982 -81.5882 241.888 -0.49516 0.000920682 -0.149255 0.855885 +VERTEX_SE3:QUAT 1252 399.084 -75.7164 231.172 -0.482206 0.0211401 -0.145251 0.863674 +VERTEX_SE3:QUAT 1253 401.199 -69.918 220.554 -0.500164 0.0731876 -0.0798397 0.85913 +VERTEX_SE3:QUAT 1254 401.373 -64.0077 209.898 -0.527969 0.077971 0.014026 0.84556 +VERTEX_SE3:QUAT 1255 399.331 -58.7608 199.052 -0.543547 0.120679 0.143479 0.818173 +VERTEX_SE3:QUAT 1256 393.987 -54.1195 188.604 -0.538068 0.128812 0.240311 0.797584 +VERTEX_SE3:QUAT 1257 386.834 -50.7883 179.22 -0.478199 0.443711 0.234053 0.720878 +VERTEX_SE3:QUAT 1258 377.221 -45.6293 173.977 -0.488136 0.493791 0.206513 0.689381 +VERTEX_SE3:QUAT 1259 367.207 -40.212 168.687 -0.439825 0.625062 0.145867 0.628151 +VERTEX_SE3:QUAT 1260 357.914 -32.8955 164.433 -0.42625 0.708456 0.229212 0.513675 +VERTEX_SE3:QUAT 1261 347.667 -26.3635 163.903 -0.30238 0.65789 0.240235 0.646555 +VERTEX_SE3:QUAT 1262 338.87 -17.5456 163.783 -0.222917 0.696741 0.16293 0.662053 +VERTEX_SE3:QUAT 1263 332.358 -7.20004 163.751 -0.1338 0.748829 0.177625 0.624341 +VERTEX_SE3:QUAT 1264 327.446 3.78434 165.646 -0.167949 0.640033 0.417869 0.622524 +VERTEX_SE3:QUAT 1265 318.111 10.7737 170.386 -0.0683814 0.739237 0.421687 0.520609 +VERTEX_SE3:QUAT 1266 311.643 18.1149 177.781 0.140644 0.735535 0.484421 0.452266 +VERTEX_SE3:QUAT 1267 309.344 23.5067 188.613 0.268661 0.772666 0.441955 0.368081 +VERTEX_SE3:QUAT 1268 310.911 28.7223 200.046 0.271625 0.862203 0.156478 0.39792 +VERTEX_SE3:QUAT 1269 315.335 38.2193 206.309 0.438628 0.742149 0.308336 0.402182 +VERTEX_SE3:QUAT 1270 320.566 42.9186 216.639 0.564527 0.628442 0.223977 0.48601 +VERTEX_SE3:QUAT 1271 326.393 45.4013 227.33 0.500562 0.667713 0.282844 0.47286 +VERTEX_SE3:QUAT 1272 331.345 49.2524 238.051 0.553901 0.608275 0.328532 0.463963 +VERTEX_SE3:QUAT 1273 335.472 50.6884 249.675 0.613357 0.531491 0.185675 0.553927 +VERTEX_SE3:QUAT 1274 340.617 52.0432 260.796 0.746054 0.421765 0.17688 0.483974 +VERTEX_SE3:QUAT 1275 345.508 48.9614 271.595 0.847606 0.364159 0.194691 0.333239 +VERTEX_SE3:QUAT 1276 350.572 42.3239 280.308 0.849903 0.370125 0.282087 0.247183 +VERTEX_SE3:QUAT 1277 355.913 34.549 287.929 0.784301 0.229108 0.441969 0.370197 +VERTEX_SE3:QUAT 1278 355.735 26.3211 297.413 0.759154 0.0935437 0.520871 0.378984 +VERTEX_SE3:QUAT 1279 351.979 17.0657 305.135 0.886506 0.00471412 0.4136 0.207414 +VERTEX_SE3:QUAT 1280 349.437 5.88278 308.833 0.898089 0.139816 0.385683 0.158541 +VERTEX_SE3:QUAT 1281 350.257 -5.76821 313.255 0.945784 0.0788011 0.305925 0.0754557 +VERTEX_SE3:QUAT 1282 351.116 -17.5824 315.171 0.925492 0.0772366 0.366873 0.0538885 +VERTEX_SE3:QUAT 1283 351.799 -29.7606 316.562 0.88524 -0.112542 0.451198 0.0102069 +VERTEX_SE3:QUAT 1284 348.882 -41.4564 315.285 -0.895318 0.181555 -0.384151 0.133683 +VERTEX_SE3:QUAT 1285 345.662 -51.7862 310.259 -0.749945 0.330417 -0.488001 0.300436 +VERTEX_SE3:QUAT 1286 342.703 -58.1596 300.618 -0.712587 0.34775 -0.576088 0.198525 +VERTEX_SE3:QUAT 1287 339.042 -65.9752 291.689 -0.719175 0.397919 -0.517736 0.237481 +VERTEX_SE3:QUAT 1288 335.349 -72.2559 281.541 -0.820745 0.33741 -0.407814 0.214988 +VERTEX_SE3:QUAT 1289 330.069 -79.9713 273.111 -0.762812 0.492179 -0.365106 0.206337 +VERTEX_SE3:QUAT 1290 322.322 -84.6752 264.533 -0.596138 0.492917 -0.596025 0.215422 +VERTEX_SE3:QUAT 1291 317.81 -88.9369 253.912 -0.613158 0.425236 -0.633656 0.204186 +VERTEX_SE3:QUAT 1292 314.372 -94.9273 243.495 -0.465503 0.567026 -0.545108 0.405765 +VERTEX_SE3:QUAT 1293 313.663 -94.6011 231.4 -0.487199 0.642783 -0.437912 0.397115 +VERTEX_SE3:QUAT 1294 310.376 -92.1172 219.927 -0.372609 0.666932 -0.374178 0.525695 +VERTEX_SE3:QUAT 1295 309.038 -86.3007 209.835 -0.437899 0.698795 -0.26801 0.498096 +VERTEX_SE3:QUAT 1296 304.76 -79.9448 200.558 -0.321502 0.770149 -0.290307 0.468218 +VERTEX_SE3:QUAT 1297 301.918 -71.6955 191.633 -0.402167 0.750288 -0.0753402 0.519282 +VERTEX_SE3:QUAT 1298 295.252 -63.3535 185.985 -0.33455 0.809482 -0.0112879 0.482377 +VERTEX_SE3:QUAT 1299 288.739 -53.4718 182.556 -0.399389 0.82142 -0.0716802 0.400773 +VERTEX_SE3:QUAT 1300 281.441 -44.8365 177.781 -0.352121 0.916889 -0.122886 0.142215 +VERTEX_SE3:QUAT 1301 274.869 -35.5722 173.999 -0.32671 0.921082 -0.201019 0.0667832 +VERTEX_SE3:QUAT 1302 268.679 -26.2398 169.081 -0.224718 0.920215 -0.312457 0.0712522 +VERTEX_SE3:QUAT 1303 264.81 -17.418 162.15 -0.240268 0.868513 -0.431558 0.0414069 +VERTEX_SE3:QUAT 1304 260.763 -10.4069 152.793 0.13358 -0.853262 0.502347 0.0418184 +VERTEX_SE3:QUAT 1305 258.051 -4.49007 142.502 -0.0499342 0.812321 -0.578015 0.0595012 +VERTEX_SE3:QUAT 1306 258.733 -0.713095 130.943 -0.142244 0.822224 -0.536913 0.124253 +VERTEX_SE3:QUAT 1307 258.568 4.17643 119.963 -0.0646933 0.841867 -0.523749 0.112968 +VERTEX_SE3:QUAT 1308 259.253 9.82134 109.249 0.011224 0.803846 -0.592664 0.0495467 +VERTEX_SE3:QUAT 1309 261.332 13.2979 97.7372 -0.0440948 0.897691 -0.430376 0.0835614 +VERTEX_SE3:QUAT 1310 262.009 21.1268 88.6484 -0.0232357 0.856141 -0.510096 0.0792808 +VERTEX_SE3:QUAT 1311 263.689 27.1486 77.8225 0.105148 0.867553 -0.479316 0.0809415 +VERTEX_SE3:QUAT 1312 267.924 32.8296 68.2193 0.109638 0.855128 -0.492989 0.117042 +VERTEX_SE3:QUAT 1313 272.385 38.4867 58.5994 0.179073 0.855239 -0.475983 0.0996941 +VERTEX_SE3:QUAT 1314 278.038 44.1388 49.423 0.160433 0.790657 -0.568504 0.161017 +VERTEX_SE3:QUAT 1315 283.947 47.5762 39.6957 0.163079 0.775533 -0.593768 0.13926 +VERTEX_SE3:QUAT 1316 289.686 50.4422 29.8559 0.20549 0.814774 -0.532012 0.10431 +VERTEX_SE3:QUAT 1317 295.659 54.8379 20.3623 0.280547 0.798475 -0.498111 0.188722 +VERTEX_SE3:QUAT 1318 303.99 58.8322 12.2546 0.495873 0.710497 -0.451134 0.213967 +VERTEX_SE3:QUAT 1319 314.955 59.7077 8.3524 0.654585 0.537251 -0.519065 0.115983 +VERTEX_SE3:QUAT 1320 325.321 54.4826 4.22499 0.820894 0.510458 -0.166504 0.19453 +VERTEX_SE3:QUAT 1321 335.987 49.131 6.70846 0.743526 0.562652 -0.204852 0.297704 +VERTEX_SE3:QUAT 1322 347.407 46.2735 9.70046 0.813011 0.482475 -0.0469601 0.32253 +VERTEX_SE3:QUAT 1323 356.593 41.8539 15.4246 0.77401 0.585633 0.0135124 0.240333 +VERTEX_SE3:QUAT 1324 367.531 38.7463 20.8424 0.873813 0.446049 -0.0538085 0.186001 +VERTEX_SE3:QUAT 1325 376.597 31.9247 24.1749 0.947938 0.281067 -0.00291932 0.149688 +VERTEX_SE3:QUAT 1326 382.124 21.5043 27.897 0.952209 0.250688 0.0654922 0.161754 +VERTEX_SE3:QUAT 1327 387.199 11.3859 32.1268 0.948908 0.218063 0.126409 0.189848 +VERTEX_SE3:QUAT 1328 390.551 0.851295 36.976 0.977338 -0.000396582 0.148972 0.150389 +VERTEX_SE3:QUAT 1329 388.984 -10.8598 40.1903 0.97541 0.0155282 0.0741336 0.206975 +VERTEX_SE3:QUAT 1330 387.746 -21.7824 44.9163 0.977391 0.0316149 0.111584 0.176794 +VERTEX_SE3:QUAT 1331 387.482 -32.8751 49.1192 0.981878 0.0567529 0.054116 0.172529 +VERTEX_SE3:QUAT 1332 387.56 -44.1296 53.4882 0.990602 -0.0824452 0.0761319 0.0781964 +VERTEX_SE3:QUAT 1333 384.752 -55.4669 55.4154 0.965341 -0.207781 0.109147 0.114152 +VERTEX_SE3:QUAT 1334 379.022 -65.9453 57.1232 -0.948584 0.236739 -0.150898 0.146191 +VERTEX_SE3:QUAT 1335 373.513 -75.542 53.2354 -0.937134 0.271702 -0.168867 0.139434 +VERTEX_SE3:QUAT 1336 367.311 -85.1708 48.9775 -0.88681 0.333636 -0.319584 0.0110194 +VERTEX_SE3:QUAT 1337 359.822 -93.8828 46.0769 -0.788312 0.434135 -0.417344 0.126154 +VERTEX_SE3:QUAT 1338 352.947 -100.133 39.1498 -0.691291 0.624287 -0.351993 0.0921095 +VERTEX_SE3:QUAT 1339 343.276 -101.725 32.1446 -0.75611 0.506029 -0.398446 0.116074 +VERTEX_SE3:QUAT 1340 334.903 -106.678 24.7296 -0.681983 0.506642 -0.500109 0.167643 +VERTEX_SE3:QUAT 1341 328.837 -111.622 15.2086 -0.710862 0.593011 -0.281267 0.25279 +VERTEX_SE3:QUAT 1342 320.551 -112.827 6.63729 -0.691101 0.572486 -0.343661 0.276651 +VERTEX_SE3:QUAT 1343 313.159 -114.409 -2.51721 -0.605363 0.715837 -0.169973 0.303681 +VERTEX_SE3:QUAT 1344 303.733 -110.828 -9.47902 -0.668199 0.729897 0.00536801 0.143985 +VERTEX_SE3:QUAT 1345 292.218 -108.936 -11.2413 0.63112 -0.76108 -0.149636 0.00733384 +VERTEX_SE3:QUAT 1346 281.06 -106.268 -8.09521 -0.658608 0.72292 0.208395 0.0139352 +VERTEX_SE3:QUAT 1347 270.031 -104.965 -4.30049 0.637997 -0.713324 -0.256296 0.135794 +VERTEX_SE3:QUAT 1348 260.03 -103.441 2.37224 0.585044 -0.741745 -0.232158 0.231603 +VERTEX_SE3:QUAT 1349 251.124 -100.213 9.80926 0.666916 -0.649182 -0.0797135 0.356975 +VERTEX_SE3:QUAT 1350 241.527 -98.2229 16.379 0.582631 -0.654799 -0.0823373 0.474342 +VERTEX_SE3:QUAT 1351 233.435 -93.6333 24.2496 0.590673 -0.63057 -0.140826 0.483378 +VERTEX_SE3:QUAT 1352 225.946 -89.8218 32.8452 0.628417 -0.444458 -0.0537805 0.636126 +VERTEX_SE3:QUAT 1353 219.586 -86.8727 42.5906 0.640185 -0.423727 -0.164658 0.61928 +VERTEX_SE3:QUAT 1354 215.326 -84.7551 53.6347 0.435396 -0.595697 -0.146687 0.658831 +VERTEX_SE3:QUAT 1355 210.924 -77.461 62.2031 0.373934 -0.603994 -0.148201 0.688042 +VERTEX_SE3:QUAT 1356 208.412 -68.9888 69.6007 0.424662 -0.678321 -0.195924 0.566708 +VERTEX_SE3:QUAT 1357 204.23 -61.798 77.8513 0.470466 -0.527241 -0.298602 0.641494 +VERTEX_SE3:QUAT 1358 202.489 -56.7104 88.4639 0.471228 -0.608415 -0.277304 0.57522 +VERTEX_SE3:QUAT 1359 199.586 -51.3592 98.2051 0.290524 -0.631148 -0.255466 0.672298 +VERTEX_SE3:QUAT 1360 199.249 -42.4871 106.036 0.309759 -0.39971 -0.346458 0.790094 +VERTEX_SE3:QUAT 1361 202.471 -35.245 115.024 0.301774 -0.414326 -0.254307 0.820119 +VERTEX_SE3:QUAT 1362 204.366 -26.7231 122.919 0.187719 -0.631745 -0.139357 0.73908 +VERTEX_SE3:QUAT 1363 203.691 -16.0916 127.415 0.239465 -0.498503 -0.00135733 0.833156 +VERTEX_SE3:QUAT 1364 200.685 -5.4346 131.316 0.11653 -0.545854 0.0360642 0.828953 +VERTEX_SE3:QUAT 1365 198.376 6.05496 132.771 -0.0328964 -0.347056 -0.0994676 0.931974 +VERTEX_SE3:QUAT 1366 200.516 17.8529 132.451 -0.0184189 -0.32878 -0.103662 0.938519 +VERTEX_SE3:QUAT 1367 202.442 29.6323 132.487 -0.225714 -0.473891 -0.0253317 0.850787 +VERTEX_SE3:QUAT 1368 205.662 39.9183 127.466 -0.15267 -0.476035 0.0735471 0.862944 +VERTEX_SE3:QUAT 1369 205.415 50.9357 122.717 -0.205453 -0.426567 -0.00601445 0.880791 +VERTEX_SE3:QUAT 1370 207.06 61.5776 117.666 -0.146835 -0.468787 0.0194008 0.870805 +VERTEX_SE3:QUAT 1371 208.127 72.8937 113.392 -0.221048 -0.472826 0.245593 0.816858 +VERTEX_SE3:QUAT 1372 205.591 81.6614 105.852 -0.163375 -0.28618 0.235906 0.914198 +VERTEX_SE3:QUAT 1373 201.156 91.287 100.155 -0.088951 -0.338904 0.192026 0.91671 +VERTEX_SE3:QUAT 1374 197.14 101.857 96.0227 -0.268344 -0.337358 0.280433 0.857635 +VERTEX_SE3:QUAT 1375 192.91 109.549 88.2452 -0.124163 -0.337755 0.23974 0.901681 +VERTEX_SE3:QUAT 1376 188.545 119.449 83.4566 -0.142442 -0.379751 0.424221 0.809652 +VERTEX_SE3:QUAT 1377 181.327 126.039 76.2601 -0.320751 -0.399423 0.411362 0.753897 +VERTEX_SE3:QUAT 1378 176.793 130.658 66.2388 -0.483422 -0.432715 0.328039 0.686623 +VERTEX_SE3:QUAT 1379 176.54 133.791 54.8064 -0.493615 -0.505356 0.22475 0.671153 +VERTEX_SE3:QUAT 1380 178.674 137.85 44.2205 -0.435408 -0.692856 0.291524 0.495362 +VERTEX_SE3:QUAT 1381 182.797 142.277 33.8814 -0.513323 -0.616487 0.299712 0.516349 +VERTEX_SE3:QUAT 1382 186.696 145.092 23.0006 -0.511029 -0.556271 0.360574 0.547172 +VERTEX_SE3:QUAT 1383 188.579 146.893 11.3866 -0.50869 -0.403563 0.512354 0.562018 +VERTEX_SE3:QUAT 1384 186.948 145.373 -0.178353 -0.605166 -0.220166 0.480148 0.595617 +VERTEX_SE3:QUAT 1385 182.794 142.403 -11.3179 -0.543209 -0.291986 0.427538 0.660969 +VERTEX_SE3:QUAT 1386 180.021 142.387 -22.8063 -0.48065 -0.203532 0.385288 0.760988 +VERTEX_SE3:QUAT 1387 174.729 144.469 -33.2729 -0.544584 -0.110815 0.443358 0.703266 +VERTEX_SE3:QUAT 1388 168.678 144.011 -42.9953 -0.483628 0.0817687 0.578723 0.651535 +VERTEX_SE3:QUAT 1389 158.298 141.47 -48.7493 -0.508092 -0.0797223 0.531529 0.673026 +VERTEX_SE3:QUAT 1390 150.464 139.478 -57.3815 -0.475069 -0.0681981 0.547038 0.685863 +VERTEX_SE3:QUAT 1391 142.164 138.038 -65.5174 -0.545204 0.00677987 0.622978 0.560896 +VERTEX_SE3:QUAT 1392 133.515 132.917 -72.2114 -0.583127 0.00254028 0.715619 0.384508 +VERTEX_SE3:QUAT 1393 127.087 124.495 -76.8521 -0.546426 0.23421 0.707872 0.38142 +VERTEX_SE3:QUAT 1394 117.879 117.247 -77.6118 -0.49816 0.301798 0.766268 0.271272 +VERTEX_SE3:QUAT 1395 109.651 109.242 -74.6252 -0.465211 0.323441 0.781506 0.261177 +VERTEX_SE3:QUAT 1396 101.536 101.315 -71.1265 -0.592546 0.338822 0.653856 0.326435 +VERTEX_SE3:QUAT 1397 92.055 94.5916 -70.0492 -0.42604 0.494263 0.679025 0.336333 +VERTEX_SE3:QUAT 1398 82.3407 91.066 -64.702 -0.426658 0.397982 0.785357 0.206852 +VERTEX_SE3:QUAT 1399 75.5141 83.7382 -58.9773 -0.446958 0.391888 0.772387 0.223767 +VERTEX_SE3:QUAT 1400 68.1712 76.6343 -53.995 -0.476083 0.457941 0.731762 0.167807 +VERTEX_SE3:QUAT 1401 60.4775 70.6861 -47.2706 0.466548 -0.421319 -0.7776 0.0127345 +VERTEX_SE3:QUAT 1402 56.7156 63.1992 -38.7496 0.452777 -0.419931 -0.772689 0.146975 +VERTEX_SE3:QUAT 1403 55.578 56.4775 -29.2027 0.501813 -0.462287 -0.723594 0.104332 +VERTEX_SE3:QUAT 1404 52.2665 50.4963 -19.6271 0.507692 -0.539844 -0.66464 0.0952402 +VERTEX_SE3:QUAT 1405 47.6351 46.6315 -9.29759 0.345263 -0.447476 -0.759163 0.322848 +VERTEX_SE3:QUAT 1406 50.1532 42.5456 1.4147 0.278557 -0.453194 -0.766903 0.359001 +VERTEX_SE3:QUAT 1407 54.0898 39.4118 11.9161 0.13036 -0.504878 -0.689025 0.503338 +VERTEX_SE3:QUAT 1408 61.107 40.24 21.1646 0.178546 -0.444915 -0.823366 0.30371 +VERTEX_SE3:QUAT 1409 66.0738 35.5513 30.5141 0.0954493 -0.572418 -0.726348 0.3683 +VERTEX_SE3:QUAT 1410 71.3939 35.1667 40.7236 0.0192238 -0.560555 -0.737545 0.37608 +VERTEX_SE3:QUAT 1411 78.3256 34.6614 50.128 0.0577547 -0.516202 -0.730074 0.444062 +VERTEX_SE3:QUAT 1412 85.7465 34.5841 59.3579 0.0571141 -0.62697 -0.687313 0.362282 +VERTEX_SE3:QUAT 1413 91.4811 35.4492 69.8271 -0.0483824 -0.756002 -0.452511 0.470483 +VERTEX_SE3:QUAT 1414 97.8276 42.4304 76.9561 0.0931131 -0.676082 -0.498084 0.534936 +VERTEX_SE3:QUAT 1415 103.068 48.5372 85.5088 0.0690619 -0.711991 -0.501225 0.486902 +VERTEX_SE3:QUAT 1416 108.143 54.3888 94.0725 -0.119194 -0.730571 -0.329602 0.586021 +VERTEX_SE3:QUAT 1417 114.767 63.3198 96.9966 -0.0458242 -0.728362 -0.32322 0.602426 +VERTEX_SE3:QUAT 1418 120.279 72.7179 101.384 -0.10111 -0.641004 -0.330391 0.68537 +VERTEX_SE3:QUAT 1419 127.331 81.5321 103.673 0.0674908 -0.606037 -0.163391 0.775543 +VERTEX_SE3:QUAT 1420 129.23 92.7658 106.225 0.0923412 -0.595343 -0.0166131 0.797975 +VERTEX_SE3:QUAT 1421 128.145 104.528 107.356 0.0348365 -0.599471 0.0657001 0.796935 +VERTEX_SE3:QUAT 1422 126.633 116.192 106.21 -0.00836247 -0.675442 0.0298416 0.736761 +VERTEX_SE3:QUAT 1423 126.081 127.367 105.181 -0.0460774 -0.770798 -0.0440967 0.633879 +VERTEX_SE3:QUAT 1424 127.911 138.482 104.442 -0.249633 -0.699884 0.0766195 0.664812 +VERTEX_SE3:QUAT 1425 130.529 147.92 99.0191 -0.322458 -0.797053 0.0679123 0.506078 +VERTEX_SE3:QUAT 1426 135.775 156.877 93.4127 -0.48266 -0.750299 0.0218739 0.451235 +VERTEX_SE3:QUAT 1427 144.223 162.087 87.5922 -0.487949 -0.791153 0.0582478 0.364128 +VERTEX_SE3:QUAT 1428 153.192 167.557 82.2086 -0.539716 -0.725084 0.0888405 0.418409 +VERTEX_SE3:QUAT 1429 161.546 171.365 75.56 -0.49721 -0.728065 0.010729 0.471792 +VERTEX_SE3:QUAT 1430 169.843 176.531 69.4292 -0.462653 -0.498425 0.212063 0.701822 +VERTEX_SE3:QUAT 1431 171.588 181.369 58.9467 -0.579885 -0.426142 0.381284 0.58031 +VERTEX_SE3:QUAT 1432 171.919 181.016 47.0106 -0.651494 -0.324325 0.286659 0.623054 +VERTEX_SE3:QUAT 1433 172.15 180.206 35.4465 -0.60394 -0.494384 0.360529 0.510744 +VERTEX_SE3:QUAT 1434 175.08 179.814 24.1501 -0.622985 -0.512367 0.439471 0.395266 +VERTEX_SE3:QUAT 1435 178.816 177.004 13.8116 -0.663283 -0.448986 0.465977 0.375942 +VERTEX_SE3:QUAT 1436 181.468 172.731 3.79777 -0.674914 -0.523317 0.454258 0.253535 +VERTEX_SE3:QUAT 1437 186.668 168.313 -4.83365 -0.657571 -0.414292 0.626808 0.0554557 +VERTEX_SE3:QUAT 1438 192.377 160.582 -11.3196 -0.743612 -0.351475 0.565864 0.0574766 +VERTEX_SE3:QUAT 1439 197.635 151.646 -16.0967 0.639557 0.239434 -0.724969 0.0897613 +VERTEX_SE3:QUAT 1440 202.641 141.683 -18.1102 0.756877 0.226128 -0.609407 0.0680201 +VERTEX_SE3:QUAT 1441 207.282 131.229 -19.3821 0.775798 0.071508 -0.623203 0.0681331 +VERTEX_SE3:QUAT 1442 209.451 120.419 -18.3205 0.69724 0.155912 -0.680137 0.164197 +VERTEX_SE3:QUAT 1443 214.453 110.226 -17.6819 0.492726 -0.00889488 -0.869504 0.0332419 +VERTEX_SE3:QUAT 1444 215.832 99.045 -16.577 0.558823 -0.0564538 -0.824447 0.0694055 +VERTEX_SE3:QUAT 1445 216.731 88.0322 -13.9095 0.555871 -0.25903 -0.769698 0.177413 +VERTEX_SE3:QUAT 1446 216.776 79.4528 -6.50455 0.570919 -0.292516 -0.743603 0.18852 +VERTEX_SE3:QUAT 1447 216.612 71.4006 1.60296 0.460141 -0.405338 -0.708772 0.348732 +VERTEX_SE3:QUAT 1448 218.034 67.1402 11.9825 0.338665 -0.592944 -0.604047 0.410915 +VERTEX_SE3:QUAT 1449 219.733 68.2904 22.9825 0.321133 -0.428701 -0.75261 0.382971 +VERTEX_SE3:QUAT 1450 223.429 65.0949 33.7543 0.296817 -0.330622 -0.703977 0.554081 +VERTEX_SE3:QUAT 1451 230.325 63.9179 42.6204 0.337723 -0.363399 -0.57251 0.652776 +VERTEX_SE3:QUAT 1452 235.94 66.3971 52.2188 0.318399 -0.280718 -0.64969 0.630652 +VERTEX_SE3:QUAT 1453 243.139 66.7223 60.6972 0.203234 -0.320373 -0.464259 0.800326 +VERTEX_SE3:QUAT 1454 249.601 73.0971 67.3002 0.204016 -0.345565 -0.533867 0.744277 +VERTEX_SE3:QUAT 1455 257.233 77.7163 74.4542 0.144008 -0.488643 -0.518376 0.686859 +VERTEX_SE3:QUAT 1456 263.822 82.8795 81.6896 -0.0148694 -0.610721 -0.233944 0.756352 +VERTEX_SE3:QUAT 1457 268.148 93.1081 83.9084 0.0521952 -0.636453 -0.320737 0.699522 +VERTEX_SE3:QUAT 1458 272.694 102.559 88.5221 -0.124787 -0.687067 -0.386598 0.602419 +VERTEX_SE3:QUAT 1459 280.054 110.034 91.8252 -0.17666 -0.596159 -0.243994 0.744213 +VERTEX_SE3:QUAT 1460 286.592 119.077 91.6721 -0.229983 -0.561592 -0.178393 0.774531 +VERTEX_SE3:QUAT 1461 292.51 128.522 88.9942 -0.368847 -0.543907 -0.328655 0.678309 +VERTEX_SE3:QUAT 1462 301.977 134.209 86.7372 -0.419035 -0.621003 -0.298976 0.591083 +VERTEX_SE3:QUAT 1463 311.833 139.584 84.6295 -0.516917 -0.70011 -0.131383 0.474742 +VERTEX_SE3:QUAT 1464 321.626 143.841 80.661 -0.539298 -0.646463 -0.203071 0.500005 +VERTEX_SE3:QUAT 1465 331.878 147.08 76.7126 -0.477267 -0.644655 -0.271441 0.531936 +VERTEX_SE3:QUAT 1466 341.81 150.79 73.9955 -0.49417 -0.699431 -0.295579 0.42335 +VERTEX_SE3:QUAT 1467 352.61 153.934 73.2785 -0.571632 -0.67042 -0.32906 0.339842 +VERTEX_SE3:QUAT 1468 363.903 154.903 73.4265 -0.414257 -0.683647 -0.392331 0.455076 +VERTEX_SE3:QUAT 1469 374.808 158.727 74.712 -0.54726 -0.569466 -0.354998 0.500191 +VERTEX_SE3:QUAT 1470 385.925 160.31 72.6013 -0.401163 -0.587762 -0.349034 0.609738 +VERTEX_SE3:QUAT 1471 395.657 165.109 70.732 -0.429306 -0.476458 -0.410443 0.648245 +VERTEX_SE3:QUAT 1472 406.187 168.443 67.823 -0.475129 -0.318858 -0.505421 0.645858 +VERTEX_SE3:QUAT 1473 415.901 168.698 63.6165 -0.375234 -0.301559 -0.496123 0.722581 +VERTEX_SE3:QUAT 1474 426.068 171.542 60.2638 -0.255637 -0.178669 -0.468739 0.826445 +VERTEX_SE3:QUAT 1475 435.572 176.636 57.1478 -0.244089 -0.255402 -0.380163 0.854791 +VERTEX_SE3:QUAT 1476 443.381 183.357 54.2795 -0.0414261 -0.276479 -0.286671 0.916331 +VERTEX_SE3:QUAT 1477 449.101 193.048 54.4905 -0.0777502 -0.166473 -0.150715 0.971353 +VERTEX_SE3:QUAT 1478 452.164 203.634 53.0672 -0.189392 -0.0580608 -0.0372609 0.979475 +VERTEX_SE3:QUAT 1479 452.387 213.504 48.8619 -0.144146 0.0678902 -0.0662964 0.984996 +VERTEX_SE3:QUAT 1480 452.904 224.01 45.3125 0.00500851 -0.0476726 0.0566503 0.997243 +VERTEX_SE3:QUAT 1481 450.703 234.804 45.1418 0.0262783 -0.147661 -0.0541422 0.987205 +VERTEX_SE3:QUAT 1482 451.307 246.041 45.5288 0.0421862 -0.132195 0.0350682 0.989705 +VERTEX_SE3:QUAT 1483 449.756 257.217 46.1521 -0.00207939 -0.137872 0.153805 0.978433 +VERTEX_SE3:QUAT 1484 445.495 267.887 45.4552 0.0367285 0.00691638 0.187445 0.981564 +VERTEX_SE3:QUAT 1485 440.776 277.681 45.8688 0.0835002 -0.0513371 0.215849 0.971495 +VERTEX_SE3:QUAT 1486 435.38 287.768 47.1459 0.156629 -0.049282 0.245081 0.955497 +VERTEX_SE3:QUAT 1487 429.106 296.807 49.8268 0.231254 0.131359 0.131827 0.954928 +VERTEX_SE3:QUAT 1488 426.23 306.333 55.085 0.318284 0.221261 0.223524 0.894302 +VERTEX_SE3:QUAT 1489 423.004 313.89 62.554 0.334165 0.195202 0.422589 0.819541 +VERTEX_SE3:QUAT 1490 415.924 317.724 70.2432 0.184125 0.103359 0.453189 0.866045 +VERTEX_SE3:QUAT 1491 407.56 322.892 74.5747 0.119075 0.142415 0.46188 0.867298 +VERTEX_SE3:QUAT 1492 398.579 328.469 78.3135 0.0587382 0.139383 0.440638 0.88485 +VERTEX_SE3:QUAT 1493 389.716 334.233 80.863 -0.0670632 0.234008 0.608413 0.755365 +VERTEX_SE3:QUAT 1494 379.442 336.409 82.9204 -0.0542355 0.0925888 0.677992 0.727195 +VERTEX_SE3:QUAT 1495 368.682 336.529 83.296 0.0216249 0.0839978 0.68357 0.724713 +VERTEX_SE3:QUAT 1496 357.827 336.25 84.6988 0.0461432 0.0661645 0.870169 0.486106 +VERTEX_SE3:QUAT 1497 349.156 329.693 86.0794 0.00675014 0.0846911 0.867996 0.48925 +VERTEX_SE3:QUAT 1498 340.229 323.689 87.6292 -0.00762259 0.0913432 0.877268 0.471168 +VERTEX_SE3:QUAT 1499 331.705 317.205 89.3766 0.00438572 -0.0703402 0.977816 0.197253 +VERTEX_SE3:QUAT 1500 328.304 306.922 87.6676 -0.192847 0.00602747 0.980261 0.0431437 +VERTEX_SE3:QUAT 1501 328.155 296.396 88.0497 0.23435 0.0940659 -0.966457 0.046827 +VERTEX_SE3:QUAT 1502 330.195 285.741 86.5755 0.313332 0.165657 -0.867845 0.348174 +VERTEX_SE3:QUAT 1503 338.529 278.225 85.9744 0.210209 0.124204 -0.900717 0.359297 +VERTEX_SE3:QUAT 1504 347.087 271.163 85.3053 0.191903 0.197442 -0.76474 0.582548 +VERTEX_SE3:QUAT 1505 358.006 269.229 84.6038 0.375907 0.0695602 -0.718461 0.581093 +VERTEX_SE3:QUAT 1506 367.728 266.864 88.484 0.37535 0.158313 -0.746221 0.526501 +VERTEX_SE3:QUAT 1507 377.728 263.264 90.6598 0.154725 0.187327 -0.759453 0.60349 +VERTEX_SE3:QUAT 1508 388.358 261.852 89.8206 0.341007 0.287892 -0.697933 0.560109 +VERTEX_SE3:QUAT 1509 399.093 260.003 90.3906 0.509601 0.269452 -0.620732 0.531408 +VERTEX_SE3:QUAT 1510 410.108 257.884 93.0647 0.561417 0.17309 -0.642126 0.492468 +VERTEX_SE3:QUAT 1511 418.977 253.395 97.1581 0.534328 0.289509 -0.597204 0.523475 +VERTEX_SE3:QUAT 1512 429.428 250.777 99.7229 0.748173 0.16335 -0.493674 0.412115 +VERTEX_SE3:QUAT 1513 436.349 244.543 105.095 0.734977 0.154142 -0.470081 0.463759 +VERTEX_SE3:QUAT 1514 443.349 238.94 111.441 0.813047 0.101642 -0.350187 0.453863 +VERTEX_SE3:QUAT 1515 448.045 232.983 119.385 0.883001 -0.0165922 -0.138797 0.448073 +VERTEX_SE3:QUAT 1516 448.292 226.613 128.08 0.834418 -0.0526116 -0.264204 0.480806 +VERTEX_SE3:QUAT 1517 449.392 221.163 137.318 0.827886 -0.24452 -0.256542 0.434742 +VERTEX_SE3:QUAT 1518 446.824 216.325 146.861 0.795487 -0.469983 -0.228122 0.307047 +VERTEX_SE3:QUAT 1519 440.023 213.162 154.625 0.793828 -0.477008 -0.293832 0.236567 +VERTEX_SE3:QUAT 1520 432.883 208.478 162.124 0.748748 -0.475014 -0.297365 0.353994 +VERTEX_SE3:QUAT 1521 427.258 205.942 171.333 0.767187 -0.457994 -0.386758 0.228221 +VERTEX_SE3:QUAT 1522 421.458 201.693 179.109 0.722552 -0.349016 -0.549919 0.231722 +VERTEX_SE3:QUAT 1523 418.835 195.262 187.4 0.633833 -0.420442 -0.589689 0.271571 +VERTEX_SE3:QUAT 1524 416.927 190.333 196.91 0.633999 -0.440835 -0.567892 0.28497 +VERTEX_SE3:QUAT 1525 414.696 186.148 206.458 0.650684 -0.387611 -0.558621 0.3381 +VERTEX_SE3:QUAT 1526 413.55 181.537 216.005 0.58318 -0.45807 -0.490232 0.45798 +VERTEX_SE3:QUAT 1527 412.764 180.763 226.721 0.510037 -0.502167 -0.492833 0.494777 +VERTEX_SE3:QUAT 1528 412.498 181.694 237.622 0.381003 -0.516114 -0.468064 0.607765 +VERTEX_SE3:QUAT 1529 414.291 185.665 247.735 0.398079 -0.551514 -0.495897 0.539862 +VERTEX_SE3:QUAT 1530 415.406 188.196 257.611 0.406922 -0.560212 -0.518364 0.501871 +VERTEX_SE3:QUAT 1531 416.17 190.434 268.108 0.333664 -0.709634 -0.434594 0.442963 +VERTEX_SE3:QUAT 1532 415.814 195.319 277.554 0.397162 -0.632721 -0.355207 0.56192 +VERTEX_SE3:QUAT 1533 414.761 200.701 286.827 0.197377 -0.507794 -0.524667 0.65415 +VERTEX_SE3:QUAT 1534 419.91 205.556 295.086 0.221139 -0.430266 -0.417958 0.768947 +VERTEX_SE3:QUAT 1535 424.678 212.409 302.284 0.148 -0.565167 -0.342056 0.735989 +VERTEX_SE3:QUAT 1536 428.432 220.657 308.294 0.0290832 -0.497789 -0.312898 0.808366 +VERTEX_SE3:QUAT 1537 433.208 229.502 311.373 -0.0191723 -0.61818 -0.206876 0.758082 +VERTEX_SE3:QUAT 1538 436.674 239.407 313.389 -0.046291 -0.563972 -0.121711 0.815462 +VERTEX_SE3:QUAT 1539 438.752 249.526 313.311 0.0397009 -0.589748 -0.123488 0.797102 +VERTEX_SE3:QUAT 1540 440.574 260.315 314.844 0.0562779 -0.573985 0.0225709 0.816618 +VERTEX_SE3:QUAT 1541 439.358 270.971 315.019 -0.0637966 -0.517544 0.112229 0.845862 +VERTEX_SE3:QUAT 1542 438.046 281.118 312.213 -0.0403883 -0.399197 0.23809 0.884491 +VERTEX_SE3:QUAT 1543 433.691 290.245 308.922 -0.0492366 -0.458588 0.222969 0.858812 +VERTEX_SE3:QUAT 1544 429.737 299.605 305.179 -0.0897631 -0.437406 0.14049 0.883675 +VERTEX_SE3:QUAT 1545 427.243 309.339 301.519 -0.15696 -0.424917 0.134524 0.881313 +VERTEX_SE3:QUAT 1546 426.152 318.863 297.072 -0.163874 -0.173712 0.241339 0.940598 +VERTEX_SE3:QUAT 1547 421.14 327.101 292.614 -0.114572 -0.23101 0.306594 0.916246 +VERTEX_SE3:QUAT 1548 415.618 334.782 288.53 -0.0775396 -0.236098 0.394243 0.88477 +VERTEX_SE3:QUAT 1549 408.28 341.461 285.072 0.0564007 -0.344774 0.372457 0.859783 +VERTEX_SE3:QUAT 1550 400.994 348.474 282.48 0.042868 -0.201345 0.486024 0.849355 +VERTEX_SE3:QUAT 1551 391.668 353.345 280.777 -0.231363 -0.183166 0.451896 0.84185 +VERTEX_SE3:QUAT 1552 384.218 357.58 274.638 -0.10497 -0.246916 0.552266 0.789314 +VERTEX_SE3:QUAT 1553 374.964 361.174 269.506 -0.0967975 -0.128958 0.438386 0.884205 +VERTEX_SE3:QUAT 1554 366.781 366.888 266.06 -0.105656 -0.218927 0.586694 0.772462 +VERTEX_SE3:QUAT 1555 357.367 369.303 261.5 -0.110226 -0.0260829 0.736432 0.666961 +VERTEX_SE3:QUAT 1556 347.321 367.651 259.737 -0.200703 -0.06464 0.880755 0.424041 +VERTEX_SE3:QUAT 1557 340.144 360.54 256.9 -0.0597404 -0.0466857 0.866519 0.493352 +VERTEX_SE3:QUAT 1558 331.638 354.569 255.448 -0.152531 -0.052718 0.847787 0.505185 +VERTEX_SE3:QUAT 1559 323.641 348.555 252.896 -0.205993 -0.00828457 0.875273 0.437487 +VERTEX_SE3:QUAT 1560 315.786 341.612 250.981 -0.295646 0.0101067 0.900332 0.319208 +VERTEX_SE3:QUAT 1561 309.923 333.059 249.761 -0.363086 -0.00629473 0.781284 0.507666 +VERTEX_SE3:QUAT 1562 301.97 327.28 246.546 -0.399716 -0.0696665 0.822197 0.399207 +VERTEX_SE3:QUAT 1563 296.661 319.566 242.504 -0.403466 -0.102551 0.861443 0.290884 +VERTEX_SE3:QUAT 1564 292.628 310.823 238.682 -0.488728 -0.0216047 0.860096 0.144612 +VERTEX_SE3:QUAT 1565 290.769 301.057 237.448 0.477586 -0.085679 -0.874026 0.02547 +VERTEX_SE3:QUAT 1566 290.752 291.063 239.918 0.404364 -0.151685 -0.893117 0.125791 +VERTEX_SE3:QUAT 1567 292.415 281.426 243.907 0.284719 -0.130815 -0.940365 0.132426 +VERTEX_SE3:QUAT 1568 295.072 272.09 247.733 0.211459 -0.159558 -0.94615 0.186082 +VERTEX_SE3:QUAT 1569 298.756 263.131 251.987 0.346356 -0.10915 -0.920785 0.142401 +VERTEX_SE3:QUAT 1570 300.81 253.595 255.493 0.209933 -0.115722 -0.966574 0.0909477 +VERTEX_SE3:QUAT 1571 302.845 244.083 258.176 0.182996 -0.159026 -0.951194 0.190929 +VERTEX_SE3:QUAT 1572 306.696 234.943 262.211 0.340833 -0.0939847 -0.866932 0.351324 +VERTEX_SE3:QUAT 1573 312.728 227.867 266.608 0.424405 -0.128029 -0.793769 0.416438 +VERTEX_SE3:QUAT 1574 318.91 222.145 273.07 0.43912 -0.0595313 -0.694161 0.567247 +VERTEX_SE3:QUAT 1575 326.619 219.443 279.473 0.419641 -0.0981086 -0.611368 0.663706 +VERTEX_SE3:QUAT 1576 334.253 218.889 286.633 0.409463 -0.119254 -0.548121 0.719501 +VERTEX_SE3:QUAT 1577 340.685 220.355 294.244 0.39854 -0.261005 -0.421617 0.771545 +VERTEX_SE3:QUAT 1578 344.74 224.417 302.785 0.45007 -0.212106 -0.385976 0.776834 +VERTEX_SE3:QUAT 1579 348.702 228.043 311.736 0.462248 -0.329086 -0.314554 0.760976 +VERTEX_SE3:QUAT 1580 350.22 232.47 320.665 0.480831 -0.234469 -0.134949 0.834035 +VERTEX_SE3:QUAT 1581 349.499 238.397 329.364 0.470781 -0.242913 0.128157 0.838412 +VERTEX_SE3:QUAT 1582 344.335 243.703 336.503 0.314583 -0.184289 0.264748 0.892739 +VERTEX_SE3:QUAT 1583 337.923 250.63 340.89 0.34671 -0.270753 0.242719 0.864623 +VERTEX_SE3:QUAT 1584 331.116 257.269 345.035 0.277415 -0.325527 0.317483 0.846332 +VERTEX_SE3:QUAT 1585 323.257 263.746 346.942 0.201664 -0.265084 0.342532 0.878484 +VERTEX_SE3:QUAT 1586 315.836 270.649 348.144 0.150023 -0.26798 0.466103 0.829715 +VERTEX_SE3:QUAT 1587 306.553 275.609 347.488 0.0292029 -0.31523 0.382979 0.867816 +VERTEX_SE3:QUAT 1588 299.218 282.365 345.043 0.0780189 -0.364222 0.454516 0.809117 +VERTEX_SE3:QUAT 1589 291.335 287.917 342.311 -0.0323242 -0.365994 0.439455 0.819685 +VERTEX_SE3:QUAT 1590 284.198 293.674 338.378 -0.145039 -0.288218 0.581762 0.746624 +VERTEX_SE3:QUAT 1591 276.48 295.641 332.217 -0.110793 -0.28949 0.713831 0.627985 +VERTEX_SE3:QUAT 1592 268.311 294.175 326.124 -0.152814 -0.212333 0.82151 0.50664 +VERTEX_SE3:QUAT 1593 260.655 289.786 320.911 -0.358799 -0.179807 0.757409 0.515038 +VERTEX_SE3:QUAT 1594 254.289 284.949 314.571 -0.445127 -0.19381 0.829671 0.275583 +VERTEX_SE3:QUAT 1595 251.678 276.494 309.09 -0.324092 -0.0099342 0.892002 0.314958 +VERTEX_SE3:QUAT 1596 246.498 268.074 307.004 -0.292622 0.0816569 0.875374 0.376065 +VERTEX_SE3:QUAT 1597 239.552 260.342 306.036 -0.249817 0.0869076 0.963961 0.0286004 +VERTEX_SE3:QUAT 1598 238.951 250.514 308.041 -0.0288706 -0.0819347 -0.993301 0.0762005 +VERTEX_SE3:QUAT 1599 241.193 240.898 309.595 -0.0666654 -0.124292 -0.973554 0.179721 +VERTEX_SE3:QUAT 1600 245.632 232.221 311.968 -0.0200459 -0.240619 -0.945671 0.217734 +VERTEX_SE3:QUAT 1601 250.412 224.624 316.602 0.100785 -0.0487155 -0.910657 0.39771 +VERTEX_SE3:QUAT 1602 258.206 218.257 317.77 0.0762142 -0.0364975 -0.837648 0.539635 +VERTEX_SE3:QUAT 1603 267.552 214.662 319.165 0.106344 -0.0723715 -0.676046 0.725545 +VERTEX_SE3:QUAT 1604 277.171 216.217 321.969 0.162961 -0.205486 -0.526689 0.80859 +VERTEX_SE3:QUAT 1605 284.732 220.743 326.357 0.154845 -0.238944 -0.4955 0.820615 +VERTEX_SE3:QUAT 1606 292.114 226.234 330.894 0.17124 -0.121454 -0.427098 0.879496 +VERTEX_SE3:QUAT 1607 298.726 232.922 335.019 0.2142 -0.0908791 -0.400144 0.886422 +VERTEX_SE3:QUAT 1608 304.946 239.396 339.49 0.252209 -0.156795 -0.259108 0.919059 +VERTEX_SE3:QUAT 1609 308.236 247.426 344.706 0.210264 0.0149488 -0.309741 0.92716 +VERTEX_SE3:QUAT 1610 313.286 255.17 348.645 0.0975814 0.0880305 -0.299145 0.945114 +VERTEX_SE3:QUAT 1611 318.682 263.738 350.206 0.136788 -0.0457001 -0.053949 0.988074 +VERTEX_SE3:QUAT 1612 318.814 273.377 352.67 0.235529 -0.0727441 0.115894 0.962187 +VERTEX_SE3:QUAT 1613 315.197 281.672 356.496 0.304768 -0.0214456 0.276202 0.911246 +VERTEX_SE3:QUAT 1614 309.261 287.963 361.467 0.384263 -0.161916 0.314904 0.85262 +VERTEX_SE3:QUAT 1615 301.752 293.075 366.615 0.458822 -0.207737 0.439099 0.743989 +VERTEX_SE3:QUAT 1616 292.832 294.981 371.004 0.490367 -0.231454 0.439826 0.715907 +VERTEX_SE3:QUAT 1617 283.865 295.937 375.04 0.449907 -0.172159 0.428848 0.764222 +VERTEX_SE3:QUAT 1618 275.366 297.783 379.971 0.425663 -0.0607078 0.466647 0.772895 +VERTEX_SE3:QUAT 1619 267.5 299.782 385.348 0.226784 -0.0997186 0.556491 0.79306 +VERTEX_SE3:QUAT 1620 258.122 301.948 387.435 0.299279 -0.131075 0.620951 0.71251 +VERTEX_SE3:QUAT 1621 248.92 301.809 389.469 0.139598 0.0191227 0.539125 0.830356 +VERTEX_SE3:QUAT 1622 239.886 304.901 391.383 0.13958 -0.0275492 0.648949 0.747411 +VERTEX_SE3:QUAT 1623 229.833 305.378 392.826 0.145086 -0.163001 0.70649 0.67324 +VERTEX_SE3:QUAT 1624 220.023 304.375 391.982 0.0908819 -0.0973899 0.765995 0.628894 +VERTEX_SE3:QUAT 1625 210.317 301.822 391.536 0.0301128 -0.0848017 0.75596 0.648402 +VERTEX_SE3:QUAT 1626 200.314 299.54 390.485 0.238415 -0.0557726 0.840528 0.483281 +VERTEX_SE3:QUAT 1627 191.989 293.337 391.153 0.144329 0.0124671 0.877525 0.457125 +VERTEX_SE3:QUAT 1628 184.361 287.016 392.266 0.15056 0.0153814 0.895366 0.418825 +VERTEX_SE3:QUAT 1629 177.413 280.114 393.759 0.244481 0.00356797 0.847314 0.47146 +VERTEX_SE3:QUAT 1630 169.917 273.855 396.028 0.107519 -0.116831 0.864124 0.477578 +VERTEX_SE3:QUAT 1631 161.666 268.54 394.431 0.0241256 -0.169942 0.867103 0.467623 +VERTEX_SE3:QUAT 1632 154.215 263.515 391.551 0.0268763 -0.225582 0.819858 0.525569 +VERTEX_SE3:QUAT 1633 145.872 259.544 387.747 -0.0613041 -0.314649 0.708399 0.628816 +VERTEX_SE3:QUAT 1634 137.843 258.875 382.181 -0.196585 -0.302091 0.730568 0.57997 +VERTEX_SE3:QUAT 1635 130.667 256.83 376.016 -0.107853 -0.192845 0.841544 0.492933 +VERTEX_SE3:QUAT 1636 123.563 251.846 371.695 -0.132319 -0.182652 0.869276 0.439874 +VERTEX_SE3:QUAT 1637 116.991 245.765 367.67 -0.179382 -0.13078 0.9193 0.324969 +VERTEX_SE3:QUAT 1638 112.123 237.859 364.218 -0.215602 -0.0733629 0.931529 0.283525 +VERTEX_SE3:QUAT 1639 107.895 229.554 361.963 -0.161859 0.0284871 0.958785 0.23178 +VERTEX_SE3:QUAT 1640 103.913 220.464 361.808 -0.33503 0.0320444 0.93921 0.0679173 +VERTEX_SE3:QUAT 1641 102.822 210.913 362.28 -0.39294 0.0380743 0.918347 0.0280444 +VERTEX_SE3:QUAT 1642 102.479 201.279 363.01 0.413563 -0.133379 -0.898705 0.0592049 +VERTEX_SE3:QUAT 1643 103.203 192.115 366.459 0.507523 -0.277351 -0.768638 0.2733 +VERTEX_SE3:QUAT 1644 104.444 185.79 373.847 0.380546 -0.244693 -0.839182 0.301801 +VERTEX_SE3:QUAT 1645 108.268 179.533 379.956 0.334652 -0.382729 -0.800587 0.317155 +VERTEX_SE3:QUAT 1646 111.297 175.105 387.805 0.362932 -0.415714 -0.804355 0.22017 +VERTEX_SE3:QUAT 1647 112.743 170.064 396.38 0.253435 -0.557149 -0.759073 0.221728 +VERTEX_SE3:QUAT 1648 114.097 167.665 405.859 0.289668 -0.493862 -0.752287 0.32597 +VERTEX_SE3:QUAT 1649 116.451 165.219 415.004 0.397781 -0.464151 -0.669477 0.422059 +VERTEX_SE3:QUAT 1650 118.736 163.817 424.014 0.301081 -0.565655 -0.545092 0.54061 +VERTEX_SE3:QUAT 1651 121.317 166.768 432.975 0.0978911 -0.631029 -0.424552 0.641853 +VERTEX_SE3:QUAT 1652 125.556 172.821 438.988 0.0829205 -0.555954 -0.513171 0.64861 +VERTEX_SE3:QUAT 1653 131.114 177.934 445.228 0.245007 -0.615781 -0.400633 0.632675 +VERTEX_SE3:QUAT 1654 132.78 183.937 452.739 0.147176 -0.721077 -0.243775 0.631634 +VERTEX_SE3:QUAT 1655 133.562 192.059 457.512 0.0205571 -0.734067 -0.33151 0.592305 +VERTEX_SE3:QUAT 1656 137.495 199.917 461.821 0.076473 -0.695786 -0.108409 0.70589 +VERTEX_SE3:QUAT 1657 137.833 208.701 463.54 -0.184536 -0.736256 -0.177333 0.626439 +VERTEX_SE3:QUAT 1658 142.567 216.983 463.319 -0.216077 -0.633477 -0.380925 0.637898 +VERTEX_SE3:QUAT 1659 149.61 222.938 464.544 -0.0585104 -0.517579 -0.4582 0.720237 +VERTEX_SE3:QUAT 1660 156.388 229.088 467.686 -0.0672769 -0.435659 -0.431735 0.786943 +VERTEX_SE3:QUAT 1661 163.081 235.638 469.88 -0.0853985 -0.406074 -0.424769 0.804601 +VERTEX_SE3:QUAT 1662 170.178 241.869 471.315 -0.185007 -0.278499 -0.191968 0.922691 +VERTEX_SE3:QUAT 1663 174.018 250.046 468.979 -0.158993 -0.315048 -0.00624968 0.935643 +VERTEX_SE3:QUAT 1664 174.712 259.135 465.907 -0.172672 -0.361337 0.0347172 0.91565 +VERTEX_SE3:QUAT 1665 174.749 267.732 462.219 0.0381972 -0.242925 0.313652 0.917143 +VERTEX_SE3:QUAT 1666 168.568 274.873 461.137 0.147539 -0.0936019 0.438606 0.88153 +VERTEX_SE3:QUAT 1667 160.472 279.463 462.428 0.058368 -0.0325974 0.289068 0.954971 +VERTEX_SE3:QUAT 1668 154.72 287.24 462.909 0.0486131 -0.0975596 0.512347 0.851833 +VERTEX_SE3:QUAT 1669 145.958 291.023 462.525 0.124668 -0.147326 0.522772 0.830339 +VERTEX_SE3:QUAT 1670 137.186 294.802 462.557 0.163726 -0.0854355 0.549016 0.815154 +VERTEX_SE3:QUAT 1671 128.275 297.139 463.938 0.0105403 -0.206127 0.573016 0.793129 +VERTEX_SE3:QUAT 1672 119.317 300.444 461.178 0.0145465 -0.216557 0.542536 0.811509 +VERTEX_SE3:QUAT 1673 110.904 304.009 458.776 -0.12404 -0.217475 0.695367 0.673635 +VERTEX_SE3:QUAT 1674 102.581 303.148 454.165 -0.199666 -0.285213 0.66131 0.664421 +VERTEX_SE3:QUAT 1675 95.4877 303.11 448.166 -0.355406 -0.382103 0.542365 0.658426 +VERTEX_SE3:QUAT 1676 91.4276 303.833 439.678 -0.353031 -0.158127 0.63537 0.668334 +VERTEX_SE3:QUAT 1677 84.7944 302.529 433.164 -0.335421 -0.150067 0.671723 0.643242 +VERTEX_SE3:QUAT 1678 77.4147 300.742 427.347 -0.269994 -0.00582331 0.717182 0.642432 +VERTEX_SE3:QUAT 1679 68.9821 298.308 423.864 -0.246944 0.0854575 0.71608 0.64726 +VERTEX_SE3:QUAT 1680 60.3006 296.023 422.041 -0.24142 0.165691 0.628366 0.720707 +VERTEX_SE3:QUAT 1681 51.0143 296.003 420.822 -0.16816 0.183622 0.675028 0.694509 +VERTEX_SE3:QUAT 1682 41.633 295.773 421.449 -0.0598763 -0.0490033 0.719952 0.689697 +VERTEX_SE3:QUAT 1683 32.6642 294.631 419.904 0.00108701 -0.0660488 0.672498 0.737145 +VERTEX_SE3:QUAT 1684 23.3573 294.778 418.95 -0.0671255 -0.107836 0.7521 0.646693 +VERTEX_SE3:QUAT 1685 14.288 293.013 416.868 -0.0666769 -0.108895 0.683323 0.718864 +VERTEX_SE3:QUAT 1686 5.17562 293.064 414.514 -0.0178539 -0.15625 0.739733 0.654264 +VERTEX_SE3:QUAT 1687 -3.68148 291.259 411.925 -0.0739677 -0.243868 0.700139 0.666981 +VERTEX_SE3:QUAT 1688 -11.9184 290.4 408.151 0.0237551 -0.154417 0.860982 0.484047 +VERTEX_SE3:QUAT 1689 -19.5282 285.218 405.407 0.148813 -0.306354 0.833775 0.434535 +VERTEX_SE3:QUAT 1690 -26.6445 280.587 401.397 -0.116648 -0.415863 0.798233 0.419852 +VERTEX_SE3:QUAT 1691 -31.397 277.324 393.908 -0.152725 -0.374948 0.832922 0.377265 +VERTEX_SE3:QUAT 1692 -35.9279 272.788 386.896 -0.117228 -0.2083 0.936133 0.257923 +VERTEX_SE3:QUAT 1693 -38.5956 265.473 383.004 -0.0716591 -0.265588 0.953368 0.12417 +VERTEX_SE3:QUAT 1694 -39.78 257.495 378.142 0.0723875 -0.159957 0.981576 0.0753833 +VERTEX_SE3:QUAT 1695 -40.5427 249.04 375.42 0.187962 -0.228935 0.943553 0.148213 +VERTEX_SE3:QUAT 1696 -43.1147 241.015 371.578 0.249175 -0.215432 0.900017 0.28543 +VERTEX_SE3:QUAT 1697 -48.4843 233.962 368.628 0.307773 -0.229704 0.879465 0.281164 +VERTEX_SE3:QUAT 1698 -53.7572 227.044 365.804 0.309722 -0.302068 0.830001 0.352031 +VERTEX_SE3:QUAT 1699 -60.6071 221.804 362.876 0.277652 -0.235613 0.916992 0.162853 +VERTEX_SE3:QUAT 1700 -63.9113 213.642 359.089 0.112991 -0.0927789 0.967919 0.204345 +VERTEX_SE3:QUAT 1701 -67.0739 205.341 357.484 0.085713 -0.114084 0.983652 0.109851 +VERTEX_SE3:QUAT 1702 -68.748 196.951 355.297 -0.156727 -0.218129 0.961874 0.0515271 +VERTEX_SE3:QUAT 1703 -68.49 188.664 351.335 -0.0369872 0.00985545 -0.977143 0.209111 +VERTEX_SE3:QUAT 1704 -64.2912 180.366 350.76 0.0869452 -0.187004 -0.917834 0.339192 +VERTEX_SE3:QUAT 1705 -58.2165 174.495 354.53 0.0795529 -0.192375 -0.889079 0.407679 +VERTEX_SE3:QUAT 1706 -51.1066 169.601 358.093 -0.0402116 -0.205384 -0.840994 0.498929 +VERTEX_SE3:QUAT 1707 -43.1089 165.894 360.474 -0.12947 -0.100691 -0.826537 0.538456 +VERTEX_SE3:QUAT 1708 -34.6026 162.656 360.606 -0.138885 -0.0774915 -0.795224 0.585086 +VERTEX_SE3:QUAT 1709 -25.8605 160.343 359.385 -0.13425 -0.00568118 -0.694575 0.70676 +VERTEX_SE3:QUAT 1710 -16.8783 161.263 357.469 -0.0342144 -0.0673236 -0.683083 0.726426 +VERTEX_SE3:QUAT 1711 -8.21866 162.37 357.439 -0.0733026 -0.13443 -0.651069 0.743414 +VERTEX_SE3:QUAT 1712 0.484889 164.473 357.723 -0.0972441 -0.161984 -0.679931 0.708518 +VERTEX_SE3:QUAT 1713 9.63498 165.659 358.28 -0.235643 -0.19309 -0.667532 0.679404 +VERTEX_SE3:QUAT 1714 18.6139 166.117 357.368 -0.195162 -0.117061 -0.736809 0.636648 +VERTEX_SE3:QUAT 1715 27.8692 165.393 355.89 -0.261226 -0.121761 -0.593113 0.751767 +VERTEX_SE3:QUAT 1716 36.2819 167.332 353.64 -0.329455 0.00827047 -0.493986 0.804592 +VERTEX_SE3:QUAT 1717 42.8472 170.233 348.345 -0.278074 0.0312938 -0.494967 0.822619 +VERTEX_SE3:QUAT 1718 49.3956 173.964 343.543 -0.329854 0.111263 -0.600016 0.720276 +VERTEX_SE3:QUAT 1719 56.1652 175.007 337.684 -0.32625 0.185566 -0.59452 0.711106 +VERTEX_SE3:QUAT 1720 62.2457 176.345 331.432 -0.174708 0.289433 -0.654738 0.676036 +VERTEX_SE3:QUAT 1721 69.07 177.951 326.096 -0.0756901 0.353012 -0.629757 0.687793 +VERTEX_SE3:QUAT 1722 76.2933 180.321 321.39 -0.00921193 0.326947 -0.648095 0.687745 +VERTEX_SE3:QUAT 1723 84.247 182.562 317.704 0.0436968 0.248554 -0.420624 0.871428 +VERTEX_SE3:QUAT 1724 90.2709 188.724 316.706 0.161809 0.211685 -0.14945 0.952193 +VERTEX_SE3:QUAT 1725 92.5658 196.801 318.774 0.110101 0.329972 -0.0349998 0.936894 +VERTEX_SE3:QUAT 1726 93.1452 205.218 320.928 0.140727 0.130514 -0.0810259 0.978058 +VERTEX_SE3:QUAT 1727 94.1426 213.508 323.113 0.107835 0.275239 0.0192778 0.955114 +VERTEX_SE3:QUAT 1728 93.2941 221.885 325.221 0.128748 0.208071 0.093721 0.965063 +VERTEX_SE3:QUAT 1729 91.2377 230.182 327.909 0.046557 0.383946 0.116912 0.91474 +VERTEX_SE3:QUAT 1730 89.1904 239.052 329.849 0.0154357 0.360801 0.313156 0.878361 +VERTEX_SE3:QUAT 1731 83.9987 246.001 332.421 0.120869 0.287196 0.29791 0.902307 +VERTEX_SE3:QUAT 1732 79.5403 252.686 335.724 0.169119 0.290576 0.359971 0.870279 +VERTEX_SE3:QUAT 1733 74.5113 258.232 340.172 -0.0152172 0.276419 0.490599 0.826241 +VERTEX_SE3:QUAT 1734 67.1716 262.023 342.851 0.0886465 0.396279 0.482578 0.776031 +VERTEX_SE3:QUAT 1735 60.6864 265.971 347.547 0.0647476 0.411739 0.604186 0.679145 +VERTEX_SE3:QUAT 1736 53.8445 267.391 352.91 0.279773 0.277691 0.68686 0.610605 +VERTEX_SE3:QUAT 1737 47.7887 265.8 358.906 0.330078 0.303558 0.731559 0.51354 +VERTEX_SE3:QUAT 1738 42.5302 262.906 365.871 0.508179 0.226499 0.675202 0.484308 +VERTEX_SE3:QUAT 1739 38.8945 258.47 372.763 0.537906 0.0423323 0.745662 0.390964 +VERTEX_SE3:QUAT 1740 34.4836 252.238 376.3 0.586164 -0.0285797 0.732668 0.344664 +VERTEX_SE3:QUAT 1741 29.8037 245.386 378.72 0.403943 -0.236266 0.854178 0.226691 +VERTEX_SE3:QUAT 1742 24.9921 238.268 376.049 0.534115 -0.197842 0.785517 0.241957 +VERTEX_SE3:QUAT 1743 19.9566 231.015 375.105 0.533764 -0.192814 0.763913 0.307173 +VERTEX_SE3:QUAT 1744 14.3563 224.458 374.667 0.40442 -0.0862997 0.826321 0.382349 +VERTEX_SE3:QUAT 1745 8.42823 217.809 375.405 0.361217 -0.112919 0.887515 0.262848 +VERTEX_SE3:QUAT 1746 3.90368 210.59 374.749 0.371931 -0.067011 0.882132 0.281105 +VERTEX_SE3:QUAT 1747 -0.590731 202.93 374.907 0.329753 -0.0185957 0.941561 0.0661872 +VERTEX_SE3:QUAT 1748 -1.52779 194.211 374.416 0.424053 0.0830047 0.899556 0.0639379 +VERTEX_SE3:QUAT 1749 -1.85072 185.959 375.986 -0.427622 -0.00595001 -0.897208 0.110097 +VERTEX_SE3:QUAT 1750 -0.051929 177.815 374.933 -0.484433 0.0104731 -0.864217 0.135438 +VERTEX_SE3:QUAT 1751 2.27431 170.118 372.887 -0.50946 0.12493 -0.757327 0.388972 +VERTEX_SE3:QUAT 1752 6.5037 164.674 367.148 -0.5539 0.307836 -0.716105 0.292616 +VERTEX_SE3:QUAT 1753 7.16546 159.894 360.562 -0.554121 0.194173 -0.73237 0.344792 +VERTEX_SE3:QUAT 1754 9.653 154.375 354.325 -0.635096 0.278908 -0.660426 0.287577 +VERTEX_SE3:QUAT 1755 9.67529 148.959 347.422 -0.67538 0.302878 -0.628893 0.237951 +VERTEX_SE3:QUAT 1756 8.52494 142.989 341.489 -0.610734 0.294088 -0.619728 0.395542 +VERTEX_SE3:QUAT 1757 9.36015 139.332 333.95 -0.718547 0.311689 -0.473104 0.403377 +VERTEX_SE3:QUAT 1758 8.45782 135.553 326.876 -0.682406 0.383401 -0.492907 0.379959 +VERTEX_SE3:QUAT 1759 6.99863 132.715 318.962 -0.551682 0.262369 -0.575426 0.543778 +VERTEX_SE3:QUAT 1760 9.84854 131.006 311.212 -0.479332 0.224284 -0.555012 0.641794 +VERTEX_SE3:QUAT 1761 13.6739 131.04 303.58 -0.429099 0.0747819 -0.662916 0.608954 +VERTEX_SE3:QUAT 1762 19.723 129.553 297.82 -0.557 0.097822 -0.46795 0.67912 +VERTEX_SE3:QUAT 1763 23.9075 130.143 290.513 -0.626979 0.283811 -0.22311 0.690341 +VERTEX_SE3:QUAT 1764 23.0314 131.603 282.324 -0.642851 0.320244 -0.226344 0.657994 +VERTEX_SE3:QUAT 1765 21.8999 132.601 274.345 -0.540453 0.373927 -0.273307 0.702419 +VERTEX_SE3:QUAT 1766 21.2319 135.491 266.208 -0.538888 0.38456 -0.252059 0.705818 +VERTEX_SE3:QUAT 1767 20.3584 138.298 258.262 -0.291528 0.519864 -0.233988 0.768116 +VERTEX_SE3:QUAT 1768 20.3927 145.006 252.817 -0.17002 0.544385 -0.263146 0.778134 +VERTEX_SE3:QUAT 1769 21.96 152.222 248.632 -0.0912096 0.49667 -0.277958 0.817153 +VERTEX_SE3:QUAT 1770 24.7009 159.619 245.606 0.0963979 0.476598 -0.137836 0.862881 +VERTEX_SE3:QUAT 1771 27.0897 167.563 246.463 -0.0216871 0.299985 -0.0942009 0.949034 +VERTEX_SE3:QUAT 1772 27.7331 175.676 245.896 0.0950852 0.260521 -0.0628015 0.95872 +VERTEX_SE3:QUAT 1773 28.3364 183.882 247.503 0.194262 0.3298 -0.0607516 0.921848 +VERTEX_SE3:QUAT 1774 29.7942 191.727 250.413 0.144809 0.388083 -0.23701 0.878777 +VERTEX_SE3:QUAT 1775 33.547 199.12 251.606 0.24957 0.463823 -0.0840029 0.845888 +VERTEX_SE3:QUAT 1776 36.1168 206.121 255.306 0.360209 0.47295 -0.0829114 0.799809 +VERTEX_SE3:QUAT 1777 39.617 212.083 259.837 0.409626 0.531753 -0.137654 0.728352 +VERTEX_SE3:QUAT 1778 44.2756 217.058 264.229 0.567344 0.431788 -0.0307269 0.700525 +VERTEX_SE3:QUAT 1779 48.2246 219.664 271.067 0.6011 0.405399 0.0199976 0.688427 +VERTEX_SE3:QUAT 1780 51.3756 221.814 278.568 0.546576 0.512797 -0.0521681 0.659978 +VERTEX_SE3:QUAT 1781 56.6012 224.576 283.894 0.58352 0.552348 -0.0731524 0.590818 +VERTEX_SE3:QUAT 1782 62.5212 227.028 289.402 0.514694 0.361949 -0.0431701 0.776028 +VERTEX_SE3:QUAT 1783 65.9204 230.947 296.195 0.496946 0.304676 -0.0069749 0.812507 +VERTEX_SE3:QUAT 1784 67.7141 235.273 303.199 0.607565 0.328382 0.0152937 0.723047 +VERTEX_SE3:QUAT 1785 70.4235 237.039 310.475 0.727465 0.23944 0.0907463 0.636576 +VERTEX_SE3:QUAT 1786 71.736 236.146 318.758 0.677949 0.116024 0.0613867 0.723294 +VERTEX_SE3:QUAT 1787 71.665 236.736 326.808 0.606912 0.232482 0.0135015 0.759887 +VERTEX_SE3:QUAT 1788 73.1661 238.957 334.683 0.628347 0.203489 0.220965 0.717598 +VERTEX_SE3:QUAT 1789 72.2328 239.45 342.832 0.663875 0.170494 0.075992 0.724173 +VERTEX_SE3:QUAT 1790 72.563 239.954 350.676 0.701326 0.173206 0.105391 0.683399 +VERTEX_SE3:QUAT 1791 72.8465 239.573 359.581 0.737235 -0.0810644 0.394029 0.542822 +VERTEX_SE3:QUAT 1792 67.9956 236.568 365.376 0.654679 -0.350769 0.499844 0.445548 +VERTEX_SE3:QUAT 1793 60.235 233.609 366.792 0.58161 -0.361384 0.546953 0.481636 +VERTEX_SE3:QUAT 1794 52.5478 231.697 367.301 0.685326 -0.311412 0.562599 0.34181 +VERTEX_SE3:QUAT 1795 46.1033 227.254 367.825 0.618287 -0.395387 0.64723 0.206115 +VERTEX_SE3:QUAT 1796 39.8415 222.728 364.973 0.43628 -0.568277 0.689345 0.107349 +VERTEX_SE3:QUAT 1797 35.0635 220.068 358.974 0.349456 -0.665747 0.659177 0.0121312 +VERTEX_SE3:QUAT 1798 31.8665 219.5 351.955 -0.356857 0.671453 -0.64921 0.0181983 +VERTEX_SE3:QUAT 1799 28.6852 218.632 344.639 -0.313059 0.736643 -0.58529 0.129565 +VERTEX_SE3:QUAT 1800 26.1504 219.844 337.164 -0.270666 0.710785 -0.620695 0.190425 +VERTEX_SE3:QUAT 1801 25.4513 220.784 328.961 -0.171661 0.770539 -0.561949 0.247015 +VERTEX_SE3:QUAT 1802 25.7263 223.598 321.666 -0.148964 0.825274 -0.525257 0.144351 +VERTEX_SE3:QUAT 1803 25.8687 227.194 314.31 0.147121 -0.851293 0.503341 0.0174253 +VERTEX_SE3:QUAT 1804 24.579 230.927 307.309 0.0226396 -0.876662 0.48011 0.0211272 +VERTEX_SE3:QUAT 1805 24.627 235.249 300.575 0.0904621 -0.831243 0.548277 0.0156243 +VERTEX_SE3:QUAT 1806 23.6822 238.63 293.225 -0.0288609 -0.781491 0.597066 0.178745 +VERTEX_SE3:QUAT 1807 23.352 240.938 285.745 -0.114522 -0.69866 0.693585 0.133036 +VERTEX_SE3:QUAT 1808 23.5553 241.031 277.978 -0.0706252 -0.771033 0.631895 0.0350391 +VERTEX_SE3:QUAT 1809 24.6865 242.436 270.053 0.000310667 0.754829 -0.654927 0.0361137 +VERTEX_SE3:QUAT 1810 25.5329 243.481 262.804 0.0812372 0.778907 -0.611887 0.110899 +VERTEX_SE3:QUAT 1811 28.2122 245.213 255.487 0.158723 0.767771 -0.553842 0.280348 +VERTEX_SE3:QUAT 1812 32.8368 248.311 249.761 0.184996 0.73664 -0.572551 0.308744 +VERTEX_SE3:QUAT 1813 38.5495 250.377 244.246 0.258603 0.721465 -0.563855 0.3077 +VERTEX_SE3:QUAT 1814 44.3336 252.513 239.254 0.274246 0.630554 -0.624707 0.370043 +VERTEX_SE3:QUAT 1815 50.9279 252.951 235.31 0.409986 0.62006 -0.570034 0.349997 +VERTEX_SE3:QUAT 1816 58.3631 253.209 232.627 0.358585 0.561166 -0.613095 0.424999 +VERTEX_SE3:QUAT 1817 66.007 253.404 230.117 0.55488 0.420238 -0.583931 0.41777 +VERTEX_SE3:QUAT 1818 73.467 250.565 230.834 0.55494 0.420798 -0.544785 0.467097 +VERTEX_SE3:QUAT 1819 80.8279 249.042 231.586 0.671306 0.329441 -0.479297 0.459446 +VERTEX_SE3:QUAT 1820 87.7608 246.177 234.509 0.664535 0.180512 -0.479604 0.543864 +VERTEX_SE3:QUAT 1821 93.5574 243.853 239.233 0.478576 0.148604 -0.56502 0.655465 +VERTEX_SE3:QUAT 1822 100.077 243.618 242.944 0.370682 0.17195 -0.52828 0.744277 +VERTEX_SE3:QUAT 1823 106.893 245.006 246.196 0.337856 0.206327 -0.392696 0.830103 +VERTEX_SE3:QUAT 1824 112.823 248.88 249.463 0.489567 0.210772 -0.289171 0.79516 +VERTEX_SE3:QUAT 1825 117.357 252.215 254.751 0.611814 0.215279 -0.361744 0.669686 +VERTEX_SE3:QUAT 1826 122.723 252.512 260.365 0.645092 0.0757374 -0.40171 0.645561 +VERTEX_SE3:QUAT 1827 126.953 251.346 266.614 0.806284 0.09093 -0.303059 0.499792 +VERTEX_SE3:QUAT 1828 130.113 247.734 272.515 0.862236 -0.00131353 -0.251445 0.439684 +VERTEX_SE3:QUAT 1829 131.219 243.141 278.633 0.794029 0.12415 -0.446123 0.393801 +VERTEX_SE3:QUAT 1830 135.338 238.127 282.997 0.850177 0.180859 -0.387174 0.307548 +VERTEX_SE3:QUAT 1831 139.263 232.265 286.37 0.901656 0.12977 -0.291502 0.291895 +VERTEX_SE3:QUAT 1832 141.828 226.321 289.85 0.814943 0.212963 -0.288433 0.455325 +VERTEX_SE3:QUAT 1833 146.038 222.376 295.035 0.905477 0.169916 -0.265046 0.28459 +VERTEX_SE3:QUAT 1834 149.54 216.449 298.572 0.928894 0.0617948 -0.196927 0.3075 +VERTEX_SE3:QUAT 1835 150.641 210.356 303.257 0.926172 0.159068 -0.0262869 0.340899 +VERTEX_SE3:QUAT 1836 152.22 204.617 308.255 0.950581 0.0855095 -0.111356 0.276917 +VERTEX_SE3:QUAT 1837 153.023 198.145 312.434 0.891854 0.0656508 -0.234777 0.381006 +VERTEX_SE3:QUAT 1838 154.862 193.134 317.396 0.9308 -0.0312559 -0.266726 0.247975 +VERTEX_SE3:QUAT 1839 154.854 186.674 321.559 0.938518 -0.0983446 -0.277895 0.179687 +VERTEX_SE3:QUAT 1840 153.827 179.885 325.064 0.940351 -0.129913 -0.262404 0.173222 +VERTEX_SE3:QUAT 1841 152.288 173.464 328.156 0.896124 -0.161352 -0.352679 0.215742 +VERTEX_SE3:QUAT 1842 150.813 167.142 332.288 0.843584 -0.142082 -0.477037 0.201532 +VERTEX_SE3:QUAT 1843 150.284 161.271 336.746 0.800027 -0.250538 -0.457696 0.296145 +VERTEX_SE3:QUAT 1844 149 156.509 342.218 0.786515 -0.26201 -0.390702 0.400122 +VERTEX_SE3:QUAT 1845 147.902 152.922 348.884 0.771829 -0.281652 -0.329114 0.465442 +VERTEX_SE3:QUAT 1846 146.762 150.289 355.817 0.730052 -0.340156 -0.212537 0.553304 +VERTEX_SE3:QUAT 1847 144.218 149.435 362.806 0.705643 -0.499697 -0.0770396 0.496422 +VERTEX_SE3:QUAT 1848 139.252 150.201 368.235 0.662156 -0.518505 -0.110656 0.529582 +VERTEX_SE3:QUAT 1849 134.562 151.579 373.592 0.607963 -0.540278 0.0344289 0.580772 +VERTEX_SE3:QUAT 1850 129.131 154.355 377.989 0.449173 -0.649028 0.00395243 0.613995 +VERTEX_SE3:QUAT 1851 124.769 159.478 381.191 0.441419 -0.64197 0.168526 0.603841 +VERTEX_SE3:QUAT 1852 119.198 164.427 382.954 0.399803 -0.732203 0.216259 0.507217 +VERTEX_SE3:QUAT 1853 113.587 168.573 383.137 0.454472 -0.697803 0.244305 0.496831 +VERTEX_SE3:QUAT 1854 107.612 172.445 383.724 0.447439 -0.59852 0.177721 0.640302 +VERTEX_SE3:QUAT 1855 101.823 176.54 386.007 0.344406 -0.680522 0.198659 0.615474 +VERTEX_SE3:QUAT 1856 96.4836 181.508 386.5 0.271127 -0.686424 0.481349 0.47288 +VERTEX_SE3:QUAT 1857 90.8289 184.27 383.15 0.06711 -0.741911 0.500613 0.440966 +VERTEX_SE3:QUAT 1858 87.2741 187.652 378.084 0.163975 -0.725841 0.508132 0.433669 +VERTEX_SE3:QUAT 1859 82.8162 190.665 373.048 -0.00534236 -0.825839 0.495498 0.269151 +VERTEX_SE3:QUAT 1860 81.2188 194.026 366.962 -0.154095 -0.793544 0.51531 0.284602 +VERTEX_SE3:QUAT 1861 81.4973 196.68 359.873 -0.0861797 -0.654664 0.697029 0.279534 +VERTEX_SE3:QUAT 1862 80.2403 196.432 352.746 -0.318168 -0.637139 0.655725 0.250693 +VERTEX_SE3:QUAT 1863 81.1574 195.33 345.852 -0.245359 -0.686728 0.598554 0.331569 +VERTEX_SE3:QUAT 1864 80.7768 196.225 338.462 -0.246864 -0.787533 0.429149 0.366988 +VERTEX_SE3:QUAT 1865 81.7365 199.743 332.172 -0.230872 -0.832514 0.479271 0.154655 +VERTEX_SE3:QUAT 1866 83.7726 202.699 325.951 -0.244965 -0.770627 0.527822 0.259865 +VERTEX_SE3:QUAT 1867 84.8721 204.591 319.166 -0.308374 -0.677517 0.637172 0.199721 +VERTEX_SE3:QUAT 1868 86.252 203.779 312.206 -0.302071 -0.756611 0.567928 0.117266 +VERTEX_SE3:QUAT 1869 88.9354 204.6 305.849 -0.250059 -0.564514 0.768277 0.168954 +VERTEX_SE3:QUAT 1870 89.7192 202.409 299.141 -0.367101 -0.45374 0.810182 0.0544352 +VERTEX_SE3:QUAT 1871 91.9795 198.174 294.052 0.361319 0.385263 -0.847896 0.0457529 +VERTEX_SE3:QUAT 1872 94.8654 193.231 290.033 0.418487 0.170215 -0.890172 0.0590717 +VERTEX_SE3:QUAT 1873 97.0471 186.511 288.93 0.539796 0.279819 -0.77094 0.189664 +VERTEX_SE3:QUAT 1874 101.682 181.178 287.888 0.468758 0.375444 -0.749294 0.279045 +VERTEX_SE3:QUAT 1875 106.85 177.225 286.183 0.478413 0.179274 -0.800918 0.312269 +VERTEX_SE3:QUAT 1876 111.751 172.287 286.572 0.517463 0.19444 -0.698148 0.454988 +VERTEX_SE3:QUAT 1877 117.903 169.3 288.726 0.447672 0.0939671 -0.671192 0.583319 +VERTEX_SE3:QUAT 1878 123.891 167.572 291.61 0.424175 0.00978179 -0.55143 0.718265 +VERTEX_SE3:QUAT 1879 129.307 168.554 295.977 0.336136 0.0905371 -0.608439 0.713175 +VERTEX_SE3:QUAT 1880 135.368 169.669 298.761 0.522241 0.264908 -0.518777 0.622863 +VERTEX_SE3:QUAT 1881 141.665 169.423 302.237 0.504512 0.245946 -0.364646 0.742975 +VERTEX_SE3:QUAT 1882 146.709 171.485 306.324 0.377302 0.363211 -0.300246 0.797229 +VERTEX_SE3:QUAT 1883 151.669 175.46 309.111 0.497211 0.399527 -0.227634 0.735759 +VERTEX_SE3:QUAT 1884 156.456 178.252 313.766 0.558507 0.289416 -0.19785 0.751773 +VERTEX_SE3:QUAT 1885 160.238 180.726 319.036 0.612687 0.141982 0.0541895 0.775577 +VERTEX_SE3:QUAT 1886 160.747 182.908 325.698 0.679869 0.243844 0.011004 0.691518 +VERTEX_SE3:QUAT 1887 162.353 183.372 332.005 0.726088 -0.00934053 0.0474092 0.685901 +VERTEX_SE3:QUAT 1888 161.098 183.115 338.318 0.748156 -0.108601 0.181782 0.628827 +VERTEX_SE3:QUAT 1889 157.607 181.798 344.242 0.628885 -0.100165 0.404851 0.656175 +VERTEX_SE3:QUAT 1890 152.626 180.885 348.92 0.595712 -0.0812943 0.519322 0.607308 +VERTEX_SE3:QUAT 1891 147.386 178.951 353.223 0.600306 -0.126765 0.483019 0.624704 +VERTEX_SE3:QUAT 1892 142.05 177.65 357.367 0.52114 -0.201854 0.532771 0.635471 +VERTEX_SE3:QUAT 1893 135.65 176.447 360.21 0.470421 -0.246305 0.575327 0.622123 +VERTEX_SE3:QUAT 1894 128.942 175.963 361.49 0.357701 -0.231493 0.682358 0.594011 +VERTEX_SE3:QUAT 1895 122.285 174.601 361.747 0.348797 -0.220496 0.726032 0.55009 +VERTEX_SE3:QUAT 1896 115.768 172.332 362.012 0.232214 -0.166536 0.804978 0.519955 +VERTEX_SE3:QUAT 1897 109.555 169.357 361.478 0.19932 0.0649662 0.923533 0.321151 +VERTEX_SE3:QUAT 1898 106.379 163.952 362.545 0.131196 -0.0883253 0.975186 0.154914 +VERTEX_SE3:QUAT 1899 105.129 157.634 361.497 0.141235 -0.251814 0.936551 0.198784 +VERTEX_SE3:QUAT 1900 102.521 152.317 358.386 0.0767776 -0.308621 0.945165 0.0743018 +VERTEX_SE3:QUAT 1901 101.962 147.07 354.184 -0.114629 -0.241803 0.961537 0.0619531 +VERTEX_SE3:QUAT 1902 102.007 141.066 351.168 -0.0579606 -0.190459 0.97998 0.00231665 +VERTEX_SE3:QUAT 1903 102.816 135.181 348.608 -0.0294261 0.236677 -0.962788 0.127113 +VERTEX_SE3:QUAT 1904 104.942 129.917 345.109 0.0387092 0.214094 -0.882505 0.416953 +VERTEX_SE3:QUAT 1905 110.201 126.334 342.872 0.13171 0.200844 -0.868421 0.433772 +VERTEX_SE3:QUAT 1906 116.137 123.361 341.407 0.135444 0.0185969 -0.858049 0.495036 +VERTEX_SE3:QUAT 1907 122.263 120.689 342.298 0.13684 0.0892278 -0.822764 0.5444 +VERTEX_SE3:QUAT 1908 128.744 118.646 342.379 0.165946 0.17401 -0.70093 0.671476 +VERTEX_SE3:QUAT 1909 135.314 118.998 342.257 0.340635 0.136145 -0.673659 0.641573 +VERTEX_SE3:QUAT 1910 141.473 118.672 344.106 0.473169 0.0299642 -0.569731 0.671282 +VERTEX_SE3:QUAT 1911 146.439 118.58 348.405 0.405405 0.229711 -0.671303 0.576395 +VERTEX_SE3:QUAT 1912 152.581 117.359 349.881 0.527034 0.0921088 -0.494806 0.684777 +VERTEX_SE3:QUAT 1913 157.221 117.205 354.557 0.619792 0.0284918 -0.390815 0.679933 +VERTEX_SE3:QUAT 1914 160.484 117.285 360.174 0.632824 -0.0320705 -0.340317 0.694759 +VERTEX_SE3:QUAT 1915 163.103 117.374 366.399 0.578468 0.0442011 -0.40821 0.70483 +VERTEX_SE3:QUAT 1916 166.903 117.502 372.217 0.496599 0.0624038 -0.329917 0.800406 +VERTEX_SE3:QUAT 1917 170.42 119.534 377.276 0.576785 0.0889411 -0.274173 0.764354 +VERTEX_SE3:QUAT 1918 173.767 121.125 382.925 0.727378 0.126335 -0.303904 0.602166 +VERTEX_SE3:QUAT 1919 177.081 119.65 388.2 0.717637 0.0461592 -0.329059 0.612035 +VERTEX_SE3:QUAT 1920 180.074 118.014 393.843 0.729263 0.00574084 -0.349949 0.587944 +VERTEX_SE3:QUAT 1921 182.45 116.087 399.687 0.723019 -0.179611 -0.325759 0.58212 +VERTEX_SE3:QUAT 1922 183.117 114.841 405.84 0.604584 -0.193474 -0.324785 0.701114 +VERTEX_SE3:QUAT 1923 184.133 115.897 411.967 0.60178 -0.169729 -0.401484 0.669226 +VERTEX_SE3:QUAT 1924 185.949 115.934 418.089 0.486201 -0.191244 -0.334299 0.784397 +VERTEX_SE3:QUAT 1925 187.991 118.375 423.559 0.487564 -0.184169 -0.213084 0.826413 +VERTEX_SE3:QUAT 1926 188.77 121.609 429.158 0.6162 -0.358649 -0.145478 0.685934 +VERTEX_SE3:QUAT 1927 187.157 122.984 435.21 0.624411 -0.204254 -0.168278 0.734897 +VERTEX_SE3:QUAT 1928 186.725 124.231 441.324 0.593248 -0.225142 0.00566913 0.772875 +VERTEX_SE3:QUAT 1929 184.598 126.266 447.04 0.5077 -0.285137 -0.0398248 0.812005 +VERTEX_SE3:QUAT 1930 182.747 129.711 452.385 0.291322 -0.473095 -0.0405495 0.830463 +VERTEX_SE3:QUAT 1931 181.267 135.13 454.853 0.358976 -0.469451 0.101496 0.800282 +VERTEX_SE3:QUAT 1932 178.085 140.054 457.573 0.222582 -0.46811 0.143681 0.843022 +VERTEX_SE3:QUAT 1933 174.89 145.551 459.029 0.201086 -0.472113 0.251186 0.820719 +VERTEX_SE3:QUAT 1934 171.262 150.596 459.164 0.105654 -0.51847 0.373962 0.761695 +VERTEX_SE3:QUAT 1935 167.123 154.421 457.384 -0.0348872 -0.634686 0.440863 0.633716 +VERTEX_SE3:QUAT 1936 164.195 158.039 453.054 -0.0767688 -0.690883 0.515348 0.501202 +VERTEX_SE3:QUAT 1937 162.024 160.258 447.875 -0.105646 -0.732634 0.537259 0.404276 +VERTEX_SE3:QUAT 1938 160.505 162.388 442.268 -0.207771 -0.66202 0.570182 0.439832 +VERTEX_SE3:QUAT 1939 159.627 163.487 436.098 -0.1218 -0.59659 0.590207 0.53 +VERTEX_SE3:QUAT 1940 157.127 164.801 430.352 -0.14141 -0.541983 0.649022 0.51481 +VERTEX_SE3:QUAT 1941 154.018 165.545 424.924 -0.0999426 -0.605854 0.628963 0.476821 +VERTEX_SE3:QUAT 1942 151.23 166.086 419.313 -0.229435 -0.564408 0.709236 0.354667 +VERTEX_SE3:QUAT 1943 149.853 164.841 413.561 -0.121781 -0.459059 0.691967 0.543706 +VERTEX_SE3:QUAT 1944 146.011 164.374 408.711 -0.0349735 -0.405361 0.770079 0.491363 +VERTEX_SE3:QUAT 1945 141.982 162.668 404.462 0.0428312 -0.43655 0.780536 0.445368 +VERTEX_SE3:QUAT 1946 137.93 161.319 400.275 -0.06615 -0.381575 0.898175 0.208103 +VERTEX_SE3:QUAT 1947 136.437 157.157 395.656 -0.135339 -0.455253 0.858785 0.192136 +VERTEX_SE3:QUAT 1948 135.764 153.777 390.453 -0.145418 -0.487128 0.850954 0.132051 +VERTEX_SE3:QUAT 1949 135.565 150.333 385.196 -0.146407 -0.47454 0.853061 0.160198 +VERTEX_SE3:QUAT 1950 135.222 147.22 379.954 -0.193502 -0.35043 0.869856 0.288281 +VERTEX_SE3:QUAT 1951 133.576 143.442 375.318 -0.229755 -0.409053 0.863919 0.183119 +VERTEX_SE3:QUAT 1952 132.961 139.554 370.554 -0.275989 -0.351416 0.873145 0.194819 +VERTEX_SE3:QUAT 1953 132.415 135.125 366.364 -0.212189 -0.42958 0.876072 0.0541731 +VERTEX_SE3:QUAT 1954 133.405 131.28 361.74 -0.197787 -0.533041 0.822633 0.00487081 +VERTEX_SE3:QUAT 1955 134.639 128.556 356.529 -0.313327 -0.441776 0.839453 0.0444857 +VERTEX_SE3:QUAT 1956 135.924 124.921 352.226 -0.111846 -0.46937 0.8742 0.054371 +VERTEX_SE3:QUAT 1957 136.674 121.718 347.499 0.0801117 0.716525 -0.692942 0.00219042 +VERTEX_SE3:QUAT 1958 137.828 121.576 342.092 0.253524 0.534771 -0.796452 0.124138 +VERTEX_SE3:QUAT 1959 140.909 119.241 337.663 0.236454 0.535912 -0.809952 0.0294182 +VERTEX_SE3:QUAT 1960 143.204 116.711 332.898 0.227123 0.529644 -0.806894 0.129668 +VERTEX_SE3:QUAT 1961 145.902 114.563 328.397 0.272123 0.631465 -0.685315 0.239884 +VERTEX_SE3:QUAT 1962 150.435 113.873 324.725 0.207266 0.550103 -0.760085 0.276943 +VERTEX_SE3:QUAT 1963 154.755 112.569 320.784 0.118227 0.537659 -0.74373 0.379225 +VERTEX_SE3:QUAT 1964 158.38 112.048 316.847 0.102241 0.376671 -0.748962 0.535464 +VERTEX_SE3:QUAT 1965 163.707 111.512 314.757 0.177607 0.449517 -0.631995 0.605782 +VERTEX_SE3:QUAT 1966 169.186 112.274 313.026 0.0935862 0.564321 -0.566411 0.593264 +VERTEX_SE3:QUAT 1967 173.835 114.335 310.178 0.113564 0.687564 -0.54639 0.464561 +VERTEX_SE3:QUAT 1968 177.787 116.968 306.807 0.27592 0.717959 -0.49976 0.3983 +VERTEX_SE3:QUAT 1969 182.67 119.022 304.283 0.336822 0.683601 -0.468528 0.446902 +VERTEX_SE3:QUAT 1970 187.518 120.817 303.046 0.331717 0.755259 -0.272165 0.495454 +VERTEX_SE3:QUAT 1971 191.911 124.784 303 0.441762 0.701999 -0.236953 0.505863 +VERTEX_SE3:QUAT 1972 196.983 127.454 304.088 0.520771 0.665419 -0.191481 0.49935 +VERTEX_SE3:QUAT 1973 202.176 129.189 306.156 0.601413 0.630045 -0.148227 0.468374 +VERTEX_SE3:QUAT 1974 206.83 130.132 308.809 0.760428 0.48644 -0.284286 0.322967 +VERTEX_SE3:QUAT 1975 212.148 128.197 310.486 0.778154 0.496731 -0.205722 0.324675 +VERTEX_SE3:QUAT 1976 216.992 126.273 312.652 0.76352 0.380621 -0.164634 0.495035 +VERTEX_SE3:QUAT 1977 220.565 125.409 316.617 0.714526 0.432607 -0.245436 0.492 +VERTEX_SE3:QUAT 1978 225.095 124.24 319.639 0.795436 0.439562 -0.18695 0.372983 +VERTEX_SE3:QUAT 1979 229.781 122.127 322.326 0.78051 0.384529 0.00366709 0.492877 +VERTEX_SE3:QUAT 1980 232.36 120.559 327.172 0.80033 0.177085 0.0672927 0.568845 +VERTEX_SE3:QUAT 1981 233.182 118.319 332.368 0.764598 0.191488 0.207954 0.579204 +VERTEX_SE3:QUAT 1982 233.311 116.422 337.703 0.652656 0.366307 0.334933 0.572432 +VERTEX_SE3:QUAT 1983 233.892 115.543 343.603 0.657712 0.354951 0.398859 0.531353 +VERTEX_SE3:QUAT 1984 233.719 114.427 349.327 0.683084 0.331382 0.452326 0.467957 +VERTEX_SE3:QUAT 1985 233.478 112.148 354.197 0.711222 0.394422 0.401098 0.421564 +VERTEX_SE3:QUAT 1986 234.377 109.874 359.013 0.68574 0.430569 0.317461 0.493548 +VERTEX_SE3:QUAT 1987 235.38 108.959 364.365 0.730231 0.496778 0.377453 0.278393 +VERTEX_SE3:QUAT 1988 238.15 106.551 368.744 0.737804 0.501017 0.386185 0.23556 +VERTEX_SE3:QUAT 1989 241.215 103.853 373.052 0.749681 0.431153 0.264199 0.426947 +VERTEX_SE3:QUAT 1990 242.996 102.024 378.029 0.81324 0.238786 0.225589 0.480344 +VERTEX_SE3:QUAT 1991 243.414 99.3537 383.059 0.75735 0.224343 0.199473 0.579915 +VERTEX_SE3:QUAT 1992 243.509 97.5027 388.087 0.644616 0.26307 0.291018 0.65618 +VERTEX_SE3:QUAT 1993 243.028 97.3574 393.446 0.477161 0.339256 0.35128 0.730633 +VERTEX_SE3:QUAT 1994 241.767 98.4403 398.443 0.409395 0.278516 0.489923 0.717495 +VERTEX_SE3:QUAT 1995 239.038 98.8815 402.877 0.422892 0.21611 0.485205 0.73419 +VERTEX_SE3:QUAT 1996 235.994 99.2917 407.286 0.529995 0.0980059 0.48974 0.685314 +VERTEX_SE3:QUAT 1997 232.869 99.0052 411.306 0.758151 -0.00499089 0.355746 0.546468 +VERTEX_SE3:QUAT 1998 230.293 96.661 415.161 0.757714 0.0147493 0.325657 0.565331 +VERTEX_SE3:QUAT 1999 227.798 94.601 419.926 0.581625 -0.116721 0.356507 0.721797 +VERTEX_SE3:QUAT 2000 223.926 94.7221 423.51 0.576724 -0.041278 0.326639 0.747658 +VERTEX_SE3:QUAT 2001 220.467 95.0818 427.737 0.535272 -0.135151 0.303665 0.776534 +VERTEX_SE3:QUAT 2002 217.145 96.3067 431.494 0.565303 -0.112381 0.458254 0.676614 +VERTEX_SE3:QUAT 2003 213.023 95.8362 434.753 0.635002 -0.0235557 0.420458 0.647636 +VERTEX_SE3:QUAT 2004 209.809 94.4079 438.874 0.525826 -0.100231 0.396161 0.746001 +VERTEX_SE3:QUAT 2005 206.032 94.8074 442.663 0.608675 -0.251567 0.329303 0.676601 +VERTEX_SE3:QUAT 2006 201.635 95.0355 445.497 0.65793 -0.265311 0.37525 0.596595 +VERTEX_SE3:QUAT 2007 197.022 94.1478 448.194 0.65401 -0.235755 0.45382 0.557439 +VERTEX_SE3:QUAT 2008 192.741 92.6262 450.029 0.588488 -0.427365 0.423696 0.539928 +VERTEX_SE3:QUAT 2009 187.64 92.3137 450.866 0.396769 -0.554341 0.397818 0.61402 +VERTEX_SE3:QUAT 2010 182.917 94.1138 450.455 0.26543 -0.522826 0.537031 0.606463 +VERTEX_SE3:QUAT 2011 178.48 95.4806 448.651 0.251712 -0.592916 0.527409 0.554014 +VERTEX_SE3:QUAT 2012 174.12 97.1697 446.511 0.29386 -0.578671 0.514947 0.560014 +VERTEX_SE3:QUAT 2013 169.813 98.7599 445.146 0.256314 -0.592287 0.601433 0.470933 +VERTEX_SE3:QUAT 2014 165.351 99.5087 442.373 0.263727 -0.674269 0.557805 0.405787 +VERTEX_SE3:QUAT 2015 161.483 100.853 439.346 0.278543 -0.742504 0.428194 0.433304 +VERTEX_SE3:QUAT 2016 157.549 103.356 437.063 0.441053 -0.747942 0.391121 0.305088 +VERTEX_SE3:QUAT 2017 153.352 105.037 435.224 0.507411 -0.645005 0.451977 0.349599 +VERTEX_SE3:QUAT 2018 148.204 105.39 433.504 0.548053 -0.688712 0.374665 0.291444 +VERTEX_SE3:QUAT 2019 143.132 106.38 432.202 0.541154 -0.667458 0.325911 0.394251 +VERTEX_SE3:QUAT 2020 138.398 108.063 431.795 0.615144 -0.669252 0.303697 0.285426 +VERTEX_SE3:QUAT 2021 133.685 108.344 431.212 0.555353 -0.795058 0.102877 0.221093 +VERTEX_SE3:QUAT 2022 129.047 110.496 431.302 0.451699 -0.822701 0.317376 0.13566 +VERTEX_SE3:QUAT 2023 125.096 112.641 429.314 -0.368651 0.82719 -0.422506 0.0366325 +VERTEX_SE3:QUAT 2024 122.902 114.854 425.706 0.392262 -0.790523 0.457798 0.107815 +VERTEX_SE3:QUAT 2025 119.58 116.574 422.218 0.355393 -0.805088 0.463665 0.102678 +VERTEX_SE3:QUAT 2026 116.473 118.603 418.49 -0.351683 0.826234 -0.44003 0.00545214 +VERTEX_SE3:QUAT 2027 113.953 120.732 414.371 -0.373618 0.794196 -0.479222 0.00304983 +VERTEX_SE3:QUAT 2028 111.143 122.379 410.226 0.160536 -0.855479 0.480039 0.109297 +VERTEX_SE3:QUAT 2029 109.586 124.635 406.504 0.147405 -0.81151 0.511819 0.240342 +VERTEX_SE3:QUAT 2030 107.858 126.92 402.415 0.0618418 -0.925792 0.333033 0.167848 +VERTEX_SE3:QUAT 2031 107.305 130.321 399.434 0.0678253 0.913461 -0.401235 6.7092e-05 +VERTEX_SE3:QUAT 2032 107.987 133.47 395.999 -0.221158 -0.86746 0.442477 0.05308 +VERTEX_SE3:QUAT 2033 110.287 135.951 392.327 -0.257947 -0.868502 0.411702 0.098327 +VERTEX_SE3:QUAT 2034 112.5 138.264 388.39 -0.269442 -0.849481 0.385014 0.239891 +VERTEX_SE3:QUAT 2035 114.45 140.832 384.381 -0.207208 -0.860401 0.450404 0.117946 +VERTEX_SE3:QUAT 2036 115.929 142.803 380.578 -0.174368 -0.779703 0.507092 0.32329 +VERTEX_SE3:QUAT 2037 115.872 144.666 375.822 -0.23163 -0.751197 0.509422 0.350057 +VERTEX_SE3:QUAT 2038 116.235 146.265 371.498 -0.320842 -0.771053 0.471293 0.283586 +VERTEX_SE3:QUAT 2039 117.279 147.611 367.115 -0.29332 -0.797047 0.50134 0.16534 +VERTEX_SE3:QUAT 2040 119.34 149.327 362.81 -0.343991 -0.781649 0.506267 0.119954 +VERTEX_SE3:QUAT 2041 121.23 150.045 358.994 -0.355669 -0.72552 0.584895 0.0708427 +VERTEX_SE3:QUAT 2042 123.526 150.13 355.127 -0.376421 -0.720524 0.57822 0.0693873 +VERTEX_SE3:QUAT 2043 126.355 150.024 350.856 -0.506991 -0.552589 0.65921 0.0551995 +VERTEX_SE3:QUAT 2044 128.668 147.932 347.285 -0.64255 -0.529132 0.553167 0.0339902 +VERTEX_SE3:QUAT 2045 131.971 145.415 344.491 0.653963 0.478254 -0.58612 0.00828517 +VERTEX_SE3:QUAT 2046 135.118 142.945 341.983 -0.647126 -0.359378 0.671889 0.0252907 +VERTEX_SE3:QUAT 2047 137.134 139.253 339.854 0.56026 0.336926 -0.741715 0.149827 +VERTEX_SE3:QUAT 2048 140.099 135.789 338.739 0.539408 0.391625 -0.726524 0.166831 +VERTEX_SE3:QUAT 2049 143.548 132.987 337.31 0.47799 0.240467 -0.828302 0.166182 +VERTEX_SE3:QUAT 2050 146.186 129.258 336.426 0.461339 0.184379 -0.80876 0.314767 +VERTEX_SE3:QUAT 2051 149.453 125.909 336.943 0.417332 0.0669439 -0.842373 0.334305 +VERTEX_SE3:QUAT 2052 152.433 122.379 337.774 0.43161 0.016583 -0.825818 0.362578 +VERTEX_SE3:QUAT 2053 155.621 119.512 339.381 0.311489 -0.0248041 -0.833294 0.45605 +VERTEX_SE3:QUAT 2054 158.856 117.547 341.105 0.362678 -0.193989 -0.745934 0.523847 +VERTEX_SE3:QUAT 2055 162.228 116.52 344.182 0.502657 -0.118945 -0.681477 0.518437 +VERTEX_SE3:QUAT 2056 164.594 114.746 347.052 0.516044 -0.162906 -0.610321 0.578505 +VERTEX_SE3:QUAT 2057 166.981 113.748 350.714 0.587363 -0.15967 -0.72603 0.319986 +VERTEX_SE3:QUAT 2058 168.152 110.67 353.755 0.421066 -0.356911 -0.734064 0.39556 +VERTEX_SE3:QUAT 2059 169.538 109.269 357.822 0.374106 -0.37135 -0.649844 0.547583 +VERTEX_SE3:QUAT 2060 171.388 108.972 361.555 0.406146 -0.360833 -0.678969 0.493808 +VERTEX_SE3:QUAT 2061 173.589 108.116 365.522 0.386337 -0.33787 -0.657273 0.551889 +VERTEX_SE3:QUAT 2062 175.809 107.588 369.421 0.487142 -0.339012 -0.60699 0.528513 +VERTEX_SE3:QUAT 2063 176.974 106.828 373.519 0.303612 -0.327076 -0.590391 0.672518 +VERTEX_SE3:QUAT 2064 179.587 107.915 377.015 0.326061 -0.284949 -0.449266 0.78144 +VERTEX_SE3:QUAT 2065 181.82 109.928 380.154 0.301483 -0.310949 -0.457224 0.776766 +VERTEX_SE3:QUAT 2066 184.239 111.879 383.506 0.200523 -0.355881 -0.501518 0.762639 +VERTEX_SE3:QUAT 2067 186.834 114.543 386.021 0.209033 -0.514958 -0.413906 0.720976 +VERTEX_SE3:QUAT 2068 188.23 117.494 388.71 0.19677 -0.373552 -0.418128 0.804307 +VERTEX_SE3:QUAT 2069 190.212 120.186 391.195 0.0431952 -0.388011 -0.325569 0.861154 +VERTEX_SE3:QUAT 2070 192.607 123.878 392.638 0.0174803 -0.432873 -0.427377 0.793514 +VERTEX_SE3:QUAT 2071 195.588 126.944 393.971 0.0226397 -0.461829 -0.502258 0.73071 +VERTEX_SE3:QUAT 2072 198.482 129.173 396.096 0.0055617 -0.600534 -0.45873 0.654901 +VERTEX_SE3:QUAT 2073 201.055 131.976 398.001 -0.149917 -0.646043 -0.416895 0.621572 +VERTEX_SE3:QUAT 2074 204.315 135.012 398.856 -0.220092 -0.657393 -0.275093 0.666121 +VERTEX_SE3:QUAT 2075 207.329 138.374 398.889 -0.118597 -0.712116 -0.0791368 0.687432 +VERTEX_SE3:QUAT 2076 208.85 142.339 398.061 -0.0446475 -0.626043 0.0365875 0.777649 +VERTEX_SE3:QUAT 2077 208.618 146.277 397.058 -0.115111 -0.69773 0.0908374 0.701192 +VERTEX_SE3:QUAT 2078 208.92 150.144 395.334 -0.152018 -0.712581 0.110042 0.676024 +VERTEX_SE3:QUAT 2079 209.498 153.634 393.574 -0.366123 -0.677502 0.237237 0.592169 +VERTEX_SE3:QUAT 2080 210.649 156.103 390.012 -0.362044 -0.683678 0.155844 0.614183 +VERTEX_SE3:QUAT 2081 211.788 158.554 387.236 -0.396249 -0.677422 0.113164 0.609328 +VERTEX_SE3:QUAT 2082 213.157 160.973 384.502 -0.370596 -0.642499 -0.0528297 0.668627 +VERTEX_SE3:QUAT 2083 215.201 164.237 382.533 -0.364779 -0.660233 -0.0564819 0.654093 +VERTEX_SE3:QUAT 2084 217.133 166.929 380.69 -0.534538 -0.621521 0.00439649 0.572679 +VERTEX_SE3:QUAT 2085 219.858 168.587 378.193 -0.438207 -0.590505 0.149341 0.661042 +VERTEX_SE3:QUAT 2086 220.998 170.322 374.443 -0.434863 -0.644056 0.333796 0.53354 +VERTEX_SE3:QUAT 2087 221.721 171.431 370.982 -0.360654 -0.718653 0.379506 0.457648 +VERTEX_SE3:QUAT 2088 222.621 172.897 367.122 -0.298951 -0.776519 0.360265 0.421729 +VERTEX_SE3:QUAT 2089 223.052 174.987 363.713 -0.385184 -0.752698 0.416465 0.334119 +VERTEX_SE3:QUAT 2090 224.145 176.101 359.591 -0.409825 -0.719742 0.437924 0.349625 +VERTEX_SE3:QUAT 2091 225.233 177.128 355.639 -0.319078 -0.712164 0.454171 0.429815 +VERTEX_SE3:QUAT 2092 225.514 177.949 351.759 -0.344593 -0.694598 0.509043 0.373718 +VERTEX_SE3:QUAT 2093 226.235 178.711 347.881 -0.313803 -0.719158 0.412002 0.463244 +VERTEX_SE3:QUAT 2094 226.689 180.093 344.078 -0.392942 -0.658443 0.395293 0.505759 +VERTEX_SE3:QUAT 2095 227.163 181.757 340.201 -0.358366 -0.522992 0.545258 0.548405 +VERTEX_SE3:QUAT 2096 226.598 182.115 336.111 -0.345694 -0.543262 0.580389 0.498508 +VERTEX_SE3:QUAT 2097 226.003 181.664 332.66 -0.451532 -0.511781 0.627093 0.375437 +VERTEX_SE3:QUAT 2098 226.141 180.501 328.825 -0.53357 -0.410235 0.670986 0.311108 +VERTEX_SE3:QUAT 2099 226.194 178.235 325.298 -0.445659 -0.304349 0.645195 0.540818 +VERTEX_SE3:QUAT 2100 224.55 177.132 321.727 -0.367788 -0.138907 0.718877 0.573282 +VERTEX_SE3:QUAT 2101 221.795 175.683 319.275 -0.316886 -0.11236 0.812901 0.475552 +VERTEX_SE3:QUAT 2102 219.088 173.501 317.372 -0.524927 -0.0293825 0.764503 0.372992 +VERTEX_SE3:QUAT 2103 217.674 170.653 315.984 -0.557792 -0.000201536 0.79611 0.234684 +VERTEX_SE3:QUAT 2104 216.701 167.213 315.257 -0.57647 0.0678631 0.805971 0.116141 +VERTEX_SE3:QUAT 2105 215.627 163.195 315.541 -0.684499 0.191856 0.701795 0.0462163 +VERTEX_SE3:QUAT 2106 214.498 160.105 316.422 0.618408 -0.0938919 -0.779982 0.0195806 +VERTEX_SE3:QUAT 2107 214.214 156.399 317.332 0.68527 -0.161398 -0.700118 0.119126 +VERTEX_SE3:QUAT 2108 213.651 152.83 319.122 0.689939 -0.163179 -0.697009 0.107402 +VERTEX_SE3:QUAT 2109 213.49 149.426 320.91 0.550318 -0.444596 -0.66433 0.241143 +VERTEX_SE3:QUAT 2110 213.196 147.929 324.121 0.626189 -0.528274 -0.537584 0.199541 +VERTEX_SE3:QUAT 2111 211.57 147.089 327.406 0.664191 -0.641082 -0.313607 0.222521 +VERTEX_SE3:QUAT 2112 209.206 147.191 330.282 0.653787 -0.670521 -0.230586 0.264186 +VERTEX_SE3:QUAT 2113 206.328 148.033 332.866 0.511811 -0.751279 -0.173059 0.379052 +VERTEX_SE3:QUAT 2114 203.92 149.71 335.281 0.463995 -0.705815 -0.090742 0.52754 +VERTEX_SE3:QUAT 2115 202.336 151.801 337.571 0.458784 -0.719069 -0.0254426 0.521355 +VERTEX_SE3:QUAT 2116 199.944 153.678 339.095 0.487137 -0.743753 0.0870814 0.449384 +VERTEX_SE3:QUAT 2117 196.988 155.759 340.153 0.298263 -0.743639 -0.107472 0.588634 +VERTEX_SE3:QUAT 2118 195.983 158.686 341.835 0.253488 -0.755624 0.0745233 0.599351 +VERTEX_SE3:QUAT 2119 194.35 161.695 342.391 0.00424658 -0.788448 0.0240711 0.614615 +VERTEX_SE3:QUAT 2120 194.15 165.325 341.931 -0.112439 -0.859054 -0.151211 0.47594 +VERTEX_SE3:QUAT 2121 195.524 168.754 342.116 -0.0825283 -0.789053 -0.00469497 0.608738 +VERTEX_SE3:QUAT 2122 196.208 172.271 341.409 -0.174155 -0.818616 -0.0376809 0.546002 +VERTEX_SE3:QUAT 2123 197.324 175.2 340.777 -0.374116 -0.802073 0.136119 0.445183 +VERTEX_SE3:QUAT 2124 199.155 177.202 338.838 -0.56195 -0.693786 -0.0101952 0.450298 +VERTEX_SE3:QUAT 2125 201.857 178.247 336.965 -0.705283 -0.591423 0.0676429 0.384994 +VERTEX_SE3:QUAT 2126 204.289 178.044 334.746 -0.73495 -0.5759 0.0317971 0.356618 +VERTEX_SE3:QUAT 2127 207.057 177.287 332.431 -0.659204 -0.694944 -0.00148447 0.287228 +VERTEX_SE3:QUAT 2128 210.506 177.487 330.649 -0.653703 -0.695599 0.0943845 0.282678 +VERTEX_SE3:QUAT 2129 213.367 177.39 328.775 -0.792917 -0.492374 0.227226 0.277882 +VERTEX_SE3:QUAT 2130 215.126 175.937 326.913 -0.698214 -0.604729 0.315542 0.217334 +VERTEX_SE3:QUAT 2131 217.481 175.146 324.387 -0.711614 -0.511602 0.395956 0.274022 +VERTEX_SE3:QUAT 2132 218.933 173.331 322.007 -0.718736 -0.542861 0.422826 0.0996918 +VERTEX_SE3:QUAT 2133 221.343 171.546 320.033 -0.651801 -0.564688 0.495098 0.105646 +VERTEX_SE3:QUAT 2134 223.554 170.153 317.691 -0.682761 -0.334599 0.598414 0.252551 +VERTEX_SE3:QUAT 2135 223.917 167.856 315.318 -0.833457 -0.165545 0.474096 0.230602 +VERTEX_SE3:QUAT 2136 223.744 164.929 314.109 -0.826141 -0.0716297 0.525506 0.190271 +VERTEX_SE3:QUAT 2137 223.288 161.585 313.227 -0.806494 -0.0956995 0.580434 0.0592132 +VERTEX_SE3:QUAT 2138 223.577 158.124 313.024 -0.834237 0.118151 0.538126 0.0225765 +VERTEX_SE3:QUAT 2139 222.404 154.862 313.552 -0.875764 0.0127832 0.475584 0.0818191 +VERTEX_SE3:QUAT 2140 222.066 151.688 313.424 -0.786916 0.24621 0.550932 0.128911 +VERTEX_SE3:QUAT 2141 220.134 148.726 314.182 -0.61388 0.558799 0.524264 0.189847 +VERTEX_SE3:QUAT 2142 217.301 147.951 315.531 -0.493822 0.523146 0.691176 0.0687989 +VERTEX_SE3:QUAT 2143 215.736 147.331 318.002 -0.540787 0.524888 0.654932 0.0557269 +VERTEX_SE3:QUAT 2144 214.136 145.762 320.167 0.412621 -0.441066 -0.781035 0.158715 +VERTEX_SE3:QUAT 2145 214.144 144.423 323.033 0.331391 -0.546505 -0.758033 0.129995 +VERTEX_SE3:QUAT 2146 213.94 143.314 326.253 0.215738 -0.627954 -0.744311 0.0716454 +VERTEX_SE3:QUAT 2147 213.542 142.793 329.531 0.0870657 -0.538021 -0.816432 0.190766 +VERTEX_SE3:QUAT 2148 214.203 141.868 332.401 0.094533 -0.569889 -0.787951 0.21313 +VERTEX_SE3:QUAT 2149 215.049 141.22 335.089 -0.0611069 -0.531623 -0.79047 0.297993 +VERTEX_SE3:QUAT 2150 216.816 140.637 337.392 -0.166018 -0.389949 -0.815413 0.394309 +VERTEX_SE3:QUAT 2151 219.323 139.481 338.723 -0.023494 -0.417475 -0.780664 0.464463 +VERTEX_SE3:QUAT 2152 221.705 139.247 340.609 0.0544344 -0.526513 -0.730252 0.431917 +VERTEX_SE3:QUAT 2153 223.576 139.756 343.023 0.103871 -0.539929 -0.568718 0.611758 +VERTEX_SE3:QUAT 2154 225.75 140.781 345.536 -0.0136462 -0.65104 -0.508534 0.563342 +VERTEX_SE3:QUAT 2155 227.883 142.119 347.337 0.04025 -0.704984 -0.307881 0.637642 +VERTEX_SE3:QUAT 2156 228.951 144.903 348.114 -0.0261151 -0.680711 -0.225457 0.696506 +VERTEX_SE3:QUAT 2157 229.908 147.923 348.94 -0.0449928 -0.682545 -0.284698 0.671606 +VERTEX_SE3:QUAT 2158 231.274 150.193 349.903 -0.0608745 -0.658338 -0.205393 0.721595 +VERTEX_SE3:QUAT 2159 232.374 153.136 350.028 -0.2041 -0.646933 -0.0895275 0.72925 +VERTEX_SE3:QUAT 2160 233.592 156.094 349.196 -0.235441 -0.689437 0.0253591 0.684544 +VERTEX_SE3:QUAT 2161 234.508 159.082 347.922 -0.260894 -0.657114 0.206166 0.676485 +VERTEX_SE3:QUAT 2162 235.101 160.96 346.003 -0.313374 -0.546234 0.253785 0.734179 +VERTEX_SE3:QUAT 2163 235.298 162.828 343.471 -0.413385 -0.581902 0.0801748 0.695755 +VERTEX_SE3:QUAT 2164 236.227 164.452 341.078 -0.233952 -0.495424 0.240599 0.801207 +VERTEX_SE3:QUAT 2165 235.817 166.59 339 -0.434001 -0.396993 0.23001 0.775329 +VERTEX_SE3:QUAT 2166 235.39 168.046 336.386 -0.406021 -0.366658 0.210054 0.8103 +VERTEX_SE3:QUAT 2167 235.219 169.289 334.094 -0.590139 -0.313252 0.2314 0.707151 +VERTEX_SE3:QUAT 2168 235.008 169.73 330.959 -0.525925 -0.3958 0.350932 0.666027 +VERTEX_SE3:QUAT 2169 234.489 169.66 328.558 -0.597457 -0.224967 0.406343 0.653698 +VERTEX_SE3:QUAT 2170 233.253 169.158 325.374 -0.604056 -0.144545 0.366373 0.692816 +VERTEX_SE3:QUAT 2171 232.213 169.1 322.98 -0.44617 -0.293658 0.633357 0.559961 +VERTEX_SE3:QUAT 2172 230.854 168.459 320.774 -0.334991 -0.181937 0.783416 0.490855 +VERTEX_SE3:QUAT 2173 229.253 167.17 319.095 -0.265466 -0.125444 0.826348 0.480562 +VERTEX_SE3:QUAT 2174 227.125 165.561 318.005 -0.046203 0.0196473 0.857838 0.511462 +VERTEX_SE3:QUAT 2175 224.914 164.031 318.194 0.112888 -0.00615567 0.886203 0.449291 +VERTEX_SE3:QUAT 2176 222.871 162.478 318.216 0.00208826 -0.166166 0.94961 0.265754 +VERTEX_SE3:QUAT 2177 221.921 160.175 317.196 -0.135092 -0.130974 0.969918 0.154452 +VERTEX_SE3:QUAT 2178 221.962 157.392 316.672 -0.184187 0.0594902 0.977318 0.0859429 +VERTEX_SE3:QUAT 2179 221.503 154.627 317.236 -0.224137 0.203813 0.93366 0.191056 +VERTEX_SE3:QUAT 2180 220.781 152.041 318.136 -0.104264 0.116199 0.972786 0.171213 +VERTEX_SE3:QUAT 2181 220.079 149.68 318.442 -0.0914259 0.20261 0.974757 0.020955 +VERTEX_SE3:QUAT 2182 220.537 147.089 319.132 0.0761067 -0.181022 -0.977453 0.0776211 +VERTEX_SE3:QUAT 2183 221.225 144.408 320.342 -0.0709524 -0.271525 -0.953647 0.108614 +VERTEX_SE3:QUAT 2184 222.213 142.329 321.497 0.0640129 -0.259703 -0.955303 0.125908 +VERTEX_SE3:QUAT 2185 223.311 140.222 322.834 0.0435592 -0.299114 -0.950831 0.06749 +VERTEX_SE3:QUAT 2186 223.96 137.977 324.314 -0.0082179 -0.294175 -0.941492 0.164274 +VERTEX_SE3:QUAT 2187 225.314 135.802 325.939 0.094486 -0.257751 -0.855494 0.439051 +VERTEX_SE3:QUAT 2188 227.223 135.28 327.116 0.127992 -0.405477 -0.744776 0.51431 +VERTEX_SE3:QUAT 2189 228.863 135.152 328.992 0.0791168 -0.259992 -0.706501 0.653453 +VERTEX_SE3:QUAT 2190 231.05 135.247 330.298 0.253521 -0.328466 -0.703862 0.576555 +VERTEX_SE3:QUAT 2191 232.787 135.085 332.107 0.357127 -0.346869 -0.735065 0.460241 +VERTEX_SE3:QUAT 2192 233.927 134.592 334.025 0.21743 -0.49546 -0.62797 0.559372 +VERTEX_SE3:QUAT 2193 235.663 135.178 336.069 0.0979041 -0.37512 -0.811903 0.436477 +VERTEX_SE3:QUAT 2194 237.637 134.635 337.511 0.17574 -0.294983 -0.704953 0.620598 +VERTEX_SE3:QUAT 2195 239.131 134.512 339.207 0.337027 -0.0814215 -0.528048 0.775209 +VERTEX_SE3:QUAT 2196 240.952 135.464 340.743 0.282326 -0.0711083 -0.548906 0.783542 +VERTEX_SE3:QUAT 2197 242.918 136.302 341.982 0.161903 -0.186326 -0.618773 0.745782 +VERTEX_SE3:QUAT 2198 244.782 136.865 343.028 0.232764 -0.230296 -0.521572 0.787875 +VERTEX_SE3:QUAT 2199 246.312 137.961 344.226 0.205778 -0.315783 -0.483831 0.789838 +EDGE_SE3:QUAT 0 1 0.309576 2.34636 0.00315914 -0.139007 0.0806488 0.14657 0.976059 1 9.62965e-19 9.62965e-19 5.88441e-08 -2.03096e-08 3.40337e-09 1 9.62965e-19 5.88441e-08 -2.03096e-08 3.40337e-09 1 5.88441e-08 -2.03096e-08 3.40337e-09 4108.72 -34.2982 884.091 3951.5 40.2084 4100.08 +EDGE_SE3:QUAT 1 2 -0.034127 2.24359 -0.503123 -0.127533 -0.0213306 0.150102 0.980178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3934.45 -9.14727 63.005 3998.72 10.7561 3909.38 +EDGE_SE3:QUAT 2 3 0.138899 2.43125 -0.157531 0.00121791 -0.063752 0.00803582 0.997933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.84 0.47106 -517.426 3983.74 -2.04693 4065.59 +EDGE_SE3:QUAT 3 4 0.0941858 2.24481 -0.15806 -0.0907382 -0.0311999 0.0233004 0.995113 1 1.20371e-20 1.20371e-20 1.83689e-10 6.41125e-10 -6.91561e-09 1 1.20371e-20 1.83689e-10 6.41125e-10 -6.91561e-09 1 1.83689e-10 6.41125e-10 -6.91561e-09 3979.28 10.1662 -221.62 3997.33 -4.26681 4010.04 +EDGE_SE3:QUAT 4 5 -0.019968 2.43874 -0.141006 0.14682 -0.0160644 -0.00998598 0.988982 1 7.73381e-19 7.73381e-19 -5.49689e-08 -2.64098e-09 1.20286e-09 1 7.73381e-19 -5.49689e-08 -2.64098e-09 1.20286e-09 1 -5.49689e-08 -2.64098e-09 1.20286e-09 3916.62 -7.39114 -107.077 3999.45 1.19465 4002.45 +EDGE_SE3:QUAT 5 6 -0.057963 2.38913 -0.0656954 0.00744535 0.0573407 -0.189817 0.980115 1 1.88079e-22 1.88079e-22 8.55746e-10 -1.66101e-10 4.88703e-11 1 1.88079e-22 8.55746e-10 -1.66101e-10 4.88703e-11 1 8.55746e-10 -1.66101e-10 4.88703e-11 4051.02 -13.3295 455.764 3989.43 -43.9256 3907.12 +EDGE_SE3:QUAT 6 7 0.284131 2.59971 -0.069789 0.174316 0.120257 0.00202164 0.977317 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4095.18 95.1606 956.489 3957.88 61.6914 4216.71 +EDGE_SE3:QUAT 7 8 0.381814 2.34619 -0.170979 0.140444 0.167241 -0.0505931 0.974549 1 1.20371e-20 1.20371e-20 -1.28911e-09 -9.67004e-10 -7.20082e-09 1 1.20371e-20 -1.28911e-09 -9.67004e-10 -7.20082e-09 1 -1.28911e-09 -9.67004e-10 -7.20082e-09 4445.78 102.031 1540.78 3886.91 64.5763 4514.44 +EDGE_SE3:QUAT 8 9 0.217387 2.42673 -0.0999375 0.0799257 -0.00178671 0.035696 0.99616 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975 -2.35829 -48.1981 3999.78 -1.0137 3995.45 +EDGE_SE3:QUAT 9 10 0.236729 2.5202 0.0829723 -0.160833 0.0639475 0.074949 0.982052 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.77 -47.3805 645.131 3974.1 4.03949 4078.77 +EDGE_SE3:QUAT 10 11 -0.0512516 2.58576 -0.0726493 0.170367 -0.134099 0.032038 0.975687 1 1.54375e-18 1.54375e-18 5.76423e-08 5.27149e-08 -2.07532e-08 1 1.54375e-18 5.76423e-08 5.27149e-08 -2.07532e-08 1 5.76423e-08 5.27149e-08 -2.07532e-08 4199.06 -104.185 -1166.22 3933.99 61.5178 4311.06 +EDGE_SE3:QUAT 11 12 0.100961 2.83888 0.058294 -0.0830016 0.130511 0.0148521 0.987855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4261.92 -48.1376 1114.33 3933.15 -27.4811 4288.6 +EDGE_SE3:QUAT 12 13 -0.0544223 2.38861 0.129309 0.312134 0.105764 0.18632 0.925565 1 3.90001e-18 3.90001e-18 1.01333e-07 1.8093e-08 -5.93866e-08 1 3.90001e-18 1.01333e-07 1.8093e-08 -5.93866e-08 1 1.01333e-07 1.8093e-08 -5.93866e-08 3591.27 -37.7061 38.5097 3999.7 -19.8768 3842.12 +EDGE_SE3:QUAT 13 14 0.0951564 2.91598 0.334549 0.0468146 0.0309502 -0.0436027 0.997471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.59 5.4492 271.668 3995.22 -4.91018 4010.75 +EDGE_SE3:QUAT 14 15 -0.471701 2.45736 -0.495194 -0.0832386 -0.0429816 -0.0409007 0.994762 1 1.92593e-19 1.92593e-19 2.77365e-08 -9.29853e-10 -1.3677e-09 1 1.92593e-19 2.77365e-08 -9.29853e-10 -1.3677e-09 1 2.77365e-08 -9.29853e-10 -1.3677e-09 4008.65 14.6559 -383.294 3990.63 3.87282 4029.68 +EDGE_SE3:QUAT 15 16 -0.374254 2.51657 0.0109317 0.11527 -0.00329853 -0.0315075 0.992829 1 1.92596e-19 1.92596e-19 -2.756e-08 7.64581e-10 -9.87327e-11 1 1.92596e-19 -2.756e-08 7.64581e-10 -9.87327e-11 1 -2.756e-08 7.64581e-10 -9.87327e-11 3946.87 1.84732 17.3427 3999.94 -0.503501 3996.05 +EDGE_SE3:QUAT 16 17 -0.00510188 2.6334 0.349385 -0.0569492 0.0470723 0.191629 0.978682 1 8.66668e-19 8.66668e-19 -1.26459e-08 9.01829e-09 5.4325e-08 1 8.66668e-19 -1.26459e-08 9.01829e-09 5.4325e-08 1 -1.26459e-08 9.01829e-09 5.4325e-08 4045.75 0.316493 488.891 3985.05 47.1799 3911.83 +EDGE_SE3:QUAT 17 18 0.387595 3.02983 0.066416 -0.12543 -0.0770029 0.015945 0.988981 1 1.92593e-19 1.92593e-19 -9.69606e-10 2.74362e-08 3.58668e-09 1 1.92593e-19 -9.69606e-10 2.74362e-08 3.58668e-09 1 -9.69606e-10 2.74362e-08 3.58668e-09 4021.55 40.3412 -587.708 3981.76 -21.5572 4083.47 +EDGE_SE3:QUAT 18 19 0.252916 2.56527 -0.304143 -0.0216152 -0.103362 -0.0713846 0.991843 1 1.95602e-19 1.95602e-19 5.41696e-09 2.72925e-08 -1.81982e-10 1 1.95602e-19 5.41696e-09 2.72925e-08 -1.81982e-10 1 5.41696e-09 2.72925e-08 -1.81982e-10 4180.06 -9.24205 -872.247 3956.44 28.8862 4161.55 +EDGE_SE3:QUAT 19 20 0.0259897 3.12414 0.00960713 0.177603 -0.0535178 0.110384 0.976426 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.65 -51.4782 -645.434 3972.09 -17.2271 4052.08 +EDGE_SE3:QUAT 20 21 0.0361642 3.05298 -0.0994 -0.0324897 0.0298112 -0.0363075 0.998367 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.29 -4.29442 224.085 3997.05 -4.64231 4007.23 +EDGE_SE3:QUAT 21 22 0.112505 2.95107 0.154583 -0.0646097 0.0556387 0.0268045 0.995998 1 2.52778e-19 2.52778e-19 -2.79695e-08 -1.3938e-08 -9.45439e-09 1 2.52778e-19 -2.79695e-08 -1.3938e-08 -9.45439e-09 1 -2.79695e-08 -1.3938e-08 -9.45439e-09 4037.37 -13.6786 468.207 3986.5 1.37388 4051.19 +EDGE_SE3:QUAT 22 23 -0.00874804 2.85614 -0.134111 -0.0475112 0.0480184 0.0195641 0.997524 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.03 -8.60845 397.195 3990.23 1.24541 4037.53 +EDGE_SE3:QUAT 23 24 0.516916 2.81965 -0.0189855 0.175074 -0.0640371 0.00804422 0.982438 1 1.88079e-22 1.88079e-22 -5.49858e-11 1.53495e-10 8.59202e-10 1 1.88079e-22 -5.49858e-11 1.53495e-10 8.59202e-10 1 -5.49858e-11 1.53495e-10 8.59202e-10 3942.02 -45.8402 -512.632 3986.28 15.337 4064.37 +EDGE_SE3:QUAT 24 25 -0.0649857 2.80244 0.2754 -0.082326 -0.242094 0.0207483 0.966531 1 1.58889e-18 1.58889e-18 5.30981e-08 5.60867e-08 6.23153e-09 1 1.58889e-18 5.30981e-08 5.60867e-08 6.23153e-09 1 5.30981e-08 5.60867e-08 6.23153e-09 5040.99 194.518 -2326.8 3798.35 -189.672 5066.38 +EDGE_SE3:QUAT 25 26 -0.0771604 2.74112 -0.0312855 -0.0721281 0.064045 0.0787683 0.992215 1 3.85186e-19 3.85186e-19 2.97545e-08 -2.56124e-08 3.59396e-10 1 3.85186e-19 2.97545e-08 -2.56124e-08 3.59396e-10 1 2.97545e-08 -2.56124e-08 3.59396e-10 4062.22 -13.2762 582.492 3978.74 16.1737 4058.21 +EDGE_SE3:QUAT 26 27 -0.048794 2.73317 -0.0392042 0.120673 -0.113356 0.207954 0.964025 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4281.54 11.125 -1215.32 3920.2 -98.5595 4166.81 +EDGE_SE3:QUAT 27 28 0.0119386 2.90225 -0.240756 -0.0289552 0.0690008 0.0924023 0.992906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4081.06 2.56652 587.207 3979.3 25.309 4050.26 +EDGE_SE3:QUAT 28 29 -0.141502 2.99391 0.00925092 0.0929819 -0.131765 0.00591579 0.986893 1 7.70372e-19 7.70372e-19 -5.67439e-08 1.09432e-09 7.5057e-09 1 7.70372e-19 -5.67439e-08 1.09432e-09 7.5057e-09 1 -5.67439e-08 1.09432e-09 7.5057e-09 4254.2 -58.5715 -1112.92 3934.59 38.0315 4288.64 +EDGE_SE3:QUAT 29 30 0.197594 2.61945 -0.0962157 0.0170545 0.114952 -0.104195 0.987744 1 7.52316e-22 7.52316e-22 1.76116e-09 -1.83697e-10 2.06783e-10 1 7.52316e-22 1.76116e-09 -1.83697e-10 2.06783e-10 1 1.76116e-09 -1.83697e-10 2.06783e-10 4222.13 -26.3889 971.104 3948.58 -52.0832 4179.87 +EDGE_SE3:QUAT 30 31 0.230428 3.27097 0.0514496 -0.138867 -0.0570195 0.0329026 0.98812 1 9.62965e-20 9.62965e-20 2.42846e-11 -1.57005e-08 1.17936e-08 1 9.62965e-20 2.42846e-11 -1.57005e-08 1.17936e-08 1 2.42846e-11 -1.57005e-08 1.17936e-08 3960.52 28.375 -390.884 3992.69 -14.8773 4033.33 +EDGE_SE3:QUAT 31 32 -0.224712 2.82546 -0.185205 -0.0462261 -0.0302993 0.185008 0.981181 1 7.70372e-19 7.70372e-19 6.26038e-10 3.00643e-09 -5.4493e-08 1 7.70372e-19 6.26038e-10 3.00643e-09 -5.4493e-08 1 6.26038e-10 3.00643e-09 -5.4493e-08 3995.2 3.76248 -129.071 3999.76 -8.83083 3866.84 +EDGE_SE3:QUAT 32 33 0.353059 2.96096 -0.183962 0.038007 -0.0264556 0.151274 0.987407 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.71 -1.76914 -273.111 3995.03 -21.443 3926.96 +EDGE_SE3:QUAT 33 34 -0.0451522 2.79876 -0.0662132 -0.0145135 0.00589013 0.11723 0.992981 1 1.96355e-19 1.96355e-19 3.39583e-09 -9.62756e-10 -2.75551e-08 1 1.96355e-19 3.39583e-09 -9.62756e-10 -2.75551e-08 1 3.39583e-09 -9.62756e-10 -2.75551e-08 4000.25 -0.358271 66.384 3999.68 4.25163 3946.12 +EDGE_SE3:QUAT 34 35 0.0712974 2.59336 -0.119227 -0.0467543 -0.175817 0.117169 0.976306 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4449.72 132.408 -1430.62 3914.56 -143.642 4403.55 +EDGE_SE3:QUAT 35 36 0.199713 3.05338 -0.176071 -0.0796125 0.0928983 0.145218 0.981806 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4162.58 -0.779728 887.563 3953.98 52.3643 4103.58 +EDGE_SE3:QUAT 36 37 0.0935414 3.08577 0.0999248 0.0980073 0.0329882 0.0305721 0.994169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.09 11.0793 224.55 3997.39 5.27005 4008.77 +EDGE_SE3:QUAT 37 38 -0.35453 3.26772 -0.327349 -0.19089 -0.00925882 -0.0661535 0.979336 1 1.20371e-20 1.20371e-20 -4.01936e-10 -6.79912e-09 -1.30588e-09 1 1.20371e-20 -4.01936e-10 -6.79912e-09 -1.30588e-09 1 -4.01936e-10 -6.79912e-09 -1.30588e-09 3865.58 24.6619 -217.661 3995.87 6.3311 3993.83 +EDGE_SE3:QUAT 38 39 0.00249936 2.44752 -0.0540098 -0.0120277 0.0320138 0.0398503 0.99862 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.53 -0.587533 262.184 3995.71 5.00869 4010.76 +EDGE_SE3:QUAT 39 40 -0.0904856 2.83461 0.000222251 0.0436439 0.0196539 0.122304 0.991338 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.27 1.97637 89.9248 3999.77 4.30362 3942.05 +EDGE_SE3:QUAT 40 41 0.178274 2.9757 -0.162468 -0.182665 -0.086118 -0.219705 0.954435 1 9.62965e-19 9.62965e-19 6.01208e-08 1.63842e-08 -5.01233e-09 1 9.62965e-19 6.01208e-08 1.63842e-08 -5.01233e-09 1 6.01208e-08 1.63842e-08 -5.01233e-09 4171.16 41.738 -1149.13 3920.37 84.1438 4111.54 +EDGE_SE3:QUAT 41 42 -0.137809 2.87031 0.183792 -0.184133 0.260286 0.0475845 0.946616 1 3.85863e-18 3.85863e-18 -5.35255e-08 1.07414e-07 9.64152e-09 1 3.85863e-18 -5.35255e-08 1.07414e-07 9.64152e-09 1 -5.35255e-08 1.07414e-07 9.64152e-09 5217.46 -332.29 2691.61 3784.34 -323.281 5344.02 +EDGE_SE3:QUAT 42 43 0.126584 2.92759 0.0474793 -0.0544326 -0.139186 0.217481 0.964555 1 9.62965e-19 9.62965e-19 -8.81426e-10 3.29951e-08 -5.18629e-08 1 9.62965e-19 -8.81426e-10 3.29951e-08 -5.18629e-08 1 -8.81426e-10 3.29951e-08 -5.18629e-08 4188.12 105.528 -922.523 3977.59 -128.485 4010.78 +EDGE_SE3:QUAT 43 44 -0.308986 2.99939 0.20294 -0.0302986 -0.0444281 0.17064 0.983865 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.55 9.6038 -279.566 3996.8 -23.0181 3902.75 +EDGE_SE3:QUAT 44 45 -0.00481081 2.9988 -0.0936046 -0.0510756 -0.0588501 0.0768386 0.993994 1 4.81482e-20 4.81482e-20 -1.38705e-08 -1.1575e-09 6.97177e-10 1 4.81482e-20 -1.38705e-08 -1.1575e-09 6.97177e-10 1 -1.38705e-08 -1.1575e-09 6.97177e-10 4033.41 16.0651 -421.523 3990.53 -19.6264 4020.22 +EDGE_SE3:QUAT 45 46 0.00978783 2.82854 0.245613 -0.0330986 0.119195 0.063258 0.990301 1 1.20371e-20 1.20371e-20 7.08168e-09 4.0727e-10 8.744e-10 1 1.20371e-20 7.08168e-09 4.0727e-10 8.744e-10 1 7.08168e-09 4.0727e-10 8.744e-10 4242.82 4.25653 1024.66 3941.03 25.1083 4231.19 +EDGE_SE3:QUAT 46 47 0.0419054 2.90798 -0.0544217 0.0550993 0.0535219 -0.00658805 0.997024 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4034.61 11.9064 434.975 3988.51 2.40203 4046.58 +EDGE_SE3:QUAT 47 48 -0.00661405 3.4765 -0.215438 -0.00201135 0.055937 0.166392 0.98447 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4047.23 11.7627 437.405 3989.96 37.019 3936.5 +EDGE_SE3:QUAT 48 49 0.00231518 3.43102 0.202065 -0.0606544 0.0068065 0.0510712 0.996828 1 4.81482e-20 4.81482e-20 -1.79038e-10 8.28064e-10 -1.38373e-08 1 4.81482e-20 -1.79038e-10 8.28064e-10 -1.38373e-08 1 -1.79038e-10 8.28064e-10 -1.38373e-08 3987.32 -3.0014 91.0042 3999.34 2.48166 3991.6 +EDGE_SE3:QUAT 49 50 0.096195 3.02416 0.132259 -0.09336 -0.101633 -0.0099997 0.990381 1 3.85212e-19 3.85212e-19 -2.78539e-08 -2.77795e-08 6.23338e-10 1 3.85212e-19 -2.78539e-08 -2.77795e-08 6.23338e-10 1 -2.78539e-08 -2.77795e-08 6.23338e-10 4135.92 41.1447 -843.992 3960.13 -19.7978 4170.39 +EDGE_SE3:QUAT 50 51 -0.101877 3.29919 -0.0215778 0.00508371 0.0673464 -0.0876494 0.993859 1 1.9264e-19 1.9264e-19 2.31721e-09 -2.28596e-10 2.78682e-08 1 1.9264e-19 2.31721e-09 -2.28596e-10 2.78682e-08 1 2.31721e-09 -2.28596e-10 2.78682e-08 4073.22 -8.31168 546.525 3982.51 -24.5252 4042.6 +EDGE_SE3:QUAT 51 52 0.202366 3.37611 0.0177919 -0.0568028 -0.141696 -0.000739383 0.988279 1 7.52316e-22 7.52316e-22 -2.54462e-10 -1.0654e-10 1.78568e-09 1 7.52316e-22 -2.54462e-10 -1.0654e-10 1.78568e-09 1 -2.54462e-10 -1.0654e-10 1.78568e-09 4325.51 41.3571 -1211.69 3921.96 -29.5092 4338.41 +EDGE_SE3:QUAT 52 53 -0.0341671 3.18552 0.178588 0.28025 0.105245 -0.0509478 0.952779 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3900.16 138.151 950.491 3962.96 65.0085 4203.94 +EDGE_SE3:QUAT 53 54 -0.139096 3.31629 0.00421493 -0.0680862 0.115982 -0.190268 0.972476 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4110.08 -69.47 734.273 3983.66 -86.5884 3983.82 +EDGE_SE3:QUAT 54 55 0.0294886 2.93009 -0.23316 0.00575157 0.0559543 -0.0313835 0.997923 1 1.20371e-20 1.20371e-20 -3.92466e-10 -1.57087e-11 -6.96846e-09 1 1.20371e-20 -3.92466e-10 -1.57087e-11 -6.96846e-09 1 -3.92466e-10 -1.57087e-11 -6.96846e-09 4050.78 -1.0575 454.131 3987.41 -6.92871 4046.97 +EDGE_SE3:QUAT 55 56 -0.131081 3.08406 -0.322746 -0.0876199 0.0302193 0.10049 0.990612 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.14 -12.7895 342.262 3991.65 15.735 3988.46 +EDGE_SE3:QUAT 56 57 -0.0596602 3.19991 0.0581845 -0.163401 0.132574 0.0962048 0.972866 1 7.70372e-19 7.70372e-19 5.66168e-08 2.96367e-09 9.02518e-09 1 7.70372e-19 5.66168e-08 2.96367e-09 9.02518e-09 1 5.66168e-08 2.96367e-09 9.02518e-09 4277.1 -77.9761 1297.62 3911.41 -15.8293 4346.88 +EDGE_SE3:QUAT 57 58 -0.53461 3.22758 -0.0258737 -0.106248 0.0250076 -0.0353789 0.993395 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.52 -7.58323 151.699 3998.95 -3.46413 4000.66 +EDGE_SE3:QUAT 58 59 -0.199454 3.29214 -0.0178188 -0.0979521 0.0411126 0.291118 0.950771 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4054.38 -1.33448 619.712 3974.97 96.6405 3753.76 +EDGE_SE3:QUAT 59 60 0.127137 3.01706 -0.25908 0.107806 0.0185623 0.283338 0.952761 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3961.97 -16.6308 -215.982 3992.81 -48.1432 3687.34 +EDGE_SE3:QUAT 60 61 0.196029 3.55941 0.07817 -0.000773032 0.0682439 0.0394711 0.996887 1 4.70198e-23 4.70198e-23 -4.36388e-10 -1.73945e-11 -2.98069e-11 1 4.70198e-23 -4.36388e-10 -1.73945e-11 -2.98069e-11 1 -4.36388e-10 -1.73945e-11 -2.98069e-11 4075.31 4.27989 554.01 3981.58 11.3763 4069.08 +EDGE_SE3:QUAT 61 62 -0.0888788 3.56689 -0.0877961 0.130264 -0.0449843 0.0995352 0.985444 1 2.40741e-19 2.40741e-19 -3.09272e-09 1.70373e-08 2.59101e-08 1 2.40741e-19 -3.09272e-09 1.70373e-08 2.59101e-08 1 -3.09272e-09 1.70373e-08 2.59101e-08 3994.81 -28.6923 -506.307 3982.44 -17.3247 4023.06 +EDGE_SE3:QUAT 62 63 0.0411224 3.36322 -0.0633307 -0.067124 0.113252 -0.0735586 0.988563 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4160.32 -52.867 863.781 3962.4 -54.0704 4156.7 +EDGE_SE3:QUAT 63 64 -0.257987 3.50326 -0.0486499 0.0090073 -0.0895187 0.0210624 0.995722 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4131.7 0.618195 -738.612 3967.79 -6.63708 4130.25 +EDGE_SE3:QUAT 64 65 0.239512 3.38815 0.0157726 0.0738181 0.0049775 0.0890885 0.993272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3978.42 -2.41392 -39.1905 3999.73 -2.91832 3968.47 +EDGE_SE3:QUAT 65 66 -0.546521 3.71035 0.0809922 0.220671 0.0117025 0.17712 0.95906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3833.26 -53.2961 -363.87 3983.87 -40.6892 3902.56 +EDGE_SE3:QUAT 66 67 -0.527426 3.54041 -0.13827 -0.0775627 0.0474567 -0.166919 0.981769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.83 -9.74748 208.406 3999.29 -14.5162 3898.44 +EDGE_SE3:QUAT 67 68 -0.102045 3.42381 0.125405 -0.0371547 -0.168537 -0.105556 0.979323 1 2.0463e-19 2.0463e-19 1.23148e-08 -6.82071e-10 -3.0174e-08 1 2.0463e-19 1.23148e-08 -6.82071e-10 -3.0174e-08 1 1.23148e-08 -6.82071e-10 -3.0174e-08 4510.69 -48.7162 -1526.86 3885.91 76.2101 4471.64 +EDGE_SE3:QUAT 68 69 -0.0660117 3.47876 -0.0859495 0.113482 0.0156758 0.0287052 0.993002 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3950.2 4.08607 84.1151 3999.73 1.38129 3998.42 +EDGE_SE3:QUAT 69 70 -0.236781 3.70733 0.135516 -0.007325 -0.0114062 0.213725 0.9768 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.88 0.640394 -66.858 3999.85 -6.26717 3818.38 +EDGE_SE3:QUAT 70 71 0.0680033 3.42541 -0.23282 0.0400042 -0.0285427 0.046859 0.997692 1 1.20371e-20 1.20371e-20 3.08869e-10 -6.92362e-09 2.58324e-10 1 1.20371e-20 3.08869e-10 -6.92362e-09 2.58324e-10 1 3.08869e-10 -6.92362e-09 2.58324e-10 4009.2 -4.13761 -250.387 3995.93 -5.1833 4006.82 +EDGE_SE3:QUAT 71 72 -0.0988674 3.53575 -0.129181 0.100663 0.0664482 0.123177 0.985027 1 2.40741e-19 2.40741e-19 -2.93216e-08 9.8916e-09 -2.65604e-09 1 2.40741e-19 -2.93216e-08 9.8916e-09 -2.65604e-09 1 -2.93216e-08 9.8916e-09 -2.65604e-09 3991.8 23.747 366.272 3995.56 25.9752 3971.64 +EDGE_SE3:QUAT 72 73 -0.126983 3.49572 0.0561846 -0.103955 0.00792464 0.179943 0.978136 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.02 -14.7296 278.703 3992.74 29.7176 3888.73 +EDGE_SE3:QUAT 73 74 -0.222091 3.42637 -0.0675352 0.00844732 -0.0258343 -0.0288769 0.999213 1 3.00927e-21 3.00927e-21 -3.47121e-09 1.01952e-10 8.78875e-11 1 3.00927e-21 -3.47121e-09 1.01952e-10 8.78875e-11 1 -3.47121e-09 1.01952e-10 8.78875e-11 4010.08 -1.31579 -203.924 3997.45 3.08172 4007.03 +EDGE_SE3:QUAT 74 75 -0.465116 3.70537 0.128699 0.0252376 -0.0552671 0.00983356 0.998104 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4047.34 -5.12801 -449.501 3987.63 -0.390532 4049.5 +EDGE_SE3:QUAT 75 76 0.281437 3.37347 0.14111 -0.121594 0.151892 0.193702 0.961573 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4490.51 31.7924 1581.83 3878.19 105.83 4399.57 +EDGE_SE3:QUAT 76 77 -0.277953 3.49889 0.0403024 0.256265 -0.0232921 0.229979 0.93856 1 7.70372e-19 7.70372e-19 7.3172e-09 -1.24887e-08 -5.3283e-08 1 7.70372e-19 7.3172e-09 -1.24887e-08 -5.3283e-08 1 7.3172e-09 -1.24887e-08 -5.3283e-08 3900.88 -99.2088 -842.498 3941.52 -79.5351 3952 +EDGE_SE3:QUAT 77 78 -0.30321 3.68266 -0.274752 -0.0628729 -0.0648783 -0.12379 0.988187 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4074.84 4.82922 -609.319 3976.96 33.1482 4029.36 +EDGE_SE3:QUAT 78 79 -0.261141 4.0444 -0.269701 0.106366 0.0540207 0.16226 0.97951 1 1.92593e-19 1.92593e-19 -2.72184e-08 -4.73823e-09 -4.41565e-10 1 1.92593e-19 -2.72184e-08 -4.73823e-09 -4.41565e-10 1 -2.72184e-08 -4.73823e-09 -4.41565e-10 3963.65 10.9485 205.342 3999.87 13.228 3903.59 +EDGE_SE3:QUAT 79 80 -0.430928 3.46215 0.110747 -0.116941 0.0822458 -0.0306565 0.989253 1 4.81482e-20 4.81482e-20 -1.0188e-09 1.73094e-09 -1.38871e-08 1 4.81482e-20 -1.0188e-09 1.73094e-09 -1.38871e-08 1 -1.0188e-09 1.73094e-09 -1.38871e-08 4036.72 -41.4745 612.065 3980.71 -26.7798 4087.66 +EDGE_SE3:QUAT 80 81 -0.0834893 3.52907 0.0879758 -0.0552372 -0.0134689 0.157185 0.985931 1 4.81482e-20 4.81482e-20 -1.3682e-08 -2.18861e-09 -6.11269e-11 1 4.81482e-20 -1.3682e-08 -2.18861e-09 -6.11269e-11 1 -1.3682e-08 -2.18861e-09 -6.11269e-11 3987.48 -0.946179 -1.01642 3999.93 2.75966 3900.85 +EDGE_SE3:QUAT 81 82 -0.201549 3.63678 -0.130353 -0.0985312 -0.073303 -0.0222352 0.992181 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.93 29.3441 -616.177 3977.61 -6.42191 4090.79 +EDGE_SE3:QUAT 82 83 0.00503593 3.39106 0.197202 0.000519403 0.128476 0.0927183 0.987369 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4269.78 39.4395 1073.32 3939.15 58.4677 4235.4 +EDGE_SE3:QUAT 83 84 -0.111946 3.70765 0.149598 0.0798504 -0.0326286 0.0779945 0.993215 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.84 -11.4647 -332.531 3992.42 -11.0598 4003.01 +EDGE_SE3:QUAT 84 85 0.409333 3.65492 -0.294709 0.0850852 -0.0925746 0.0908342 0.987897 1 7.70372e-19 7.70372e-19 5.97438e-09 -3.87545e-09 -5.60244e-08 1 7.70372e-19 5.97438e-09 -3.87545e-09 -5.60244e-08 1 5.97438e-09 -3.87545e-09 -5.60244e-08 4143.41 -17.8257 -848.307 3957.19 -22.0522 4139.37 +EDGE_SE3:QUAT 85 86 -0.0399519 3.63759 -0.111035 0.0463354 -0.0863741 0.131411 0.98647 1 4.81482e-20 4.81482e-20 1.39358e-08 1.76513e-09 -1.34583e-09 1 4.81482e-20 1.39358e-08 1.76513e-09 -1.34583e-09 1 1.39358e-08 1.76513e-09 -1.34583e-09 4133.66 8.06705 -767.695 3965.86 -46.2436 4073.17 +EDGE_SE3:QUAT 86 87 -0.193786 3.65898 -0.214606 0.0636973 -0.0786251 -0.0523539 0.993489 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4069.75 -26.6287 -592.976 3980.81 24.6908 4075.01 +EDGE_SE3:QUAT 87 88 -0.309431 3.51429 0.114361 0.0769699 -0.0539792 0.0543079 0.994089 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.61 -15.2575 -482.363 3985.29 -7.54455 4045.51 +EDGE_SE3:QUAT 88 89 -0.360865 3.76956 0.16137 0.0949978 0.0796669 0.247197 0.961001 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.39 22.3853 300.386 4001.71 28.8496 3774.07 +EDGE_SE3:QUAT 89 90 -0.0177595 3.52362 -0.290377 0.172837 0.114824 0.0540409 0.976741 1 1.92593e-19 1.92593e-19 -2.49293e-09 -5.33101e-09 -2.76226e-08 1 1.92593e-19 -2.49293e-09 -5.33101e-09 -2.76226e-08 1 -2.49293e-09 -5.33101e-09 -2.76226e-08 4027.55 84.7487 783.919 3976.81 65.9335 4135.36 +EDGE_SE3:QUAT 90 91 -0.0359211 4.02306 -0.244736 0.167584 -0.0771284 0.0904202 0.978668 1 9.62965e-19 9.62965e-19 5.70649e-08 -2.37803e-08 -1.48845e-09 1 9.62965e-19 5.70649e-08 -2.37803e-08 -1.48845e-09 1 5.70649e-08 -2.37803e-08 -1.48845e-09 4037.64 -56.6967 -789.822 3962.13 -5.25178 4117.28 +EDGE_SE3:QUAT 91 92 -0.133912 4.1225 0.342548 -0.0604143 -0.109983 0.0939044 0.987642 1 3.85186e-19 3.85186e-19 3.09861e-08 -2.42882e-08 -4.96834e-09 1 3.85186e-19 3.09861e-08 -2.42882e-08 -4.96834e-09 1 3.09861e-08 -2.42882e-08 -4.96834e-09 4147.26 51.4596 -821.508 3966.85 -57.5455 4126.58 +EDGE_SE3:QUAT 92 93 -0.225422 4.20837 -0.0751461 -0.0586077 -0.0272685 -0.0357171 0.997269 1 1.08334e-19 1.08334e-19 1.45234e-08 7.25818e-09 -1.39062e-08 1 1.08334e-19 1.45234e-08 7.25818e-09 -1.39062e-08 1 1.45234e-08 7.25818e-09 -1.39062e-08 4000.89 6.64536 -242.479 3996.16 3.27227 4009.53 +EDGE_SE3:QUAT 93 94 0.0118957 3.81651 -0.155819 0.117958 -0.0907667 0.223758 0.963213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4189.69 4.47313 -1022.1 3940.31 -98.0123 4045.08 +EDGE_SE3:QUAT 94 95 -0.307501 4.02642 -0.00131728 -0.108472 -0.000837845 0.0783534 0.991007 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3954.89 -6.81305 94.294 3998.99 4.82188 3977.39 +EDGE_SE3:QUAT 95 96 -0.208402 3.91881 -0.0558548 -0.00679609 0.0370146 0.139865 0.989455 1 1.88079e-22 1.88079e-22 -8.60663e-10 -1.21557e-10 -3.25735e-11 1 1.88079e-22 -8.60663e-10 -1.21557e-10 -3.25735e-11 1 -8.60663e-10 -1.21557e-10 -3.25735e-11 4022.22 3.70261 300.2 3994.83 21.1363 3944.15 +EDGE_SE3:QUAT 96 97 -0.0611476 3.8266 -0.102697 0.00695461 -0.0614073 -0.0273052 0.997715 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4060.11 -4.27964 -494.806 3985.21 7.64441 4057.32 +EDGE_SE3:QUAT 97 98 -0.0303635 3.71066 -0.0994848 0.0484982 -0.0584313 0.281104 0.956668 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.46 18.0141 -578.171 3983.36 -84.4206 3765.79 +EDGE_SE3:QUAT 98 99 -0.129053 3.95451 0.47491 -0.0875998 -0.0871375 -0.030168 0.991879 1 2.0463e-19 2.0463e-19 -2.31058e-10 2.69506e-08 9.31619e-09 1 2.0463e-19 -2.31058e-10 2.69506e-08 9.31619e-09 1 -2.31058e-10 2.69506e-08 9.31619e-09 4102.23 29.4941 -741.206 3967.81 -5.30559 4129.28 +EDGE_SE3:QUAT 99 100 -0.269008 3.82902 -0.25887 -0.129825 0.0945014 0.0320557 0.986503 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4091.72 -51.0757 813.575 3962.87 -16.7587 4155.03 +EDGE_SE3:QUAT 100 101 -0.283338 3.67304 -0.0975927 0.127295 0.0865018 0.146677 0.977138 1 9.62965e-19 9.62965e-19 2.19275e-09 -3.53227e-08 -5.04509e-08 1 9.62965e-19 2.19275e-09 -3.53227e-08 -5.04509e-08 1 2.19275e-09 -3.53227e-08 -5.04509e-08 3979.65 36.9679 435.138 3996.22 38.7416 3958.41 +EDGE_SE3:QUAT 101 102 -0.56376 3.63117 -0.149669 0.0573693 -0.0621026 -0.152934 0.984613 1 2.40741e-19 2.40741e-19 2.52311e-08 -1.81096e-08 -1.27401e-10 1 2.40741e-19 2.52311e-08 -1.81096e-08 -1.27401e-10 1 2.52311e-08 -1.81096e-08 -1.27401e-10 4021.22 -19.2891 -375.411 3994.57 29.8899 3940.83 +EDGE_SE3:QUAT 102 103 -0.163856 4.07665 -0.13856 0.0403729 -0.0743431 0.162687 0.983044 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4100.66 11.2095 -663.551 3974.86 -52.6245 4001.31 +EDGE_SE3:QUAT 103 104 -0.17015 4.24423 0.098688 0.00806079 0.0278261 0.0691865 0.997183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.24 2.08085 214.843 3997.26 7.53634 3992.36 +EDGE_SE3:QUAT 104 105 -0.496547 3.94804 -0.0237533 0.0572307 0.107276 -0.107671 0.986724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4204.5 -3.61653 958.084 3947.73 -40.7567 4171.23 +EDGE_SE3:QUAT 105 106 -0.448794 3.97553 0.195343 0.132397 0.142782 -0.0499703 0.979585 1 7.70372e-19 7.70372e-19 5.69433e-08 -6.79036e-10 8.75646e-09 1 7.70372e-19 5.69433e-08 -6.79036e-10 8.75646e-09 1 5.69433e-08 -6.79036e-10 8.75646e-09 4309.13 76.969 1288.73 3914.76 37.6463 4369.26 +EDGE_SE3:QUAT 106 107 -0.486305 4.21294 -0.0577924 0.0352246 -0.190781 0.05671 0.97936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4663.01 17.1139 -1765.81 3851.95 -32.5823 4655.11 +EDGE_SE3:QUAT 107 108 -0.0385234 4.1348 -0.0780564 -0.0578142 0.000666645 0.136915 0.988894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.84 -3.45866 98.8025 3998.96 8.79887 3927.23 +EDGE_SE3:QUAT 108 109 0.0192893 4.01021 0.0265097 0.0879428 -0.109457 0.0907769 0.985923 1 1.92593e-19 1.92593e-19 2.81745e-08 2.0647e-09 -3.49278e-09 1 1.92593e-19 2.81745e-08 2.0647e-09 -3.49278e-09 1 2.81745e-08 2.0647e-09 -3.49278e-09 4205.94 -19.3583 -1002.01 3942.32 -22.0202 4203.92 +EDGE_SE3:QUAT 109 110 -0.229034 4.1835 0.0665407 -0.113283 -0.0372061 0.225134 0.967004 1 9.62965e-19 9.62965e-19 -2.58887e-08 -1.28705e-08 5.31892e-08 1 9.62965e-19 -2.58887e-08 -1.28705e-08 5.31892e-08 1 -2.58887e-08 -1.28705e-08 5.31892e-08 3945.92 -7.62023 23.6904 3998.97 15.2365 3794.51 +EDGE_SE3:QUAT 110 111 -0.66681 3.5759 -0.134454 0.0929661 0.00885363 0.247049 0.964493 1 1.95602e-19 1.95602e-19 2.76476e-08 3.43963e-09 -7.21125e-10 1 1.95602e-19 2.76476e-08 3.43963e-09 -7.21125e-10 1 2.76476e-08 3.43963e-09 -7.21125e-10 3973.61 -11.8302 -199.632 3994.84 -35.6416 3764.05 +EDGE_SE3:QUAT 111 112 -0.123391 3.84675 -0.214241 0.145993 0.0281556 0.0290225 0.988459 1 7.70372e-19 7.70372e-19 5.4919e-08 1.99793e-09 1.02852e-09 1 7.70372e-19 5.4919e-08 1.99793e-09 1.02852e-09 1 5.4919e-08 1.99793e-09 1.02852e-09 3921.66 11.263 167.86 3998.84 3.96882 4003.55 +EDGE_SE3:QUAT 112 113 0.228906 3.79181 -0.291629 -0.129556 -0.0152101 0.0388881 0.990692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3933.6 2.49963 -58.6197 3999.94 -0.982537 3994.69 +EDGE_SE3:QUAT 113 114 -0.34931 4.09239 0.0519959 -0.0211142 -0.0550119 0.147487 0.987307 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4036.07 13.1117 -391.564 3992.43 -29.6986 3950.84 +EDGE_SE3:QUAT 114 115 -0.509045 4.31694 -0.173882 -0.165926 0.0630195 0.0153196 0.984003 1 7.52316e-22 7.52316e-22 -1.12943e-10 2.89226e-10 -1.72156e-09 1 7.52316e-22 -1.12943e-10 2.89226e-10 -1.72156e-09 1 -1.12943e-10 2.89226e-10 -1.72156e-09 3956.61 -43.8312 520.973 3985.18 -12.6483 4065.8 +EDGE_SE3:QUAT 115 116 0.170335 4.20981 -0.0127005 -0.0432059 -0.0154524 -0.0627998 0.996971 1 4.81482e-20 4.81482e-20 -2.87309e-10 -5.68768e-10 1.38462e-08 1 4.81482e-20 -2.87309e-10 -5.68768e-10 1.38462e-08 1 -2.87309e-10 -5.68768e-10 1.38462e-08 3998.52 3.07261 -155.207 3998.32 4.86275 3990.21 +EDGE_SE3:QUAT 116 117 -0.1271 4.24621 -0.219016 0.0930871 0.0887035 -0.00587599 0.991681 1 3.85938e-19 3.85938e-19 -2.75107e-08 -2.76625e-08 1.85511e-09 1 3.85938e-19 -2.75107e-08 -2.76625e-08 1.85511e-09 1 -2.75107e-08 -2.76625e-08 1.85511e-09 4093.27 35.4617 726.718 3970 15.927 4127.8 +EDGE_SE3:QUAT 117 118 -0.128487 4.31399 -0.262685 0.0736729 -0.117912 -0.118648 0.983154 1 1.92593e-19 1.92593e-19 2.7867e-08 -3.91122e-09 -2.7011e-09 1 1.92593e-19 2.7867e-08 -3.91122e-09 -2.7011e-09 1 2.7867e-08 -3.91122e-09 -2.7011e-09 4145.85 -66.4443 -837.53 3969.49 74.0262 4111.26 +EDGE_SE3:QUAT 118 119 -0.237234 4.03175 -0.135374 0.0504897 -0.160476 0.137371 0.976129 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4471.46 55.5119 -1469.23 3894.79 -93.5662 4406.17 +EDGE_SE3:QUAT 119 120 0.215522 3.9566 -0.328506 -0.136296 -0.0135016 -0.0268114 0.990213 1 1.20371e-20 1.20371e-20 1.40417e-10 9.40497e-10 -6.87577e-09 1 1.20371e-20 1.40417e-10 9.40497e-10 -6.87577e-09 1 1.40417e-10 9.40497e-10 -6.87577e-09 3931.16 10.8692 -148.396 3998.45 1.17393 4002.59 +EDGE_SE3:QUAT 120 121 -0.157828 4.33462 -0.161631 -0.0895828 -0.0623248 -0.0692141 0.991615 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4048.45 19.8406 -573.609 3979.3 11.124 4061.39 +EDGE_SE3:QUAT 121 122 -0.45222 4.7293 0.283949 -0.100361 0.129363 0.0894963 0.982437 1 1.92593e-19 1.92593e-19 2.83939e-08 1.86399e-09 4.13674e-09 1 1.92593e-19 2.83939e-08 1.86399e-09 4.13674e-09 1 2.83939e-08 1.86399e-09 4.13674e-09 4291.66 -28.5831 1199.34 3921.06 15.1599 4299.91 +EDGE_SE3:QUAT 122 123 -0.0500732 4.25934 0.129389 -0.0469864 0.0561875 -0.157694 0.984768 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.39 -15.6107 345.515 3995.24 -27.5199 3929.75 +EDGE_SE3:QUAT 123 124 -0.0579459 4.58648 0.0987284 -0.0610826 -0.0392634 -0.104815 0.991837 1 2.88889e-19 2.88889e-19 -1.37937e-08 -1.09393e-08 -2.76671e-08 1 2.88889e-19 -1.37937e-08 -1.09393e-08 -2.76671e-08 1 -1.37937e-08 -1.09393e-08 -2.76671e-08 4022.02 7.34968 -386.764 3990.06 18.7583 3993 +EDGE_SE3:QUAT 124 125 -0.12114 4.04248 -0.0955195 0.125291 -0.0756058 0.0370677 0.98854 1 1.92593e-19 1.92593e-19 4.8284e-10 -2.74525e-08 3.35677e-09 1 1.92593e-19 4.8284e-10 -2.74525e-08 3.35677e-09 1 4.8284e-10 -2.74525e-08 3.35677e-09 4043.39 -39.1065 -660.342 3974.39 6.49183 4100.68 +EDGE_SE3:QUAT 125 126 -0.215732 4.24445 0.209536 -0.0517727 -0.0950358 0.185415 0.976683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4080.66 45.4622 -615.012 3986.46 -64.7429 3953.87 +EDGE_SE3:QUAT 126 127 0.0129442 4.11133 -0.0710511 0.220059 0.0261418 0.100343 0.96996 1 1.92593e-19 1.92593e-19 -5.49259e-10 6.12638e-09 2.69182e-08 1 1.92593e-19 -5.49259e-10 6.12638e-09 2.69182e-08 1 -5.49259e-10 6.12638e-09 2.69182e-08 3805.29 -17.455 -63.6712 3998.44 -8.0205 3958.72 +EDGE_SE3:QUAT 127 128 -0.101962 4.22125 -0.212053 0.036871 -0.0297001 -0.073748 0.996152 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.81 -4.78915 -203.079 3997.81 7.73104 3988.49 +EDGE_SE3:QUAT 128 129 -0.248672 4.29061 -0.139132 0.0640954 0.0933049 0.111339 0.987314 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4087.93 40.7874 655.819 3979.81 48.5122 4054.78 +EDGE_SE3:QUAT 129 130 -0.122296 4.35716 0.243284 -0.0379977 0.130102 0.00783157 0.990741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4280.22 -21.3838 1107.15 3932.46 -11.7068 4285.75 +EDGE_SE3:QUAT 130 131 0.0225997 4.20993 0.174774 0.0294307 -0.0598744 0.124564 0.989966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4062.67 4.09344 -518.596 3983.93 -31.4304 4004.07 +EDGE_SE3:QUAT 131 132 -0.38998 4.31347 -0.0665395 0.110847 -0.100256 0.13151 0.979983 1 1.92593e-19 1.92593e-19 -2.79977e-08 -3.11446e-09 3.53512e-09 1 1.92593e-19 -2.79977e-08 -3.11446e-09 3.53512e-09 1 -2.79977e-08 -3.11446e-09 3.53512e-09 4182.78 -20.5185 -991.384 3942.47 -39.5952 4162.75 +EDGE_SE3:QUAT 132 133 -0.273019 4.61107 -0.257495 0.101852 -0.179692 0.102342 0.973069 1 1.15556e-18 1.15556e-18 -3.11232e-08 -5.41983e-08 3.88049e-08 1 1.15556e-18 -3.11232e-08 -5.41983e-08 3.88049e-08 1 -3.11232e-08 -5.41983e-08 3.88049e-08 4611.61 -18.934 -1743.37 3854.39 -20.036 4611.21 +EDGE_SE3:QUAT 133 134 -0.110441 4.40772 0.19816 -0.157128 0.00943191 0.0606941 0.985666 1 7.70372e-19 7.70372e-19 5.47735e-08 3.04497e-09 1.53957e-09 1 7.70372e-19 5.47735e-08 3.04497e-09 1.53957e-09 1 5.47735e-08 3.04497e-09 1.53957e-09 3909.49 -16.895 184.953 3997.08 5.217 3993.51 +EDGE_SE3:QUAT 134 135 0.113882 4.49096 -0.145341 -0.0275371 -0.140611 0.0883489 0.985731 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4304.85 62.2151 -1151.85 3933.49 -74.104 4276.66 +EDGE_SE3:QUAT 135 136 -0.22419 4.63403 0.114277 0.0561068 0.0464976 0.240707 0.967859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.5 7.92991 182.523 4000.19 15.3531 3775.33 +EDGE_SE3:QUAT 136 137 -0.114568 4.37186 -0.0512219 0.070078 0.00916058 0.181943 0.980766 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.33 -4.50785 -79.9952 3998.91 -11.9938 3868.56 +EDGE_SE3:QUAT 137 138 -0.0404931 4.03461 0.224798 0.159576 0.0843455 0.0270337 0.983204 1 4.81482e-20 4.81482e-20 9.99535e-10 2.33118e-09 1.38019e-08 1 4.81482e-20 9.99535e-10 2.33118e-09 1.38019e-08 1 9.99535e-10 2.33118e-09 1.38019e-08 3988.24 53.6502 608.063 3982.84 31.917 4087.18 +EDGE_SE3:QUAT 138 139 -0.155393 4.3507 -0.0551047 0.018268 -0.149651 0.117944 0.981509 1 2.93874e-22 2.93874e-22 -1.11484e-09 -1.33865e-10 1.70058e-10 1 2.93874e-22 -1.11484e-09 -1.33865e-10 1.70058e-10 1 -1.11484e-09 -1.33865e-10 1.70058e-10 4383.27 56.7501 -1298.61 3915.88 -84.2381 4328.96 +EDGE_SE3:QUAT 139 140 -0.386801 4.5085 0.113592 -0.0740339 0.0758122 0.0873224 0.990528 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4093.61 -13.3795 689.805 3970.81 20.6737 4085.03 +EDGE_SE3:QUAT 140 141 -0.153461 4.36285 0.16816 -0.0182148 -0.00323735 -0.0104853 0.999774 1 1.22251e-20 1.22251e-20 6.94648e-09 7.95273e-10 -9.35757e-12 1 1.22251e-20 6.94648e-09 7.95273e-10 -9.35757e-12 1 6.94648e-09 7.95273e-10 -9.35757e-12 3998.87 0.260519 -28.1741 3999.95 0.146471 3999.76 +EDGE_SE3:QUAT 141 142 -0.378836 4.52825 -0.144586 0.0615274 0.141187 -0.109574 0.981975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4361.82 -14.3734 1284.56 3912.72 -51.8988 4328.94 +EDGE_SE3:QUAT 142 143 -0.028061 4.6517 -0.10217 -0.126084 0.0462979 -0.0323018 0.990412 1 8.1852e-19 8.1852e-19 5.45527e-08 -1.61338e-08 2.44864e-10 1 8.1852e-19 5.45527e-08 -1.61338e-08 2.44864e-10 1 5.45527e-08 -1.61338e-08 2.44864e-10 3960.8 -20.2456 314.066 3995.17 -9.93491 4020.21 +EDGE_SE3:QUAT 143 144 -0.343436 4.50568 -0.102552 -0.106722 -0.039714 0.177907 0.977437 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3954.15 0.689915 -75.6137 4000.29 -0.00921909 3873.1 +EDGE_SE3:QUAT 144 145 -0.602136 4.64947 -0.198365 0.10168 0.0987768 -0.0444335 0.988903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4136.94 37.5218 863.175 3957.07 5.67723 4170.4 +EDGE_SE3:QUAT 145 146 -0.243425 4.45192 -0.074969 0.0771057 -0.0195272 -0.108954 0.990859 1 1.92593e-19 1.92593e-19 -2.75032e-08 3.0724e-09 6.02103e-11 1 1.92593e-19 -2.75032e-08 3.0724e-09 6.02103e-11 1 -2.75032e-08 3.0724e-09 6.02103e-11 3976.6 -0.900441 -52.3937 4000.02 1.11165 3952.89 +EDGE_SE3:QUAT 146 147 -0.20809 4.66307 -0.019332 -0.0583459 -0.0225469 0.117876 0.991056 1 2.43751e-19 2.43751e-19 -1.35671e-08 -6.82242e-09 2.74118e-08 1 2.43751e-19 -1.35671e-08 -6.82242e-09 2.74118e-08 1 -1.35671e-08 -6.82242e-09 2.74118e-08 3988.37 2.46991 -94.097 3999.81 -4.12618 3946.41 +EDGE_SE3:QUAT 147 148 -0.600696 4.50838 0.172296 -0.0525388 0.0157946 -0.0127633 0.998412 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.43 -3.09687 117.856 3999.19 -1.0185 4002.82 +EDGE_SE3:QUAT 148 149 -0.122176 4.54367 0.129849 0.0785697 0.165343 0.113483 0.97653 1 7.70372e-19 7.70372e-19 -8.11557e-09 -6.92836e-09 -5.66843e-08 1 7.70372e-19 -8.11557e-09 -6.92836e-09 -5.66843e-08 1 -8.11557e-09 -6.92836e-09 -5.66843e-08 4339.68 130.611 1262.92 3936.82 136.084 4312.86 +EDGE_SE3:QUAT 149 150 -0.0626617 4.75051 -0.0580603 -0.0456973 -0.0147983 0.082367 0.995444 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.88 1.49798 -71.9136 3999.82 -2.43955 3974.09 +EDGE_SE3:QUAT 150 151 -0.504146 4.27629 -0.061912 -0.0160956 -0.0936881 -0.101691 0.990264 1 1.92593e-19 1.92593e-19 -2.68531e-09 8.94031e-11 2.79924e-08 1 1.92593e-19 -2.68531e-09 8.94031e-11 2.79924e-08 1 -2.68531e-09 8.94031e-11 2.79924e-08 4146.36 -15.961 -781.863 3965.39 40.0525 4106.03 +EDGE_SE3:QUAT 151 152 -0.311071 4.39324 0.0171448 0.0570126 -0.101625 0.0310678 0.992702 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4164.78 -19.0998 -861.829 3956.93 0.416884 4173.92 +EDGE_SE3:QUAT 152 153 0.0199627 5.04425 0.0185079 0.079851 -0.0646834 0.0252674 0.994385 1 1.20371e-20 1.20371e-20 4.74983e-10 -5.40327e-10 -6.96295e-09 1 1.20371e-20 4.74983e-10 -5.40327e-10 -6.96295e-09 1 4.74983e-10 -5.40327e-10 -6.96295e-09 4047.4 -20.266 -544.946 3982.03 1.41226 4070.35 +EDGE_SE3:QUAT 153 154 -0.304117 4.52703 -0.387539 -0.0446697 0.0802547 0.126506 0.987704 1 1.92593e-19 1.92593e-19 -2.5006e-09 6.62602e-10 -2.7839e-08 1 1.92593e-19 -2.5006e-09 6.62602e-10 -2.7839e-08 1 -2.5006e-09 6.62602e-10 -2.7839e-08 4114.8 5.56774 711.559 3970.26 41.3657 4058.76 +EDGE_SE3:QUAT 154 155 -0.107441 4.98712 -0.0814978 0.0254046 -0.157236 0.0199617 0.987032 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4427.68 -8.75391 -1380.64 3900.4 -0.312164 4428.67 +EDGE_SE3:QUAT 155 156 -0.1339 4.6706 0.259055 -0.0979226 0.00901033 0.120862 0.987787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3972.15 -11.1203 209.802 3996.06 14.3473 3952.07 +EDGE_SE3:QUAT 156 157 -0.405243 4.80942 0.288363 0.159303 0.057801 -0.104025 0.980031 1 1.92593e-19 1.92593e-19 2.2642e-09 2.72603e-08 -4.04233e-09 1 1.92593e-19 2.2642e-09 2.72603e-08 -4.04233e-09 1 2.2642e-09 2.72603e-08 -4.04233e-09 4000.37 44.5595 648.188 3972.41 -16.3542 4058.59 +EDGE_SE3:QUAT 157 158 0.123411 4.77357 0.182837 0.0417094 0.149263 0.0388093 0.987155 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4356.84 54.5827 1260.03 3918.41 54.0105 4357.77 +EDGE_SE3:QUAT 158 159 -0.417436 4.67744 -0.339672 0.115496 0.0223245 -0.0182162 0.99289 1 2.0463e-19 2.0463e-19 2.76808e-08 6.53933e-09 -7.64899e-11 1 2.0463e-19 2.76808e-08 6.53933e-09 -7.64899e-11 1 2.76808e-08 6.53933e-09 -7.64899e-11 3956.65 11.7975 200.438 3997.44 -0.234709 4008.68 +EDGE_SE3:QUAT 159 160 -0.341395 4.76493 0.129712 0.0607867 0.126507 0.108489 0.98414 1 5.77779e-19 5.77779e-19 2.76416e-08 3.34042e-08 2.86827e-08 1 5.77779e-19 2.76416e-08 3.34042e-08 2.86827e-08 1 2.76416e-08 3.34042e-08 2.86827e-08 4198.31 70.1234 948.565 3958.42 78.7064 4166.01 +EDGE_SE3:QUAT 160 161 -0.303122 4.52556 -0.194101 0.13178 0.0189005 -0.176125 0.975324 1 7.70372e-19 7.70372e-19 -5.44316e-08 9.23169e-09 -3.48429e-09 1 7.70372e-19 -5.44316e-08 9.23169e-09 -3.48429e-09 1 -5.44316e-08 9.23169e-09 -3.48429e-09 3971.55 25.0835 414.469 3985.5 -38.5451 3916.93 +EDGE_SE3:QUAT 161 162 -0.319518 4.62353 0.0640671 -0.0431151 -0.0328347 0.0476152 0.997394 1 1.20371e-20 1.20371e-20 3.49423e-10 -6.91988e-09 -3.20059e-10 1 1.20371e-20 3.49423e-10 -6.91988e-09 -3.20059e-10 1 3.49423e-10 -6.91988e-09 -3.20059e-10 4006.55 6.02916 -237.137 3996.83 -6.44872 4004.92 +EDGE_SE3:QUAT 162 163 -0.210639 4.52239 0.0393287 0.0536102 -0.215712 0.00814285 0.97495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4849.02 -71.3674 -2045.13 3817.49 63.302 4860.25 +EDGE_SE3:QUAT 163 164 0.133529 4.76596 0.128886 -0.0456512 0.0144311 0.0848233 0.995245 1 1.92593e-19 1.92593e-19 6.07684e-10 -1.18279e-09 2.76458e-08 1 1.92593e-19 6.07684e-10 -1.18279e-09 2.76458e-08 1 6.07684e-10 -1.18279e-09 2.76458e-08 3998.03 -3.29078 160.285 3998.13 7.06661 3977.58 +EDGE_SE3:QUAT 164 165 -0.29204 5.04835 0.0207555 0.154717 -0.138297 -0.0161387 0.978098 1 8.1852e-19 8.1852e-19 5.44081e-08 -1.04348e-09 6.80321e-09 1 8.1852e-19 5.44081e-08 -1.04348e-09 6.80321e-09 1 5.44081e-08 -1.04348e-09 6.80321e-09 4185.33 -106.979 -1097.65 3945.87 81.0374 4280.04 +EDGE_SE3:QUAT 165 166 -0.205148 4.7758 -0.0176451 0.0479648 0.109267 0.104611 0.987328 1 2.40741e-19 2.40741e-19 1.67019e-08 3.67279e-09 2.93235e-08 1 2.40741e-19 1.67019e-08 3.67279e-09 2.93235e-08 1 1.67019e-08 3.67279e-09 2.93235e-08 4153.3 48.8326 823.125 3966.52 59.2364 4118.73 +EDGE_SE3:QUAT 166 167 -0.146779 5.12411 -0.18858 -0.0755946 -0.0953309 -0.00606583 0.992553 1 1.92593e-19 1.92593e-19 2.80604e-08 2.39278e-10 -2.68997e-09 1 1.92593e-19 2.80604e-08 2.39278e-10 -2.68997e-09 1 2.80604e-08 2.39278e-10 -2.68997e-09 4126.2 31.2016 -786.413 3964.66 -14.636 4148.91 +EDGE_SE3:QUAT 167 168 -0.350251 4.90488 -0.0278337 -0.0429992 0.136661 0.0331426 0.989129 1 9.75002e-19 9.75002e-19 2.87814e-08 -5.40284e-08 -5.08956e-09 1 9.75002e-19 2.87814e-08 -5.40284e-08 -5.08956e-09 1 2.87814e-08 -5.40284e-08 -5.08956e-09 4317.1 -14.0796 1184.6 3923.44 2.08479 4320.1 +EDGE_SE3:QUAT 168 169 -0.182334 4.92192 -0.0947893 0.17383 -0.0426137 0.120459 0.976451 1 7.70372e-19 7.70372e-19 5.47651e-08 5.5668e-09 -4.48554e-09 1 7.70372e-19 5.47651e-08 5.5668e-09 -4.48554e-09 1 5.47651e-08 5.5668e-09 -4.48554e-09 3958.91 -45.9369 -574.062 3976.55 -22.4524 4021.74 +EDGE_SE3:QUAT 169 170 -0.112068 4.83079 0.277882 -0.0347248 0.0843384 0.117164 0.988915 1 1.20371e-20 1.20371e-20 -6.97301e-09 -7.95173e-10 -6.34672e-10 1 1.20371e-20 -6.97301e-09 -7.95173e-10 -6.34672e-10 1 -6.97301e-09 -7.95173e-10 -6.34672e-10 4123.82 8.72839 728.803 3969.19 40.1211 4073.73 +EDGE_SE3:QUAT 170 171 -0.391545 5.06979 -0.370353 0.0546154 -0.0177369 -0.0188369 0.998172 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.22 -3.53648 -128.974 3999.05 1.53385 4002.73 +EDGE_SE3:QUAT 171 172 -0.24583 4.93552 0.11415 -0.125375 -0.121767 0.0059993 0.98459 1 1.92593e-19 1.92593e-19 1.02521e-09 -2.73091e-08 -3.62391e-09 1 1.92593e-19 1.02521e-09 -2.73091e-08 -3.62391e-09 1 1.02521e-09 -2.73091e-08 -3.62391e-09 4168.15 73.0813 -988.864 3950.44 -49.1302 4230.88 +EDGE_SE3:QUAT 172 173 -0.33564 5.08249 0.348345 -0.0024165 -0.0594527 0.118467 0.991174 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.9 10.4208 -467.602 3987.73 -28.6437 3997.78 +EDGE_SE3:QUAT 173 174 -0.17606 4.79256 -0.498405 0.109878 -0.0156342 -0.0164217 0.993686 1 7.73381e-19 7.73381e-19 5.5111e-08 -4.52726e-09 -2.64524e-10 1 7.73381e-19 5.5111e-08 -4.52726e-09 -2.64524e-10 1 5.5111e-08 -4.52726e-09 -2.64524e-10 3954.25 -5.2095 -101.334 3999.49 1.23868 4001.47 +EDGE_SE3:QUAT 174 175 -0.366719 4.74298 -0.214977 -0.0571201 -0.0507482 0.0780808 0.994015 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.06 13.477 -349.029 3993.71 -15.9784 4005.73 +EDGE_SE3:QUAT 175 176 -0.0317328 5.27238 -0.146332 -0.0620336 -0.038278 0.0541191 0.99587 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.88 9.36068 -263.849 3996.3 -8.5826 4005.55 +EDGE_SE3:QUAT 176 177 0.112124 4.96909 -0.0427343 -0.0494612 -0.0292394 -0.0703826 0.995864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.88 5.31608 -274.12 3994.99 8.90466 3998.85 +EDGE_SE3:QUAT 177 178 -0.319859 5.34084 0.313169 -0.0278137 0.134814 0.146127 0.979642 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4312.95 52.5602 1167.95 3931.52 89.1873 4230.63 +EDGE_SE3:QUAT 178 179 -0.0548795 5.07152 -0.128528 -0.01845 0.0612922 0.131916 0.989192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.54 7.88194 513.649 3984.73 33.8564 3995.3 +EDGE_SE3:QUAT 179 180 -0.20636 5.02541 -0.237816 0.0424612 0.0722306 0.0393346 0.995707 1 4.81482e-20 4.81482e-20 -9.57977e-10 -6.79375e-10 -1.39528e-08 1 4.81482e-20 -9.57977e-10 -6.79375e-10 -1.39528e-08 1 -9.57977e-10 -6.79375e-10 -1.39528e-08 4070.8 17.1859 564.092 3981.67 16.6466 4071.82 +EDGE_SE3:QUAT 180 181 -0.0150107 5.24915 -0.356364 -0.00675137 -0.138526 0.0681209 0.98799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4316.93 38.5973 -1170.07 3927.76 -51.1592 4298.55 +EDGE_SE3:QUAT 181 182 -0.0702591 4.83655 0.273411 0.254933 0.0860507 0.096444 0.958281 1 3.12964e-18 3.12964e-18 1.04955e-07 2.7423e-08 -9.19377e-10 1 3.12964e-18 1.04955e-07 2.7423e-08 -9.19377e-10 1 1.04955e-07 2.7423e-08 -9.19377e-10 3762.47 33.7694 329.707 4002.26 26.7645 3985.23 +EDGE_SE3:QUAT 182 183 -0.052219 5.14599 -0.0984045 -0.0819551 0.130807 0.0401517 0.987198 1 1.20371e-20 1.20371e-20 -9.74946e-10 5.32221e-10 -7.10828e-09 1 1.20371e-20 -9.74946e-10 5.32221e-10 -7.10828e-09 1 -9.74946e-10 5.32221e-10 -7.10828e-09 4278.1 -37.4056 1145.82 3928.33 -10.8967 4298.52 +EDGE_SE3:QUAT 183 184 0.121144 5.42878 0.0655772 -0.011158 0.00866244 0.0450676 0.998884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.91 -0.338082 75.1258 3999.63 1.71516 3993.29 +EDGE_SE3:QUAT 184 185 -0.145709 5.19004 0.261559 -0.0972112 0.0657865 0.248644 0.961456 1 9.62965e-19 9.62965e-19 2.13391e-08 9.70935e-09 -5.14665e-08 1 9.62965e-19 2.13391e-08 9.70935e-09 -5.14665e-08 1 2.13391e-08 9.70935e-09 -5.14665e-08 4106.86 5.23023 776.031 3964.16 94.2384 3897.37 +EDGE_SE3:QUAT 185 186 0.0634827 5.52941 0.242054 -0.135037 -0.0256284 0.172833 0.975314 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3926.48 -12.1415 80.7417 3998 15.518 3879.94 +EDGE_SE3:QUAT 186 187 -0.131337 5.10194 0.0121111 0.0599108 0.0641797 0.199699 0.975916 1 2.40741e-19 2.40741e-19 2.43154e-08 1.92935e-08 -1.44382e-10 1 2.40741e-19 2.43154e-08 1.92935e-08 -1.44382e-10 1 2.43154e-08 1.92935e-08 -1.44382e-10 4013.5 19.7282 341.529 3997.17 32.4313 3868.34 +EDGE_SE3:QUAT 187 188 -0.201836 5.00554 -0.0995082 0.126262 -0.0797981 0.155758 0.976437 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4115.84 -25.1602 -867.994 3953.32 -47.62 4082.56 +EDGE_SE3:QUAT 188 189 -0.106768 5.22345 0.00194544 -0.0337798 0.139648 -0.00184988 0.989623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4324.98 -25.3098 1194.48 3922.99 -18.6827 4329.53 +EDGE_SE3:QUAT 189 190 -0.170693 5.13457 -0.239454 -0.169647 -0.0738808 0.169789 0.967953 1 1.54074e-18 1.54074e-18 -5.32822e-08 -7.24637e-12 -5.32822e-08 1 1.54074e-18 -5.32822e-08 -7.24637e-12 -5.32822e-08 1 -5.32822e-08 -7.24637e-12 -5.32822e-08 3890.75 11.8256 -205.434 4001.7 -11.8265 3890.55 +EDGE_SE3:QUAT 190 191 -0.395819 5.07936 -0.118689 0.075276 -0.0386753 -0.0294223 0.995978 1 1.92593e-19 1.92593e-19 2.77121e-08 -9.73473e-10 -9.38718e-10 1 1.92593e-19 2.77121e-08 -9.73473e-10 -9.38718e-10 1 2.77121e-08 -9.73473e-10 -9.38718e-10 3996.95 -11.2666 -281.004 3995.6 6.38342 4016.15 +EDGE_SE3:QUAT 191 192 0.0756512 5.27631 -0.203461 0.0592623 0.00173384 0.123793 0.990535 1 1.92593e-19 1.92593e-19 -3.57125e-10 1.60645e-09 2.74969e-08 1 1.92593e-19 -3.57125e-10 1.60645e-09 2.74969e-08 1 -3.57125e-10 1.60645e-09 2.74969e-08 3987.1 -2.91721 -73.4692 3999.35 -6.30882 3939.85 +EDGE_SE3:QUAT 192 193 -0.148301 5.13324 0.123038 -0.0839676 0.106465 0.184571 0.973421 1 1.92593e-19 1.92593e-19 -4.70303e-09 2.70941e-08 1.14287e-09 1 1.92593e-19 -4.70303e-09 2.70941e-08 1.14287e-09 1 -4.70303e-09 2.70941e-08 1.14287e-09 4226.65 17.263 1041.7 3940.56 83.1549 4118.59 +EDGE_SE3:QUAT 193 194 -0.483433 5.32701 0.225054 0.104586 0.170131 0.00598973 0.979837 1 9.75002e-19 9.75002e-19 -2.76199e-08 -5.64419e-08 -5.77472e-09 1 9.75002e-19 -2.76199e-08 -5.64419e-08 -5.77472e-09 1 -2.76199e-08 -5.64419e-08 -5.77472e-09 4437.69 104.618 1468.99 3898.79 86.8298 4481.3 +EDGE_SE3:QUAT 194 195 -0.31677 5.39303 0.293368 -0.0928304 0.00194706 0.153551 0.983769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.15 -9.8983 182.571 3996.56 17.6614 3913.31 +EDGE_SE3:QUAT 195 196 -0.135369 5.14315 -0.184949 0.201076 -0.0861135 -0.0150932 0.975666 1 1.92593e-19 1.92593e-19 -1.34055e-09 -2.70502e-08 5.72443e-09 1 1.92593e-19 -1.34055e-09 -2.70502e-08 5.72443e-09 1 -1.34055e-09 -2.70502e-08 5.72443e-09 3932.78 -66.8112 -623.327 3983.59 36.118 4093.59 +EDGE_SE3:QUAT 196 197 -0.165803 5.35893 -0.271544 0.00973701 0.103771 0.127468 0.986351 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4162.1 36.9993 822.596 3965.01 59.9589 4097.48 +EDGE_SE3:QUAT 197 198 0.144959 5.48418 -0.079034 -0.0159186 -0.00668171 -0.010121 0.9998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.75 0.434499 -55.3676 3999.8 0.265517 4000.36 +EDGE_SE3:QUAT 198 199 -0.301128 5.23791 0.0928514 -0.0830121 -0.0642736 0.0860294 0.990746 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.03 23.1012 -421.374 3991.69 -23.4877 4013.99 +EDGE_SE3:QUAT 199 200 -0.0867122 5.27757 -0.0665635 0.215131 -0.0359922 0.230105 0.948407 1 7.70372e-19 7.70372e-19 -5.38188e-08 -1.1086e-08 7.00463e-09 1 7.70372e-19 -5.38188e-08 -1.1086e-08 7.00463e-09 1 -5.38188e-08 -1.1086e-08 7.00463e-09 3978.59 -70.0522 -837.594 3946.25 -81.08 3951.92 +EDGE_SE3:QUAT 200 201 -0.143054 5.12167 0.412392 0.0766933 -0.124972 0.146604 0.978268 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4295.24 15.6786 -1173.5 3925.8 -67.9519 4232.8 +EDGE_SE3:QUAT 201 202 -0.191139 5.54298 0.0254931 -0.0478871 -0.0754567 -0.105598 0.990385 1 2.40741e-19 2.40741e-19 1.62841e-08 -5.10994e-10 -2.90401e-08 1 2.40741e-19 1.62841e-08 -5.10994e-10 -2.90401e-08 1 1.62841e-08 -5.10994e-10 -2.90401e-08 4099.43 0.516997 -668.113 3973.14 30.8153 4064 +EDGE_SE3:QUAT 202 203 0.0445456 5.26398 0.302903 0.0746829 0.0365647 0.192472 0.977773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.45 3.14607 106.085 4000.22 4.71034 3853.57 +EDGE_SE3:QUAT 203 204 -0.110015 5.48798 0.0654081 0.0701292 -0.0725871 -0.0106636 0.994836 1 3.85186e-19 3.85186e-19 -2.7314e-08 2.81939e-08 -3.72302e-11 1 3.85186e-19 -2.7314e-08 2.81939e-08 -3.72302e-11 1 -2.7314e-08 2.81939e-08 -3.72302e-11 4061.98 -22.5244 -577.333 3980.69 12.0094 4081.2 +EDGE_SE3:QUAT 204 205 -0.328545 5.36611 -0.0909893 0.0686756 0.0633158 0.0449201 0.994614 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.48 20.1185 469.656 3987.85 16.532 4046.27 +EDGE_SE3:QUAT 205 206 -0.200141 5.42112 -0.141061 -0.0418641 -0.0879955 0.0878889 0.991352 1 1.92593e-19 1.92593e-19 2.2177e-09 1.6147e-09 -2.78862e-08 1 1.92593e-19 2.2177e-09 1.6147e-09 -2.78862e-08 1 2.2177e-09 1.6147e-09 -2.78862e-08 4100.31 29.548 -664.296 3976.62 -37.7258 4076.42 +EDGE_SE3:QUAT 206 207 -0.169137 5.06881 -0.0954697 0.00926555 -0.0958696 -0.000987635 0.99535 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4150.78 -4.25383 -792.049 3963.28 2.56596 4151.12 +EDGE_SE3:QUAT 207 208 -0.22101 5.62372 0.0114263 -0.0548621 -0.0218366 0.219131 0.973907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.41 -0.609752 -22.0527 4000.01 3.29587 3807.37 +EDGE_SE3:QUAT 208 209 -0.312914 5.65463 0.0347459 0.0321377 -0.0460741 0.126827 0.990333 1 1.20371e-20 1.20371e-20 6.9083e-09 8.66435e-10 -3.67046e-10 1 1.20371e-20 6.9083e-09 8.66435e-10 -3.67046e-10 1 6.9083e-09 8.66435e-10 -3.67046e-10 4037.75 0.740553 -411.555 3989.55 -25.644 3977.54 +EDGE_SE3:QUAT 209 210 -0.015326 5.50782 0.0262791 -0.112354 0.0483333 0.0687902 0.990105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.93 -23.6975 474.708 3985.28 9.02744 4036.5 +EDGE_SE3:QUAT 210 211 -0.400758 5.7178 -0.406284 -0.0273461 0.131653 0.101789 0.985677 1 1.95602e-19 1.95602e-19 -3.22567e-10 3.63588e-10 -2.79003e-08 1 1.95602e-19 -3.22567e-10 3.63588e-10 -2.79003e-08 1 -3.22567e-10 3.63588e-10 -2.79003e-08 4299.46 29.0161 1140.74 3930.59 56.6097 4261.01 +EDGE_SE3:QUAT 211 212 -0.625074 5.59709 0.409066 0.282436 0.0187789 0.0789193 0.95585 1 3.08149e-18 3.08149e-18 1.06147e-07 8.49027e-09 -3.00621e-09 1 3.08149e-18 1.06147e-07 8.49027e-09 -3.00621e-09 1 1.06147e-07 8.49027e-09 -3.00621e-09 3682.72 -30.4968 -120.921 3997.09 -8.20168 3976.88 +EDGE_SE3:QUAT 212 213 -0.354407 5.56588 -0.0924738 0.0200684 -0.207977 -0.0472692 0.976785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4770.41 -88.1244 -1919.43 3837.02 91.9262 4763.09 +EDGE_SE3:QUAT 213 214 -0.0193132 5.39542 0.0900524 -0.155925 0.136409 0.106246 0.972518 1 1.54074e-18 1.54074e-18 -6.02565e-08 5.0557e-08 -2.15043e-09 1 1.54074e-18 -6.02565e-08 5.0557e-08 -2.15043e-09 1 -6.02565e-08 5.0557e-08 -2.15043e-09 4315.23 -68.2277 1349.48 3904.23 -5.41793 4367.32 +EDGE_SE3:QUAT 214 215 0.0456187 5.81754 0.00850447 0.00274958 0.105079 -0.0264341 0.994109 1 1.83671e-25 1.83671e-25 -2.75543e-11 7.32952e-13 -2.91245e-12 1 1.83671e-25 -2.75543e-11 7.32952e-13 -2.91245e-12 1 -2.75543e-11 7.32952e-13 -2.91245e-12 4182.66 -6.05403 874.151 3955.97 -12.1384 4179.9 +EDGE_SE3:QUAT 215 216 -0.0703799 5.79631 -0.112912 0.121981 0.0135969 0.0402365 0.991623 1 1.92593e-19 1.92593e-19 2.75247e-08 1.1752e-09 9.46532e-11 1 1.92593e-19 2.75247e-08 1.1752e-09 9.46532e-11 1 2.75247e-08 1.1752e-09 9.46532e-11 3940.95 1.72324 47.831 3999.97 0.72073 3993.99 +EDGE_SE3:QUAT 216 217 0.174997 5.43972 -0.245783 -0.0895063 -0.148653 0.0780455 0.981733 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4272.85 99.9771 -1146.74 3941.49 -97.9732 4280.53 +EDGE_SE3:QUAT 217 218 -0.48206 5.79064 0.119992 -0.024721 0.0487622 0.101207 0.993362 1 1.92593e-19 1.92593e-19 -1.47084e-09 4.04152e-10 -2.77212e-08 1 1.92593e-19 -1.47084e-09 4.04152e-10 -2.77212e-08 1 -1.47084e-09 4.04152e-10 -2.77212e-08 4040.69 1.04876 417.667 3989.31 20.5345 4002.17 +EDGE_SE3:QUAT 218 219 -0.312286 5.37765 -0.0203698 -0.0224934 -0.00518081 0.134127 0.990695 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.94 -0.0816995 -4.54367 4000 0.529309 3928.01 +EDGE_SE3:QUAT 219 220 -0.162626 5.4538 -0.0654228 0.0458903 0.026477 0.0637256 0.99656 1 1.92593e-19 1.92593e-19 5.64255e-10 1.3597e-09 2.76866e-08 1 1.92593e-19 5.64255e-10 1.3597e-09 2.76866e-08 1 5.64255e-10 1.3597e-09 2.76866e-08 3999.19 4.56366 175.14 3998.41 5.79931 3991.37 +EDGE_SE3:QUAT 220 221 -0.113658 5.73669 0.0694969 0.0443727 0.0131596 -0.00298448 0.998924 1 4.81482e-20 4.81482e-20 -1.38678e-08 2.50828e-11 -1.85643e-10 1 4.81482e-20 -1.38678e-08 2.50828e-11 -1.85643e-10 1 -1.38678e-08 2.50828e-11 -1.85643e-10 3994.96 2.36663 106.619 3999.29 0.0282317 4002.8 +EDGE_SE3:QUAT 221 222 0.0993246 5.74857 -0.0249915 0.0238557 -0.126245 0.233802 0.963758 1 7.52316e-22 7.52316e-22 1.72804e-09 4.22409e-10 -2.20776e-10 1 7.52316e-22 1.72804e-09 4.22409e-10 -2.20776e-10 1 1.72804e-09 4.22409e-10 -2.20776e-10 4255.84 82.244 -1048.95 3955.14 -133.797 4039.46 +EDGE_SE3:QUAT 222 223 -0.256878 5.52372 -0.0844406 0.0716174 0.126016 0.0895846 0.985376 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4193.54 69.3881 950.678 3957.32 72.6548 4181.95 +EDGE_SE3:QUAT 223 224 -0.125363 5.64962 0.170865 -0.0100339 -0.056949 0.0174462 0.998174 1 4.81482e-20 4.81482e-20 -2.5957e-10 1.38521e-08 1.6777e-10 1 4.81482e-20 -2.5957e-10 1.38521e-08 1.6777e-10 1 -2.5957e-10 1.38521e-08 1.6777e-10 4051.44 3.74185 -458.331 3987.23 -4.91388 4050.63 +EDGE_SE3:QUAT 224 225 0.15603 6.0776 0.00784151 0.092323 0.0353535 0.0369001 0.994417 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3980.03 11.2986 238.634 3997.07 6.31934 4008.67 +EDGE_SE3:QUAT 225 226 -0.235475 5.97387 0.0932511 0.0599837 -0.0769709 -0.0531772 0.993806 1 1.92593e-19 1.92593e-19 2.78695e-08 -1.75783e-09 -1.94953e-09 1 1.92593e-19 2.78695e-08 -1.75783e-09 -1.94953e-09 1 2.78695e-08 -1.75783e-09 -1.94953e-09 4068.33 -24.929 -581.391 3981.45 23.7737 4071.41 +EDGE_SE3:QUAT 226 227 -0.167287 5.46253 -0.000331261 -0.204968 -0.0703756 -0.0222799 0.975981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3917.78 61.8514 -592.2 3982.1 -19.8145 4083.84 +EDGE_SE3:QUAT 227 228 -0.282642 6.17386 -0.119759 0.0356378 0.133156 0.0269546 0.990087 1 4.81482e-20 4.81482e-20 1.42316e-08 5.40561e-10 1.87721e-09 1 4.81482e-20 1.42316e-08 5.40561e-10 1.87721e-09 1 1.42316e-08 5.40561e-10 1.87721e-09 4285.39 35.7459 1116.38 3932.82 33.9564 4287.56 +EDGE_SE3:QUAT 228 229 -0.160985 5.71219 -0.443924 -0.0267238 0.0712861 0.0898933 0.993037 1 1.20371e-20 1.20371e-20 -6.96747e-09 -6.0968e-10 -5.25281e-10 1 1.20371e-20 -6.96747e-09 -6.0968e-10 -5.25281e-10 1 -6.96747e-09 -6.0968e-10 -5.25281e-10 4086.16 3.3647 603.334 3978.25 25.4126 4056.69 +EDGE_SE3:QUAT 229 230 -0.583371 5.51949 -0.292225 0.171337 0.0167288 0.0351511 0.984443 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3883.21 2.71048 56.9106 4000 0.890987 3995.69 +EDGE_SE3:QUAT 230 231 0.0175421 5.94857 0.219256 0.0966309 -0.0499942 0.115145 0.987373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.59 -17.5429 -526.867 3981.47 -24.7093 4014.91 +EDGE_SE3:QUAT 231 232 -0.254754 6.22931 0.393475 -0.0204513 -0.0691517 0.0401465 0.996588 1 1.20371e-20 1.20371e-20 -6.97932e-09 -3.03529e-10 4.70673e-10 1 1.20371e-20 -6.97932e-09 -3.03529e-10 4.70673e-10 1 -6.97932e-09 -3.03529e-10 4.70673e-10 4072.66 10.4295 -550.346 3982.13 -13.8393 4067.89 +EDGE_SE3:QUAT 232 233 0.0655856 5.89454 -0.250337 0.0539658 -0.0457643 0.00115101 0.997493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.91 -10.0809 -367.94 3991.77 2.51798 4033.56 +EDGE_SE3:QUAT 233 234 -0.30234 5.49689 0.0338909 0.127149 -0.00943793 -0.05297 0.990423 1 8.18708e-19 8.18708e-19 5.48726e-08 -5.60484e-09 -1.33974e-08 1 8.18708e-19 5.48726e-08 -5.60484e-09 -1.33974e-08 1 5.48726e-08 -5.60484e-09 -1.33974e-08 3935.16 2.16719 6.43942 3999.93 -0.900844 3988.6 +EDGE_SE3:QUAT 234 235 -0.0243212 5.93523 -0.256443 -0.0272873 -0.0649283 0.0873266 0.993687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4056.22 14.9139 -490.383 3986.69 -24.3164 4028.69 +EDGE_SE3:QUAT 235 236 0.016278 5.65294 -0.396578 0.214145 0.0624148 -0.0368945 0.974107 1 7.70372e-19 7.70372e-19 5.46291e-08 -4.22714e-10 4.04126e-09 1 7.70372e-19 5.46291e-08 -4.22714e-10 4.04126e-09 1 5.46291e-08 -4.22714e-10 4.04126e-09 3895.32 61.4892 566.785 3982.63 13.6187 4073.31 +EDGE_SE3:QUAT 236 237 -0.262817 5.78737 0.0409484 0.238907 0.128685 0.0739322 0.959634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3900.48 105.856 741.17 3992.57 87.2358 4106.92 +EDGE_SE3:QUAT 237 238 -0.325102 5.92616 -0.25773 0.145222 0.0500467 0.154887 0.975918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3916.21 2.61915 110.816 4000.55 2.57048 3904.61 +EDGE_SE3:QUAT 238 239 -0.312095 5.84901 0.169865 0.0536566 -0.0130145 0.0763489 0.995551 1 4.81482e-20 4.81482e-20 -1.3826e-08 -1.03536e-09 2.90942e-10 1 4.81482e-20 -1.3826e-08 -1.03536e-09 2.90942e-10 1 -1.3826e-08 -1.03536e-09 2.90942e-10 3994.18 -3.94033 -151.855 3998.28 -6.01937 3982.38 +EDGE_SE3:QUAT 239 240 -0.270969 5.85949 0.00883322 0.0722076 0.13219 0.0638595 0.986526 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4232.85 69.2537 1039.29 3946.71 67.668 4237.39 +EDGE_SE3:QUAT 240 241 0.014131 5.75934 -0.0662322 -0.176187 -0.0303449 -0.0390338 0.983114 1 8.1852e-19 8.1852e-19 5.43821e-08 -1.5106e-08 -4.74671e-09 1 8.1852e-19 5.43821e-08 -1.5106e-08 -4.74671e-09 1 5.43821e-08 -1.5106e-08 -4.74671e-09 3900.2 28.7608 -313.659 3993.63 0.709206 4018.27 +EDGE_SE3:QUAT 241 242 -0.14536 6.13459 -0.0940673 -0.0417564 0.145723 0.0880877 0.984511 1 2.0463e-19 2.0463e-19 1.15294e-08 9.47055e-11 2.97075e-08 1 2.0463e-19 1.15294e-08 9.47055e-11 2.97075e-08 1 1.15294e-08 9.47055e-11 2.97075e-08 4375.68 18.7051 1295.02 3911.67 46.1444 4351.62 +EDGE_SE3:QUAT 242 243 -0.180294 5.86854 -0.241483 0.0546807 -0.0542666 0.166982 0.982946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4057.06 0.505423 -530.405 3982.63 -43.1871 3957.49 +EDGE_SE3:QUAT 243 244 -0.363265 5.61547 0.106496 0.0712055 -0.124645 0.091276 0.985425 1 4.81482e-20 4.81482e-20 1.41765e-08 1.08361e-09 -1.93703e-09 1 4.81482e-20 1.41765e-08 1.08361e-09 -1.93703e-09 1 1.41765e-08 1.08361e-09 -1.93703e-09 4274.76 -7.1337 -1125.8 3929.61 -29.65 4261.71 +EDGE_SE3:QUAT 244 245 -0.128275 6.26146 0.127475 0.0576542 0.0317195 0.0755676 0.994967 1 1.92593e-19 1.92593e-19 -6.23929e-10 -1.71943e-09 -2.76498e-08 1 1.92593e-19 -6.23929e-10 -1.71943e-09 -2.76498e-08 1 -6.23929e-10 -1.71943e-09 -2.76498e-08 3996.45 6.50137 198.653 3998.1 7.8286 3986.91 +EDGE_SE3:QUAT 245 246 -0.255626 5.72931 0.176481 -0.160298 -0.0685653 0.167975 0.970251 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3902.34 10.2497 -190.951 4001.32 -10.3134 3892.26 +EDGE_SE3:QUAT 246 247 -0.191182 5.80532 -0.175629 0.042282 0.00121243 0.0188275 0.998928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.85 -0.0647801 0.129153 4000 -0.0287953 3998.58 +EDGE_SE3:QUAT 247 248 -0.0639874 6.03937 -0.47701 0.0681323 -0.162795 0.0498548 0.983041 1 4.81482e-20 4.81482e-20 -1.44475e-08 -4.28609e-10 2.46312e-09 1 4.81482e-20 -1.44475e-08 -4.28609e-10 2.46312e-09 1 -1.44475e-08 -4.28609e-10 2.46312e-09 4464.6 -27.4628 -1471.78 3889.3 3.89456 4473.22 +EDGE_SE3:QUAT 248 249 -0.683516 5.97041 -0.058421 -0.0158282 0.264401 -0.0173917 0.964126 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5395.12 -80.7227 2744.75 3725.03 -80.7869 5394.92 +EDGE_SE3:QUAT 249 250 -0.024466 6.51481 -0.26734 -0.117876 0.0590273 -0.0951951 0.986691 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3969.79 -21.1898 324.151 3996.39 -19.091 3989.12 +EDGE_SE3:QUAT 250 251 -0.343018 5.91159 0.217132 0.106276 0.0261648 0.0172184 0.993843 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3963.26 9.62873 184.198 3998.19 2.96497 4007.26 +EDGE_SE3:QUAT 251 252 -0.10454 6.32084 0.104902 0.00783366 0.0344863 0.0324477 0.998848 1 5.11575e-20 5.11575e-20 -3.94506e-09 -2.55135e-10 -1.40119e-08 1 5.11575e-20 -3.94506e-09 -2.55135e-10 -1.40119e-08 1 -3.94506e-09 -2.55135e-10 -1.40119e-08 4018.37 1.99332 273.479 3995.43 4.69312 4014.4 +EDGE_SE3:QUAT 252 253 -0.309304 6.1512 -0.00233222 -0.136485 -0.00141752 0.0413556 0.989778 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3926.15 -5.33315 55.8274 3999.62 1.53937 3993.82 +EDGE_SE3:QUAT 253 254 -0.339203 6.23377 0.0520339 0.0351033 0.129114 0.1176 0.984006 1 2.40741e-19 2.40741e-19 -1.04509e-08 -2.9132e-08 1.66961e-10 1 2.40741e-19 -1.04509e-08 -2.9132e-08 1.66961e-10 1 -1.04509e-08 -2.9132e-08 1.66961e-10 4234.37 65.6358 1007.8 3951.32 81.2091 4183.98 +EDGE_SE3:QUAT 254 255 -0.305297 6.36827 0.0970656 0.124251 0.0268314 -0.0360174 0.991234 1 7.82409e-19 7.82409e-19 5.53416e-08 5.30296e-09 1.08914e-09 1 7.82409e-19 5.53416e-08 5.30296e-09 1.08914e-09 1 5.53416e-08 5.30296e-09 1.08914e-09 3955.48 16.6639 263.506 3995.39 -2.08605 4012.05 +EDGE_SE3:QUAT 255 256 -0.347856 5.99615 0.0901372 0.00456855 -0.00788824 -0.058735 0.998232 1 7.52316e-22 7.52316e-22 1.73185e-09 -1.02033e-10 -1.26608e-11 1 7.52316e-22 1.73185e-09 -1.02033e-10 -1.26608e-11 1 1.73185e-09 -1.02033e-10 -1.26608e-11 4000.8 -0.213847 -59.5761 3999.79 1.72218 3987.09 +EDGE_SE3:QUAT 256 257 -0.322463 6.42515 0.0339395 0.0120451 -0.0592462 0.00356815 0.998164 1 1.88079e-22 1.88079e-22 5.18112e-11 -1.02244e-11 -8.71902e-10 1 1.88079e-22 5.18112e-11 -1.02244e-11 -8.71902e-10 1 5.18112e-11 -1.02244e-11 -8.71902e-10 4056.28 -2.69417 -480.274 3985.94 0.144831 4056.81 +EDGE_SE3:QUAT 257 258 -0.536965 6.03317 0.468718 -0.0697162 -0.0679867 0.0413441 0.994388 1 4.81482e-20 4.81482e-20 8.57197e-10 1.05953e-09 -1.39109e-08 1 4.81482e-20 8.57197e-10 1.05953e-09 -1.39109e-08 1 8.57197e-10 1.05953e-09 -1.39109e-08 4044.68 22.3048 -510.701 3985.56 -17.786 4057.28 +EDGE_SE3:QUAT 258 259 -0.406777 6.1681 -0.0936252 -0.0163185 0.0515036 0.0738443 0.995805 1 2.0463e-19 2.0463e-19 -5.46026e-09 -7.46491e-10 2.74233e-08 1 2.0463e-19 -5.46026e-09 -7.46491e-10 2.74233e-08 1 -5.46026e-09 -7.46491e-10 2.74233e-08 4044.04 1.36201 427.176 3988.86 15.2643 4023.3 +EDGE_SE3:QUAT 259 260 -0.757978 6.40952 -0.311826 0.0337691 0.049483 0.0868797 0.994416 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.16 10.3438 357.936 3993.04 17.0255 4001.53 +EDGE_SE3:QUAT 260 261 -0.468945 5.83799 -0.0920029 0.0875296 0.104046 0.104558 0.98518 1 1.92593e-19 1.92593e-19 -2.29751e-09 -3.07858e-09 -2.77732e-08 1 1.92593e-19 -2.29751e-09 -3.07858e-09 -2.77732e-08 1 -2.29751e-09 -3.07858e-09 -2.77732e-08 4093.07 54.203 716.274 3977.45 56.9522 4079.99 +EDGE_SE3:QUAT 261 262 -0.245229 5.98632 0.0188235 -0.276635 0.0411815 0.0537927 0.958584 1 4.81482e-20 4.81482e-20 8.85175e-10 -3.80287e-09 1.33993e-08 1 4.81482e-20 8.85175e-10 -3.80287e-09 1.33993e-08 1 8.85175e-10 -3.80287e-09 1.33993e-08 3747.45 -68.8177 466.676 3987.5 -6.38393 4041.99 +EDGE_SE3:QUAT 262 263 -0.640393 6.06467 0.03308 -0.00805911 -0.0431796 0.101811 0.993834 1 3.00927e-21 3.00927e-21 -3.45996e-09 -3.58119e-10 1.4147e-10 1 3.00927e-21 -3.45996e-09 -3.58119e-10 1.4147e-10 1 -3.45996e-09 -3.58119e-10 1.4147e-10 4027.13 5.64999 -332.182 3993.71 -17.3092 3985.93 +EDGE_SE3:QUAT 263 264 -0.114828 6.18771 -0.116027 0.122006 -0.00661716 0.176583 0.976673 1 1.92593e-19 1.92593e-19 2.71831e-08 4.72631e-09 -1.33897e-09 1 1.92593e-19 2.71831e-08 4.72631e-09 -1.33897e-09 1 2.71831e-08 4.72631e-09 -1.33897e-09 3961.63 -19.6093 -301.606 3991.24 -31.4765 3896.45 +EDGE_SE3:QUAT 264 265 0.00817974 6.29367 0.112753 -0.0898623 0.0456934 0.281504 0.95425 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4060.87 1.92142 620.077 3975.9 92.1532 3776.19 +EDGE_SE3:QUAT 265 266 -0.426388 6.11575 -0.196116 0.021673 -0.171054 0.0875365 0.981126 1 7.52316e-22 7.52316e-22 -1.80979e-09 -1.57203e-10 3.17593e-10 1 7.52316e-22 -1.80979e-09 -1.57203e-10 3.17593e-10 1 -1.80979e-09 -1.57203e-10 3.17593e-10 4516.8 50.2296 -1530.93 3885.2 -70.7338 4488.03 +EDGE_SE3:QUAT 266 267 -0.134459 6.39244 -0.267376 0.0136094 0.0127574 0.156171 0.987554 1 3.00927e-21 3.00927e-21 3.42684e-09 5.43054e-10 2.75191e-11 1 3.00927e-21 3.42684e-09 5.43054e-10 2.75191e-11 1 3.42684e-09 5.43054e-10 2.75191e-11 4000.57 0.807142 73.2445 3999.79 4.99539 3903.76 +EDGE_SE3:QUAT 267 268 -0.182552 5.93951 0.162018 -0.151801 -0.0375995 -0.07793 0.984616 1 7.70372e-19 7.70372e-19 5.49781e-08 -3.53644e-09 -3.28427e-09 1 7.70372e-19 5.49781e-08 -3.53644e-09 -3.28427e-09 1 5.49781e-08 -3.53644e-09 -3.28427e-09 3953.63 32.0426 -432.025 3987.1 9.57152 4021.51 +EDGE_SE3:QUAT 268 269 -0.0619914 6.40439 -0.29027 -0.153364 0.074268 0.100649 0.980221 1 7.70372e-19 7.70372e-19 5.54113e-08 4.21605e-09 5.65572e-09 1 7.70372e-19 5.54113e-08 4.21605e-09 5.65572e-09 1 5.54113e-08 4.21605e-09 5.65572e-09 4049.5 -47.5958 772.413 3962.93 13.5492 4103.06 +EDGE_SE3:QUAT 269 270 -0.152431 6.64759 0.223066 0.0325306 0.164991 0.256526 0.951795 1 1.92593e-19 1.92593e-19 -2.74866e-08 -8.10536e-09 -3.5947e-09 1 1.92593e-19 -2.74866e-08 -8.10536e-09 -3.5947e-09 1 -2.74866e-08 -8.10536e-09 -3.5947e-09 4300.9 164.146 1153.17 3974.05 193.105 4041.91 +EDGE_SE3:QUAT 270 271 -0.320611 6.13611 -0.0688432 -0.0683907 -0.0176526 0.0897238 0.993459 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.2 1.59891 -65.4955 3999.93 -1.97318 3968.71 +EDGE_SE3:QUAT 271 272 -0.161742 6.09741 0.362319 0.150356 -0.196376 -0.0083385 0.968896 1 4.81482e-20 4.81482e-20 2.75087e-09 -2.48555e-09 -1.4486e-08 1 4.81482e-20 2.75087e-09 -2.48555e-09 -1.4486e-08 1 2.75087e-09 -2.48555e-09 -1.4486e-08 4535.31 -187.381 -1701.96 3886.94 167.16 4625.46 +EDGE_SE3:QUAT 272 273 0.0583132 6.43807 -0.108293 0.105035 -0.0943168 0.190406 0.971503 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4186.36 1.08586 -988.429 3943.77 -77.55 4085.47 +EDGE_SE3:QUAT 273 274 -0.472193 6.38896 -0.0533209 0.052695 0.183225 0.074302 0.978842 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4523.77 119.991 1557.79 3892.39 123.466 4512.79 +EDGE_SE3:QUAT 274 275 -0.236899 6.49557 0.16961 -0.0561488 -0.00269105 0.0513777 0.997096 1 4.81482e-20 4.81482e-20 -4.29241e-11 7.78933e-10 -1.38375e-08 1 4.81482e-20 -4.29241e-11 7.78933e-10 -1.38375e-08 1 -4.29241e-11 7.78933e-10 -1.38375e-08 3987.4 -0.694384 13.1424 3999.96 0.63533 3989.45 +EDGE_SE3:QUAT 275 276 -0.716297 6.12593 -0.215297 0.163982 -0.0226701 -0.0154186 0.986082 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3897.59 -10.9877 -144.359 3999.09 2.46827 4004.2 +EDGE_SE3:QUAT 276 277 0.0164821 6.33045 -0.0342758 0.186898 0.00710621 -0.00430228 0.982344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3861.28 6.12117 63.3351 3999.77 0.132403 4000.93 +EDGE_SE3:QUAT 277 278 -0.286431 6.53894 -0.120103 -0.0327511 -0.0400416 0.147169 0.987758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.5 7.82758 -253.136 3997.19 -18.07 3929.16 +EDGE_SE3:QUAT 278 279 -0.246005 6.25946 -0.195018 0.0434559 0.198551 0.146494 0.968106 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4569.95 193.274 1627.57 3906.06 206.431 4491.66 +EDGE_SE3:QUAT 279 280 -0.0611148 6.42381 -0.263094 -0.136375 0.0853769 -0.0500129 0.985704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.34 -47.534 589.798 3984.15 -34.1035 4074.72 +EDGE_SE3:QUAT 280 281 -0.333064 6.38048 -0.314865 -0.0174058 -0.0260401 0.0667273 0.99728 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.1 2.61819 -193.31 3997.85 -6.57296 3991.5 +EDGE_SE3:QUAT 281 282 -0.189917 6.3211 0.1137 -0.0444407 0.052928 -0.0704207 0.99512 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.65 -12.5463 384.4 3991.9 -15.9793 4016.71 +EDGE_SE3:QUAT 282 283 -0.0766213 6.47139 -0.0208244 0.046659 0.112464 -0.0286949 0.992145 1 1.92593e-19 1.92593e-19 5.17337e-10 2.75442e-08 -1.14475e-09 1 1.92593e-19 5.17337e-10 2.75442e-08 -1.14475e-09 1 5.17337e-10 2.75442e-08 -1.14475e-09 4207.73 15.9392 955.315 3947.94 -0.201169 4213.15 +EDGE_SE3:QUAT 283 284 -0.45883 6.34663 0.0169473 -0.118857 -0.0320982 0.23618 0.963878 1 1.92593e-19 1.92593e-19 2.67488e-08 6.57444e-09 7.37522e-10 1 1.92593e-19 2.67488e-08 6.57444e-09 7.37522e-10 1 2.67488e-08 6.57444e-09 7.37522e-10 3942.32 -12.7474 90.9676 3997.19 25.1611 3775.7 +EDGE_SE3:QUAT 284 285 -0.327711 6.80639 0.0518325 0.0379961 -0.125591 0.269567 0.954 1 2.70834e-20 2.70834e-20 1.02854e-08 2.89902e-09 -1.36818e-09 1 2.70834e-20 1.02854e-08 2.89902e-09 -1.36818e-09 1 1.02854e-08 2.89902e-09 -1.36818e-09 4264.53 92.6047 -1074.97 3956.88 -155.665 3979.64 +EDGE_SE3:QUAT 285 286 -0.290724 6.01131 -0.0293298 -0.150219 0.0397721 0.190463 0.969318 1 3.08149e-18 3.08149e-18 1.08989e-07 1.92527e-08 1.02245e-08 1 3.08149e-18 1.08989e-07 1.92527e-08 1.02245e-08 1 1.08989e-07 1.92527e-08 1.02245e-08 4006.89 -34.4694 636.806 3970.02 54.8883 3952.05 +EDGE_SE3:QUAT 286 287 -0.424432 6.93194 -0.0643508 0.0077367 -0.148372 -0.0577184 0.987216 1 1.20371e-20 1.20371e-20 -7.16025e-09 4.5499e-10 1.06166e-09 1 1.20371e-20 -7.16025e-09 4.5499e-10 1.06166e-09 1 -7.16025e-09 4.5499e-10 1.06166e-09 4368.65 -39.541 -1269.51 3916.06 49.5963 4355.56 +EDGE_SE3:QUAT 287 288 -0.297208 6.12743 -0.0431291 0.0418556 -0.118225 0.136477 0.982672 1 1.20371e-20 1.20371e-20 -7.03686e-09 -9.31558e-10 8.95077e-10 1 1.20371e-20 -7.03686e-09 -9.31558e-10 8.95077e-10 1 -7.03686e-09 -9.31558e-10 8.95077e-10 4248.11 27.6537 -1041.91 3941.7 -67.0703 4180.62 +EDGE_SE3:QUAT 288 289 -0.525706 6.24599 0.0182872 -0.0214775 -0.0727135 0.094236 0.992659 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4074.54 17.4436 -558.195 3982.79 -29.7389 4040.87 +EDGE_SE3:QUAT 289 290 -0.100283 6.65924 -0.0202723 0.022602 0.0249507 0.356726 0.933602 1 3.09352e-18 3.09352e-18 6.86665e-09 6.20161e-09 1.03687e-07 1 3.09352e-18 6.86665e-09 6.20161e-09 1.03687e-07 1 6.86665e-09 6.20161e-09 1.03687e-07 3998.75 1.70789 73.9815 4000.43 5.11386 3491.78 +EDGE_SE3:QUAT 290 291 -0.447946 6.38099 0.0912921 -0.145131 -0.0710885 0.0181253 0.986689 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.79 40.8442 -526.599 3986.02 -20.6369 4066.73 +EDGE_SE3:QUAT 291 292 -0.437648 6.42267 -0.291973 -0.00388182 0.189311 0.143122 0.971423 1 7.70372e-19 7.70372e-19 -1.08632e-08 -3.14328e-09 -5.79324e-08 1 7.70372e-19 -1.08632e-08 -3.14328e-09 -5.79324e-08 1 -1.08632e-08 -3.14328e-09 -5.79324e-08 4602.68 137.504 1665.92 3884.05 160.554 4520.81 +EDGE_SE3:QUAT 292 293 -0.686808 6.39745 -0.41544 0.186031 0.159142 0.0318743 0.969046 1 7.70372e-19 7.70372e-19 5.61079e-08 5.29802e-09 7.80591e-09 1 7.70372e-19 5.61079e-08 5.29802e-09 7.80591e-09 1 5.61079e-08 5.29802e-09 7.80591e-09 4198.79 154.498 1211.67 3947.23 129.902 4333.15 +EDGE_SE3:QUAT 293 294 -0.345817 6.58243 -0.489054 0.0883403 0.0529236 0.234 0.966767 1 7.70372e-19 7.70372e-19 -3.36319e-10 -5.71733e-09 -5.36869e-08 1 7.70372e-19 -3.36319e-10 -5.71733e-09 -5.36869e-08 1 -3.36319e-10 -5.71733e-09 -5.36869e-08 3971.64 5.95327 145.498 4000.87 7.30499 3783.83 +EDGE_SE3:QUAT 294 295 -0.264623 6.66272 -0.0729631 0.101141 -0.084807 -0.0843738 0.987653 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.44 -39.6091 -567.201 3985.52 37.1206 4049.88 +EDGE_SE3:QUAT 295 296 -0.104761 6.82995 -0.176551 0.12981 0.0331192 0.0271146 0.990615 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3944.22 13.6563 216.679 3997.77 5.27831 4008.68 +EDGE_SE3:QUAT 296 297 -0.494166 6.45357 0.0678106 -0.156805 -0.0424242 0.0534587 0.985269 1 7.70372e-19 7.70372e-19 5.47807e-08 3.56523e-09 -1.30616e-09 1 7.70372e-19 5.47807e-08 3.56523e-09 -1.30616e-09 1 5.47807e-08 3.56523e-09 -1.30616e-09 3914.06 16.2947 -226.962 3998.33 -8.88523 4000.98 +EDGE_SE3:QUAT 297 298 -0.267864 6.52842 -0.529777 -0.068828 0.105991 0.104921 0.986418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4199.51 -3.9379 960.124 3947.01 35.7677 4174.42 +EDGE_SE3:QUAT 298 299 -0.578899 6.85439 -0.138608 0.0423495 0.021802 0.0394274 0.998087 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.71 3.49249 153.722 3998.68 3.30462 3999.67 +EDGE_SE3:QUAT 299 300 -0.567463 6.7604 -0.228164 0.148728 -0.0393387 0.0183092 0.987926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3939.97 -25.408 -338.582 3993.22 3.03521 4027.11 +EDGE_SE3:QUAT 300 301 -0.37315 6.79207 -0.0907477 -0.0339715 -0.178501 -0.0911718 0.979117 1 7.82409e-19 7.82409e-19 -1.19714e-08 -5.37563e-08 1.25768e-09 1 7.82409e-19 -1.19714e-08 -5.37563e-08 1.25768e-09 1 -1.19714e-08 -5.37563e-08 1.25768e-09 4575.39 -46.6783 -1629.85 3872.1 69.4792 4546.75 +EDGE_SE3:QUAT 301 302 -0.295714 6.84785 0.0235838 0.0393751 -0.108737 -0.162999 0.979825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4139.5 -55.8467 -778.896 3974.1 76.9014 4039.43 +EDGE_SE3:QUAT 302 303 -0.179905 7.29074 0.244776 0.0766976 -0.0276323 0.20329 0.975719 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.73 -7.72673 -390.685 3988.87 -42.5475 3871.95 +EDGE_SE3:QUAT 303 304 -0.0841305 6.7189 -0.0227137 -0.0234045 -0.0157654 0.0720839 0.996999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.55 1.47278 -104.921 3999.42 -3.63892 3981.95 +EDGE_SE3:QUAT 304 305 -0.515095 6.35768 -0.131391 -0.00602015 0.0134609 0.0791989 0.99675 1 1.92593e-19 1.92593e-19 3.95453e-10 -1.06091e-10 2.76764e-08 1 1.92593e-19 3.95453e-10 -1.06091e-10 2.76764e-08 1 3.95453e-10 -1.06091e-10 2.76764e-08 4003.01 0.025757 112.448 3999.21 4.49578 3978.07 +EDGE_SE3:QUAT 305 306 -0.34483 6.94195 -0.295624 -0.120087 0.129492 -0.0945267 0.979733 1 9.62965e-19 9.62965e-19 -5.85382e-08 1.13314e-08 -3.3529e-08 1 9.62965e-19 -5.85382e-08 1.13314e-08 -3.3529e-08 1 -5.85382e-08 1.13314e-08 -3.3529e-08 4132.07 -89.0318 894.638 3968.72 -84.9819 4154.01 +EDGE_SE3:QUAT 306 307 -0.360654 6.31188 -0.289864 0.0835159 0.0351591 0.0621316 0.993946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.51 9.38011 215.246 3997.86 7.72067 3995.97 +EDGE_SE3:QUAT 307 308 -0.211023 6.70287 -0.0711932 0.00224724 0.0243177 0.0887139 0.995758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.01 1.43379 190.237 3997.86 8.45108 3977.55 +EDGE_SE3:QUAT 308 309 -0.333972 6.89795 0.0157005 0.0855836 -0.0252764 0.0504761 0.99473 1 1.92593e-19 1.92593e-19 -2.7664e-08 -1.26541e-09 9.28577e-10 1 1.92593e-19 -2.7664e-08 -1.26541e-09 9.28577e-10 1 -2.7664e-08 -1.26541e-09 9.28577e-10 3986.42 -10.4623 -251.696 3995.66 -4.95354 4005.53 +EDGE_SE3:QUAT 309 310 -0.297803 6.43858 -0.254418 0.156961 0.146888 0.0835875 0.973037 1 1.92593e-19 1.92593e-19 -3.1466e-09 -5.31722e-09 -2.78241e-08 1 1.92593e-19 -3.1466e-09 -5.31722e-09 -2.78241e-08 1 -3.1466e-09 -5.31722e-09 -2.78241e-08 4137.49 122.906 1004.46 3966.74 112.234 4208.09 +EDGE_SE3:QUAT 310 311 -0.46854 6.70652 -0.12492 0.0989375 -0.0269435 0.0473662 0.9936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3978.74 -13.1097 -268.639 3995.09 -4.381 4008.92 +EDGE_SE3:QUAT 311 312 -0.553157 6.9924 -0.209855 -0.0758408 -0.0751922 -0.115627 0.987535 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4098.61 9.55557 -708.393 3969.19 32.2552 4068.13 +EDGE_SE3:QUAT 312 313 -0.190387 6.8444 0.0548031 -0.0283058 -0.0872951 -0.0069743 0.995756 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4122.12 9.67736 -719.042 3969.44 -2.68215 4125.13 +EDGE_SE3:QUAT 313 314 -0.499322 6.72073 -0.397197 0.0780507 0.0407482 0.0206203 0.995903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.74 12.5461 305.015 3994.7 5.93248 4021.41 +EDGE_SE3:QUAT 314 315 -0.399944 7.03738 0.0820129 -0.0164481 -0.0168677 -0.00765756 0.999693 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.57 1.07691 -136.526 3998.83 0.411781 4004.42 +EDGE_SE3:QUAT 315 316 -0.365543 7.21318 0.00551926 0.106024 -0.0480461 0.0380272 0.992474 1 2.40741e-19 2.40741e-19 -2.80827e-08 1.30191e-08 1.07636e-10 1 2.40741e-19 -2.80827e-08 1.30191e-08 1.07636e-10 1 -2.80827e-08 1.30191e-08 1.07636e-10 4000.63 -21.6164 -429.617 3988.43 -1.63149 4039.81 +EDGE_SE3:QUAT 316 317 -0.363702 6.71003 -0.0816142 0.105571 -0.0295302 0.0449763 0.992955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.21 -15.0788 -289.544 3994.38 -3.91236 4012.7 +EDGE_SE3:QUAT 317 318 0.0849018 6.59515 -0.18179 -0.0194778 0.00460188 0.0698174 0.997359 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.17 -0.502788 52.7961 3999.79 2.01245 3981.19 +EDGE_SE3:QUAT 318 319 -0.146053 6.99745 -0.391504 0.00755314 0.047131 0.0332559 0.998306 1 4.81482e-20 4.81482e-20 6.48366e-10 1.49327e-10 1.3915e-08 1 4.81482e-20 6.48366e-10 1.49327e-10 1.3915e-08 1 6.48366e-10 1.49327e-10 1.3915e-08 4034.85 3.21477 376.221 3991.39 6.78113 4030.65 +EDGE_SE3:QUAT 319 320 -0.304011 6.8591 0.358295 0.0364779 0.0400911 0.233081 0.970945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.7 7.27677 196.082 3999.42 18.7376 3791.71 +EDGE_SE3:QUAT 320 321 -0.462606 7.0951 0.162486 -0.0598515 -0.0660965 -0.00283738 0.996013 1 4.70198e-23 4.70198e-23 2.88581e-11 2.62515e-11 -4.35761e-10 1 4.70198e-23 2.88581e-11 2.62515e-11 -4.35761e-10 1 2.88581e-11 2.62515e-11 -4.35761e-10 4056.28 16.4726 -536.117 3982.85 -5.61102 4070.58 +EDGE_SE3:QUAT 321 322 -0.791495 6.90249 -0.259468 -0.00653233 -0.0472339 -0.0773553 0.995863 1 4.83363e-20 4.83363e-20 -2.02024e-10 -1.38878e-08 -3.00646e-11 1 4.83363e-20 -2.02024e-10 -1.38878e-08 -3.00646e-11 1 -2.02024e-10 -1.38878e-08 -3.00646e-11 4036.28 -2.96085 -383.561 3991.12 14.8644 4012.51 +EDGE_SE3:QUAT 322 323 -0.558502 6.82855 -0.215796 -0.0965572 -0.033609 -0.00500142 0.994747 1 7.70419e-19 7.70419e-19 5.53329e-08 4.44146e-11 -1.4562e-09 1 7.70419e-19 5.53329e-08 4.44146e-11 -1.4562e-09 1 5.53329e-08 4.44146e-11 -1.4562e-09 3981.11 13.1832 -271.973 3995.56 -1.9854 4018.31 +EDGE_SE3:QUAT 323 324 -0.466523 6.87013 -0.223378 0.0840431 -0.118386 0.152975 0.977507 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4268.86 10.467 -1130.2 3930.09 -67.2846 4203.5 +EDGE_SE3:QUAT 324 325 -0.37936 6.8786 0.0721103 0.265566 -0.120595 -0.0464169 0.955394 1 3.08149e-18 3.08149e-18 1.07883e-07 -1.17166e-08 -8.81126e-09 1 3.08149e-18 1.07883e-07 -1.17166e-08 -8.81126e-09 1 1.07883e-07 -1.17166e-08 -8.81126e-09 3844.86 -108.57 -733.102 3991.74 80.7863 4118.34 +EDGE_SE3:QUAT 325 326 -0.289139 7.01799 -0.410432 0.0368893 -0.0707938 -0.0582673 0.995104 1 4.81482e-20 4.81482e-20 9.21088e-10 -6.3423e-10 -1.39357e-08 1 4.81482e-20 9.21088e-10 -6.3423e-10 -1.39357e-08 1 9.21088e-10 -6.3423e-10 -1.39357e-08 4067.39 -16.9677 -544.758 3983.17 20.5515 4059.25 +EDGE_SE3:QUAT 326 327 -0.313599 7.17681 -0.0650597 0.0650398 0.0722448 -0.0222221 0.995016 1 1.20371e-20 1.20371e-20 -5.22527e-10 -4.38113e-10 -6.98094e-09 1 1.20371e-20 -5.22527e-10 -4.38113e-10 -6.98094e-09 1 -5.22527e-10 -4.38113e-10 -6.98094e-09 4071.97 17.8964 602.88 3978.16 1.56076 4086.91 +EDGE_SE3:QUAT 327 328 -0.142028 7.36609 0.325096 -0.156272 0.00540003 0.0848131 0.984051 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3911.44 -18.6976 197.341 3996.28 9.03639 3980.35 +EDGE_SE3:QUAT 328 329 -0.432911 6.8723 -0.335111 -0.164745 -0.024037 0.0541807 0.984554 1 8.1852e-19 8.1852e-19 5.47311e-08 5.59054e-09 -1.39425e-08 1 8.1852e-19 5.47311e-08 5.59054e-09 -1.39425e-08 1 5.47311e-08 5.59054e-09 -1.39425e-08 3892.6 3.52629 -78.6362 4000.01 -1.74963 3989.42 +EDGE_SE3:QUAT 329 330 -0.374752 6.90405 -0.0921492 -0.111851 -0.0435717 0.118718 0.985645 1 2.0463e-19 2.0463e-19 2.65104e-08 1.0325e-08 4.11112e-10 1 2.0463e-19 2.65104e-08 1.0325e-08 4.11112e-10 1 2.65104e-08 1.0325e-08 4.11112e-10 3956.97 8.88961 -177.93 3999.53 -9.18755 3950.63 +EDGE_SE3:QUAT 330 331 -0.418741 7.20122 0.173939 -0.0345592 -0.0686348 0.145282 0.986402 1 4.81482e-20 4.81482e-20 -1.37863e-08 -2.10946e-09 7.75772e-10 1 4.81482e-20 -1.37863e-08 -2.10946e-09 7.75772e-10 1 -1.37863e-08 -2.10946e-09 7.75772e-10 4050.92 21.4805 -476.341 3989.33 -37.3361 3971.27 +EDGE_SE3:QUAT 331 332 -0.283408 7.27622 0.37317 0.074642 0.00801418 -0.0829709 0.99372 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.25 5.57001 136.784 3998.42 -6.2878 3977 +EDGE_SE3:QUAT 332 333 -0.0439516 7.06051 0.524772 0.098181 -0.045776 0.0552405 0.992579 1 2.40741e-19 2.40741e-19 -2.83383e-08 1.25125e-08 2.56563e-10 1 2.40741e-19 -2.83383e-08 1.25125e-08 2.56563e-10 1 -2.83383e-08 1.25125e-08 2.56563e-10 4006.74 -18.9739 -428.417 3988.14 -6.33577 4033.09 +EDGE_SE3:QUAT 333 334 -0.620351 6.80363 0.241013 -0.154046 -0.0384402 0.0862203 0.983544 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3908.87 7.12716 -136.879 3999.94 -5.19786 3974.06 +EDGE_SE3:QUAT 334 335 -0.00122861 7.13909 0.264631 0.0221875 0.0639963 -0.0980887 0.99287 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4069.31 -4.14338 538.699 3982.65 -25.5587 4032.79 +EDGE_SE3:QUAT 335 336 -0.676931 7.47576 0.234261 0.214319 -0.0232974 0.205288 0.954663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3924.07 -67.765 -678.957 3961.48 -62.6844 3939.23 +EDGE_SE3:QUAT 336 337 -0.570969 7.34148 -0.077271 0.270759 -0.0239696 0.212833 0.938518 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3866.33 -108.929 -831.179 3943.55 -66.3304 3978.38 +EDGE_SE3:QUAT 337 338 -0.639534 7.03021 0.120211 -0.0302431 0.0342447 0.023485 0.99868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.28 -3.68027 283.128 3994.96 2.50221 4017.73 +EDGE_SE3:QUAT 338 339 -0.244482 6.96866 0.100132 0.116668 0.170887 0.23407 0.949946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4140.13 153.166 926.623 4003.27 161.037 3975.42 +EDGE_SE3:QUAT 339 340 -0.590541 7.34072 -0.265232 -0.0319771 0.0965437 -0.013614 0.994722 1 2.52778e-19 2.52778e-19 1.4179e-08 -2.81392e-08 7.40228e-09 1 2.52778e-19 1.4179e-08 -2.81392e-08 7.40228e-09 1 1.4179e-08 -2.81392e-08 7.40228e-09 4146.56 -16.9886 790.762 3963.84 -13.2793 4149.91 +EDGE_SE3:QUAT 340 341 -0.22826 6.96128 -0.236419 -0.120852 -0.0595079 0.0802956 0.987627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3970.98 23.1951 -347.513 3995.33 -19.0247 4003.61 +EDGE_SE3:QUAT 341 342 -0.224573 7.50232 -0.0103397 -0.0638402 -0.0521564 0.181132 0.979998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.56 12.6343 -259.071 3998.44 -21.0586 3884.62 +EDGE_SE3:QUAT 342 343 -0.668816 7.5394 -0.126265 -0.0107754 0.0415582 0.07105 0.996548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.44 1.18655 341.232 3992.86 11.9616 4008.71 +EDGE_SE3:QUAT 343 344 -0.298319 7.38752 0.0805687 0.0741641 0.0555629 0.175585 0.980093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.82 14.1681 267.937 3998.49 21.3196 3893.5 +EDGE_SE3:QUAT 344 345 -0.29589 7.19103 -0.0827902 -0.00411101 0.00590532 -0.0312245 0.999486 1 7.52316e-22 7.52316e-22 -1.73395e-09 5.42555e-11 -9.77924e-12 1 7.52316e-22 -1.73395e-09 5.42555e-11 -9.77924e-12 1 -1.73395e-09 5.42555e-11 -9.77924e-12 4000.45 -0.117521 45.638 3999.87 -0.707643 3996.62 +EDGE_SE3:QUAT 345 346 -0.291639 6.9415 0.0866416 0.0257097 0.0748242 -0.0206336 0.996652 1 1.92593e-19 1.92593e-19 4.70853e-10 2.76646e-08 -6.34767e-10 1 1.92593e-19 4.70853e-10 2.76646e-08 -6.34767e-10 1 4.70853e-10 2.76646e-08 -6.34767e-10 4090.17 5.52741 616.326 3977.13 -3.15343 4091.11 +EDGE_SE3:QUAT 346 347 -0.574383 7.16629 -0.137711 -0.137306 0.0735968 0.0321674 0.987267 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.84 -42.5856 637.877 3976.45 -9.25299 4095.11 +EDGE_SE3:QUAT 347 348 0.0276832 7.08087 0.0455649 -0.0838124 -0.175656 -0.0792994 0.977667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4565.53 20.2712 -1651.38 3866.3 10.9589 4568.48 +EDGE_SE3:QUAT 348 349 -0.325504 7.412 -0.281264 0.0196377 0.104368 0.260761 0.959544 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4118.4 61.8865 707.048 3986.38 98.927 3847.96 +EDGE_SE3:QUAT 349 350 -0.509986 7.34314 0.0661294 0.178799 -0.192687 0.113899 0.958087 1 9.62965e-19 9.62965e-19 -6.53327e-08 1.69837e-09 4.26792e-08 1 9.62965e-19 -6.53327e-08 1.69837e-09 4.26792e-08 1 -6.53327e-08 1.69837e-09 4.26792e-08 4705.57 -118.093 -2007.26 3826.07 65.8501 4781.56 +EDGE_SE3:QUAT 350 351 -0.485624 7.1146 0.0951602 0.0266429 0.144465 0.144651 0.978517 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4298.45 89.2744 1139.23 3942.51 110.757 4217.6 +EDGE_SE3:QUAT 351 352 -0.27928 7.44962 -0.399931 0.0855313 -0.0838089 0.120269 0.985493 1 1.92593e-19 1.92593e-19 -2.85337e-09 1.81656e-09 2.7883e-08 1 1.92593e-19 -2.85337e-09 1.81656e-09 2.7883e-08 1 -2.85337e-09 1.81656e-09 2.7883e-08 4124.21 -11.9225 -798.875 3961.39 -35.3817 4095.62 +EDGE_SE3:QUAT 352 353 -0.298114 7.19215 -0.182184 0.0971547 0.209084 -0.0572264 0.971375 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4811.75 69.2886 2029.71 3819.15 46.9642 4836.4 +EDGE_SE3:QUAT 353 354 -0.222754 7.7395 -0.0274145 0.0204047 -0.19417 0.181283 0.963856 1 1.20371e-20 1.20371e-20 7.22672e-09 1.40917e-09 -1.41113e-09 1 1.20371e-20 7.22672e-09 1.40917e-09 -1.41113e-09 1 7.22672e-09 1.40917e-09 -1.41113e-09 4645.09 169.721 -1734.04 3884.61 -199.865 4515.3 +EDGE_SE3:QUAT 354 355 -0.271032 7.5927 0.0930726 0.0111529 -0.0362472 0.0598846 0.997485 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.55 0.274048 -297.817 3994.51 -8.74128 4007.71 +EDGE_SE3:QUAT 355 356 -0.412509 7.50273 -0.292252 -0.0585837 -0.176386 0.0461187 0.981493 1 4.81482e-20 4.81482e-20 -2.48319e-09 -1.1667e-09 1.44673e-08 1 4.81482e-20 -2.48319e-09 -1.1667e-09 1.44673e-08 1 -2.48319e-09 -1.1667e-09 1.44673e-08 4494.9 96.393 -1514.5 3892.69 -94.2427 4500.12 +EDGE_SE3:QUAT 356 357 -0.533048 7.50008 -0.179659 -0.105909 -0.0484356 -0.237185 0.964459 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4058.54 8.7043 -654.652 3971.51 77.5092 3878.38 +EDGE_SE3:QUAT 357 358 -0.365779 7.37409 -0.313321 -0.102741 0.00360448 -0.0735418 0.991979 1 7.52316e-22 7.52316e-22 1.2616e-10 1.72091e-09 1.77217e-10 1 7.52316e-22 1.2616e-10 1.72091e-09 1.77217e-10 1 1.2616e-10 1.72091e-09 1.77217e-10 3958.5 4.68185 -61.5656 3999.47 3.32032 3979.09 +EDGE_SE3:QUAT 358 359 -0.333859 7.58047 -0.00191225 0.0742758 -0.0484694 0.0962528 0.991398 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.36 -11.5737 -470.318 3985.53 -18.8767 4017.37 +EDGE_SE3:QUAT 359 360 -0.353983 7.40668 0.266628 0.0317904 -0.0859681 0.139884 0.985916 1 1.20371e-20 1.20371e-20 6.95616e-09 9.61903e-10 -6.44515e-10 1 1.20371e-20 6.95616e-09 9.61903e-10 -6.44515e-10 1 6.95616e-09 9.61903e-10 -6.44515e-10 4128.86 15.0709 -741.135 3969.04 -50.6035 4054.63 +EDGE_SE3:QUAT 360 361 -0.207234 7.18792 -0.350799 -0.0848538 -0.0178131 0.0126902 0.996153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.3 5.33161 -128.18 3999.08 -1.33595 4003.45 +EDGE_SE3:QUAT 361 362 -0.424558 7.33838 -0.196343 0.0770092 -0.0516341 -0.00736731 0.995665 1 2.40741e-19 2.40741e-19 -2.75647e-08 1.42426e-08 3.06632e-10 1 2.40741e-19 -2.75647e-08 1.42426e-08 3.06632e-10 1 -2.75647e-08 1.42426e-08 3.06632e-10 4017.09 -16.3905 -406.117 3990.32 6.33149 4040.59 +EDGE_SE3:QUAT 362 363 -0.561393 7.27867 0.309537 -0.0768062 0.119012 0.0890544 0.985904 1 9.62965e-19 9.62965e-19 3.2299e-08 -5.27349e-08 5.88166e-10 1 9.62965e-19 3.2299e-08 -5.27349e-08 5.88166e-10 1 3.2299e-08 -5.27349e-08 5.88166e-10 4247.97 -12.5126 1077.16 3934.71 25.3512 4239.84 +EDGE_SE3:QUAT 363 364 -0.486635 7.56633 -0.103664 0.206539 0.053709 0.0461246 0.975874 1 4.81482e-20 4.81482e-20 4.19349e-10 2.94286e-09 1.35789e-08 1 4.81482e-20 4.19349e-10 2.94286e-09 1.35789e-08 1 4.19349e-10 2.94286e-09 1.35789e-08 3849.65 27.4828 290.683 3997.82 13.8795 4011.78 +EDGE_SE3:QUAT 364 365 -0.514154 7.47371 -0.146699 0.00473699 -0.166715 0.0866776 0.982176 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4476.48 61.3211 -1460.65 3895.49 -78.53 4446.52 +EDGE_SE3:QUAT 365 366 -0.293974 7.69241 -0.184646 0.113647 -0.172526 0.323485 0.923405 1 3.08149e-18 3.08149e-18 -2.48733e-08 -1.7328e-09 1.12273e-07 1 3.08149e-18 -2.48733e-08 -1.7328e-09 1.12273e-07 1 -2.48733e-08 -1.7328e-09 1.12273e-07 4659.1 219.018 -1829.91 3897.08 -305.086 4292.2 +EDGE_SE3:QUAT 366 367 -0.321001 7.65856 -0.0380661 0.049144 0.0504261 0.0931187 0.993162 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.58 12.6147 344.022 3993.99 17.7801 3994.56 +EDGE_SE3:QUAT 367 368 -0.360642 7.68212 -0.149365 0.122914 0.0177656 -0.0885681 0.988298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3956.96 17.2009 267.129 3994.33 -11.1138 3986.01 +EDGE_SE3:QUAT 368 369 -0.832715 7.53936 0.187119 -0.0941798 0.112869 -0.0194154 0.988946 1 1.20371e-20 1.20371e-20 -7.6031e-10 7.17692e-10 -7.02914e-09 1 1.20371e-20 -7.6031e-10 7.17692e-10 -7.02914e-09 1 -7.6031e-10 7.17692e-10 -7.02914e-09 4159.51 -53.5631 904.567 3956.7 -38.672 4193.48 +EDGE_SE3:QUAT 369 370 -0.172716 7.79385 -0.0444712 -0.0827853 -0.147782 -0.0231651 0.985277 1 3.00927e-21 3.00927e-21 5.43141e-10 2.88633e-10 -3.57862e-09 1 3.00927e-21 5.43141e-10 2.88633e-10 -3.57862e-09 1 5.43141e-10 2.88633e-10 -3.57862e-09 4353.73 52.591 -1292.23 3912.91 -30.7448 4379 +EDGE_SE3:QUAT 370 371 -0.451431 7.54874 -0.139212 0.123402 -0.0581367 -0.0712095 0.98809 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.72 -23.357 -348.341 3995.09 17.8417 4009.35 +EDGE_SE3:QUAT 371 372 -0.657986 7.68795 -0.627736 0.033797 0.0357157 0.0897155 0.994753 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.49 6.17992 246.317 3996.81 11.3987 3982.86 +EDGE_SE3:QUAT 372 373 -0.34169 7.84668 -0.117384 -0.0239514 0.0913955 0.0816455 0.992173 1 1.20371e-20 1.20371e-20 -7.00763e-09 -5.54781e-10 -6.64129e-10 1 1.20371e-20 -7.00763e-09 -5.54781e-10 -6.64129e-10 1 -7.00763e-09 -5.54781e-10 -6.64129e-10 4140.97 7.58773 770.451 3965.5 29.3421 4116.6 +EDGE_SE3:QUAT 373 374 -0.34697 7.76301 -0.354946 -0.0108089 -0.103921 0.187536 0.976685 1 2.0463e-19 2.0463e-19 -1.53478e-09 -2.84463e-08 -7.09774e-10 1 2.0463e-19 -1.53478e-09 -2.84463e-08 -7.09774e-10 1 -1.53478e-09 -2.84463e-08 -7.09774e-10 4148.62 49.9827 -787.413 3972.55 -82.241 4008.41 +EDGE_SE3:QUAT 374 375 -0.0424051 7.4423 -0.276585 0.173438 0.0528754 -0.172368 0.968201 1 1.92593e-19 1.92593e-19 -4.05719e-09 -2.69923e-08 4.09215e-09 1 1.92593e-19 -4.05719e-09 -2.69923e-08 4.09215e-09 1 -4.05719e-09 -2.69923e-08 4.09215e-09 4016.44 48.5646 757.1 3960.1 -47.8861 4017.92 +EDGE_SE3:QUAT 375 376 -0.583376 7.79937 0.207895 -0.113136 -0.0154386 0.195125 0.974109 1 9.63717e-19 9.63717e-19 -2.57657e-08 -9.81142e-09 5.3479e-08 1 9.63717e-19 -2.57657e-08 -9.81142e-09 5.3479e-08 1 -2.57657e-08 -9.81142e-09 5.3479e-08 3952 -12.7262 141.813 3996.64 22.4879 3850.9 +EDGE_SE3:QUAT 376 377 -0.335348 7.86063 -0.0166185 -0.0542678 0.13287 0.132373 0.980754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4320.85 27.8142 1200.53 3923.98 69.2589 4262.54 +EDGE_SE3:QUAT 377 378 -0.83003 7.67272 -0.363291 -0.014682 0.00186328 0.22784 0.973586 1 7.70372e-19 7.70372e-19 4.54273e-10 -6.84585e-10 5.40496e-08 1 7.70372e-19 4.54273e-10 -6.84585e-10 5.40496e-08 1 4.54273e-10 -6.84585e-10 5.40496e-08 3999.8 -0.309262 52.5122 3999.75 7.44879 3793.01 +EDGE_SE3:QUAT 378 379 -0.691847 7.71225 -0.33019 -0.0583396 -0.00114532 0.0377303 0.997583 1 4.81482e-20 4.81482e-20 -1.38443e-08 -5.21901e-10 -4.52062e-11 1 4.81482e-20 -1.38443e-08 -5.21901e-10 -4.52062e-11 1 -1.38443e-08 -5.21901e-10 -4.52062e-11 3986.44 -0.758444 17.2329 3999.96 0.488968 3994.36 +EDGE_SE3:QUAT 379 380 -0.604076 7.97076 0.118447 0.0953602 -0.212365 0.0473575 0.971373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4831.01 -81.3146 -2054.73 3816.91 61.5732 4858.42 +EDGE_SE3:QUAT 380 381 -0.291867 7.57737 -0.163002 0.0326909 0.0225145 0.0831374 0.995747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.98 2.93611 145.65 3998.93 5.88676 3977.61 +EDGE_SE3:QUAT 381 382 -0.615846 7.81495 -0.17678 0.014751 -0.0107311 -0.125742 0.991895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.07 -0.609737 -61.78 3999.84 3.4023 3937.69 +EDGE_SE3:QUAT 382 383 -0.532356 8.14314 0.17478 0.206055 -0.00702952 0.191302 0.959633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3888.94 -56.8014 -505.683 3975.42 -50.9165 3912.39 +EDGE_SE3:QUAT 383 384 -0.313333 7.97462 -0.227508 0.039708 -0.0668972 0.050602 0.995684 1 9.62965e-20 9.62965e-20 1.29668e-08 1.10206e-09 1.29668e-08 1 9.62965e-20 1.29668e-08 1.10206e-09 1.29668e-08 1 1.29668e-08 1.10206e-09 1.29668e-08 4072.16 -6.00913 -565.742 3980.41 -10.5558 4068.23 +EDGE_SE3:QUAT 384 385 -0.283436 7.76934 0.211141 0.00237442 -0.105681 0.00756822 0.994368 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4184.91 0.975039 -879.726 3955.32 -3.05122 4184.7 +EDGE_SE3:QUAT 385 386 -0.483736 7.4754 -0.165366 0.134383 -0.00237462 0.174129 0.975507 1 7.70372e-19 7.70372e-19 5.42884e-08 9.30707e-09 -2.6604e-09 1 7.70372e-19 5.42884e-08 9.30707e-09 -2.6604e-09 1 5.42884e-08 9.30707e-09 -2.6604e-09 3947.05 -22.3733 -290.841 3991.3 -30.8395 3898 +EDGE_SE3:QUAT 386 387 -0.518186 8.02919 -0.177613 -0.121285 -0.0563546 0.249514 0.959092 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3937.24 -3.51905 -53.8296 4000.29 9.8454 3747.05 +EDGE_SE3:QUAT 387 388 -0.534848 7.96382 0.145327 0.00755639 0.178829 0.0521568 0.982468 1 7.82409e-19 7.82409e-19 -1.05252e-08 5.40844e-08 -2.84208e-09 1 7.82409e-19 -1.05252e-08 5.40844e-08 -2.84208e-09 1 -1.05252e-08 5.40844e-08 -2.84208e-09 4555.19 54.4745 1590.67 3877.24 62.391 4544.54 +EDGE_SE3:QUAT 388 389 -0.527383 7.47808 0.0305279 -0.0497426 0.0866661 0.0575582 0.993329 1 4.81482e-20 4.81482e-20 1.40148e-08 6.98064e-10 1.29053e-09 1 4.81482e-20 1.40148e-08 6.98064e-10 1.29053e-09 1 1.40148e-08 6.98064e-10 1.29053e-09 4123.76 -8.74332 743.333 3967.04 13.495 4120.4 +EDGE_SE3:QUAT 389 390 -0.470209 8.19047 -0.202055 -0.0317376 -0.00769263 0.0361272 0.998813 1 9.70488e-20 9.70488e-20 -1.38734e-08 -2.68693e-09 1.38809e-08 1 9.70488e-20 -1.38734e-08 -2.68693e-09 1.38809e-08 1 -1.38734e-08 -2.68693e-09 1.38809e-08 3996.53 0.71651 -47.5938 3999.89 -0.806563 3995.34 +EDGE_SE3:QUAT 390 391 -0.571074 7.88843 0.0521591 0.0186344 -0.0211746 0.17184 0.984721 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.57 0.472389 -200.01 3997.52 -17.901 3891.85 +EDGE_SE3:QUAT 391 392 -0.502405 7.67308 0.208518 -0.0751792 0.0121546 0.0347183 0.996491 1 4.81482e-20 4.81482e-20 -2.38713e-10 1.03003e-09 -1.38361e-08 1 4.81482e-20 -2.38713e-10 1.03003e-09 -1.38361e-08 1 -2.38713e-10 1.03003e-09 -1.38361e-08 3981.43 -4.99426 127.545 3998.84 1.98179 3999.22 +EDGE_SE3:QUAT 392 393 -0.432538 7.86255 -0.0821153 0.0506752 0.0543042 0.169237 0.982773 1 4.81482e-20 4.81482e-20 1.3681e-08 2.43114e-09 4.71992e-10 1 4.81482e-20 1.3681e-08 2.43114e-09 4.71992e-10 1 1.3681e-08 2.43114e-09 4.71992e-10 4013.76 14.5729 314.36 3996.54 25.9326 3909.47 +EDGE_SE3:QUAT 393 394 -0.0259057 8.07498 0.0848604 -0.131659 -0.0484974 -0.142844 0.97975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.84 29.1545 -599.679 3975.05 34.3308 4005.56 +EDGE_SE3:QUAT 394 395 -0.321955 7.95411 -0.00655352 -0.221501 -0.118834 0.088895 0.963801 1 9.62965e-19 9.62965e-19 5.04999e-08 3.41465e-08 3.05385e-09 1 9.62965e-19 5.04999e-08 3.41465e-08 3.05385e-09 1 5.04999e-08 3.41465e-08 3.05385e-09 3902.09 84.7272 -647.917 3994.47 -70.7982 4066.73 +EDGE_SE3:QUAT 395 396 -0.212872 7.88984 -0.152072 0.0553802 -0.0281979 -0.0571882 0.996427 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.3 -5.62533 -185.869 3998.22 5.7566 3995.49 +EDGE_SE3:QUAT 396 397 -0.199692 7.69973 0.074323 0.118242 -0.025722 0.0517695 0.991301 1 4.81482e-20 4.81482e-20 5.1508e-10 -1.60191e-09 -1.37896e-08 1 4.81482e-20 5.1508e-10 -1.60191e-09 -1.37896e-08 1 5.1508e-10 -1.60191e-09 -1.37896e-08 3962.73 -16.43 -274.587 3994.76 -4.76729 4007.94 +EDGE_SE3:QUAT 397 398 -0.0399324 8.44915 0.0608697 -0.108224 -0.0779217 0.076867 0.988083 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.62 35.5515 -513.827 3988.15 -31.1283 4040.84 +EDGE_SE3:QUAT 398 399 -0.449499 8.06697 0.231987 0.145904 0.0428401 -0.0775959 0.98532 1 8.1852e-19 8.1852e-19 -5.5938e-08 -1.02089e-08 -1.59774e-09 1 8.1852e-19 -5.5938e-08 -1.02089e-08 -1.59774e-09 1 -5.5938e-08 -1.02089e-08 -1.59774e-09 3968.71 32.4359 468.533 3985.18 -9.56223 4029.77 +EDGE_SE3:QUAT 399 400 -0.794015 7.98809 -0.0829212 0.0989862 -0.000232196 0.0247611 0.994781 1 1.20371e-20 1.20371e-20 3.54156e-11 -6.85953e-10 -6.90287e-09 1 1.20371e-20 3.54156e-11 -6.85953e-10 -6.90287e-09 1 3.54156e-11 -6.85953e-10 -6.90287e-09 3961.02 -2.01545 -31.0383 3999.9 -0.483371 3997.77 +EDGE_SE3:QUAT 400 401 -0.455065 8.2242 -0.0808607 -0.159064 0.08197 0.040806 0.983013 1 1.20371e-20 1.20371e-20 6.38367e-10 -1.08739e-09 6.93219e-09 1 1.20371e-20 6.38367e-10 -1.08739e-09 6.93219e-09 1 6.38367e-10 -1.08739e-09 6.93219e-09 4026.83 -56.0303 727.059 3970.17 -14.0155 4121.38 +EDGE_SE3:QUAT 401 402 -0.613504 7.76772 0.267523 0.0189596 -0.0668654 -0.131996 0.988811 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4059.32 -17.5234 -497.109 3987.17 35.0843 3991.07 +EDGE_SE3:QUAT 402 403 -0.157235 8.32398 -0.165429 0.0986939 0.107138 0.107877 0.983435 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4085.34 59.4048 718.716 3978.67 60.8332 4077.75 +EDGE_SE3:QUAT 403 404 -0.355657 7.87783 -0.152468 -0.005 -0.149031 0.0356536 0.988177 1 3.00927e-21 3.00927e-21 3.58672e-09 1.41004e-10 -5.38091e-10 1 3.00927e-21 3.58672e-09 1.41004e-10 -5.38091e-10 1 3.58672e-09 1.41004e-10 -5.38091e-10 4377.24 25.0636 -1285.21 3912.78 -31.2812 4372.26 +EDGE_SE3:QUAT 404 405 -0.331895 8.03068 0.373353 0.143285 0.0289752 0.192018 0.970443 1 7.70372e-19 7.70372e-19 5.38685e-08 1.06688e-08 -1.54321e-09 1 7.70372e-19 5.38685e-08 1.06688e-08 -1.54321e-09 1 5.38685e-08 1.06688e-08 -1.54321e-09 3917.62 -15.9581 -105.488 3996.91 -21.371 3852.26 +EDGE_SE3:QUAT 405 406 -0.0335054 7.74224 -0.0119202 0.0829707 -0.171003 0.119698 0.974447 1 1.92593e-19 1.92593e-19 -5.48906e-09 1.29065e-09 2.89847e-08 1 1.92593e-19 -5.48906e-09 1.29065e-09 2.89847e-08 1 -5.48906e-09 1.29065e-09 2.89847e-08 4555.89 17.0113 -1635.36 3869.46 -57.4761 4526.12 +EDGE_SE3:QUAT 406 407 -0.099727 8.12803 -0.450084 0.133962 -0.0917823 -0.0450266 0.985699 1 4.81482e-20 4.81482e-20 1.0668e-09 -2.0223e-09 -1.38595e-08 1 4.81482e-20 1.0668e-09 -2.0223e-09 -1.38595e-08 1 1.0668e-09 -2.0223e-09 -1.38595e-08 4031.93 -52.7402 -653.586 3980.01 38.0132 4095.61 +EDGE_SE3:QUAT 407 408 -0.309291 7.60617 -0.122528 0.057719 0.0908695 -0.10912 0.988182 1 4.81482e-20 4.81482e-20 -1.39881e-08 1.41258e-09 -1.42727e-09 1 4.81482e-20 -1.39881e-08 1.41258e-09 -1.42727e-09 1 -1.39881e-08 1.41258e-09 -1.42727e-09 4146.06 0.539044 814.344 3961 -36.1912 4111.75 +EDGE_SE3:QUAT 408 409 -0.454336 7.90957 -0.450462 -0.019983 0.0164681 -0.0296661 0.999224 1 1.20371e-20 1.20371e-20 6.93687e-09 -2.10461e-10 1.05802e-10 1 1.20371e-20 6.93687e-09 -2.10461e-10 1.05802e-10 1 6.93687e-09 -2.10461e-10 1.05802e-10 4002.27 -1.39954 124.484 3999.08 -1.93418 4000.35 +EDGE_SE3:QUAT 409 410 -0.0539003 7.84394 -0.411482 0.212397 -0.0330829 0.0863697 0.972797 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3871.73 -51.6143 -462.917 3984.71 -9.05197 4022.34 +EDGE_SE3:QUAT 410 411 -0.630566 8.2324 0.232811 0.145941 -0.0336548 0.0562181 0.987121 1 7.70372e-19 7.70372e-19 5.50191e-08 2.46645e-09 -2.69021e-09 1 7.70372e-19 5.50191e-08 2.46645e-09 -2.69021e-09 1 5.50191e-08 2.46645e-09 -2.69021e-09 3946.64 -26.368 -359.154 3991.28 -4.74157 4019.2 +EDGE_SE3:QUAT 411 412 -0.0149138 8.0262 -0.0306016 -0.0068954 -0.0109035 0.183448 0.982945 1 3.00927e-21 3.00927e-21 -3.41078e-09 -6.37142e-10 2.66524e-11 1 3.00927e-21 -3.41078e-09 -6.37142e-10 2.66524e-11 1 -3.41078e-09 -6.37142e-10 2.66524e-11 4000.95 0.57667 -68.0299 3999.81 -5.6576 3866.53 +EDGE_SE3:QUAT 412 413 -0.446793 8.44206 0.0396303 -0.0741868 0.144557 -0.0406376 0.985874 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4301.86 -73.7349 1183.61 3930.18 -67.2608 4317.27 +EDGE_SE3:QUAT 413 414 -0.160378 8.1025 -0.00574811 -0.0895009 -0.203851 0.0348679 0.974279 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4658.33 155.032 -1799.79 3865.18 -147.554 4685.51 +EDGE_SE3:QUAT 414 415 -0.144983 8.19039 0.0125573 0.0176594 -0.0731139 0.0879431 0.993282 1 3.00927e-21 3.00927e-21 3.48521e-09 3.02686e-10 -2.63371e-10 1 3.00927e-21 3.48521e-09 3.02686e-10 -2.63371e-10 1 3.48521e-09 3.02686e-10 -2.63371e-10 4089.25 6.28292 -608.441 3978.13 -26.074 4059.57 +EDGE_SE3:QUAT 415 416 -0.455274 8.15199 -0.308835 -0.0204601 0.111642 0.170694 0.978765 1 7.70419e-19 7.70419e-19 -5.9449e-09 -9.78972e-10 -5.57215e-08 1 7.70419e-19 -5.9449e-09 -9.78972e-10 -5.57215e-08 1 -5.9449e-09 -9.78972e-10 -5.57215e-08 4206.68 44.5036 936.478 3956.14 84.3349 4091.81 +EDGE_SE3:QUAT 416 417 -0.343895 7.86727 -0.0852366 -0.0130636 -0.0468413 0.172443 0.983818 1 7.82409e-19 7.82409e-19 -9.05492e-09 -2.79027e-09 5.50816e-08 1 7.82409e-19 -9.05492e-09 -2.79027e-09 5.50816e-08 1 -9.05492e-09 -2.79027e-09 5.50816e-08 4026.81 9.81917 -333.336 3994.71 -28.6457 3908.55 +EDGE_SE3:QUAT 417 418 -0.264065 7.59963 0.0670919 0.044928 -0.056112 0.130347 0.988859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4056.71 -0.172046 -513.362 3983.75 -31.7999 3996.82 +EDGE_SE3:QUAT 418 419 -0.213044 8.20317 0.194941 0.200335 0.16677 0.221576 0.939658 1 7.70372e-19 7.70372e-19 5.27434e-08 1.55845e-08 2.59044e-09 1 7.70372e-19 5.27434e-08 1.55845e-08 2.59044e-09 1 5.27434e-08 1.55845e-08 2.59044e-09 3919.14 103.008 635.575 4021.64 102.919 3883.3 +EDGE_SE3:QUAT 419 420 -0.678106 8.43123 0.0384138 0.0680487 -0.0175903 0.175663 0.981938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.86 -6.94596 -274.701 3994.09 -26.7445 3894.95 +EDGE_SE3:QUAT 420 421 -0.282068 8.38335 0.349728 -0.15504 -0.0072142 0.00144827 0.987881 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3904.55 3.988 -53.0014 3999.85 -0.209026 4000.69 +EDGE_SE3:QUAT 421 422 -0.11032 8.04324 0.232228 -0.0593257 0.00288715 0.00783924 0.998204 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.12 -0.89849 28.5421 3999.94 0.102372 3999.96 +EDGE_SE3:QUAT 422 423 -0.0827175 8.25325 0.02771 -0.0496951 -0.0918569 0.044615 0.99353 1 4.81482e-20 4.81482e-20 -1.40052e-08 -7.66283e-10 1.21942e-09 1 4.81482e-20 -1.40052e-08 -7.66283e-10 1.21942e-09 1 -1.40052e-08 -7.66283e-10 1.21942e-09 4116.46 27.9922 -722.132 3970.93 -27.0287 4118.38 +EDGE_SE3:QUAT 423 424 -0.051738 8.39132 -0.345242 0.0835632 -0.219072 0.160218 0.95883 1 8.1852e-19 8.1852e-19 -7.3046e-09 -5.55531e-08 4.3738e-09 1 8.1852e-19 -7.3046e-09 -5.55531e-08 4.3738e-09 1 -7.3046e-09 -5.55531e-08 4.3738e-09 4978.42 116.292 -2244.6 3799.82 -147.856 4903.68 +EDGE_SE3:QUAT 424 425 -0.272124 8.30664 0.292815 0.107423 -0.0102622 0.031197 0.993671 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3957.43 -7.03157 -120.553 3998.92 -1.57673 3999.7 +EDGE_SE3:QUAT 425 426 -0.505192 8.05424 0.148819 -0.0582775 -0.0246326 0.0425491 0.997089 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.27 5.0387 -166.073 3998.54 -3.98471 3999.61 +EDGE_SE3:QUAT 426 427 -0.216109 8.3111 -0.206841 0.145463 0.100493 0.112702 0.977773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.6 56.1182 575.923 3990.55 52.204 4028.43 +EDGE_SE3:QUAT 427 428 -0.226197 8.08873 0.170219 -0.0666224 -0.110279 -0.217216 0.967583 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4237.99 -42.3244 -1043.33 3945.2 109.273 4067.01 +EDGE_SE3:QUAT 428 429 -0.31399 8.46374 -0.0542676 0.174412 0.0119746 0.154127 0.972462 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3888.21 -27.7606 -223.313 3993.26 -24.1995 3914.87 +EDGE_SE3:QUAT 429 430 -0.0632004 8.36706 -0.0438551 0.000263552 0.011714 0.0575652 0.998273 1 3.02102e-21 3.02102e-21 1.67293e-11 3.47594e-09 -3.06346e-12 1 3.02102e-21 1.67293e-11 3.47594e-09 -3.06346e-12 1 1.67293e-11 3.47594e-09 -3.06346e-12 4002.17 0.200238 93.1092 3999.47 2.6784 3988.91 +EDGE_SE3:QUAT 430 431 -0.0932633 8.48432 -0.319093 0.0436617 0.110269 0.0689761 0.990544 1 2.40741e-19 2.40741e-19 -1.62784e-08 2.63326e-08 -3.11192e-09 1 2.40741e-19 -1.62784e-08 2.63326e-08 -3.11192e-09 1 -1.62784e-08 2.63326e-08 -3.11192e-09 4172.91 40.6034 868.955 3959.87 45.5458 4161.5 +EDGE_SE3:QUAT 431 432 -0.335184 8.4427 -0.0692374 -0.0914225 0.138485 0.101655 0.980882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4347.46 -14.7882 1291.92 3910.41 28.9882 4339.56 +EDGE_SE3:QUAT 432 433 -0.400961 8.69468 -0.16408 -0.0297971 0.0891266 -0.0279047 0.995183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4122.19 -16.9439 720.277 3969.95 -16.5751 4122.63 +EDGE_SE3:QUAT 433 434 -0.237304 8.48499 -0.172595 -0.00976675 0.124748 0.0263496 0.99179 1 1.20371e-20 1.20371e-20 8.95936e-10 -2.39034e-11 7.10409e-09 1 1.20371e-20 8.95936e-10 -2.39034e-11 7.10409e-09 1 8.95936e-10 -2.39034e-11 7.10409e-09 4261.85 4.64051 1057.2 3937.58 12.3002 4259.45 +EDGE_SE3:QUAT 434 435 -0.481472 8.4064 -0.135244 0.189737 0.131018 -0.071804 0.970401 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4208.6 107.302 1238.92 3923.06 46.8452 4331.98 +EDGE_SE3:QUAT 435 436 -0.510141 8.39678 -0.138307 -0.0538632 0.090362 -0.0408955 0.99361 1 2.40741e-19 2.40741e-19 -1.25801e-08 2.82857e-08 5.22341e-10 1 2.40741e-19 -1.25801e-08 2.82857e-08 5.22341e-10 1 -1.25801e-08 2.82857e-08 5.22341e-10 4110.43 -28.1693 709.356 3971.92 -25.7248 4115.34 +EDGE_SE3:QUAT 436 437 -0.100163 8.45733 -0.156752 0.0819267 0.0101079 -0.0573827 0.994934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.68 6.00056 135.852 3998.55 -3.96292 3991.36 +EDGE_SE3:QUAT 437 438 -0.497065 8.40827 -0.0848201 0.0156752 0.112611 0.0656141 0.991346 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4200.75 28.692 920.719 3953.36 38.9075 4184.52 +EDGE_SE3:QUAT 438 439 0.0728362 8.48836 0.117855 0.0145322 0.159202 0.0150182 0.987025 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4435.01 23.1553 1390.46 3899.78 23.2509 4434.95 +EDGE_SE3:QUAT 439 440 -0.27031 8.28368 -0.297655 -0.00826604 -0.0897048 -0.0160589 0.995805 1 7.52316e-22 7.52316e-22 1.75581e-09 -2.61286e-11 -1.58541e-10 1 7.52316e-22 1.75581e-09 -2.61286e-11 -1.58541e-10 1 1.75581e-09 -2.61286e-11 -1.58541e-10 4132.13 0.0844331 -739.705 3967.69 4.78421 4131.38 +EDGE_SE3:QUAT 440 441 -0.589943 8.15622 0.05806 0.168385 0.0050453 0.0347174 0.985097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3886.68 -4.55838 -30.1833 3999.82 -0.930242 3995.27 +EDGE_SE3:QUAT 441 442 -0.438567 8.15895 0.235384 0.0166038 0.128965 0.112678 0.985087 1 4.81482e-20 4.81482e-20 -1.41069e-08 -1.72982e-09 -1.74179e-09 1 4.81482e-20 -1.41069e-08 -1.72982e-09 -1.74179e-09 1 -1.41069e-08 -1.72982e-09 -1.74179e-09 4254.41 55.7645 1042.99 3945.41 74.7601 4204.73 +EDGE_SE3:QUAT 442 443 -0.53293 8.53888 -0.0874597 0.0159264 -0.00344385 0.249066 0.968349 1 3.08149e-18 3.08149e-18 1.18787e-09 -1.36467e-09 -1.07526e-07 1 3.08149e-18 1.18787e-09 -1.36467e-09 -1.07526e-07 1 1.18787e-09 -1.36467e-09 -1.07526e-07 4000.2 -0.320446 -70.6649 3999.6 -10.6416 3753.07 +EDGE_SE3:QUAT 443 444 -0.0841777 8.56999 -0.0324157 0.013005 0.0403692 -0.17956 0.982832 1 7.52316e-22 7.52316e-22 -1.71114e-09 3.11792e-10 -7.3745e-11 1 7.52316e-22 -1.71114e-09 3.11792e-10 -7.3745e-11 1 -1.71114e-09 3.11792e-10 -7.3745e-11 4027.51 -5.36315 336.962 3993.73 -30.6215 3899.22 +EDGE_SE3:QUAT 444 445 -0.430555 8.61658 -0.17106 -0.00384343 0.0727989 0.106231 0.991666 1 7.52316e-22 7.52316e-22 -1.73858e-09 -1.87261e-10 -1.26158e-10 1 7.52316e-22 -1.73858e-09 -1.87261e-10 -1.26158e-10 1 -1.73858e-09 -1.87261e-10 -1.26158e-10 4084.61 12.5655 588.096 3980.28 32.4023 4039.53 +EDGE_SE3:QUAT 445 446 -0.430427 8.42864 -0.233572 -0.0370884 -0.0469612 -0.0216078 0.997974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.68 6.2104 -387.439 3990.69 2.25857 4035.31 +EDGE_SE3:QUAT 446 447 -0.700204 8.2062 0.16272 -0.0117843 -0.11432 0.126126 0.985335 1 1.20371e-20 1.20371e-20 -7.0071e-09 -9.39803e-10 7.64521e-10 1 1.20371e-20 -7.0071e-09 -9.39803e-10 7.64521e-10 1 -7.0071e-09 -9.39803e-10 7.64521e-10 4197.33 45.5024 -911.672 3957.82 -68.0543 4134.25 +EDGE_SE3:QUAT 447 448 -0.684199 8.67849 0.0117224 -0.0103537 0.144198 -0.0318841 0.988981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4350.18 -25.2865 1235.05 3918.65 -29.6975 4346.54 +EDGE_SE3:QUAT 448 449 -0.457052 8.52647 -0.117354 0.141769 0.0359258 0.166303 0.975169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3917.18 -7.56923 -7.18394 3999.37 -8.92194 3886.94 +EDGE_SE3:QUAT 449 450 -0.635385 8.70871 -0.227139 0.0688815 -0.0113509 0.204768 0.976318 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.97 -6.9036 -249.525 3994.71 -30.0324 3847.23 +EDGE_SE3:QUAT 450 451 -0.754977 8.86982 0.0264329 -0.0990407 -0.0249378 0.170357 0.980075 1 1.93345e-19 1.93345e-19 -2.69002e-08 -6.47075e-09 -4.56754e-10 1 1.93345e-19 -2.69002e-08 -6.47075e-09 -4.56754e-10 1 -2.69002e-08 -6.47075e-09 -4.56754e-10 3959.56 -3.95374 9.3401 3999.63 6.85626 3882.72 +EDGE_SE3:QUAT 451 452 -0.244757 8.61658 0.151907 -0.15272 -0.102101 0.0446379 0.981967 1 1.92593e-19 1.92593e-19 -2.06755e-09 2.72048e-08 4.55054e-09 1 1.92593e-19 -2.06755e-09 2.72048e-08 4.55054e-09 1 -2.06755e-09 2.72048e-08 4.55054e-09 4032.55 66.8852 -722.205 3977.22 -48.8496 4117.87 +EDGE_SE3:QUAT 452 453 -0.687116 8.26651 0.333672 -0.0187336 0.0575408 -0.0348031 0.99756 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.01 -7.12005 456.429 3987.54 -9.6296 4046.57 +EDGE_SE3:QUAT 453 454 -0.727494 8.91946 0.363207 -0.0718765 -0.0752114 -0.0952682 0.990001 1 1.92593e-19 1.92593e-19 -2.78757e-08 2.38282e-09 2.44543e-09 1 1.92593e-19 -2.78757e-08 2.38282e-09 2.44543e-09 1 -2.78757e-08 2.38282e-09 2.44543e-09 4094.45 11.2911 -688.536 3970.9 24.1032 4078.81 +EDGE_SE3:QUAT 454 455 -0.72395 8.25713 0.220334 0.138586 0.0664608 0.170747 0.973254 1 7.70372e-19 7.70372e-19 -5.40878e-08 -1.0178e-08 -7.48062e-10 1 7.70372e-19 -5.40878e-08 -1.0178e-08 -7.48062e-10 1 -5.40878e-08 -1.0178e-08 -7.48062e-10 3931.79 13.0908 216.955 4000.82 13.9132 3892 +EDGE_SE3:QUAT 455 456 -0.61813 8.99913 -0.0660829 0.00933001 -0.0498749 0.0134482 0.998621 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4040.03 -1.11872 -403.889 3989.97 -2.22336 4039.65 +EDGE_SE3:QUAT 456 457 -0.591065 8.42161 -0.162141 -0.160535 0.0136545 0.274639 0.947953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3980.67 -37.1631 600.043 3968.23 92.9039 3782.05 +EDGE_SE3:QUAT 457 458 -0.0576283 8.8079 -0.168258 -0.150984 0.041248 0.0916568 0.983413 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3966.19 -34.41 484.405 3983.74 13.5685 4023.77 +EDGE_SE3:QUAT 458 459 -0.575312 8.72801 -0.278793 -0.09715 -0.158053 0.0157661 0.982513 1 4.81482e-20 4.81482e-20 -2.20842e-09 -1.56335e-09 1.43142e-08 1 4.81482e-20 -2.20842e-09 -1.56335e-09 1.43142e-08 1 -2.20842e-09 -1.56335e-09 1.43142e-08 4366.05 91.3736 -1333.67 3914.05 -76.0384 4402.81 +EDGE_SE3:QUAT 459 460 -0.250894 8.40306 0.0555823 0.0665892 0.0333966 0.177659 0.981269 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.8 3.53331 114.106 4000.03 6.08859 3876.29 +EDGE_SE3:QUAT 460 461 -0.73559 8.41833 0.0654651 0.105133 0.218392 -0.00264046 0.970178 1 2.0463e-19 2.0463e-19 -3.13393e-08 -2.30085e-09 -1.3968e-08 1 2.0463e-19 -3.13393e-08 -2.30085e-09 -1.3968e-08 1 -3.13393e-08 -2.30085e-09 -1.3968e-08 4812.04 159.045 2039.28 3831.26 146.023 4856.23 +EDGE_SE3:QUAT 461 462 -0.250822 9.22315 -0.206573 0.016149 0.0139752 0.202649 0.979019 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000 0.867158 66.7526 3999.91 5.24107 3836.78 +EDGE_SE3:QUAT 462 463 -0.338042 8.62796 -0.136403 -0.126133 -0.0917159 0.166363 0.973654 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.43 39.2292 -441.28 3997.37 -42.6013 3934.37 +EDGE_SE3:QUAT 463 464 -0.35854 8.91106 -0.108576 0.136543 -0.0220925 0.0955944 0.985763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3951.22 -22.7745 -325.384 3991.76 -13.6891 3989.24 +EDGE_SE3:QUAT 464 465 -0.519363 8.81591 -0.134388 0.153059 0.0916316 -0.000416237 0.98396 1 9.65974e-19 9.65974e-19 -5.44346e-08 -2.83119e-08 2.85609e-09 1 9.65974e-19 -5.44346e-08 -2.83119e-08 2.85609e-09 1 -5.44346e-08 -2.83119e-08 2.85609e-09 4034.51 59.8421 727.734 3972.83 30.5864 4128.21 +EDGE_SE3:QUAT 465 466 -0.429435 8.70918 -0.119875 0.121776 0.000823819 0.153945 0.980546 1 2.0463e-19 2.0463e-19 -2.82901e-08 2.65158e-09 1.93411e-10 1 2.0463e-19 -2.82901e-08 2.65158e-09 1.93411e-10 1 -2.82901e-08 2.65158e-09 1.93411e-10 3950.84 -16.0282 -213.521 3994.99 -21.0083 3915.36 +EDGE_SE3:QUAT 466 467 -0.40782 8.30685 -0.073455 -0.0478427 0.105505 0.0406094 0.992437 1 4.81482e-20 4.81482e-20 -1.41021e-08 -4.4206e-10 -1.54381e-09 1 4.81482e-20 -1.41021e-08 -4.4206e-10 -1.54381e-09 1 -1.41021e-08 -4.4206e-10 -1.54381e-09 4183.74 -12.3746 899.339 3953.24 6.58297 4186.3 +EDGE_SE3:QUAT 467 468 -0.926222 8.60876 -0.0358898 0.042097 -0.0988911 0.0215 0.993975 1 1.92593e-19 1.92593e-19 3.7233e-10 -2.75923e-08 1.07133e-09 1 1.92593e-19 3.7233e-10 -2.75923e-08 1.07133e-09 1 3.7233e-10 -2.75923e-08 1.07133e-09 4157.67 -13.9359 -828.363 3960.03 0.686295 4162.91 +EDGE_SE3:QUAT 468 469 -0.211459 8.85658 -0.016834 -0.0280837 -0.069517 -0.0608788 0.995325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4080.24 1.10678 -583.556 3979.36 15.3707 4068.57 +EDGE_SE3:QUAT 469 470 -0.444296 9.07182 -0.0125556 -0.0806779 0.133046 0.224703 0.961924 1 8.1852e-19 8.1852e-19 -2.56802e-08 5.05261e-08 -1.37475e-09 1 8.1852e-19 -2.56802e-08 5.05261e-08 -1.37475e-09 1 -2.56802e-08 5.05261e-08 -1.37475e-09 4355.86 65.1742 1293.67 3920.76 136.722 4179.93 +EDGE_SE3:QUAT 470 471 -0.465088 9.02252 -0.239444 0.0948415 0.0156203 0.126305 0.987324 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3963.54 -3.35362 -21.0648 3999.69 -4.46209 3935.71 +EDGE_SE3:QUAT 471 472 -0.462644 8.3948 -0.232568 -0.00180562 -0.0834293 -0.0742198 0.993744 1 1.92593e-19 1.92593e-19 2.08058e-09 2.75804e-08 -2.96129e-10 1 1.92593e-19 2.08058e-09 2.75804e-08 -2.96129e-10 1 2.08058e-09 2.75804e-08 -2.96129e-10 4112.36 -12.084 -679.795 3973.25 26.7231 4090.34 +EDGE_SE3:QUAT 472 473 -0.360409 8.65031 -0.23905 -0.15262 -0.0205747 0.142331 0.977766 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3907.42 -14.4281 99.1771 3997.75 13.4486 3919.56 +EDGE_SE3:QUAT 473 474 -0.506134 8.71895 -0.375582 0.0288376 -0.0450014 0.0094222 0.998526 1 1.20371e-20 1.20371e-20 6.95731e-09 4.76776e-11 -3.16775e-10 1 1.20371e-20 6.95731e-09 4.76776e-11 -3.16775e-10 1 6.95731e-09 4.76776e-11 -3.16775e-10 4029.78 -4.92727 -365.417 3991.76 -0.329636 4032.75 +EDGE_SE3:QUAT 474 475 -0.67935 8.78415 -0.0333761 -0.0616878 -0.10959 -0.203173 0.971033 1 4.81482e-20 4.81482e-20 -1.39007e-08 2.77286e-09 1.78608e-09 1 4.81482e-20 -1.39007e-08 2.77286e-09 1.78608e-09 1 -1.39007e-08 2.77286e-09 1.78608e-09 4230.12 -38.0202 -1020.63 3946.58 99.6506 4080.23 +EDGE_SE3:QUAT 475 476 -0.263802 8.75715 -0.423868 -0.0212445 -0.126003 0.109166 0.985776 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4238.87 54.0806 -1010.53 3948.56 -71.3824 4193.01 +EDGE_SE3:QUAT 476 477 -0.542922 8.84389 -0.357758 -0.0710549 -0.0289262 -0.00884938 0.997014 1 7.52316e-22 7.52316e-22 5.19359e-11 1.22782e-10 -1.7326e-09 1 7.52316e-22 5.19359e-11 1.22782e-10 -1.7326e-09 1 5.19359e-11 1.22782e-10 -1.7326e-09 3993.9 8.41132 -237.9 3996.5 -0.422031 4013.79 +EDGE_SE3:QUAT 477 478 -0.673258 8.84958 -0.01523 0.0182372 -0.221052 0.083211 0.971535 1 1.88079e-22 1.88079e-22 9.34605e-10 8.0369e-11 -2.12535e-10 1 1.88079e-22 9.34605e-10 8.0369e-11 -2.12535e-10 1 9.34605e-10 8.0369e-11 -2.12535e-10 4912.34 96.1324 -2118.84 3811.55 -108.434 4885.97 +EDGE_SE3:QUAT 478 479 -0.557606 8.79233 -0.576861 -0.113549 -0.0978339 -0.0129084 0.988619 1 3.85938e-19 3.85938e-19 -2.75461e-08 -2.75115e-08 -2.11138e-09 1 3.85938e-19 -2.75461e-08 -2.75115e-08 -2.11138e-09 1 -2.75461e-08 -2.75115e-08 -2.11138e-09 4107.09 47.7825 -812.31 3963.49 -21.8712 4158 +EDGE_SE3:QUAT 479 480 -0.638846 8.95141 -0.15764 0.0107042 -0.159835 0.217618 0.962798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4394.57 133.466 -1318.75 3935.49 -173.464 4205.59 +EDGE_SE3:QUAT 480 481 -0.214639 9.22694 -0.526404 0.0937334 0.0510288 0.139904 0.984397 1 4.81482e-20 4.81482e-20 2.04376e-09 -1.36463e-08 1.44895e-09 1 4.81482e-20 2.04376e-09 -1.36463e-08 1.44895e-09 1 2.04376e-09 -1.36463e-08 1.44895e-09 3977.84 12.4958 236.412 3998.77 15.3735 3934.69 +EDGE_SE3:QUAT 481 482 -0.381238 8.46583 -0.227078 -0.0107872 0.0664529 0.040666 0.996902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.21 1.37955 544.035 3982.1 10.4259 4066.06 +EDGE_SE3:QUAT 482 483 -0.510911 9.0723 -0.103562 -0.0412687 -0.153009 0.0558853 0.98578 1 1.92593e-19 1.92593e-19 -4.25638e-09 -1.76165e-09 2.86253e-08 1 1.92593e-19 -4.25638e-09 -1.76165e-09 2.86253e-08 1 -4.25638e-09 -1.76165e-09 2.86253e-08 4369.04 66.14 -1282.56 3917.63 -68.9503 4363.36 +EDGE_SE3:QUAT 483 484 -0.495418 9.14981 0.169744 -0.0432847 0.285636 0.0313605 0.956846 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5723.05 -36.2901 3149.12 3671.87 -36.6773 5726.61 +EDGE_SE3:QUAT 484 485 -0.121365 9.07715 -0.24743 0.0219173 -0.0868746 -0.0112522 0.995915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4120.3 -10.4798 -709.794 3970.34 8.3887 4121.71 +EDGE_SE3:QUAT 485 486 -0.474532 8.76304 0.201055 0.00725893 -0.0100999 0.0501695 0.998663 1 3.76158e-21 3.76158e-21 -1.90637e-09 3.37803e-09 -2.85431e-12 1 3.76158e-21 -1.90637e-09 3.37803e-09 -2.85431e-12 1 -1.90637e-09 3.37803e-09 -2.85431e-12 4001.59 -0.180513 -84.885 3999.54 -2.14646 3991.73 +EDGE_SE3:QUAT 486 487 -0.991476 8.768 -0.347736 -0.0750279 -0.0448917 0.0126602 0.99609 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.33 13.6752 -346.842 3992.98 -5.65465 4029.2 +EDGE_SE3:QUAT 487 488 -0.63093 9.12548 0.0871263 -0.0537218 -0.0922019 0.0750682 0.991452 1 2.40741e-19 2.40741e-19 1.15812e-08 2.87032e-08 7.23741e-10 1 2.40741e-19 1.15812e-08 2.87032e-08 7.23741e-10 1 1.15812e-08 2.87032e-08 7.23741e-10 4106.07 33.7687 -696.311 3974.39 -37.6132 4095.08 +EDGE_SE3:QUAT 488 489 -0.564825 8.67107 -0.0471743 0.155684 0.11256 -0.0540264 0.979885 1 9.62965e-19 9.62965e-19 5.5584e-08 -2.82381e-08 1.11456e-08 1 9.62965e-19 5.5584e-08 -2.82381e-08 1.11456e-08 1 5.5584e-08 -2.82381e-08 1.11456e-08 4147.18 72.9395 1017.95 3944.12 25.2722 4232.45 +EDGE_SE3:QUAT 489 490 -0.259572 9.28362 -0.198192 -0.0204051 0.0724243 0.14771 0.986164 1 1.95602e-19 1.95602e-19 7.52146e-09 -2.68641e-08 3.08422e-10 1 1.95602e-19 7.52146e-09 -2.68641e-08 3.08422e-10 1 7.52146e-09 -2.68641e-08 3.08422e-10 4088.71 13.5765 608.007 3979.3 45.1648 4003.1 +EDGE_SE3:QUAT 490 491 -0.50513 8.92568 -0.0618592 -0.119458 -0.172844 0.0515148 0.97632 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4375.91 142.534 -1386.53 3920.54 -131.676 4422.37 +EDGE_SE3:QUAT 491 492 -0.408612 9.38717 -0.345543 -0.0183526 -0.0925576 0.164486 0.981856 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4114.23 37.3911 -690.474 3977.59 -63.1229 4007.36 +EDGE_SE3:QUAT 492 493 -0.602028 9.22086 0.258643 0.0905089 -0.0998993 0.0690165 0.988466 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4158.74 -26.4879 -896.071 3953.09 -9.3746 4172.45 +EDGE_SE3:QUAT 493 494 -0.314061 9.56316 -0.515217 -0.0519251 0.0573805 0.0912041 0.992821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4054.59 -5.67684 515.71 3983.32 20.2656 4032.1 +EDGE_SE3:QUAT 494 495 -0.665567 9.16043 0.104826 0.188002 -0.102027 0.118031 0.969698 1 9.62965e-19 9.62965e-19 5.18092e-08 8.97506e-09 2.00273e-08 1 9.62965e-19 5.18092e-08 8.97506e-09 2.00273e-08 1 5.18092e-08 8.97506e-09 2.00273e-08 4133.27 -77.478 -1084.64 3933.09 -3.57596 4218.92 +EDGE_SE3:QUAT 495 496 -0.60809 9.16694 0.0305522 0.162212 -0.0852218 0.182205 0.966036 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4140.74 -39.8225 -1024.72 3935.8 -59.1673 4113.2 +EDGE_SE3:QUAT 496 497 -0.272442 9.28466 0.163712 0.109682 -0.13459 0.0811067 0.981467 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4309.01 -40.4923 -1247.56 3915.94 -2.93085 4330.82 +EDGE_SE3:QUAT 497 498 -0.617168 9.15838 -0.143053 -0.0240001 -0.00580296 0.0789129 0.996576 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.82 0.210967 -23.326 3999.99 -0.622592 3975.21 +EDGE_SE3:QUAT 498 499 -0.426391 8.90356 -0.151122 -0.0496591 -0.0307335 0.0309028 0.997815 1 1.20371e-20 1.20371e-20 -2.34906e-10 6.92307e-09 3.57681e-10 1 1.20371e-20 -2.34906e-10 6.92307e-09 3.57681e-10 1 -2.34906e-10 6.92307e-09 3.57681e-10 4002.94 6.13921 -226.82 3997.04 -4.43041 4008.99 +EDGE_SE3:QUAT 499 500 -0.387328 9.48708 -0.0618141 0.162315 0.0276619 0.261696 0.951001 1 3.08149e-18 3.08149e-18 6.49258e-09 -1.70988e-08 -1.05792e-07 1 3.08149e-18 6.49258e-09 -1.70988e-08 -1.05792e-07 1 6.49258e-09 -1.70988e-08 -1.05792e-07 3909.03 -35.0032 -287.817 3986.71 -59.4368 3740.48 +EDGE_SE3:QUAT 500 501 -0.650188 9.38705 0.0315168 -0.0174147 0.070615 0.0328646 0.99681 1 3.00927e-21 3.00927e-21 -3.49399e-09 -1.07615e-10 -2.50886e-10 1 3.00927e-21 -3.49399e-09 -1.07615e-10 -2.50886e-10 1 -3.49399e-09 -1.07615e-10 -2.50886e-10 4081.47 -1.24711 581.014 3979.6 7.91612 4078.36 +EDGE_SE3:QUAT 501 502 -0.38382 9.3472 0.277036 0.0740761 0.151991 0.193712 0.966378 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4214.68 124.687 1007.85 3973.24 140.593 4086.53 +EDGE_SE3:QUAT 502 503 -0.614648 9.20333 0.231558 -0.0299992 -0.000584207 0.126876 0.991465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.76 -0.794211 40.6052 3999.81 3.534 3935.97 +EDGE_SE3:QUAT 503 504 -0.881434 9.36376 -0.229905 -0.0281512 0.172593 -0.0389235 0.983821 1 8.1852e-19 8.1852e-19 1.16399e-08 -5.53395e-08 6.1144e-11 1 8.1852e-19 1.16399e-08 -5.53395e-08 6.1144e-11 1 1.16399e-08 -5.53395e-08 6.1144e-11 4503.84 -59.5022 1511.68 3887.72 -61.465 4500.95 +EDGE_SE3:QUAT 504 505 -0.42393 9.71696 -0.168597 -0.0438659 -0.110839 0.00170515 0.992868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4194.67 23.3643 -922.191 3951.83 -14.5486 4202.36 +EDGE_SE3:QUAT 505 506 -0.183723 8.94497 0.174357 -0.0108962 -0.0848985 -0.0112927 0.996266 1 1.95602e-19 1.95602e-19 -3.7733e-09 -2.76187e-08 4.66208e-11 1 1.95602e-19 -3.7733e-09 -2.76187e-08 4.66208e-11 1 -3.7733e-09 -2.76187e-08 4.66208e-11 4117.84 2.066 -698.029 3971.05 2.28631 4117.8 +EDGE_SE3:QUAT 506 507 -0.459382 8.91285 0.211475 -0.0498881 0.0372427 0.145654 0.987375 1 4.81482e-20 4.81482e-20 1.37638e-08 1.9757e-09 6.95442e-10 1 4.81482e-20 1.37638e-08 1.9757e-09 6.95442e-10 1 1.37638e-08 1.9757e-09 6.95442e-10 4025.06 -3.10511 376.499 3990.71 27.3871 3950.16 +EDGE_SE3:QUAT 507 508 -0.398699 9.34449 -0.167154 -0.0754867 -0.0437296 0.0438602 0.995221 1 1.92593e-19 1.92593e-19 -2.77045e-08 -1.39488e-09 1.01424e-09 1 1.92593e-19 -2.77045e-08 -1.39488e-09 1.01424e-09 1 -2.77045e-08 -1.39488e-09 1.01424e-09 4000.67 12.9222 -307.682 3994.92 -9.39934 4015.77 +EDGE_SE3:QUAT 508 509 -0.245417 9.59185 0.155445 -0.100352 -0.0148101 -0.2278 0.96841 1 7.70372e-19 7.70372e-19 3.19538e-09 4.65553e-09 -5.39953e-08 1 7.70372e-19 3.19538e-09 4.65553e-09 -5.39953e-08 1 3.19538e-09 4.65553e-09 -5.39953e-08 3993.05 14.5381 -374.013 3988.06 49.2081 3825.76 +EDGE_SE3:QUAT 509 510 -0.139135 9.58476 -0.155281 -0.105415 -0.0762546 -0.0382814 0.990761 1 7.70372e-19 7.70372e-19 -5.57366e-08 1.22465e-09 4.63868e-09 1 7.70372e-19 -5.57366e-08 1.22465e-09 4.63868e-09 1 -5.57366e-08 1.22465e-09 4.63868e-09 4062.39 31.8166 -662.455 3973.88 -2.99496 4100.98 +EDGE_SE3:QUAT 510 511 -0.202847 9.71777 0.115507 -0.0974677 -0.265632 -0.069694 0.956599 1 3.27408e-18 3.27408e-18 3.36496e-08 1.05739e-07 -9.54182e-10 1 3.27408e-18 3.36496e-08 1.05739e-07 -9.54182e-10 1 3.36496e-08 1.05739e-07 -9.54182e-10 5467.6 76.082 -2879.11 3708.69 -69.5607 5486.18 +EDGE_SE3:QUAT 511 512 -0.787163 9.18029 0.0561565 -0.131537 -0.0149091 0.0293271 0.990765 1 7.70372e-19 7.70372e-19 -5.50067e-08 -1.78822e-09 3.73041e-10 1 7.70372e-19 -5.50067e-08 -1.78822e-09 3.73041e-10 1 -5.50067e-08 -1.78822e-09 3.73041e-10 3931.95 3.61552 -70.304 3999.85 -1.11565 3997.72 +EDGE_SE3:QUAT 512 513 -0.48935 9.43241 -0.0310052 0.113336 -0.120859 0.141306 0.976002 1 9.62965e-19 9.62965e-19 -1.98044e-08 -7.831e-09 -5.2227e-08 1 9.62965e-19 -1.98044e-08 -7.831e-09 -5.2227e-08 1 -1.98044e-08 -7.831e-09 -5.2227e-08 4278.85 -14.3931 -1196.36 3920.74 -48.7078 4250.36 +EDGE_SE3:QUAT 513 514 -0.628207 9.10212 -0.0928819 -0.134668 0.0298205 0.103042 0.985067 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3965.69 -25.5563 395.639 3988.37 16.8017 3995.76 +EDGE_SE3:QUAT 514 515 -0.341669 9.50942 -0.0747988 -0.0794903 -0.0991002 -0.0427346 0.990976 1 2.40741e-19 2.40741e-19 2.66263e-08 -1.79453e-09 1.10925e-08 1 2.40741e-19 2.66263e-08 -1.79453e-09 1.10925e-08 1 2.66263e-08 -1.79453e-09 1.10925e-08 4150.34 26.8774 -856.362 3957.39 -0.522047 4168.31 +EDGE_SE3:QUAT 515 516 -0.504645 9.56655 -0.507149 -0.0516796 -0.100693 -0.0587403 0.991837 1 4.81482e-20 4.81482e-20 1.4073e-08 -6.97104e-10 -1.49902e-09 1 4.81482e-20 1.4073e-08 -6.97104e-10 -1.49902e-09 1 1.4073e-08 -6.97104e-10 -1.49902e-09 4169.67 9.23118 -868.328 3956.02 14.6 4166.55 +EDGE_SE3:QUAT 516 517 -0.203325 8.9715 -0.0865699 0.0634379 0.026603 0.132882 0.988742 1 1.92593e-19 1.92593e-19 2.74518e-08 3.75595e-09 2.42951e-10 1 1.92593e-19 2.74518e-08 3.75595e-09 2.42951e-10 1 2.74518e-08 3.75595e-09 2.42951e-10 3986.38 3.07465 106.169 3999.81 5.08321 3931.85 +EDGE_SE3:QUAT 517 518 -0.349449 9.31498 0.102329 -0.201226 -0.0759332 -0.000664848 0.976597 1 3.00927e-21 3.00927e-21 -2.45397e-10 -7.13552e-10 3.42471e-09 1 3.00927e-21 -2.45397e-10 -7.13552e-10 3.42471e-09 1 -2.45397e-10 -7.13552e-10 3.42471e-09 3921.02 60.7938 -582.601 3984.24 -26.3845 4082.99 +EDGE_SE3:QUAT 518 519 -0.16056 9.4388 -0.00506501 0.0530277 0.0880876 -0.159261 0.981868 1 4.81482e-20 4.81482e-20 -1.3895e-08 2.1479e-09 -1.41579e-09 1 4.81482e-20 -1.3895e-08 2.1479e-09 -1.41579e-09 1 -1.3895e-08 2.1479e-09 -1.41579e-09 4143.91 -12.6993 803.053 3963.4 -59.7455 4053.7 +EDGE_SE3:QUAT 519 520 -0.114796 9.18146 0.0221445 0.125913 0.066415 -0.013715 0.989721 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.29 34.7957 547.963 3982.81 10.1026 4072.95 +EDGE_SE3:QUAT 520 521 -0.327903 9.54871 -0.148041 -0.0562987 -0.0883443 -0.0516504 0.993156 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4126.28 12.7155 -758.417 3965.76 9.8078 4128.28 +EDGE_SE3:QUAT 521 522 -0.674035 9.70161 -0.110938 -0.0434773 0.0670834 -0.0566233 0.99519 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4056.34 -16.9812 509.765 3985.36 -19.0933 4051.08 +EDGE_SE3:QUAT 522 523 -0.391019 9.37523 0.116584 -0.0561763 0.0707964 0.057333 0.994256 1 4.81482e-20 4.81482e-20 1.07211e-09 -6.77143e-10 1.39559e-08 1 4.81482e-20 1.07211e-09 -6.77143e-10 1.39559e-08 1 1.07211e-09 -6.77143e-10 1.39559e-08 4078.88 -10.7055 611.93 3977.07 11.2429 4078.35 +EDGE_SE3:QUAT 523 524 -0.282783 9.40961 -0.107838 -0.0742359 -0.094395 0.131118 0.984066 1 3.85186e-19 3.85186e-19 2.3604e-08 3.13524e-08 7.26058e-10 1 3.85186e-19 2.3604e-08 3.13524e-08 7.26058e-10 1 2.3604e-08 3.13524e-08 7.26058e-10 4072.36 44.405 -624.276 3983.75 -52.9286 4025.63 +EDGE_SE3:QUAT 524 525 -0.41343 9.44433 0.141631 0.15821 0.002995 0.0828801 0.983916 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3903.56 -14.2821 -131.298 3997.93 -7.08001 3976.21 +EDGE_SE3:QUAT 525 526 -0.517318 9.31252 -0.33059 0.200719 -0.104719 0.205832 0.952039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4241.18 -58.622 -1334.07 3899.44 -65.962 4232.86 +EDGE_SE3:QUAT 526 527 -0.538286 9.41893 -0.605382 0.0383541 -0.103846 0.131935 0.985057 1 1.20371e-20 1.20371e-20 -7.00335e-09 -8.99825e-10 7.83106e-10 1 1.20371e-20 -7.00335e-09 -8.99825e-10 7.83106e-10 1 -7.00335e-09 -8.99825e-10 7.83106e-10 4189.77 19.3899 -906.046 3954.52 -56.5845 4126.03 +EDGE_SE3:QUAT 527 528 -0.548128 9.65316 -0.0102529 0.196001 0.0371253 -0.196797 0.959936 1 7.70372e-19 7.70372e-19 5.41746e-08 -9.51928e-09 5.97977e-09 1 7.70372e-19 5.41746e-08 -9.51928e-09 5.97977e-09 1 5.41746e-08 -9.51928e-09 5.97977e-09 3971.16 58.7409 726.618 3959.76 -59.2243 3969.91 +EDGE_SE3:QUAT 528 529 -0.548302 9.5752 -0.0619605 -0.0262027 0.0949452 0.0946329 0.990628 1 2.0463e-19 2.0463e-19 9.54174e-09 -2.68585e-08 4.69821e-10 1 2.0463e-19 9.54174e-09 -2.68585e-08 4.69821e-10 1 9.54174e-09 -2.68585e-08 4.69821e-10 4153.31 10.7138 805.363 3962.76 35.9928 4120.24 +EDGE_SE3:QUAT 529 530 -0.669194 9.47948 -0.0681406 -0.0765393 -0.132175 0.0299708 0.987812 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4248.54 61.0791 -1078.05 3939.94 -51.8024 4268.38 +EDGE_SE3:QUAT 530 531 -0.420198 9.57957 -0.0105999 -0.0103153 0.144322 -0.0613319 0.987574 1 7.82409e-19 7.82409e-19 -3.42377e-09 5.52858e-08 5.78869e-10 1 7.82409e-19 -3.42377e-09 5.52858e-08 5.78869e-10 1 -3.42377e-09 5.52858e-08 5.78869e-10 4345.16 -41.0099 1225.5 3921.47 -51.3316 4330.54 +EDGE_SE3:QUAT 531 532 -0.829309 9.26922 0.0399403 0.0880113 -0.231036 0.0763977 0.96594 1 2.40741e-19 2.40741e-19 2.65086e-08 2.19532e-09 7.62949e-09 1 2.40741e-19 2.65086e-08 2.19532e-09 7.62949e-09 1 2.65086e-08 2.19532e-09 7.62949e-09 5052.53 -30.4791 -2346.94 3775.25 12.5741 5060.17 +EDGE_SE3:QUAT 532 533 -0.654298 9.31729 0.276387 0.0879356 0.0185486 0.0678729 0.993638 1 1.95602e-19 1.95602e-19 2.73401e-08 5.39274e-09 -1.38386e-10 1 1.95602e-19 2.73401e-08 5.39274e-09 -1.38386e-10 1 2.73401e-08 5.39274e-09 -1.38386e-10 3970.3 2.4048 74.5936 3999.88 1.96604 3982.81 +EDGE_SE3:QUAT 533 534 -0.498283 9.25378 -0.127003 -0.128729 0.0524549 0.233693 0.962323 1 9.62965e-19 9.62965e-19 2.13337e-08 1.12586e-08 -5.14382e-08 1 9.62965e-19 2.13337e-08 1.12586e-08 -5.14382e-08 1 2.13337e-08 1.12586e-08 -5.14382e-08 4066.68 -17.1628 745.564 3962.64 82.6057 3914.51 +EDGE_SE3:QUAT 534 535 -0.810578 9.72815 -0.155335 -0.017779 -0.122193 -0.129236 0.983896 1 1.93345e-19 1.93345e-19 -5.33565e-09 -2.70797e-08 6.17082e-10 1 1.93345e-19 -5.33565e-09 -2.70797e-08 6.17082e-10 1 -5.33565e-09 -2.70797e-08 6.17082e-10 4250.42 -39.8631 -1034.47 3944.12 70.8287 4184.88 +EDGE_SE3:QUAT 535 536 -0.41302 9.42531 0.0801834 -0.126383 0.132466 0.0163158 0.982962 1 1.42235e-21 1.42235e-21 3.2718e-10 -3.13068e-10 2.43116e-09 1 1.42235e-21 3.2718e-10 -3.13068e-10 2.43116e-09 1 3.2718e-10 -3.13068e-10 2.43116e-09 4231.99 -77.2657 1127.45 3934.92 -47.5473 4294.82 +EDGE_SE3:QUAT 536 537 -0.487913 9.89979 0.0555873 -0.140335 -0.0885015 0.132757 0.977164 1 9.62965e-19 9.62965e-19 -5.03293e-08 -3.56232e-08 -1.94219e-09 1 9.62965e-19 -5.03293e-08 -3.56232e-08 -1.94219e-09 1 -5.03293e-08 -3.56232e-08 -1.94219e-09 3969.18 40.191 -451.354 3995.75 -39.4751 3977.46 +EDGE_SE3:QUAT 537 538 -0.556098 9.54358 0.026677 -0.0361539 -0.15636 -0.095318 0.982425 1 2.0463e-19 2.0463e-19 2.49714e-09 -8.37699e-10 2.75683e-08 1 2.0463e-19 2.49714e-09 -8.37699e-10 2.75683e-08 1 2.49714e-09 -8.37699e-10 2.75683e-08 4434.27 -33.4127 -1396.83 3900.59 60.1174 4403.15 +EDGE_SE3:QUAT 538 539 -0.717609 9.68314 -0.0691863 -0.0112959 0.178321 -0.0246703 0.983598 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4556.68 -34.0251 1593.49 3874.88 -36.4266 4554.75 +EDGE_SE3:QUAT 539 540 -0.605328 9.43228 -0.131774 -0.122512 0.0945634 0.0909716 0.983754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4133.82 -38.0025 902.107 3951.89 12.6394 4160.75 +EDGE_SE3:QUAT 540 541 -0.167845 9.45358 -0.208455 0.0901409 0.00576798 0.126483 0.987848 1 1.92593e-19 1.92593e-19 2.74237e-08 3.48251e-09 -4.72909e-10 1 1.92593e-19 2.74237e-08 3.48251e-09 -4.72909e-10 1 2.74237e-08 3.48251e-09 -4.72909e-10 3969.03 -5.98134 -90.1607 3998.85 -8.50564 3937.54 +EDGE_SE3:QUAT 541 542 -0.44258 9.89785 -0.261431 -0.157703 0.0662338 0.0140673 0.985162 1 7.52316e-22 7.52316e-22 -1.17857e-10 2.75292e-10 -1.72489e-09 1 7.52316e-22 -1.17857e-10 2.75292e-10 -1.72489e-09 1 -1.17857e-10 2.75292e-10 -1.72489e-09 3973.44 -43.6591 545.018 3983.71 -13.4895 4072.13 +EDGE_SE3:QUAT 542 543 -0.511602 9.64552 -0.221048 0.0160682 -0.163285 0.0518684 0.985083 1 3.00927e-21 3.00927e-21 3.61222e-09 1.80837e-10 -6.0156e-10 1 3.00927e-21 3.61222e-09 1.80837e-10 -6.0156e-10 1 3.61222e-09 1.80837e-10 -6.0156e-10 4465.97 23.2437 -1444.33 3893.46 -36.4923 4456.24 +EDGE_SE3:QUAT 543 544 -0.628632 9.60198 -0.103298 -0.0378283 0.0578022 0.0407389 0.996779 1 4.81482e-20 4.81482e-20 -1.39332e-08 -5.10399e-10 -8.46331e-10 1 4.81482e-20 -1.39332e-08 -5.10399e-10 -8.46331e-10 1 -1.39332e-08 -5.10399e-10 -8.46331e-10 4052.23 -6.09876 484.969 3985.47 7.08963 4051.31 +EDGE_SE3:QUAT 544 545 -0.658812 9.55893 0.341673 0.160889 0.0605733 0.0841983 0.981507 1 7.70372e-19 7.70372e-19 5.46364e-08 5.54064e-09 1.65385e-09 1 7.70372e-19 5.46364e-08 5.54064e-09 1.65385e-09 1 5.46364e-08 5.54064e-09 1.65385e-09 3918 23.5781 301.91 3997.79 17.5384 3993.18 +EDGE_SE3:QUAT 545 546 -0.879834 9.8329 0.0265257 -0.16841 0.0535594 0.153619 0.972199 1 9.62965e-19 9.62965e-19 -5.84158e-08 1.98369e-08 -1.5157e-09 1 9.62965e-19 -5.84158e-08 1.98369e-08 -1.5157e-09 1 -5.84158e-08 1.98369e-08 -1.5157e-09 4010.27 -46.9452 718.249 3964.42 38.2237 4029.33 +EDGE_SE3:QUAT 546 547 -0.698719 9.66613 -0.0241941 0.0626012 0.0951689 0.235058 0.965283 1 7.70372e-19 7.70372e-19 3.05788e-09 5.62228e-09 5.40558e-08 1 7.70372e-19 3.05788e-09 5.62228e-09 5.40558e-08 1 3.05788e-09 5.62228e-09 5.40558e-08 4050.54 45.5647 528.276 3995.11 64.6296 3845.21 +EDGE_SE3:QUAT 547 548 -0.392541 9.1025 -0.0642423 -0.0452016 0.00394579 0.137273 0.989493 1 4.81482e-20 4.81482e-20 1.37365e-08 1.89314e-09 2.22974e-10 1 4.81482e-20 1.37365e-08 1.89314e-09 2.22974e-10 1 1.37365e-08 1.89314e-09 2.22974e-10 3994.4 -2.50696 104.077 3999 8.69843 3927.2 +EDGE_SE3:QUAT 548 549 -0.833943 9.66826 0.0902021 -0.0339372 0.0659206 -0.0672016 0.994981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4057.39 -15.2051 501.986 3985.79 -20.5156 4043.93 +EDGE_SE3:QUAT 549 550 -0.156264 9.67854 -0.230059 0.0844977 -0.119776 0.0343198 0.988603 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4223.94 -37.7817 -1036.22 3940.31 11.9362 4247.79 +EDGE_SE3:QUAT 550 551 -0.693862 9.70656 -0.00299733 -0.127717 -0.141101 -0.0692313 0.979278 1 1.92593e-19 1.92593e-19 2.84923e-08 -9.62442e-10 -4.46149e-09 1 1.92593e-19 2.84923e-08 -9.62442e-10 -4.46149e-09 1 2.84923e-08 -9.62442e-10 -4.46149e-09 4322.91 63.2518 -1305.18 3910.78 -19.4263 4368.98 +EDGE_SE3:QUAT 551 552 -0.57876 9.71503 -0.172023 0.276635 0.134726 -0.187933 0.93274 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4341.86 163.793 1737.57 3857.35 30.4514 4506.69 +EDGE_SE3:QUAT 552 553 -0.404805 9.84816 -0.0828074 -0.0409258 -0.137651 0.154446 0.977509 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4243.7 88.576 -1033.21 3955.44 -108.334 4154.98 +EDGE_SE3:QUAT 553 554 -0.489147 9.54185 -0.0759754 -0.0501539 -0.132544 0.0856997 0.986191 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4246.78 65.6425 -1046.07 3946.04 -72.4194 4227.47 +EDGE_SE3:QUAT 554 555 -0.385505 10.1993 -0.380177 -0.0104054 0.0392004 0.0316456 0.998676 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.82 -0.494957 318.797 3993.7 4.75154 4021.24 +EDGE_SE3:QUAT 555 556 -0.715068 9.67623 -0.28391 0.00439254 -0.0558132 0.109183 0.992444 1 4.70198e-23 4.70198e-23 4.33107e-10 4.77337e-11 -2.41912e-11 1 4.70198e-23 4.33107e-10 4.77337e-11 -2.41912e-11 1 4.33107e-10 4.77337e-11 -2.41912e-11 4049.72 7.25416 -449.096 3988.32 -24.9529 4002.12 +EDGE_SE3:QUAT 556 557 -0.335098 9.31556 -0.0433475 -0.0217449 0.270853 -0.00625767 0.962355 1 1.20371e-20 1.20371e-20 7.82196e-09 -1.67517e-10 2.19615e-09 1 1.20371e-20 7.82196e-09 -1.67517e-10 2.19615e-09 1 7.82196e-09 -1.67517e-10 2.19615e-09 5485.27 -73.0066 2856.63 3710.01 -72.5804 5487.01 +EDGE_SE3:QUAT 557 558 -0.365568 9.85068 -0.365929 -0.0153491 -0.145246 0.0277239 0.988888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4354.47 27.1024 -1244.18 3917.65 -29.629 4352.34 +EDGE_SE3:QUAT 558 559 -0.648249 10.061 -0.253492 -0.0329099 -0.0671444 -0.0641103 0.995137 1 1.20371e-20 1.20371e-20 6.97345e-09 -4.21382e-10 -4.95421e-10 1 1.20371e-20 6.97345e-09 -4.21382e-10 -4.95421e-10 1 6.97345e-09 -4.21382e-10 -4.95421e-10 4074.8 2.36859 -568.179 3980.32 15.4686 4062.69 +EDGE_SE3:QUAT 559 560 -0.234827 9.92471 -0.322342 -0.0636583 0.11953 -0.00635725 0.990767 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4216.86 -38.5643 993.284 3945.8 -26.6435 4232.9 +EDGE_SE3:QUAT 560 561 -0.154508 9.95932 0.173347 -0.0457376 -0.0346891 0.256122 0.964939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.09 3.55858 -115.334 4000.32 -7.9843 3740.07 +EDGE_SE3:QUAT 561 562 -0.745358 9.51061 -0.0528365 0.0913149 0.0591619 0.078169 0.990985 1 1.92593e-19 1.92593e-19 -1.20322e-09 -2.78749e-09 -2.76293e-08 1 1.92593e-19 -1.20322e-09 -2.78749e-09 -2.76293e-08 1 -1.20322e-09 -2.78749e-09 -2.76293e-08 4002.2 21.1524 380.406 3993.32 19.589 4011.11 +EDGE_SE3:QUAT 562 563 -0.630782 9.59009 -0.168494 0.10828 0.0255515 0.0826086 0.990353 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3954.88 3.41469 92.6527 3999.9 2.83798 3974.48 +EDGE_SE3:QUAT 563 564 -0.980712 9.75659 -0.263503 0.121194 -0.165374 0.200504 0.957999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4586.98 52.6118 -1732.36 3861.45 -123.152 4484.92 +EDGE_SE3:QUAT 564 565 -0.332127 10.0351 -0.0321541 -0.123417 0.171214 0.0956071 0.972786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4539.5 -51.0228 1662.13 3865.48 -6.79193 4563.87 +EDGE_SE3:QUAT 565 566 -0.469861 10.3012 -0.342342 0.00139818 -0.102757 0.174908 0.979207 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4159.3 43.5656 -814.384 3968.14 -77.684 4036.94 +EDGE_SE3:QUAT 566 567 -0.626115 9.42897 0.0213457 0.0491214 0.0127167 0.128329 0.990433 1 4.81482e-20 4.81482e-20 -1.3745e-08 -1.78978e-09 3.53055e-12 1 4.81482e-20 -1.3745e-08 -1.78978e-09 3.53055e-12 1 -1.3745e-08 -1.78978e-09 3.53055e-12 3990.32 0.0292562 24.1575 4000.01 -0.0994099 3934.1 +EDGE_SE3:QUAT 567 568 -0.296792 10.0441 0.0804693 0.0104459 -0.103322 -0.0603299 0.992762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4170.53 -20.8012 -844.483 3959.82 30.9517 4156.41 +EDGE_SE3:QUAT 568 569 -0.780244 9.77324 0.318724 0.0651972 0.061777 0.0315548 0.995458 1 2.40741e-19 2.40741e-19 2.72695e-08 1.49174e-08 6.28712e-10 1 2.40741e-19 2.72695e-08 1.49174e-08 6.28712e-10 1 2.72695e-08 1.49174e-08 6.28712e-10 4037.68 18.3085 471.018 3987.39 13.1118 4050.7 +EDGE_SE3:QUAT 569 570 -0.61819 9.92812 -0.0140729 0.0256827 -0.121338 0.189705 0.973976 1 7.75074e-19 7.75074e-19 2.63563e-09 3.94599e-10 -5.52414e-08 1 7.75074e-19 2.63563e-09 3.94599e-10 -5.52414e-08 1 2.63563e-09 3.94599e-10 -5.52414e-08 4246.66 58.7975 -1029.37 3949.7 -103.824 4105.35 +EDGE_SE3:QUAT 570 571 -0.494997 9.68315 0.0529065 0.0655393 0.00917518 0.148227 0.986737 1 1.92605e-19 1.92605e-19 -2.73557e-08 -4.32569e-09 3.05049e-10 1 1.92605e-19 -2.73557e-08 -4.32569e-09 3.05049e-10 1 -2.73557e-08 -4.32569e-09 3.05049e-10 3982.93 -2.73818 -44.0096 3999.56 -6.20962 3912.22 +EDGE_SE3:QUAT 571 572 -0.758361 10.0073 -0.244483 -0.302504 -0.0776999 -0.066761 0.947627 1 1.92593e-19 1.92593e-19 -2.82451e-10 -2.63656e-08 -8.19401e-09 1 1.92593e-19 -2.82451e-10 -2.63656e-08 -8.19401e-09 1 -2.82451e-10 -2.63656e-08 -8.19401e-09 3784.63 123.355 -790.898 3971.18 -36.6412 4132.84 +EDGE_SE3:QUAT 572 573 -0.548276 9.69998 -0.261585 -0.0298586 0.0642705 0.115225 0.990808 1 2.0463e-19 2.0463e-19 4.99749e-09 1.19264e-09 -2.72756e-08 1 2.0463e-19 4.99749e-09 1.19264e-09 -2.72756e-08 1 4.99749e-09 1.19264e-09 -2.72756e-08 4071.62 4.06235 553.575 3981.69 30.6546 4022.08 +EDGE_SE3:QUAT 573 574 -0.549739 9.71842 -0.0480571 -0.0988591 -0.120202 0.0655256 0.985639 1 1.92593e-19 1.92593e-19 -2.80153e-08 -2.56186e-09 2.93905e-09 1 1.92593e-19 -2.80153e-08 -2.56186e-09 2.93905e-09 1 -2.80153e-08 -2.56186e-09 2.93905e-09 4152.44 69.3279 -896.969 3961.98 -63.3097 4174.35 +EDGE_SE3:QUAT 574 575 -0.338574 10.0837 0.0401096 0.00618568 -0.00210536 0.0575908 0.998319 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.96 -0.0606153 -21.0241 3999.97 -0.644712 3986.84 +EDGE_SE3:QUAT 575 576 -0.792889 10.1542 -0.0746187 0.0858822 -0.086543 0.0710092 0.989996 1 1.92593e-19 1.92593e-19 2.79797e-08 1.58683e-09 -2.73366e-09 1 1.92593e-19 2.79797e-08 1.58683e-09 -2.73366e-09 1 2.79797e-08 1.58683e-09 -2.73366e-09 4116.29 -21.9332 -777.625 3963.71 -12.2817 4125.62 +EDGE_SE3:QUAT 576 577 -0.495678 10.0676 -0.0662107 -0.0601456 -0.00660085 0.00202552 0.998166 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.18 1.52094 -51.0689 3999.84 -0.110973 4000.64 +EDGE_SE3:QUAT 577 578 -0.663579 9.63687 -0.224098 -0.0762016 0.0584924 0.013516 0.995284 1 1.92593e-19 1.92593e-19 -2.78229e-08 -1.26304e-10 -1.67333e-09 1 1.92593e-19 -2.78229e-08 -1.26304e-10 -1.67333e-09 1 -2.78229e-08 -1.26304e-10 -1.67333e-09 4034.06 -17.99 482.118 3985.99 -3.1623 4056.56 +EDGE_SE3:QUAT 578 579 -0.663294 9.93296 0.00340817 0.121869 0.0270881 0.172005 0.977153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3939.19 -8.00174 -41.785 3998.96 -11.264 3880.25 +EDGE_SE3:QUAT 579 580 -0.724714 10.0262 -0.476432 0.0999627 -0.147391 -0.118756 0.976822 1 1.92593e-19 1.92593e-19 2.79849e-08 -4.33155e-09 -3.30289e-09 1 1.92593e-19 2.79849e-08 -4.33155e-09 -3.30289e-09 1 2.79849e-08 -4.33155e-09 -3.30289e-09 4213.63 -111.144 -1041.85 3959.68 114.035 4197.19 +EDGE_SE3:QUAT 580 581 -0.450375 9.97643 0.000961704 -0.0194372 0.0349277 0.286596 0.957217 1 3.00927e-21 3.00927e-21 3.33184e-09 9.95125e-10 1.3873e-10 1 3.00927e-21 3.33184e-09 9.95125e-10 1.3873e-10 1 3.33184e-09 9.95125e-10 1.3873e-10 4022.45 7.17452 310.552 3995.65 45.9449 3695.41 +EDGE_SE3:QUAT 581 582 -0.477419 9.83851 -0.316711 -0.0859931 0.0973534 -0.0141855 0.991426 1 1.92593e-19 1.92593e-19 -2.80205e-08 8.80635e-10 -2.63855e-09 1 1.92593e-19 -2.80205e-08 8.80635e-10 -2.63855e-09 1 -2.80205e-08 8.80635e-10 -2.63855e-09 4116.76 -39.6532 779.025 3966.54 -25.5669 4145.53 +EDGE_SE3:QUAT 582 583 -0.489504 10.1455 0.205668 0.137471 -0.0128422 0.123014 0.982753 1 1.92593e-19 1.92593e-19 1.25901e-09 -3.62658e-09 -2.73512e-08 1 1.92593e-19 1.25901e-09 -3.62658e-09 -2.73512e-08 1 1.25901e-09 -3.62658e-09 -2.73512e-08 3945.53 -22.1221 -297.549 3992.22 -19.123 3960.59 +EDGE_SE3:QUAT 583 584 -0.905063 10.1071 -0.0989094 -0.0398976 0.00373638 0.11535 0.992516 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.32 -1.81381 83.9412 3999.36 5.81541 3948.46 +EDGE_SE3:QUAT 584 585 -0.742992 10.1851 0.00754403 -0.0922848 0.191447 0.13111 0.968319 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4722.25 30.5836 1896.74 3836.39 69.8564 4687.56 +EDGE_SE3:QUAT 585 586 -0.796443 10.1387 0.144924 -0.138208 -0.0642184 0.194918 0.968907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3925.88 6.52005 -157.388 4001.24 -6.3817 3850.31 +EDGE_SE3:QUAT 586 587 -0.452708 9.89203 0.0468873 0.00217239 -0.0696476 0.306092 0.949448 1 4.81482e-20 4.81482e-20 -1.32842e-08 -4.32095e-09 8.07993e-10 1 4.81482e-20 -1.32842e-08 -4.32095e-09 8.07993e-10 1 -1.32842e-08 -4.32095e-09 8.07993e-10 4059.54 30.4539 -494.071 3993.71 -75.2048 3684.79 +EDGE_SE3:QUAT 587 588 -0.267277 10.1119 -0.271912 0.0559619 -0.0890955 0.031261 0.993958 1 6.01853e-20 6.01853e-20 -1.33796e-08 -6.64372e-10 -5.71688e-09 1 6.01853e-20 -1.33796e-08 -6.64372e-10 -5.71688e-09 1 -1.33796e-08 -6.64372e-10 -5.71688e-09 4124 -16.5634 -751.513 3966.6 -1.31568 4132.62 +EDGE_SE3:QUAT 588 589 -0.256469 9.93235 0.0518077 -0.124758 -0.102865 0.1403 0.976816 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.56 55.0955 -579.016 3991.14 -56.8945 4001.08 +EDGE_SE3:QUAT 589 590 -0.825166 9.86201 -0.277758 0.140811 0.000310956 0.16679 0.975886 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3937.25 -23.0047 -271.718 3992.05 -28.2088 3905.29 +EDGE_SE3:QUAT 590 591 -0.483526 10.4953 0.319443 0.117799 -0.133221 0.175414 0.9683 1 9.62965e-19 9.62965e-19 -1.87555e-08 -8.25411e-09 -5.18351e-08 1 9.62965e-19 -1.87555e-08 -8.25411e-09 -5.18351e-08 1 -1.87555e-08 -8.25411e-09 -5.18351e-08 4364.58 6.91261 -1363.24 3902.57 -79.7204 4297.01 +EDGE_SE3:QUAT 591 592 -0.42444 10.1619 0.0649761 0.0588268 -0.118588 0.192238 0.972379 1 4.81482e-20 4.81482e-20 1.39739e-08 2.62974e-09 -1.89303e-09 1 4.81482e-20 1.39739e-08 2.62974e-09 -1.89303e-09 1 1.39739e-08 2.62974e-09 -1.89303e-09 4264.42 43.0321 -1091.13 3939.59 -100.593 4130.44 +EDGE_SE3:QUAT 592 593 -0.425024 10.0021 0.0244831 -0.0119745 -0.0800861 0.227767 0.970343 1 2.0463e-19 2.0463e-19 3.58224e-10 2.85329e-08 8.30589e-10 1 2.0463e-19 3.58224e-10 2.85329e-08 8.30589e-10 1 3.58224e-10 2.85329e-08 8.30589e-10 4078.16 33.3486 -568.34 3987.64 -67.0432 3871.22 +EDGE_SE3:QUAT 593 594 -0.339212 9.91957 -0.235149 0.0801709 0.0353112 0.0106587 0.996098 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.5 11.1052 270.547 3995.74 3.68671 4017.75 +EDGE_SE3:QUAT 594 595 -0.899313 10.2828 -0.209313 0.0686259 0.0359584 0.11878 0.989893 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.18 7.02409 183.043 3998.9 9.96126 3951.58 +EDGE_SE3:QUAT 595 596 -0.559743 9.78734 0.23928 -5.58509e-05 -0.0053483 -0.0908151 0.995853 1 2.93874e-24 2.93874e-24 -1.07977e-10 9.84725e-12 5.71427e-13 1 2.93874e-24 -1.07977e-10 9.84725e-12 5.71427e-13 1 -1.07977e-10 9.84725e-12 5.71427e-13 4000.45 -0.0603719 -42.3229 3999.89 1.91518 3967.46 +EDGE_SE3:QUAT 596 597 -0.785378 10.1859 0.104627 -0.0107476 0.106419 -0.188429 0.976245 1 1.20371e-20 1.20371e-20 6.91045e-09 -1.37996e-09 6.69447e-10 1 1.20371e-20 6.91045e-09 -1.37996e-09 6.69447e-10 1 6.91045e-09 -1.37996e-09 6.69447e-10 4156.14 -52.6663 807.743 3971.32 -85.2235 4014.58 +EDGE_SE3:QUAT 597 598 -0.628203 10.3335 -0.208638 0.0739852 -0.078757 0.125131 0.986238 1 1.92593e-19 1.92593e-19 2.7835e-08 3.21318e-09 -2.65349e-09 1 1.92593e-19 2.7835e-08 3.21318e-09 -2.65349e-09 1 2.7835e-08 3.21318e-09 -2.65349e-09 4111.46 -6.55802 -742.819 3966.52 -37.7397 4070.72 +EDGE_SE3:QUAT 598 599 -0.42787 10.0993 -0.145721 0.00577934 -0.00391984 -0.0694162 0.997563 1 9.40395e-22 9.40395e-22 -1.67029e-09 9.8574e-10 -9.00386e-14 1 9.40395e-22 -1.67029e-09 9.8574e-10 -9.00386e-14 1 -1.67029e-09 9.8574e-10 -9.00386e-14 4000.04 -0.0908953 -26.333 3999.96 0.857379 3980.9 +EDGE_SE3:QUAT 599 600 -0.595465 10.4431 -0.169152 -0.0228006 -0.0332064 -0.0255363 0.998862 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.51 2.47144 -273.293 3995.31 2.92837 4015.98 +EDGE_SE3:QUAT 600 601 -0.142583 10.451 -0.0533729 0.0960499 0.0685549 0.210634 0.970416 1 8.1852e-19 8.1852e-19 -1.86728e-09 1.99068e-08 5.23688e-08 1 8.1852e-19 -1.86728e-09 1.99068e-08 5.23688e-08 1 -1.86728e-09 1.99068e-08 5.23688e-08 3978.57 17.3982 269.45 4000.32 22.9122 3838.01 +EDGE_SE3:QUAT 601 602 -0.566097 10.0558 -0.100616 0.0376018 -0.164763 0.150567 0.974048 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4485.09 80.8295 -1484.54 3897.18 -117.283 4400.06 +EDGE_SE3:QUAT 602 603 -0.6217 9.99367 0.161573 -0.00643527 0.200365 0.17502 0.96394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4665.23 187.544 1762.62 3885.21 212.414 4542.87 +EDGE_SE3:QUAT 603 604 -1.19346 10.1076 -0.45695 -0.134932 -0.183971 0.0471304 0.972485 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4417.55 170.462 -1485.3 3915.02 -157.605 4481.49 +EDGE_SE3:QUAT 604 605 -0.708541 10.3239 0.0799943 -0.121496 -0.270561 0.0440558 0.953989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5203.39 378.649 -2578.78 3817.84 -377.859 5254.67 +EDGE_SE3:QUAT 605 606 -0.514504 10.0083 -0.155603 0.0922656 0.0796012 0.0154871 0.992427 1 1.92593e-19 1.92593e-19 2.78735e-08 8.47545e-10 2.11488e-09 1 1.92593e-19 2.78735e-08 8.47545e-10 2.11488e-09 1 2.78735e-08 8.47545e-10 2.11488e-09 4060.92 32.5174 623.726 3978.33 18.6853 4094.01 +EDGE_SE3:QUAT 606 607 -0.816709 10.4672 -0.326773 -0.021425 -0.0373653 0.0276047 0.998691 1 1.20371e-20 1.20371e-20 -6.94825e-09 -2.03564e-10 2.51074e-10 1 1.20371e-20 -6.94825e-09 -2.03564e-10 2.51074e-10 1 -6.94825e-09 -2.03564e-10 2.51074e-10 4019.45 4.04672 -292.611 3994.82 -4.75555 4018.24 +EDGE_SE3:QUAT 607 608 -0.846873 10.2719 -0.184075 -0.0048481 -0.0313981 0.048331 0.998326 1 1.27894e-20 1.27894e-20 -1.39704e-09 -7.01184e-09 -1.11524e-12 1 1.27894e-20 -1.39704e-09 -7.01184e-09 -1.11524e-12 1 -1.39704e-09 -7.01184e-09 -1.11524e-12 4015.26 1.72906 -248.311 3996.25 -6.14472 4006.01 +EDGE_SE3:QUAT 608 609 -0.550426 10.4963 -0.0820798 0.106289 -0.000375964 0.0146356 0.994228 1 3.00927e-21 3.00927e-21 -1.20064e-11 3.68573e-10 3.44947e-09 1 3.00927e-21 -1.20064e-11 3.68573e-10 3.44947e-09 1 -1.20064e-11 3.68573e-10 3.44947e-09 3954.92 -1.46969 -21.4805 3999.95 -0.190627 3999.25 +EDGE_SE3:QUAT 609 610 -0.5275 10.3209 -0.176333 0.0923681 0.00893212 0.0837876 0.992153 1 7.70372e-19 7.70372e-19 -5.50747e-08 -4.66268e-09 3.72164e-10 1 7.70372e-19 -5.50747e-08 -4.66268e-09 3.72164e-10 1 -5.50747e-08 -4.66268e-09 3.72164e-10 3965.75 -2.48044 -22.1157 3999.82 -2.25068 3971.8 +EDGE_SE3:QUAT 610 611 -0.317657 10.0543 -0.07013 -0.141213 0.116055 0.16145 0.969806 1 9.62965e-19 9.62965e-19 -1.93313e-08 -9.53142e-09 5.18232e-08 1 9.62965e-19 -1.93313e-08 -9.53142e-09 5.18232e-08 1 -1.93313e-08 -9.53142e-09 5.18232e-08 4266.82 -27.0555 1228.48 3915.83 52.8342 4242.32 +EDGE_SE3:QUAT 611 612 -0.507478 10.1777 -0.0817114 -0.00601432 0.0793809 0.177261 0.980939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4096.95 24.8785 630.909 3979.94 58.217 3971.41 +EDGE_SE3:QUAT 612 613 -0.283178 10.2479 -0.202254 0.0066936 0.0801022 -0.0870498 0.992956 1 3.85374e-19 3.85374e-19 -7.05702e-10 2.78432e-08 -2.7787e-08 1 3.85374e-19 -7.05702e-10 2.78432e-08 -2.7787e-08 1 -7.05702e-10 2.78432e-08 -2.7787e-08 4104.39 -11.5327 655.161 3975.18 -29.3928 4074.26 +EDGE_SE3:QUAT 613 614 -0.647452 10.2341 -0.0373329 -0.0959358 -0.209031 3.62732e-05 0.973192 1 1.54074e-18 1.54074e-18 5.67076e-08 5.65697e-08 -6.60297e-09 1 1.54074e-18 5.67076e-08 5.65697e-08 -6.60297e-09 1 5.67076e-08 5.65697e-08 -6.60297e-09 4739.1 136.009 -1925.1 3842.74 -122.972 4775.91 +EDGE_SE3:QUAT 614 615 -0.549244 10.3273 0.249788 0.024492 0.0835201 0.0849708 0.992575 1 1.92593e-19 1.92593e-19 2.19216e-09 1.08946e-09 2.79038e-08 1 1.92593e-19 2.19216e-09 1.08946e-09 2.79038e-08 1 2.19216e-09 1.08946e-09 2.79038e-08 4100.28 21.9947 649.185 3976.73 32.9727 4073.8 +EDGE_SE3:QUAT 615 616 -0.633779 10.4358 -0.39259 -0.0206894 0.121686 0.161846 0.979066 1 1.88079e-22 1.88079e-22 -8.75914e-10 -1.44665e-10 -1.09031e-10 1 1.88079e-22 -8.75914e-10 -1.44665e-10 -1.09031e-10 1 -8.75914e-10 -1.44665e-10 -1.09031e-10 4247.07 50.5732 1028.19 3947.36 88.7523 4144.01 +EDGE_SE3:QUAT 616 617 -0.889207 10.5883 -0.0909876 0.0518627 -0.015497 0.0841841 0.994979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.78 -4.13612 -174.549 3997.77 -7.56491 3979.19 +EDGE_SE3:QUAT 617 618 -0.689267 10.5368 -0.25865 -0.155359 -0.0214409 0.11982 0.98033 1 7.70372e-19 7.70372e-19 -5.44148e-08 -6.69296e-09 -9.28575e-10 1 7.70372e-19 -5.44148e-08 -6.69296e-09 -9.28575e-10 1 -5.44148e-08 -6.69296e-09 -9.28575e-10 3902.82 -10.4231 55.9745 3998.88 8.05328 3941.94 +EDGE_SE3:QUAT 618 619 -0.522398 10.4864 0.15116 0.069336 -0.0444391 0.146032 0.985846 1 9.62965e-20 9.62965e-20 -1.57092e-08 1.17493e-08 1.21232e-10 1 9.62965e-20 -1.57092e-08 1.17493e-08 1.21232e-10 1 -1.57092e-08 1.17493e-08 1.21232e-10 4034.42 -7.10606 -467.316 3985.54 -32.6162 3968.35 +EDGE_SE3:QUAT 619 620 -0.716018 10.2461 0.248042 0.0763154 -0.00933139 0.142407 0.986818 1 1.92593e-19 1.92593e-19 2.74235e-08 3.87379e-09 -8.42124e-10 1 1.92593e-19 2.74235e-08 3.87379e-09 -8.42124e-10 1 2.74235e-08 3.87379e-09 -8.42124e-10 3986.33 -7.69244 -200.409 3996.48 -16.4878 3928.51 +EDGE_SE3:QUAT 620 621 -0.59825 10.7087 -0.227369 0.134259 0.033046 -0.114825 0.983716 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.8 27.013 438.62 3985.82 -20.9172 3994.16 +EDGE_SE3:QUAT 621 622 -0.4278 10.3281 0.0134387 -0.0194273 -0.0378576 -0.102013 0.993873 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.48 -0.652059 -323.507 3993.54 16.3486 3984.36 +EDGE_SE3:QUAT 622 623 -0.909622 10.4882 0.00427199 -0.052613 0.0194122 0.151931 0.986799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.65 -4.35618 244.527 3995.6 19.9774 3922.39 +EDGE_SE3:QUAT 623 624 -0.601073 10.2113 0.216325 -0.0145501 0.103585 0.0636455 0.992475 1 1.92593e-19 1.92593e-19 -2.96761e-09 3.90371e-11 -2.81624e-08 1 1.92593e-19 -2.96761e-09 3.90371e-11 -2.81624e-08 1 -2.96761e-09 3.90371e-11 -2.81624e-08 4179.21 10.4657 867.553 3956.93 26.8493 4163.85 +EDGE_SE3:QUAT 624 625 -0.90716 10.1286 -0.156409 -0.00343089 -0.0321083 0.0843314 0.995914 1 1.92593e-19 1.92593e-19 8.64124e-10 2.44549e-10 -2.76969e-08 1 1.92593e-19 8.64124e-10 2.44549e-10 -2.76969e-08 1 8.64124e-10 2.44549e-10 -2.76969e-08 4015.7 2.45818 -251.52 3996.26 -10.7129 3987.3 +EDGE_SE3:QUAT 625 626 -0.428924 10.5653 -0.347875 0.220948 0.0172263 0.0512365 0.973786 1 7.70372e-19 7.70372e-19 5.4052e-08 2.97834e-09 -3.6664e-10 1 7.70372e-19 5.4052e-08 2.97834e-09 -3.6664e-10 1 5.4052e-08 2.97834e-09 -3.6664e-10 3804.17 -5.82788 -3.91147 3999.85 -1.3148 3988.94 +EDGE_SE3:QUAT 626 627 -0.596571 10.2676 -0.177363 -0.00680099 -0.0268369 0.109233 0.993631 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.03 2.41251 -202.436 3997.69 -11.0099 3962.48 +EDGE_SE3:QUAT 627 628 -0.898967 10.1764 -0.139858 0.170715 -0.030622 0.133035 0.975818 1 7.70372e-19 7.70372e-19 5.4594e-08 6.45958e-09 -4.04261e-09 1 7.70372e-19 5.4594e-08 6.45958e-09 -4.04261e-09 1 5.4594e-08 6.45958e-09 -4.04261e-09 3943.69 -41.0992 -500.028 3980.73 -26.9998 3989.48 +EDGE_SE3:QUAT 628 629 -0.503226 10.6166 0.0357835 -0.0915479 -0.111449 0.0497182 0.988295 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4140.16 56.5154 -851.916 3963.36 -48.6731 4163.79 +EDGE_SE3:QUAT 629 630 -0.363908 10.4623 0.228345 0.111361 -0.0634688 0.103135 0.986374 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.51 -25.4508 -641.59 3973.57 -21.3379 4057.57 +EDGE_SE3:QUAT 630 631 -0.721735 10.4802 -0.150028 -0.0407382 -0.0500931 -0.0047101 0.997902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4034.08 8.20167 -405.627 3989.94 -1.51661 4040.63 +EDGE_SE3:QUAT 631 632 -0.496917 10.4412 0.133659 -0.0484787 0.0865637 0.261066 0.960209 1 2.0463e-19 2.0463e-19 -1.39173e-08 2.48714e-08 -7.44572e-10 1 2.0463e-19 -1.39173e-08 2.48714e-08 -7.44572e-10 1 -1.39173e-08 2.48714e-08 -7.44572e-10 4142.32 38.2184 793.667 3970.66 105.899 3879.1 +EDGE_SE3:QUAT 632 633 -0.0814583 10.214 -0.240402 -0.0128395 0.123701 -0.146534 0.981357 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4226.32 -60.4818 979.981 3954.2 -86.3411 4141.09 +EDGE_SE3:QUAT 633 634 -0.216227 10.4805 -0.0471638 0.210485 -0.149829 0.105726 0.960244 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4340.22 -131.795 -1529.15 3889.13 58.4704 4472.73 +EDGE_SE3:QUAT 634 635 -0.511333 10.7585 -0.0436383 0.111119 -0.0274987 0.145167 0.982763 1 7.70372e-19 7.70372e-19 -3.20605e-09 5.51391e-09 5.4831e-08 1 7.70372e-19 -3.20605e-09 5.51391e-09 5.4831e-08 1 -3.20605e-09 5.51391e-09 5.4831e-08 3990 -18.9267 -402.512 3987.61 -28.6324 3955.1 +EDGE_SE3:QUAT 635 636 -0.457879 10.1123 0.139738 0.213068 -0.053181 0.126046 0.967412 1 1.92593e-19 1.92593e-19 -2.60447e-09 2.69525e-08 -5.43296e-09 1 1.92593e-19 -2.60447e-09 2.69525e-08 -5.43296e-09 1 -2.60447e-09 2.69525e-08 -5.43296e-09 3942.57 -70.7425 -719.35 3965.1 -19.1893 4060.61 +EDGE_SE3:QUAT 636 637 -0.444168 11.0288 -0.350026 -0.120038 0.0775909 0.0676104 0.987421 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4068 -35.7068 720.273 3968.54 5.10473 4107.36 +EDGE_SE3:QUAT 637 638 -1.28493 10.389 0.22128 0.137002 -0.0513483 0.0559709 0.987654 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.22 -32.1161 -495.25 3984.45 -3.33502 4047.77 +EDGE_SE3:QUAT 638 639 -0.386966 10.439 0.145925 -0.00720408 -0.0859127 0.0384653 0.995534 1 3.00927e-21 3.00927e-21 3.50503e-09 1.41838e-10 -2.99551e-10 1 3.00927e-21 3.50503e-09 1.41838e-10 -2.99551e-10 1 3.50503e-09 1.41838e-10 -2.99551e-10 4118.77 9.69811 -700.051 3971.27 -15.7842 4113.06 +EDGE_SE3:QUAT 639 640 -0.321591 10.3395 0.112515 0.15021 -0.0112903 0.158164 0.975855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3940.74 -28.9998 -363.016 3987.94 -31.106 3930.93 +EDGE_SE3:QUAT 640 641 -0.405396 10.5119 -0.127768 0.00213626 -0.0290388 -0.182691 0.982739 1 7.52316e-22 7.52316e-22 -1.70736e-09 3.18136e-10 4.57405e-11 1 7.52316e-22 -1.70736e-09 3.18136e-10 4.57405e-11 1 -1.70736e-09 3.18136e-10 4.57405e-11 4011.67 -3.60226 -216.725 3997.66 19.498 3878.18 +EDGE_SE3:QUAT 641 642 -0.591732 10.3125 -0.0577185 0.179464 -0.109932 -0.0949776 0.972978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3966.43 -71.3665 -633.078 3990.09 61.2387 4059.17 +EDGE_SE3:QUAT 642 643 -0.723158 10.6488 -0.198471 -0.0521102 0.143485 0.20836 0.966065 1 1.20371e-20 1.20371e-20 7.03445e-09 1.46898e-09 1.10731e-09 1 1.20371e-20 7.03445e-09 1.46898e-09 1.10731e-09 1 7.03445e-09 1.46898e-09 1.10731e-09 4376.04 83.8562 1302.84 3923.31 139.184 4213.25 +EDGE_SE3:QUAT 643 644 -0.588027 10.8422 -0.408691 -0.00060949 -0.0552764 0.0323817 0.997946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4049.13 2.54348 -446.014 3987.9 -7.49355 4044.93 +EDGE_SE3:QUAT 644 645 -0.229463 10.5399 -0.329919 0.168235 -0.00989352 0.192111 0.966795 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3933.46 -38.9841 -448.09 3981.2 -47.1588 3899.05 +EDGE_SE3:QUAT 645 646 -0.407359 10.6485 -0.191019 -0.0270399 -0.0388401 0.0171673 0.998732 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.38 4.78421 -306.204 3994.3 -3.60852 4022.12 +EDGE_SE3:QUAT 646 647 -0.286935 10.6537 -0.344478 -0.121561 0.0536253 0.219815 0.966451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.18 -15.9817 719.546 3965.42 74.2294 3931.02 +EDGE_SE3:QUAT 647 648 -0.637824 10.4326 0.166047 0.198297 -0.0245309 0.0493848 0.97859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3864.9 -32.1061 -300.076 3993.76 -2.53183 4012.43 +EDGE_SE3:QUAT 648 649 -0.202963 11.085 0.29395 -0.0492699 0.0346877 0.0908512 0.99404 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.04 -5.18496 328.516 3992.87 14.0377 3993.73 +EDGE_SE3:QUAT 649 650 -0.390925 10.8892 0.0625659 0.0694371 -0.119608 -0.0178634 0.990229 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4207.98 -45.1778 -980.224 3948.05 34.6322 4225.99 +EDGE_SE3:QUAT 650 651 -0.730251 10.5612 -0.309071 -0.215028 0.00827756 0.0939095 0.972047 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3835.65 -38.342 295.89 3991.93 12.7295 3985.32 +EDGE_SE3:QUAT 651 652 -0.602471 11.2292 -0.108428 0.0902999 -0.112707 0.161223 0.976294 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4247.96 7.37874 -1096.32 3933.43 -68.9444 4176.61 +EDGE_SE3:QUAT 652 653 -0.893455 10.4409 -0.146535 0.113619 -0.0472904 0.00883178 0.992359 1 4.81482e-20 4.81482e-20 2.8725e-11 1.37723e-08 -1.57228e-09 1 4.81482e-20 2.8725e-11 1.37723e-08 -1.57228e-09 1 2.8725e-11 1.37723e-08 -1.57228e-09 3985.28 -22.0595 -386.061 3991.24 4.57304 4036.61 +EDGE_SE3:QUAT 653 654 -0.7371 10.6713 -0.0893317 -0.156848 0.0159908 0.173625 0.97211 1 7.70372e-19 7.70372e-19 -3.75663e-09 7.94033e-09 -5.42843e-08 1 7.70372e-19 -3.75663e-09 7.94033e-09 -5.42843e-08 1 -3.75663e-09 7.94033e-09 -5.42843e-08 3946.89 -34.0993 437.759 3983.18 39.591 3924.71 +EDGE_SE3:QUAT 654 655 -0.978637 10.5502 -0.371234 0.0761654 0.0814546 0.108343 0.987839 1 1.92593e-19 1.92593e-19 1.7352e-09 2.6026e-09 2.76686e-08 1 1.92593e-19 1.7352e-09 2.6026e-09 2.76686e-08 1 1.7352e-09 2.6026e-09 2.76686e-08 4048.8 33.5861 543.333 3986.67 38.2787 4025.05 +EDGE_SE3:QUAT 655 656 -0.157661 10.7377 -0.188944 -0.0604237 -0.0167899 0.127457 0.989859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.52 0.379201 -39.1027 4000.02 -0.52436 3935.14 +EDGE_SE3:QUAT 656 657 -0.573274 10.513 0.0871003 0.0466599 0.171085 -0.0483061 0.982965 1 4.81482e-20 4.81482e-20 -1.45189e-08 5.08778e-10 -2.57446e-09 1 4.81482e-20 -1.45189e-08 5.08778e-10 -2.57446e-09 1 -1.45189e-08 5.08778e-10 -2.57446e-09 4520.51 7.52698 1548.21 3879.5 -10.5943 4519.88 +EDGE_SE3:QUAT 657 658 -0.390791 10.9689 0.0399661 -0.0101269 0.0266151 0.0858836 0.995898 1 1.92593e-19 1.92593e-19 7.77034e-10 -1.51017e-10 2.76843e-08 1 1.92593e-19 7.77034e-10 -1.51017e-10 2.76843e-08 1 7.77034e-10 -1.51017e-10 2.76843e-08 4011.82 0.414317 221.532 3996.96 9.51902 3982.73 +EDGE_SE3:QUAT 658 659 -0.704652 10.7237 -0.3642 -0.0248093 -0.165203 0.0867515 0.982123 1 8.1852e-19 8.1852e-19 8.81998e-09 5.59134e-08 7.7322e-10 1 8.1852e-19 8.81998e-09 5.59134e-08 7.7322e-10 1 8.81998e-09 5.59134e-08 7.7322e-10 4438.65 83.7834 -1399.83 3906.67 -95.0755 4411.01 +EDGE_SE3:QUAT 659 660 -0.655767 10.5936 0.0925259 0.0576639 -0.101172 0.109761 0.987113 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4181.91 2.28623 -905.078 3952.81 -39.8435 4147.03 +EDGE_SE3:QUAT 660 661 -0.179866 10.9082 0.161667 0.111186 0.0649546 0.0992018 0.9867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.38 24.8103 373.42 3994.86 23.5514 3994.46 +EDGE_SE3:QUAT 661 662 -0.627559 10.6465 0.0576603 -0.134093 -0.021057 0.163002 0.977244 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3928.55 -12.5926 97.2136 3997.78 15.3245 3894.19 +EDGE_SE3:QUAT 662 663 -0.586013 10.7879 0.282935 0.0496362 0.0292698 0.334323 0.940695 1 4.81482e-20 4.81482e-20 -1.30521e-08 -4.65697e-09 1.20634e-10 1 4.81482e-20 -1.30521e-08 -4.65697e-09 1.20634e-10 1 -1.30521e-08 -4.65697e-09 1.20634e-10 3988.71 -1.37684 11.0406 3999.92 -11.5652 3551.48 +EDGE_SE3:QUAT 663 664 -0.819441 10.7968 0.016619 -0.100111 -0.0985448 0.0684949 0.987712 1 1.92593e-19 1.92593e-19 2.78309e-08 2.4853e-09 -2.30093e-09 1 1.92593e-19 2.78309e-08 2.4853e-09 -2.30093e-09 1 2.78309e-08 2.4853e-09 -2.30093e-09 4080.24 50.3295 -705.293 3976.23 -44.9679 4101.57 +EDGE_SE3:QUAT 664 665 -0.928934 11.0502 -0.000988613 0.0341958 0.09462 -0.0874346 0.991077 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4153.3 -5.46441 810.5 3961.86 -31.1916 4127.4 +EDGE_SE3:QUAT 665 666 -0.715656 10.7322 -0.344149 -0.000442811 -0.10828 0.0461747 0.993047 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4192.98 13.9207 -899.532 3954.01 -23.4559 4184.45 +EDGE_SE3:QUAT 666 667 -0.855746 11.378 -0.379846 -0.0240522 -0.00321688 0.0801408 0.996488 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.67 -0.0629034 -2.44218 4000 0.214255 3974.3 +EDGE_SE3:QUAT 667 668 -0.36083 11.0792 0.17517 -0.319146 -0.0187793 0.144338 0.936461 1 3.08149e-18 3.08149e-18 -1.04426e-07 -1.40521e-08 -8.03273e-09 1 3.08149e-18 -1.04426e-07 -1.40521e-08 -8.03273e-09 1 -1.04426e-07 -1.40521e-08 -8.03273e-09 3623.59 -88.7328 387.011 3980.6 32.8234 3947.68 +EDGE_SE3:QUAT 668 669 -0.440687 10.6327 -0.19301 0.170489 0.118632 -0.063023 0.97616 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4164.6 85.1299 1096.6 3936.61 31.1146 4264.98 +EDGE_SE3:QUAT 669 670 -0.563189 10.8161 0.0842308 0.0469735 0.120571 -6.12838e-05 0.991593 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4232.63 27.393 1011.99 3942.98 17.4907 4241.46 +EDGE_SE3:QUAT 670 671 -0.56647 10.6438 0.0119833 -0.0437635 -0.0670259 0.163195 0.983341 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.13 21.8986 -432.543 3992.27 -37.1027 3939.26 +EDGE_SE3:QUAT 671 672 -0.606983 11.0352 -0.255976 -0.103507 -0.00428764 -0.0845972 0.991015 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3961.58 8.50007 -137.372 3998.2 6.77795 3975.81 +EDGE_SE3:QUAT 672 673 -0.819499 10.9149 0.130636 -0.133194 -0.233204 -0.0329668 0.962699 1 7.70419e-19 7.70419e-19 1.86263e-09 -5.33784e-08 -7.84367e-09 1 7.70419e-19 1.86263e-09 -5.33784e-08 -7.84367e-09 1 1.86263e-09 -5.33784e-08 -7.84367e-09 4970.21 189.071 -2291.07 3801.85 -172.846 5036.82 +EDGE_SE3:QUAT 673 674 -0.627207 10.5601 -0.0943228 0.159431 0.0341282 -0.0695086 0.984167 1 1.92593e-19 1.92593e-19 1.50517e-09 4.28696e-09 2.74506e-08 1 1.92593e-19 1.50517e-09 4.28696e-09 2.74506e-08 1 1.50517e-09 4.28696e-09 2.74506e-08 3936.66 31.7448 394.926 3989.19 -7.20754 4019.01 +EDGE_SE3:QUAT 674 675 -0.406819 11.0709 -0.106341 0.0529984 -0.0318874 -0.0693396 0.995674 1 4.81482e-20 4.81482e-20 1.38365e-08 -1.00675e-09 -3.34382e-10 1 4.81482e-20 1.38365e-08 -1.00675e-09 -3.34382e-10 1 1.38365e-08 -1.00675e-09 -3.34382e-10 3999.56 -6.41265 -208.694 3997.79 7.70933 3991.56 +EDGE_SE3:QUAT 675 676 -1.02534 10.4685 -0.122083 0.0037474 0.0202186 0.0350478 0.999174 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.34 0.638607 160.095 3998.42 2.84261 4001.48 +EDGE_SE3:QUAT 676 677 -0.990466 10.9015 0.0672112 0.0384987 0.01978 0.0818243 0.995706 1 2.40741e-19 2.40741e-19 -1.34584e-08 -9.52752e-12 2.74656e-08 1 2.40741e-19 -1.34584e-08 -9.52752e-12 2.74656e-08 1 -1.34584e-08 -9.52752e-12 2.74656e-08 3997.55 2.53809 118.763 3999.34 4.56646 3976.7 +EDGE_SE3:QUAT 677 678 -0.453149 10.9806 0.0126939 0.0813751 0.0965469 -0.0466068 0.990901 1 4.81482e-20 4.81482e-20 -1.45312e-09 -1.04187e-09 -1.40406e-08 1 4.81482e-20 -1.45312e-09 -1.04187e-09 -1.40406e-08 1 -1.45312e-09 -1.04187e-09 -1.40406e-08 4142.1 26.3719 838.359 3958.93 -1.24343 4159.9 +EDGE_SE3:QUAT 678 679 -0.63812 10.9888 0.118745 -0.17592 0.0929179 0.0833594 0.976458 1 1.92593e-19 1.92593e-19 3.27959e-09 -4.59942e-09 2.77934e-08 1 1.92593e-19 3.27959e-09 -4.59942e-09 2.77934e-08 1 3.27959e-09 -4.59942e-09 2.77934e-08 4075.74 -69.7028 915.893 3951.93 -6.60266 4171.73 +EDGE_SE3:QUAT 679 680 -0.396051 11.0378 0.000106655 0.0698897 -0.0519768 -0.00069357 0.996199 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.27 -14.9523 -416.034 3989.66 4.68736 4042.81 +EDGE_SE3:QUAT 680 681 -1.05968 10.664 -0.054564 0.0772838 -0.0244316 0.168485 0.982366 1 7.70372e-19 7.70372e-19 5.47319e-08 9.08495e-09 -2.69634e-09 1 7.70372e-19 5.47319e-08 9.08495e-09 -2.69634e-09 1 5.47319e-08 9.08495e-09 -2.69634e-09 4004.48 -9.12249 -340.703 3991.29 -30.3887 3914.82 +EDGE_SE3:QUAT 681 682 -0.570195 10.935 -0.323307 0.0319232 0.0317578 0.137655 0.989456 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.26 5.06019 194.722 3998.35 12.6429 3933.54 +EDGE_SE3:QUAT 682 683 -0.431244 10.6792 -0.0175324 0.139177 -0.070835 0.0911328 0.983518 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.84 -40.2328 -713.942 3968.14 -12.4422 4090.1 +EDGE_SE3:QUAT 683 684 -0.75454 10.8729 0.187019 -0.146316 -0.197223 0.218304 0.944478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4165.74 206.866 -1063.32 4014.26 -209.327 4060.75 +EDGE_SE3:QUAT 684 685 -1.05027 10.6582 -0.247836 -0.0174916 -0.0491325 0.195402 0.979336 1 1.20371e-20 1.20371e-20 6.81953e-09 1.37773e-09 -2.68732e-10 1 1.20371e-20 6.81953e-09 1.37773e-09 -2.68732e-10 1 6.81953e-09 1.37773e-09 -2.68732e-10 4026 11.6977 -332.263 3995.35 -31.8656 3874.49 +EDGE_SE3:QUAT 685 686 -0.673661 10.7588 -0.309928 -0.0324331 0.0944299 -0.0377617 0.994286 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4135.33 -21.4961 760.035 3967.08 -22.5444 4133.83 +EDGE_SE3:QUAT 686 687 -0.610924 10.9177 -0.11625 0.0779712 0.0388258 0.123309 0.988538 1 1.20371e-20 1.20371e-20 8.88229e-10 -6.85522e-09 5.9124e-10 1 1.20371e-20 8.88229e-10 -6.85522e-09 5.9124e-10 1 8.88229e-10 -6.85522e-09 5.9124e-10 3983.93 7.86158 186.976 3999.01 10.405 3947.43 +EDGE_SE3:QUAT 687 688 -0.438587 10.6981 0.0837576 -0.183478 -0.0249661 0.109218 0.976619 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3864.23 -12.1286 47.0169 3998.93 7.25269 3951.17 +EDGE_SE3:QUAT 688 689 -0.881763 11.0278 -0.381812 -0.0848149 -0.00651258 0.189591 0.978171 1 1.95602e-19 1.95602e-19 -2.65113e-08 -8.61326e-09 -9.89801e-10 1 1.95602e-19 -2.65113e-08 -8.61326e-09 -9.89801e-10 1 -2.65113e-08 -8.61326e-09 -9.89801e-10 3975.11 -8.00692 138.77 3997.46 19.0711 3860.1 +EDGE_SE3:QUAT 689 690 -0.766406 10.8212 -0.0181258 -0.0906606 -0.059465 0.192641 0.975261 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.61 13.6056 -239.665 3999.82 -18.6237 3864.05 +EDGE_SE3:QUAT 690 691 -0.576134 11.059 0.229449 -0.000866858 0.242855 0.245373 0.938516 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4893.24 400.692 2095.17 3922.53 411.837 4652.41 +EDGE_SE3:QUAT 691 692 -0.683731 11.5154 -0.192108 0.00770178 0.0184315 -0.0626169 0.997838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.57 0.0566532 152.543 3998.54 -4.77856 3990.12 +EDGE_SE3:QUAT 692 693 -0.799839 11.0846 -0.0804355 0.012891 -0.158605 0.0614345 0.985345 1 4.83363e-20 4.83363e-20 -3.2243e-09 -1.53895e-10 1.45497e-08 1 4.83363e-20 -3.2243e-09 -1.53895e-10 1.45497e-08 1 -3.2243e-09 -1.53895e-10 1.45497e-08 4436.17 30.8496 -1392.18 3900.51 -45.5615 4421.74 +EDGE_SE3:QUAT 693 694 -0.963115 11.2598 -0.361379 0.0918161 0.0750184 0.061408 0.991045 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4034.79 31.1796 528.825 3985.96 26.5311 4053.43 +EDGE_SE3:QUAT 694 695 -0.556602 11.2311 -0.0294392 0.0914563 -4.16747e-05 0.127055 0.98767 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3970.78 -7.87903 -137.631 3997.94 -11.3115 3939.67 +EDGE_SE3:QUAT 695 696 -0.746968 11.4797 -0.282538 -0.134485 -0.00577359 -0.0286442 0.990485 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3929.66 7.03168 -90.5772 3999.33 1.18149 3998.72 +EDGE_SE3:QUAT 696 697 -1.00163 10.7302 0.0999337 -0.030003 -0.139448 -0.109939 0.98365 1 1.95602e-19 1.95602e-19 7.68265e-09 -4.08951e-10 -2.89763e-08 1 1.95602e-19 7.68265e-09 -4.08951e-10 -2.89763e-08 1 7.68265e-09 -4.08951e-10 -2.89763e-08 4338.91 -36.2452 -1219.56 3922.45 65.8272 4294.16 +EDGE_SE3:QUAT 697 698 -0.296095 11.0852 -0.157488 -0.00796591 -0.0385647 -0.00993698 0.999175 1 7.52316e-22 7.52316e-22 1.73849e-09 -1.62678e-11 -6.73545e-11 1 7.52316e-22 1.73849e-09 -1.62678e-11 -6.73545e-11 1 1.73849e-09 -1.62678e-11 -6.73545e-11 4023.79 0.900518 -311.023 3994.01 1.28333 4023.64 +EDGE_SE3:QUAT 698 699 -0.413754 10.7516 -0.194103 -0.0889015 -0.0222824 0.0480444 0.994631 1 2.0463e-19 2.0463e-19 2.72641e-08 8.32415e-09 2.5935e-10 1 2.0463e-19 2.72641e-08 8.32415e-09 2.5935e-10 1 2.72641e-08 8.32415e-09 2.5935e-10 3972.18 5.09792 -124.676 3999.35 -3.19641 3994.56 +EDGE_SE3:QUAT 699 700 -0.743353 10.9009 0.0803022 0.216314 -0.0834422 0.0880413 0.968759 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.53 -87.535 -872.453 3956.7 11.3489 4150.69 +EDGE_SE3:QUAT 700 701 -0.493406 11.0105 0.114938 0.00688941 0.208945 0.127769 0.96952 1 7.70372e-19 7.70372e-19 1.20767e-08 3.87394e-09 5.86908e-08 1 7.70372e-19 1.20767e-08 3.87394e-09 5.86908e-08 1 1.20767e-08 3.87394e-09 5.86908e-08 4742.1 168.032 1876.57 3860.48 183.711 4676.99 +EDGE_SE3:QUAT 701 702 -0.780057 10.8052 -0.168636 0.0584344 0.0786043 0.0509945 0.993884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4073.8 25.1359 598.124 3980.26 23.8499 4077.06 +EDGE_SE3:QUAT 702 703 -0.414521 11.2909 -0.0822211 -0.0364183 0.00761664 0.206428 0.977754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.77 -1.90265 144.732 3998.28 17.706 3834.63 +EDGE_SE3:QUAT 703 704 -0.859132 11.1195 -0.136461 0.139482 0.0571693 -0.0536513 0.987116 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.65 35.4681 539.784 3981.91 -1.44182 4059.96 +EDGE_SE3:QUAT 704 705 -0.645946 11.0606 -0.14626 0.0302507 0.111132 0.0689948 0.990946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4185.76 35.479 890.93 3957.09 43.2116 4170.38 +EDGE_SE3:QUAT 705 706 -0.341891 11.0247 -0.0250425 0.0447285 -0.192906 0.23338 0.952009 1 7.70372e-19 7.70372e-19 1.30117e-08 -5.28332e-08 -2.76256e-09 1 7.70372e-19 1.30117e-08 -5.28332e-08 -2.76256e-09 1 1.30117e-08 -5.28332e-08 -2.76256e-09 4658.99 203.238 -1764.95 3893.8 -245.201 4449.13 +EDGE_SE3:QUAT 706 707 -0.817217 11.1532 -0.251445 0.0997708 0.000662305 -0.0154073 0.994891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.31 1.47751 23.5395 3999.95 -0.214346 3999.18 +EDGE_SE3:QUAT 707 708 -0.731143 10.9365 0.346057 -0.127647 0.108987 0.145602 0.975002 1 1.92593e-19 1.92593e-19 2.80556e-08 3.36651e-09 3.98039e-09 1 1.92593e-19 2.80556e-08 3.36651e-09 3.98039e-09 1 2.80556e-08 3.36651e-09 3.98039e-09 4224.39 -25.273 1115.38 3928.9 45.0334 4204.77 +EDGE_SE3:QUAT 708 709 -0.514452 11.2036 0.0735535 -0.106745 0.0296692 -0.0178005 0.993684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3965.5 -11.1896 211.026 3997.61 -3.70606 4009.81 +EDGE_SE3:QUAT 709 710 -0.483434 10.5533 -0.172473 -0.154043 -0.0411356 -0.0325491 0.986671 1 7.70372e-19 7.70372e-19 -5.50206e-08 1.03557e-09 2.73453e-09 1 7.70372e-19 -5.50206e-08 1.03557e-09 2.73453e-09 1 -5.50206e-08 1.03557e-09 2.73453e-09 3940.71 29.4029 -379.332 3991.16 -1.348 4031.39 +EDGE_SE3:QUAT 710 711 -0.516401 11.3895 -0.295512 0.0353213 0.0622647 0.0018021 0.997433 1 4.81482e-20 4.81482e-20 -8.65006e-11 1.38419e-08 -4.97127e-10 1 4.81482e-20 -8.65006e-11 1.38419e-08 -4.97127e-10 1 -8.65006e-11 1.38419e-08 -4.97127e-10 4057.33 9.40839 503.17 3984.72 3.80422 4062.31 +EDGE_SE3:QUAT 711 712 -0.612996 11.2166 -0.232511 -0.0946735 0.091217 0.0545095 0.989821 1 1.92593e-19 1.92593e-19 -2.80105e-08 -1.04956e-09 -2.81537e-09 1 1.92593e-19 -2.80105e-08 -1.04956e-09 -2.81537e-09 1 -2.80105e-08 -1.04956e-09 -2.81537e-09 4120.48 -29.9209 806.182 3961.67 2.47754 4144.45 +EDGE_SE3:QUAT 712 713 -0.701473 11.3842 -0.174369 -0.0832658 -0.0565038 0.0412407 0.994069 1 1.92593e-19 1.92593e-19 -2.77341e-08 -1.40403e-09 1.3568e-09 1 1.92593e-19 -2.77341e-08 -1.40403e-09 1.3568e-09 1 -2.77341e-08 -1.40403e-09 1.3568e-09 4013.48 19.5737 -408.496 3991.01 -13.8305 4034.41 +EDGE_SE3:QUAT 713 714 -0.604779 10.8995 0.00658389 0.0516036 -0.0621429 0.0630402 0.994737 1 4.81482e-20 4.81482e-20 -1.39284e-08 -7.95127e-10 9.50207e-10 1 4.81482e-20 -1.39284e-08 -7.95127e-10 9.50207e-10 1 -1.39284e-08 -7.95127e-10 9.50207e-10 4060.89 -8.1955 -539.808 3981.92 -12.6903 4055.65 +EDGE_SE3:QUAT 714 715 -0.559313 11.0488 0.0484707 0.00882987 -0.00760188 -0.0503315 0.998665 1 3.00927e-21 3.00927e-21 3.46514e-09 -1.75096e-10 -2.31586e-11 1 3.00927e-21 3.46514e-09 -1.75096e-10 -2.31586e-11 1 3.46514e-09 -1.75096e-10 -2.31586e-11 4000.45 -0.296218 -55.2616 3999.82 1.3553 3990.63 +EDGE_SE3:QUAT 715 716 -0.341865 10.7126 -0.490345 0.0303036 -0.0349588 0.185038 0.981642 1 1.20371e-20 1.20371e-20 -6.83572e-09 -1.2753e-09 3.03248e-10 1 1.20371e-20 -6.83572e-09 -1.2753e-09 3.03248e-10 1 -6.83572e-09 -1.2753e-09 3.03248e-10 4023.83 1.88558 -333.006 3993.28 -31.7358 3890.55 +EDGE_SE3:QUAT 716 717 -0.506134 11.0387 -0.142914 0.0734874 0.0699622 -0.0800257 0.991615 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4076.46 13.982 634.153 3975.08 -17.1797 4072.44 +EDGE_SE3:QUAT 717 718 -0.604865 10.7129 -0.0981978 -0.0350557 0.0892703 -0.0162085 0.995258 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4122.51 -16.8836 725.222 3969.4 -13.1854 4126.37 +EDGE_SE3:QUAT 718 719 -0.667944 11.0233 -0.0141529 0.0316788 0.047488 0.165069 0.984629 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.64 10.9144 303.455 3996.11 24.5699 3913.67 +EDGE_SE3:QUAT 719 720 -0.125322 11.1208 -0.00714506 -0.0481008 0.1215 0.146661 0.980517 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4266.28 30.7617 1085.41 3937.52 74.2508 4189.5 +EDGE_SE3:QUAT 720 721 -0.730395 11.1688 -0.206117 0.132111 0.0203972 -0.124065 0.983229 1 8.1852e-19 8.1852e-19 -5.63811e-08 -7.27437e-09 -1.14886e-09 1 8.1852e-19 -5.63811e-08 -7.27437e-09 -1.14886e-09 1 -5.63811e-08 -7.27437e-09 -1.14886e-09 3959.85 23.0964 350.36 3990.04 -21.1251 3968.1 +EDGE_SE3:QUAT 721 722 -0.803502 10.8219 0.0584341 0.0657446 0.169626 0.0488764 0.982098 1 1.92593e-19 1.92593e-19 -2.87946e-08 -2.18626e-09 -4.70062e-09 1 1.92593e-19 -2.87946e-08 -2.18626e-09 -4.70062e-09 1 -2.87946e-08 -2.18626e-09 -4.70062e-09 4441.99 96.8714 1431.33 3903.74 93.8916 4449.72 +EDGE_SE3:QUAT 722 723 -0.494331 11.5384 -0.0162267 0.164988 -0.0822211 0.0272117 0.982486 1 3.0845e-18 3.0845e-18 -1.10437e-07 -4.67153e-10 6.29701e-09 1 3.0845e-18 -1.10437e-07 -4.67153e-10 6.29701e-09 1 -1.10437e-07 -4.67153e-10 6.29701e-09 4010.72 -58.1705 -701.952 3973.17 19.4997 4116.65 +EDGE_SE3:QUAT 723 724 -0.611406 11.1782 -0.095306 0.0825073 -0.100179 0.00867332 0.991505 1 1.92619e-19 1.92619e-19 2.80547e-08 -1.99177e-10 -2.51035e-09 1 1.92619e-19 2.80547e-08 -1.99177e-10 -2.51035e-09 1 2.80547e-08 -1.99177e-10 -2.51035e-09 4138.49 -35.7544 -830.87 3960.96 16.9756 4165.42 +EDGE_SE3:QUAT 724 725 -0.720855 10.9933 -0.206545 0.102172 0.0870612 0.0937998 0.9865 1 1.92593e-19 1.92593e-19 -1.80402e-09 -3.31024e-09 -2.76562e-08 1 1.92593e-19 -1.80402e-09 -3.31024e-09 -2.76562e-08 1 -1.80402e-09 -3.31024e-09 -2.76562e-08 4037.31 41.4027 570.298 3985.99 40.1884 4043.87 +EDGE_SE3:QUAT 725 726 -0.601577 10.7374 -0.035122 0.132257 0.143332 0.0436026 0.979828 1 9.62965e-19 9.62965e-19 -5.9944e-08 -9.05139e-09 -3.53849e-08 1 9.62965e-19 -5.9944e-08 -9.05139e-09 -3.53849e-08 1 -5.9944e-08 -9.05139e-09 -3.53849e-08 4214.34 105.904 1104.76 3946.4 90.1504 4276.71 +EDGE_SE3:QUAT 726 727 -0.63399 11.3731 0.19497 0.0193319 -0.0400117 -0.253827 0.966228 1 3.14167e-18 3.14167e-18 -5.97994e-09 1.92478e-08 1.07131e-07 1 3.14167e-18 -5.97994e-09 1.92478e-08 1.07131e-07 1 -5.97994e-09 1.92478e-08 1.07131e-07 4011.75 -8.23411 -233.536 3998.67 26.6156 3755.53 +EDGE_SE3:QUAT 727 728 -0.678178 11.2188 -0.272405 -0.0421773 -0.0509961 0.0980704 0.992977 1 4.81482e-20 4.81482e-20 -1.38342e-08 -1.42779e-09 5.78907e-10 1 4.81482e-20 -1.38342e-08 -1.42779e-09 5.78907e-10 1 -1.38342e-08 -1.42779e-09 5.78907e-10 4023.82 12.1826 -353.779 3993.56 -18.9516 3992.47 +EDGE_SE3:QUAT 728 729 -0.847751 11.4174 -0.0430258 0.0490259 0.0596696 0.0487715 0.99582 1 4.81482e-20 4.81482e-20 -7.59398e-10 1.38155e-08 -7.62546e-10 1 4.81482e-20 -7.59398e-10 1.38155e-08 -7.62546e-10 1 -7.59398e-10 1.38155e-08 -7.62546e-10 4040.33 14.9563 449.902 3988.54 14.9184 4040.43 +EDGE_SE3:QUAT 729 730 -0.609927 11.3052 0.0929451 0.0388336 0.122218 0.226226 0.965596 1 1.92593e-19 1.92593e-19 2.73656e-08 6.84098e-09 2.58596e-09 1 1.92593e-19 2.73656e-08 6.84098e-09 2.58596e-09 1 2.73656e-08 6.84098e-09 2.58596e-09 4154.51 80.9276 821.89 3980.17 109.297 3955.83 +EDGE_SE3:QUAT 730 731 -0.534446 11.0651 -0.114773 0.0358509 -0.0240805 -0.169267 0.984624 1 4.81482e-20 4.81482e-20 -1.36696e-08 2.36955e-09 1.48131e-10 1 4.81482e-20 -1.36696e-08 2.36955e-09 1.48131e-10 1 -1.36696e-08 2.36955e-09 1.48131e-10 3997.83 -2.62541 -112.675 3999.7 7.49547 3888.36 +EDGE_SE3:QUAT 731 732 -0.64102 11.234 -0.0990626 -0.14937 0.0361645 0.00273256 0.988116 1 7.7056e-19 7.7056e-19 5.49629e-08 -3.19972e-10 1.10845e-09 1 7.7056e-19 5.49629e-08 -3.19972e-10 1.10845e-09 1 5.49629e-08 -3.19972e-10 1.10845e-09 3931.06 -21.4302 285.774 3995.47 -4.25453 4020.28 +EDGE_SE3:QUAT 732 733 -0.922433 11.4408 -0.312788 -0.173661 0.0538443 0.144825 0.972609 1 7.70372e-19 7.70372e-19 5.48456e-08 6.70602e-09 5.5143e-09 1 7.70372e-19 5.48456e-08 6.70602e-09 5.5143e-09 1 5.48456e-08 6.70602e-09 5.5143e-09 4001.1 -50.0856 712.1 3965.19 33.2835 4037.83 +EDGE_SE3:QUAT 733 734 -0.60506 11.1922 -0.0494721 -0.183233 -0.106681 -0.0723725 0.97458 1 7.70372e-19 7.70372e-19 5.57778e-08 -1.72765e-09 -7.15569e-09 1 7.70372e-19 5.57778e-08 -1.72765e-09 -7.15569e-09 1 5.57778e-08 -1.72765e-09 -7.15569e-09 4108.65 83.8403 -1015.5 3944.21 -22.8243 4222 +EDGE_SE3:QUAT 734 735 -0.695813 11.1707 -0.141943 0.0585354 -0.0953899 0.0413783 0.992856 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4145.71 -16.499 -814.31 3961.06 -4.61578 4152.56 +EDGE_SE3:QUAT 735 736 -0.612279 11.3631 -0.0409167 0.0253998 -0.274163 0.0364541 0.960656 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5549.67 29.4016 -2935.72 3698.19 -30.6842 5546.93 +EDGE_SE3:QUAT 736 737 -0.693936 11.1615 -0.159543 0.0411721 0.00532379 0.0527508 0.997744 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.27 0.16472 16.319 4000 0.206262 3988.92 +EDGE_SE3:QUAT 737 738 -0.773255 11.4115 -0.0320183 0.0361166 0.031821 0.03831 0.998106 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.84 5.06459 237.619 3996.71 5.27331 4008.19 +EDGE_SE3:QUAT 738 739 -0.486133 10.9399 0.0258899 0.0593676 0.139475 -0.00902879 0.988403 1 5.75992e-22 5.75992e-22 -2.20439e-10 -9.34815e-11 -1.56129e-09 1 5.75992e-22 -2.20439e-10 -9.34815e-11 -1.56129e-09 1 -2.20439e-10 -9.34815e-11 -1.56129e-09 4316.68 38.3036 1196.87 3923.28 24.07 4330.45 +EDGE_SE3:QUAT 739 740 -0.627639 11.1223 -0.203821 0.0365626 -0.198418 -0.00127084 0.979434 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4703.58 -49.1647 -1827.1 3844.99 43.6656 4708.92 +EDGE_SE3:QUAT 740 741 -0.826792 11.2469 -0.16317 0.0179249 -0.0614944 -0.131463 0.98925 1 1.20371e-20 1.20371e-20 -6.90889e-09 9.39604e-10 3.81318e-10 1 1.20371e-20 -6.90889e-09 9.39604e-10 3.81318e-10 1 -6.90889e-09 9.39604e-10 3.81318e-10 4049.91 -14.798 -455.766 3989.15 31.6046 3982.06 +EDGE_SE3:QUAT 741 742 -0.761812 11.2122 -0.130092 -0.0092462 -0.177467 0.234881 0.955642 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4433.7 184.901 -1390.49 3945.1 -216.916 4213.37 +EDGE_SE3:QUAT 742 743 -0.627783 11.2683 0.16806 0.0763852 0.205699 -0.0814777 0.972222 1 1.92593e-19 1.92593e-19 6.53033e-09 1.43082e-09 2.96778e-08 1 1.92593e-19 6.53033e-09 1.43082e-09 2.96778e-08 1 6.53033e-09 1.43082e-09 2.96778e-08 4806.69 4.70909 2002.29 3820.51 -19.1704 4803.47 +EDGE_SE3:QUAT 743 744 -0.327276 11.2549 0.0425769 -0.0249582 0.0487123 0.186303 0.980967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.84 6.86109 428.261 3989.65 40.4468 3906.5 +EDGE_SE3:QUAT 744 745 -0.886764 11.2425 -0.27886 0.215119 0.0450026 0.00834248 0.975515 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3839.56 33.2685 315.922 3995.8 10.0221 4024.39 +EDGE_SE3:QUAT 745 746 -0.958896 10.9277 0.0167222 -0.0473589 -0.0203634 0.0987845 0.993773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.64 2.52066 -104.303 3999.6 -4.43723 3963.58 +EDGE_SE3:QUAT 746 747 -0.680805 11.0336 0.02302 0.119247 -0.106298 0.0488477 0.985949 1 4.33334e-19 4.33334e-19 2.7095e-08 -2.51538e-08 1.38659e-08 1 4.33334e-19 2.7095e-08 -2.51538e-08 1.38659e-08 1 2.7095e-08 -2.51538e-08 1.38659e-08 4153.79 -48.9589 -941.892 3950.04 11.4834 4201.12 +EDGE_SE3:QUAT 747 748 -0.514199 11.2423 -0.0921518 0.0810869 0.0449156 0.176603 0.979908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.91 7.41656 171.224 3999.88 10.9745 3881.45 +EDGE_SE3:QUAT 748 749 -0.623724 11.2712 0.0961713 0.162855 0.125171 0.0297995 0.978224 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4103.73 95.8776 941.101 3961.72 71.9712 4206.26 +EDGE_SE3:QUAT 749 750 -1.05752 11.5547 0.0709927 -0.246618 0.0194506 -0.0928118 0.964462 1 7.71124e-19 7.71124e-19 5.37084e-08 -3.36595e-09 -1.09553e-09 1 7.71124e-19 5.37084e-08 -3.36595e-09 -1.09553e-09 1 5.37084e-08 -3.36595e-09 -1.09553e-09 3758.47 26.9415 -122.327 3997.01 9.89158 3967.29 +EDGE_SE3:QUAT 750 751 -0.638147 11.18 -0.180576 0.143035 -0.0155791 0.116318 0.982735 1 7.70372e-19 7.70372e-19 5.47209e-08 5.97401e-09 -2.63159e-09 1 7.70372e-19 5.47209e-08 5.97401e-09 -2.63159e-09 1 5.47209e-08 5.97401e-09 -2.63159e-09 3942.05 -24.0868 -315.48 3991.54 -18.2154 3969.77 +EDGE_SE3:QUAT 751 752 -1.07885 11.1018 -0.0302183 -0.189424 0.00275163 0.0930692 0.977471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3868.26 -26.9915 226.531 3994.8 11.4644 3977.14 +EDGE_SE3:QUAT 752 753 -0.986006 11.0288 -0.223895 0.164313 -0.0418771 0.0552611 0.983968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3937.93 -35.4259 -431.755 3987.94 -2.60394 4033.71 +EDGE_SE3:QUAT 753 754 -0.815816 11.3841 -0.604415 0.00442774 0.0610989 0.181925 0.981402 1 1.20371e-20 1.20371e-20 -6.85565e-09 -1.28397e-09 -3.87162e-10 1 1.20371e-20 -6.85565e-09 -1.28397e-09 -3.87162e-10 1 -6.85565e-09 -1.28397e-09 -3.87162e-10 4052.1 16.1109 460.222 3989.68 42.7538 3919.79 +EDGE_SE3:QUAT 754 755 -0.860212 11.3518 -0.121041 0.00309701 0.0265677 0.0363356 0.998982 1 1.20371e-20 1.20371e-20 2.53619e-10 -6.93177e-09 3.48652e-11 1 1.20371e-20 2.53619e-10 -6.93177e-09 3.48652e-11 1 2.53619e-10 -6.93177e-09 3.48652e-11 4011.09 0.93867 211.278 3997.25 3.90793 4005.85 +EDGE_SE3:QUAT 755 756 -0.591383 11.5921 -0.245584 0.0743475 -0.12652 0.136026 0.979776 1 4.81482e-20 4.81482e-20 -1.41433e-08 -1.73589e-09 2.03668e-09 1 4.81482e-20 -1.41433e-08 -1.73589e-09 2.03668e-09 1 -1.41433e-08 -1.73589e-09 2.03668e-09 4298.74 12.7097 -1177.58 3925.02 -61.4678 4246.83 +EDGE_SE3:QUAT 756 757 -0.855391 11.0147 -0.491262 0.0120774 -0.0720476 0.24609 0.96649 1 3.00927e-21 3.00927e-21 3.38834e-09 8.65971e-10 -2.42058e-10 1 3.00927e-21 3.38834e-09 8.65971e-10 -2.42058e-10 1 3.38834e-09 8.65971e-10 -2.42058e-10 4078.57 27.3046 -568.718 3986.24 -71.6472 3836.91 +EDGE_SE3:QUAT 757 758 -0.843199 11.7381 -0.258784 -0.029511 0.150247 0.0721811 0.985568 1 1.54074e-18 1.54074e-18 5.21363e-09 5.42551e-08 5.78388e-08 1 1.54074e-18 5.21363e-09 5.42551e-08 5.78388e-08 1 5.21363e-09 5.42551e-08 5.78388e-08 4394.77 20.4555 1323.49 3908.26 41.4155 4377.41 +EDGE_SE3:QUAT 758 759 -0.767916 11.7707 0.153897 0.0800979 -0.0698122 -0.0824256 0.990917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.35 -26.103 -473.526 3989.14 26.4294 4027.84 +EDGE_SE3:QUAT 759 760 -1.04976 11.3383 -0.533734 -0.113744 -0.0314857 0.0203937 0.992802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.25 12.3824 -219.767 3997.48 -4.35831 4010.34 +EDGE_SE3:QUAT 760 761 -0.463917 11.1671 -0.22307 0.131915 0.0568103 0.0239422 0.989342 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3971.5 28.2081 408.097 3991.52 13.5632 4038.81 +EDGE_SE3:QUAT 761 762 -0.582596 11.4124 -0.0917267 -0.291147 0.0364502 -0.044381 0.954953 1 3.08149e-18 3.08149e-18 1.06047e-07 -6.35439e-09 5.9528e-10 1 3.08149e-18 1.06047e-07 -6.35439e-09 5.9528e-10 1 1.06047e-07 -6.35439e-09 5.9528e-10 3662.73 -6.71706 108.073 4000.57 -3.37738 3993.91 +EDGE_SE3:QUAT 762 763 -0.793722 11.2239 0.0973363 0.106431 -0.165098 -0.0280995 0.980115 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4381.14 -112.144 -1374.29 3913.42 98.2245 4423.29 +EDGE_SE3:QUAT 763 764 -0.579087 11.3778 0.0335751 0.0646731 0.022647 0.0866686 0.993878 1 1.92593e-19 1.92593e-19 2.75959e-08 2.46904e-09 3.0434e-10 1 1.92593e-19 2.75959e-08 2.46904e-09 3.0434e-10 1 2.75959e-08 2.46904e-09 3.0434e-10 3986.22 3.37279 111.271 3999.58 4.20926 3972.9 +EDGE_SE3:QUAT 764 765 -0.834009 11.2509 -0.37613 -0.124099 0.0902702 0.0773638 0.985122 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4109.82 -40.3421 845.972 3957.58 6.0877 4147.49 +EDGE_SE3:QUAT 765 766 -0.243703 11.3963 -0.319873 -0.151315 0.0361863 0.176479 0.971931 1 8.1852e-19 8.1852e-19 -5.67459e-08 4.63679e-09 -2.92973e-09 1 8.1852e-19 -5.67459e-08 4.63679e-09 -2.92973e-09 1 -5.67459e-08 4.63679e-09 -2.92973e-09 3991.48 -35.2733 588.247 3973.91 46.8115 3958.48 +EDGE_SE3:QUAT 766 767 -0.325849 11.1248 -0.331387 -0.0544734 0.198768 -0.0433744 0.97757 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4660.2 -116.061 1772.13 3861.28 -114.417 4664.55 +EDGE_SE3:QUAT 767 768 -0.544687 11.257 0.0664502 -0.158444 -0.0812197 0.0300592 0.983563 1 4.81482e-20 4.81482e-20 -9.44961e-10 -2.31376e-09 1.37916e-08 1 4.81482e-20 -9.44961e-10 -2.31376e-09 1.37916e-08 1 -9.44961e-10 -2.31376e-09 1.37916e-08 3980.92 50.355 -577.274 3984.66 -29.9702 4077.72 +EDGE_SE3:QUAT 768 769 -0.853867 11.2002 -0.350744 0.0524792 -0.0641976 0.0505381 0.995274 1 2.88889e-19 2.88889e-19 1.41958e-08 -2.63714e-08 1.42574e-08 1 2.88889e-19 1.41958e-08 -2.63714e-08 1.42574e-08 1 1.41958e-08 -2.63714e-08 1.42574e-08 4063.32 -9.79234 -550.379 3981.32 -9.01053 4064.12 +EDGE_SE3:QUAT 769 770 -0.600668 11.5652 0.000442668 -0.0777464 0.0117709 0.0869933 0.993101 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.13 -6.98203 173.01 3997.59 7.99087 3977.04 +EDGE_SE3:QUAT 770 771 -0.79549 11.6513 -0.0141379 0.016977 -0.0213254 0.0747219 0.996832 1 3.00927e-21 3.00927e-21 3.46215e-09 2.57112e-10 -8.1992e-11 1 3.00927e-21 3.46215e-09 2.57112e-10 -8.1992e-11 1 3.46215e-09 2.57112e-10 -8.1992e-11 4007.35 -0.688819 -184.629 3997.82 -6.89491 3986.17 +EDGE_SE3:QUAT 771 772 -0.733695 11.343 -0.181898 0.074316 0.0483893 -0.165895 0.982148 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4044.49 6.46733 521.499 3982.21 -41.5815 3956.5 +EDGE_SE3:QUAT 772 773 -0.667548 11.2929 -0.0737542 0.0289933 -0.0233171 0.0191709 0.999124 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.95 -2.58458 -193.267 3997.63 -1.4839 4007.85 +EDGE_SE3:QUAT 773 774 -0.434186 11.4654 -0.582208 0.073388 -0.122615 0.0396964 0.988941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4244.45 -29.7292 -1065.25 3936.78 5.0654 4259.69 +EDGE_SE3:QUAT 774 775 -0.965345 11.1506 -0.086137 -0.125767 -0.0206955 0.0361981 0.991183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3939.5 5.73019 -107.336 3999.59 -2.27741 3997.53 +EDGE_SE3:QUAT 775 776 -0.536134 11.5318 0.22238 0.15794 -0.050179 0.095252 0.981562 1 9.62965e-19 9.62965e-19 5.28934e-08 8.34179e-09 2.32274e-08 1 9.62965e-19 5.28934e-08 8.34179e-09 2.32274e-08 1 5.28934e-08 8.34179e-09 2.32274e-08 3979.09 -40.8221 -568.934 3978.31 -13.8531 4042.58 +EDGE_SE3:QUAT 776 777 -0.303687 11.4809 0.208928 -0.116885 0.0013654 0.139038 0.983364 1 1.92593e-19 1.92593e-19 2.73263e-08 3.74957e-09 9.23668e-10 1 1.92593e-19 2.73263e-08 3.74957e-09 9.23668e-10 1 2.73263e-08 3.74957e-09 9.23668e-10 3954.58 -14.2675 201.595 3995.73 17.436 3931.9 +EDGE_SE3:QUAT 777 778 -0.64872 11.4227 -0.0637075 0.0404169 -0.0465588 0.00542177 0.998083 1 4.81482e-20 4.81482e-20 -1.39122e-08 -2.30682e-11 6.52947e-10 1 4.81482e-20 -1.39122e-08 -2.30682e-11 6.52947e-10 1 -1.39122e-08 -2.30682e-11 6.52947e-10 4028.7 -7.5191 -377.065 3991.28 1.09487 4035.12 +EDGE_SE3:QUAT 778 779 -0.511127 11.4339 0.173992 -0.107088 -0.0348346 0.0467492 0.992539 1 7.82409e-19 7.82409e-19 5.48066e-08 9.84186e-09 -5.65611e-10 1 7.82409e-19 5.48066e-08 9.84186e-09 -5.65611e-10 1 5.48066e-08 9.84186e-09 -5.65611e-10 3965.39 11.2991 -213.807 3997.92 -6.63475 4002.52 +EDGE_SE3:QUAT 779 780 -0.551071 11.6261 0.0313922 0.117153 0.0221822 0.136965 0.983374 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3944.12 -5.07671 -19.5703 3999.55 -5.93622 3923.98 +EDGE_SE3:QUAT 780 781 -0.368953 11.3999 -0.200138 -0.120733 -0.00292675 0.053058 0.991262 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3942.24 -4.74451 53.1797 3999.61 2.03909 3989.29 +EDGE_SE3:QUAT 781 782 -1.05915 11.5086 0.0957204 0.0630822 0.0874464 0.133563 0.985157 1 1.92593e-19 1.92593e-19 -4.02825e-09 2.72981e-08 -2.35577e-09 1 1.92593e-19 -4.02825e-09 2.72981e-08 -2.35577e-09 1 -4.02825e-09 2.72981e-08 -2.35577e-09 4067.43 37.2744 585.468 3985.11 47.8299 4011.99 +EDGE_SE3:QUAT 782 783 -0.709725 11.7525 -0.454376 0.0247358 -0.0472576 -0.0926425 0.99427 1 6.01853e-20 6.01853e-20 8.24681e-09 1.31314e-08 -7.51174e-10 1 6.01853e-20 8.24681e-09 1.31314e-08 -7.51174e-10 1 8.24681e-09 1.31314e-08 -7.51174e-10 4027.5 -8.63584 -347.611 3993.34 17.1086 3995.61 +EDGE_SE3:QUAT 783 784 -0.78163 11.4085 0.252036 0.0224122 0.0369988 -0.038855 0.998308 1 1.20371e-20 1.20371e-20 6.94746e-09 -2.59335e-10 2.68595e-10 1 1.20371e-20 6.94746e-09 -2.59335e-10 2.68595e-10 1 6.94746e-09 -2.59335e-10 2.68595e-10 4021.44 2.17682 307.14 3994.08 -5.33831 4017.41 +EDGE_SE3:QUAT 784 785 -0.709233 11.2636 -0.130321 -0.00935346 0.138774 0.122174 0.982714 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4319.52 54.935 1175.57 3930.44 81.7443 4260.17 +EDGE_SE3:QUAT 785 786 -0.548202 11.5387 -0.0961448 -0.117385 0.0366969 -0.176436 0.976598 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.19 2.87257 32.531 3999.97 4.71833 3873.79 +EDGE_SE3:QUAT 786 787 -0.420477 11.5156 -0.338827 0.0513595 0.0644631 0.00468476 0.996587 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4055.46 14.3099 518.09 3984 6.41627 4065.93 +EDGE_SE3:QUAT 787 788 -0.469894 11.9811 0.163598 0.0204693 0.0156246 0.11516 0.993013 1 1.50463e-20 1.50463e-20 6.49079e-09 4.24835e-09 -8.59568e-12 1 1.50463e-20 6.49079e-09 4.24835e-09 -8.59568e-12 1 6.49079e-09 4.24835e-09 -8.59568e-12 4000.52 1.30769 94.4406 3999.6 4.93446 3949.15 +EDGE_SE3:QUAT 788 789 -0.860038 11.4528 0.202784 -0.0503885 0.0382189 -0.0812897 0.994682 1 4.81482e-20 4.81482e-20 1.17827e-09 1.37998e-08 7.77603e-10 1 4.81482e-20 1.17827e-09 1.37998e-08 7.77603e-10 1 1.17827e-09 1.37998e-08 7.77603e-10 4005.74 -8.16479 253.406 3996.75 -11.0364 3989.47 +EDGE_SE3:QUAT 789 790 -0.564072 11.8651 -0.0260731 -0.0974672 0.223871 0.215842 0.945407 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5064.69 206.619 2372.06 3802.61 243.637 4916.33 +EDGE_SE3:QUAT 790 791 -0.338362 11.5306 -0.220247 0.0935726 -0.0346158 0.105726 0.989378 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.29 -15.0033 -389.522 3989.32 -18.25 3992.6 +EDGE_SE3:QUAT 791 792 -0.682613 11.3831 -0.083461 -0.0160091 0.158014 0.160523 0.97417 1 7.73381e-19 7.73381e-19 -1.25973e-08 -2.705e-09 -5.74721e-08 1 7.73381e-19 -1.25973e-08 -2.705e-09 -5.74721e-08 1 -1.25973e-08 -2.705e-09 -5.74721e-08 4417.04 93.9863 1359.27 3916.51 127.559 4315 +EDGE_SE3:QUAT 792 793 -0.776906 11.4906 -0.168677 -0.0765966 -0.11254 0.0155877 0.990568 1 1.92593e-19 1.92593e-19 -2.81756e-08 -9.47676e-10 3.09105e-09 1 1.92593e-19 -2.81756e-08 -9.47676e-10 3.09105e-09 1 -2.81756e-08 -9.47676e-10 3.09105e-09 4176.02 44.2211 -915.347 3954.41 -31.8291 4198.51 +EDGE_SE3:QUAT 793 794 -0.527245 11.5118 0.0845881 0.0931952 -0.0579555 0.146255 0.983141 1 9.62965e-19 9.62965e-19 -8.4966e-10 -2.32256e-08 5.7256e-08 1 9.62965e-19 -8.4966e-10 -2.32256e-08 5.7256e-08 1 -8.4966e-10 -2.32256e-08 5.7256e-08 4058.01 -13.6573 -617.372 3975.21 -38.9557 4007.19 +EDGE_SE3:QUAT 794 795 -0.946223 11.484 -0.166243 -0.0925679 -0.141575 -0.042594 0.984669 1 9.62965e-19 9.62965e-19 -2.76198e-08 5.51889e-08 8.9118e-09 1 9.62965e-19 -2.76198e-08 5.51889e-08 8.9118e-09 1 -2.76198e-08 5.51889e-08 8.9118e-09 4327.45 47.7806 -1256.1 3916.31 -18.8803 4354.47 +EDGE_SE3:QUAT 795 796 -0.582038 11.5156 -0.395776 0.0105478 -0.0530952 0.112911 0.992129 1 1.92593e-19 1.92593e-19 -1.5106e-09 -4.54036e-11 2.76999e-08 1 1.92593e-19 -1.5106e-09 -4.54036e-11 2.76999e-08 1 -1.5106e-09 -4.54036e-11 2.76999e-08 4046.37 5.59608 -435.258 3988.88 -24.695 3995.82 +EDGE_SE3:QUAT 796 797 -0.887751 11.5396 -0.239636 -0.0845506 0.0939004 -0.168031 0.97765 1 1.92593e-19 1.92593e-19 -2.73904e-08 5.15208e-09 -1.64444e-09 1 1.92593e-19 -2.73904e-08 5.15208e-09 -1.64444e-09 1 -2.73904e-08 5.15208e-09 -1.64444e-09 4043.99 -44.5111 549.882 3990.85 -54.7672 3959.65 +EDGE_SE3:QUAT 797 798 -0.752756 11.6824 -0.370865 0.0494091 0.0781278 0.25843 0.961597 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.2 30.2537 416.208 3997.82 50.6377 3773.82 +EDGE_SE3:QUAT 798 799 -0.684597 11.6301 0.244128 0.0205559 0.0155031 -0.00191699 0.999667 1 1.20841e-20 1.20841e-20 -6.93318e-09 1.77755e-11 3.25664e-10 1 1.20841e-20 -6.93318e-09 1.77755e-11 3.25664e-10 1 -6.93318e-09 1.77755e-11 3.25664e-10 4002.18 1.27332 124.524 3999.03 -0.000460534 4003.86 +EDGE_SE3:QUAT 799 800 -0.49238 11.7583 -0.066847 0.0136212 -0.035945 0.0195887 0.999069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.44 -1.40057 -291.872 3994.7 -2.47566 4019.65 +EDGE_SE3:QUAT 800 801 -0.546003 11.6208 -0.138302 0.0540503 -0.181095 -0.142721 0.971552 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4442.72 -160.061 -1424.64 3925.03 172.842 4372.93 +EDGE_SE3:QUAT 801 802 -0.813674 11.6293 0.12748 -0.141648 0.134349 0.140716 0.970611 1 2.31112e-18 2.31112e-18 -5.287e-08 4.20916e-08 5.29406e-08 1 2.31112e-18 -5.287e-08 4.20916e-08 5.29406e-08 1 -5.287e-08 4.20916e-08 5.29406e-08 4345.62 -35.7392 1373.58 3899.46 34.3228 4346.67 +EDGE_SE3:QUAT 802 803 -0.691515 11.5503 -0.172471 -0.0325031 0.040544 0.115869 0.991904 1 1.20371e-20 1.20371e-20 6.91145e-09 7.9028e-10 3.26626e-10 1 1.20371e-20 6.91145e-09 7.9028e-10 3.26626e-10 1 6.91145e-09 7.9028e-10 3.26626e-10 4028.77 -0.722555 364.921 3991.62 20.7511 3979.29 +EDGE_SE3:QUAT 803 804 -0.619798 11.6852 -0.48166 -0.068217 -0.0472163 -0.0740731 0.993796 1 1.92593e-19 1.92593e-19 1.57386e-09 1.69803e-09 -2.7747e-08 1 1.92593e-19 1.57386e-09 1.69803e-09 -2.7747e-08 1 1.57386e-09 1.69803e-09 -2.7747e-08 4028.53 10.9502 -437.103 3987.64 12.715 4025.19 +EDGE_SE3:QUAT 804 805 -0.737133 11.5529 -0.37727 -0.0615022 0.0863689 0.108365 0.988441 1 3.85186e-19 3.85186e-19 -3.06805e-08 2.46748e-08 -1.57229e-09 1 3.85186e-19 -3.06805e-08 2.46748e-08 -1.57229e-09 1 -3.06805e-08 2.46748e-08 -1.57229e-09 4131.51 -3.3163 779.971 3963.8 33.8792 4099.67 +EDGE_SE3:QUAT 805 806 -0.973205 11.9503 -0.195486 0.0884293 0.0690193 -0.0632669 0.991672 1 4.81482e-20 4.81482e-20 1.10427e-09 1.12179e-09 1.39257e-08 1 4.81482e-20 1.10427e-09 1.12179e-09 1.39257e-08 1 1.10427e-09 1.12179e-09 1.39257e-08 4063.31 21.2131 622.542 3976.03 -9.21274 4078.58 +EDGE_SE3:QUAT 806 807 -0.6397 11.6864 -0.213276 -0.0705725 0.023195 0.0525028 0.995854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.03 -7.66967 228.369 3996.42 5.13833 4001.93 +EDGE_SE3:QUAT 807 808 -0.962726 11.6312 -0.295954 -0.00845849 0.0774055 0.185945 0.97947 1 7.70372e-19 7.70372e-19 4.21975e-09 1.15577e-09 5.50246e-08 1 7.70372e-19 4.21975e-09 1.15577e-09 5.50246e-08 1 4.21975e-09 1.15577e-09 5.50246e-08 4093.01 24.299 618.177 3980.91 59.4969 3955 +EDGE_SE3:QUAT 808 809 -0.479175 11.8772 -0.151463 -0.152925 -0.0180915 0.167203 0.973822 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3910.62 -20.0306 162.742 3995.54 21.994 3892.34 +EDGE_SE3:QUAT 809 810 -1.10471 11.8423 -0.267909 0.00089507 -0.0856121 -0.168961 0.981897 1 7.70372e-19 7.70372e-19 4.52229e-09 -1.67078e-09 -5.52652e-08 1 7.70372e-19 4.52229e-09 -1.67078e-09 -5.52652e-08 1 4.52229e-09 -1.67078e-09 -5.52652e-08 4108.89 -29.3247 -669.203 3977.71 60.0802 3994.7 +EDGE_SE3:QUAT 810 811 -0.816195 11.8674 -0.356986 -0.180942 0.0417406 -0.0622349 0.980635 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3876.73 -13.2498 183.744 3999.47 -7.39847 3992.2 +EDGE_SE3:QUAT 811 812 -0.633564 11.5033 -0.260587 -0.0136286 0.0386207 0.216827 0.975351 1 7.71124e-19 7.71124e-19 3.9678e-09 5.99555e-10 5.43982e-08 1 7.71124e-19 3.9678e-09 5.99555e-10 5.43982e-08 1 3.9678e-09 5.99555e-10 5.43982e-08 4025.27 6.26827 323.64 3994.6 35.6249 3837.96 +EDGE_SE3:QUAT 812 813 -0.837128 11.7531 -0.184531 0.0216578 -0.0241564 0.0598913 0.997678 1 4.81482e-20 4.81482e-20 3.68997e-10 -2.59012e-10 -1.38643e-08 1 4.81482e-20 3.68997e-10 -2.59012e-10 -1.38643e-08 1 3.68997e-10 -2.59012e-10 -1.38643e-08 4008.92 -1.37728 -208.117 3997.22 -6.07655 3996.45 +EDGE_SE3:QUAT 813 814 -0.570343 11.4482 -0.446968 -0.223069 -0.111426 0.083382 0.964817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3887.16 76.6968 -605.661 3994.74 -61.8772 4058.38 +EDGE_SE3:QUAT 814 815 -0.710177 11.384 0.339665 -0.0233433 -0.129944 0.265924 0.954911 1 4.81482e-20 4.81482e-20 1.35818e-08 3.98849e-09 -1.39863e-09 1 4.81482e-20 1.35818e-08 3.98849e-09 -1.39863e-09 1 1.35818e-08 3.98849e-09 -1.39863e-09 4183.84 99.2571 -887.967 3981.84 -135.681 3903.16 +EDGE_SE3:QUAT 815 816 -0.57173 11.8351 -0.195978 0.00762848 -0.146944 0.000197079 0.989115 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4368.93 -5.85093 -1270.01 3913.67 4.24528 4369.16 +EDGE_SE3:QUAT 816 817 -0.486409 11.7254 -0.348936 0.0434885 -0.024604 0.109565 0.992723 1 1.20371e-20 1.20371e-20 7.4391e-10 -6.89018e-09 2.57818e-10 1 1.20371e-20 7.4391e-10 -6.89018e-09 2.57818e-10 1 7.4391e-10 -6.89018e-09 2.57818e-10 4007.98 -3.52585 -250.359 3995.71 -13.8707 3967.53 +EDGE_SE3:QUAT 817 818 -0.638351 11.935 -0.337985 -0.0914472 0.083622 -0.0526127 0.990897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4057.71 -36.4557 611.295 3980.77 -29.9513 4080.08 +EDGE_SE3:QUAT 818 819 -0.781765 11.6215 -0.414289 0.0649706 0.0721222 0.0140649 0.995178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.26 21.1418 571.882 3981.03 12.1994 4079.35 +EDGE_SE3:QUAT 819 820 -0.810632 11.638 -0.0825584 -0.0236645 -0.0246526 0.332556 0.942464 1 3.0845e-18 3.0845e-18 6.78098e-10 -7.03412e-09 1.04532e-07 1 3.0845e-18 6.78098e-10 -7.03412e-09 1.04532e-07 1 6.78098e-10 -7.03412e-09 1.04532e-07 3998.76 1.77269 -77.7318 4000.35 -5.87501 3558.62 +EDGE_SE3:QUAT 820 821 -0.663002 11.7944 -0.251893 -0.00309769 0.0203493 -0.0193551 0.999601 1 1.88079e-22 1.88079e-22 -8.67727e-10 1.69247e-11 -1.75469e-11 1 1.88079e-22 -8.67727e-10 1.69247e-11 -1.75469e-11 1 -8.67727e-10 1.69247e-11 -1.75469e-11 4006.53 -0.443188 162.213 3998.37 -1.6046 4005.07 +EDGE_SE3:QUAT 821 822 -0.567233 11.3616 0.000253554 -0.00192203 0.0767485 -0.00891687 0.997009 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4095.83 -1.93577 626.555 3976.48 -3.24607 4095.53 +EDGE_SE3:QUAT 822 823 -0.737531 11.6653 -0.358376 -0.0318704 -0.0624305 0.0422325 0.996646 1 4.81482e-20 4.81482e-20 -1.39323e-08 -6.49572e-10 8.29861e-10 1 4.81482e-20 -1.39323e-08 -6.49572e-10 8.29861e-10 1 -1.39323e-08 -6.49572e-10 8.29861e-10 4054.41 11.7724 -487.19 3986.12 -13.432 4051.34 +EDGE_SE3:QUAT 823 824 -1.01612 11.5386 -0.0537675 -0.0134697 0.14262 -0.00502962 0.989673 1 7.52316e-22 7.52316e-22 2.57507e-10 -2.80621e-11 1.78947e-09 1 7.52316e-22 2.57507e-10 -2.80621e-11 1.78947e-09 1 2.57507e-10 -2.80621e-11 1.78947e-09 4344.92 -12.7569 1225.59 3918.99 -11.0107 4345.55 +EDGE_SE3:QUAT 824 825 -0.880091 11.732 -0.317146 0.0177493 -0.0141376 0.0736685 0.997025 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.82 -0.75123 -127.882 3998.92 -4.79907 3982.37 +EDGE_SE3:QUAT 825 826 -0.885587 11.4071 -0.36872 -0.0748956 0.139753 0.0623799 0.985377 1 2.40741e-19 2.40741e-19 2.6434e-08 2.10282e-09 -1.00263e-08 1 2.40741e-19 2.6434e-08 2.10282e-09 -1.00263e-08 1 2.6434e-08 2.10282e-09 -1.00263e-08 4336.87 -23.2074 1251.58 3915.55 6.6383 4343.75 +EDGE_SE3:QUAT 826 827 -0.467642 11.5437 -0.157905 -0.086752 -0.0694975 -0.0695696 0.991365 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4067.22 20.0466 -631.713 3975.26 11.6849 4077.96 +EDGE_SE3:QUAT 827 828 -0.877947 11.9023 -0.165327 0.125202 -0.0242267 0.115664 0.985068 1 4.33334e-19 4.33334e-19 2.74944e-08 -7.47593e-09 2.76374e-08 1 4.33334e-19 2.74944e-08 -7.47593e-09 2.76374e-08 1 2.74944e-08 -7.47593e-09 2.76374e-08 3968.62 -21.6817 -358.817 3989.99 -19.3081 3977.81 +EDGE_SE3:QUAT 828 829 -0.378083 11.842 0.0980594 -0.121354 0.131028 0.026302 0.983572 1 9.62965e-19 9.62965e-19 -2.79834e-08 5.47893e-08 2.74264e-09 1 9.62965e-19 -2.79834e-08 5.47893e-08 2.74264e-09 1 -2.79834e-08 5.47893e-08 2.74264e-09 4239.48 -69.8579 1132.52 3932.93 -38.4363 4295.62 +EDGE_SE3:QUAT 829 830 -0.534047 12.2367 -0.0227713 0.0898666 0.0115081 0.0861063 0.992158 1 3.85186e-19 3.85186e-19 -2.74203e-08 -4.92044e-09 -2.74203e-08 1 3.85186e-19 -2.74203e-08 -4.92044e-09 -2.74203e-08 1 -2.74203e-08 -4.92044e-09 -2.74203e-08 3967.45 -1.50421 -1.97574 3999.93 -1.4406 3970.1 +EDGE_SE3:QUAT 830 831 -0.638552 11.8148 -0.0479471 -0.091874 -0.0559161 0.124878 0.986325 1 1.92593e-19 1.92593e-19 2.74499e-08 3.7172e-09 -8.45955e-10 1 1.92593e-19 2.74499e-08 3.7172e-09 -8.45955e-10 1 2.74499e-08 3.7172e-09 -8.45955e-10 3987.3 16.6702 -296.206 3997.19 -19.4543 3958.69 +EDGE_SE3:QUAT 831 832 -0.693561 11.8404 -0.207175 0.11587 0.0131232 0.189865 0.974861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3950.76 -13.7283 -158.146 3996.2 -23.2007 3860.27 +EDGE_SE3:QUAT 832 833 -0.955312 12.0328 -0.116664 0.152938 -0.10558 -0.0264165 0.982225 1 3.12964e-18 3.12964e-18 1.09824e-07 -4.2923e-09 3.46205e-09 1 3.12964e-18 1.09824e-07 -4.2923e-09 3.46205e-09 1 1.09824e-07 -4.2923e-09 3.46205e-09 4056.37 -71.3288 -789.692 3970.98 48.4718 4147.14 +EDGE_SE3:QUAT 833 834 -0.680205 12.003 0.182472 0.0739077 -0.0450815 0.121846 0.988766 1 2.40741e-19 2.40741e-19 -2.92171e-08 1.05351e-08 8.59902e-10 1 2.40741e-19 -2.92171e-08 1.05351e-08 8.59902e-10 1 -2.92171e-08 1.05351e-08 8.59902e-10 4030.7 -9.89419 -462.327 3985.79 -25.575 3993.16 +EDGE_SE3:QUAT 834 835 -0.206924 11.7903 -0.42637 -0.0303571 -0.0161853 0.00970961 0.999361 1 1.20371e-20 1.20371e-20 6.93789e-09 7.41389e-11 -1.08042e-10 1 1.20371e-20 6.93789e-09 7.41389e-11 -1.08042e-10 1 6.93789e-09 7.41389e-11 -1.08042e-10 4000.27 1.95495 -125.857 3999.04 -0.789296 4003.58 +EDGE_SE3:QUAT 835 836 -0.375443 11.894 -0.0465132 -0.0416783 -0.139075 0.0759082 0.986488 1 4.81482e-20 4.81482e-20 1.41928e-08 1.30205e-09 -1.87453e-09 1 4.81482e-20 1.41928e-08 1.30205e-09 -1.87453e-09 1 1.41928e-08 1.30205e-09 -1.87453e-09 4289.29 63.6874 -1128.39 3936.08 -70.3369 4273.19 +EDGE_SE3:QUAT 836 837 -0.815645 11.839 -0.274518 -0.0105222 0.0549199 -0.0209569 0.998215 1 3.00927e-21 3.00927e-21 -3.484e-09 7.7621e-11 -1.8992e-10 1 3.00927e-21 -3.484e-09 7.7621e-11 -1.8992e-10 1 -3.484e-09 7.7621e-11 -1.8992e-10 4047.58 -3.91062 440.909 3988.19 -5.51986 4046.27 +EDGE_SE3:QUAT 837 838 -0.981752 11.5716 -0.25675 0.111006 0.0742979 -0.0477306 0.989889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4056.86 32.5136 660.329 3973.77 0.187396 4097.04 +EDGE_SE3:QUAT 838 839 -0.525286 11.6568 -0.0139725 -0.0646731 -0.00479095 0.18383 0.980816 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.4 -4.54162 102.939 3998.6 13.7787 3866.96 +EDGE_SE3:QUAT 839 840 -0.914139 11.7879 0.0970699 0.158648 -0.1422 -0.0622587 0.975056 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4140.93 -116.764 -1015.26 3961.69 101.436 4226.1 +EDGE_SE3:QUAT 840 841 -0.958526 12.1698 0.0309494 -0.0265585 -0.110855 0.0646969 0.991373 1 2.40741e-19 2.40741e-19 1.20819e-08 2.85274e-08 -3.5594e-10 1 2.40741e-19 1.20819e-08 2.85274e-08 -3.5594e-10 1 1.20819e-08 2.85274e-08 -3.5594e-10 4188.18 32.549 -894.778 3956.29 -40.2271 4174.26 +EDGE_SE3:QUAT 841 842 -0.718399 12.1098 -0.361176 -0.028227 0.00910946 0.0514486 0.998235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.83 -1.20755 89.9309 3999.43 2.3836 3991.43 +EDGE_SE3:QUAT 842 843 -0.833553 12.0971 -0.187412 0.153735 -0.127719 0.214395 0.95608 1 1.54074e-18 1.54074e-18 -6.6023e-08 4.32734e-08 5.2733e-09 1 1.54074e-18 -6.6023e-08 4.32734e-08 5.2733e-09 1 -6.6023e-08 4.32734e-08 5.2733e-09 4375.33 -0.147566 -1450.65 3890.57 -100.141 4286.01 +EDGE_SE3:QUAT 843 844 -0.67298 12.3228 0.0552162 0.0591981 0.0184863 0.147993 0.987042 1 8.1852e-19 8.1852e-19 -1.36847e-08 1.37311e-09 5.47888e-08 1 8.1852e-19 -1.36847e-08 1.37311e-09 5.47888e-08 1 -1.36847e-08 1.37311e-09 5.47888e-08 3986.02 0.271453 38.8903 4000.04 0.231174 3912.43 +EDGE_SE3:QUAT 844 845 -0.83395 11.6257 -0.0403711 -0.00956509 0.11307 0.190833 0.975042 1 1.95602e-19 1.95602e-19 -1.90469e-09 2.77369e-08 -5.60489e-10 1 1.95602e-19 -1.90469e-09 2.77369e-08 -5.60489e-10 1 -1.90469e-09 2.77369e-08 -5.60489e-10 4198.77 55.4572 914.831 3961.32 95.2857 4053.47 +EDGE_SE3:QUAT 845 846 -0.900095 11.7627 -0.289688 -0.0363389 0.0548873 -0.0128245 0.997749 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.89 -9.06625 436.943 3988.51 -5.48024 4046.51 +EDGE_SE3:QUAT 846 847 -0.763622 12.1299 0.0629501 -0.31814 0.1343 -0.0352043 0.937822 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3745.32 -140.715 803.403 4000.08 -108.497 4145.21 +EDGE_SE3:QUAT 847 848 -0.209499 11.9493 -0.52288 -0.251401 0.11022 0.069046 0.959105 1 4.81482e-20 4.81482e-20 1.85924e-09 -3.46283e-09 1.37679e-08 1 4.81482e-20 1.85924e-09 -3.46283e-09 1.37679e-08 1 1.85924e-09 -3.46283e-09 1.37679e-08 4008.91 -131.883 1056.14 3947.66 -55.9039 4242.65 +EDGE_SE3:QUAT 848 849 -0.689083 11.8647 -0.0322896 0.0672742 0.0347678 0.0416991 0.996256 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.52 8.82874 242.676 3996.82 6.45029 4007.67 +EDGE_SE3:QUAT 849 850 -0.724018 12.1103 0.112357 -0.0113533 -0.204415 0.0840038 0.975207 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4729.24 116.159 -1857.93 3850.54 -126.473 4701.53 +EDGE_SE3:QUAT 850 851 -0.757541 11.583 -0.133596 0.0407375 -0.0703593 0.104329 0.991214 1 1.92593e-19 1.92593e-19 -2.16582e-09 7.17898e-10 2.78322e-08 1 1.92593e-19 -2.16582e-09 7.17898e-10 2.78322e-08 1 -2.16582e-09 7.17898e-10 2.78322e-08 4086 0.7546 -615.808 3977.12 -29.0974 4049.1 +EDGE_SE3:QUAT 851 852 -0.439801 11.7832 0.0965785 0.0512885 -0.0529795 0.142152 0.987094 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.69 -1.34117 -503.066 3984.19 -34.2348 3981.38 +EDGE_SE3:QUAT 852 853 -0.830094 11.9349 -0.357196 0.0169961 0.000182591 -0.0730305 0.997185 1 1.20371e-20 1.20371e-20 6.91941e-09 -5.06419e-10 1.84299e-11 1 1.20371e-20 6.91941e-09 -5.06419e-10 1.84299e-11 1 6.91941e-09 -5.06419e-10 1.84299e-11 3998.9 0.176002 16.2876 3999.97 -0.774835 3978.73 +EDGE_SE3:QUAT 853 854 -0.834868 11.9957 -0.0346749 -0.140081 -0.0293553 0.0434865 0.988749 1 7.70372e-19 7.70372e-19 5.49274e-08 2.77649e-09 -8.89801e-10 1 7.70372e-19 5.49274e-08 2.77649e-09 -8.89801e-10 1 5.49274e-08 2.77649e-09 -8.89801e-10 3927.33 9.5451 -155.31 3999.17 -4.39242 3998.26 +EDGE_SE3:QUAT 854 855 -0.886613 12.0812 0.166329 -0.0124792 -0.0533429 0.0204226 0.998289 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4044.55 4.13582 -427.474 3988.89 -5.33629 4043.5 +EDGE_SE3:QUAT 855 856 -0.741394 11.8902 0.0608544 -0.104543 -0.0514597 0.271541 0.955347 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3952.54 -3.64814 -38 4000.07 12.2648 3701.32 +EDGE_SE3:QUAT 856 857 -0.400025 11.9365 -0.29475 -0.159376 -0.208785 0.0398743 0.964063 1 7.70372e-19 7.70372e-19 -5.77796e-08 -6.67743e-09 1.09357e-08 1 7.70372e-19 -5.77796e-08 -6.67743e-09 1.09357e-08 1 -5.77796e-08 -6.67743e-09 1.09357e-08 4537.91 238.659 -1724.56 3903.02 -225.314 4633.15 +EDGE_SE3:QUAT 857 858 -0.459052 12.32 -0.18176 -0.0670517 0.000638435 0.0386238 0.997001 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.31 -1.54223 36.0179 3999.87 0.874226 3994.33 +EDGE_SE3:QUAT 858 859 -0.797758 11.9811 0.00157771 0.0246627 0.0121672 -0.0251333 0.999306 1 2.70834e-20 2.70834e-20 6.92864e-09 3.13017e-09 -6.92696e-09 1 2.70834e-20 6.92864e-09 3.13017e-09 -6.92696e-09 1 6.92864e-09 3.13017e-09 -6.92696e-09 4000.3 1.22247 104.655 3999.29 -1.24958 4000.21 +EDGE_SE3:QUAT 859 860 -0.762697 12.29 0.0432063 -0.0641957 0.0592364 0.0324876 0.995648 1 2.40741e-19 2.40741e-19 -2.8194e-08 1.3126e-08 -9.1492e-10 1 2.40741e-19 -2.8194e-08 1.3126e-08 -9.1492e-10 1 -2.8194e-08 1.3126e-08 -9.1492e-10 4045.57 -13.984 502.12 3984.47 2.67568 4057.84 +EDGE_SE3:QUAT 860 861 -0.714176 11.7214 0.0510251 -0.0517307 0.00838142 0.0445173 0.997633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.49 -2.54323 94.1853 3999.34 2.14944 3994.27 +EDGE_SE3:QUAT 861 862 -0.747911 12.4597 -0.00509957 0.00273121 0.109285 0.131751 0.985237 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4185.38 39.697 881.083 3959.97 65.4713 4115.98 +EDGE_SE3:QUAT 862 863 -0.573406 11.9808 -0.19061 -0.00959322 -0.0181981 0.0547458 0.998288 1 3.00927e-21 3.00927e-21 3.4656e-09 1.9135e-10 -5.91412e-11 1 3.00927e-21 3.4656e-09 1.9135e-10 -5.91412e-11 1 3.4656e-09 1.9135e-10 -5.91412e-11 4004.44 1.06114 -138.761 3998.85 -3.81801 3992.82 +EDGE_SE3:QUAT 863 864 -1.07137 11.7818 -0.0870364 0.132732 0.143507 0.000275119 0.980708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4260.25 96.2139 1196.98 3930.89 70.1676 4330.73 +EDGE_SE3:QUAT 864 865 -0.903809 11.8892 0.0317133 0.000747369 0.0225856 0.176159 0.984102 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.29 2.07438 171.057 3998.49 14.8543 3883.16 +EDGE_SE3:QUAT 865 866 -0.59164 12.0358 -0.471885 -0.130224 0.112213 0.0123536 0.985037 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4139.77 -65.0611 934.657 3953.91 -35.4194 4206.99 +EDGE_SE3:QUAT 866 867 -0.601261 11.8366 -0.116046 -0.0477933 -0.00750402 -0.11448 0.992247 1 1.92593e-19 1.92593e-19 5.03548e-10 1.24527e-09 -2.75534e-08 1 1.92593e-19 5.03548e-10 1.24527e-09 -2.75534e-08 1 5.03548e-10 1.24527e-09 -2.75534e-08 3994.59 2.95553 -123.757 3998.72 8.10466 3951.3 +EDGE_SE3:QUAT 867 868 -0.436376 12.0024 -0.164691 -0.181561 0.0542373 -0.0120231 0.981809 1 7.82409e-19 7.82409e-19 5.5088e-08 -2.99642e-09 9.42834e-09 1 7.82409e-19 5.5088e-08 -2.99642e-09 9.42834e-09 1 5.5088e-08 -2.99642e-09 9.42834e-09 3905.65 -35.6477 389.788 3992.9 -13.3526 4036.93 +EDGE_SE3:QUAT 868 869 -0.846795 11.8535 0.15455 -0.0775353 -0.0141376 0.135263 0.98767 1 7.70372e-19 7.70372e-19 -4.03701e-10 4.35648e-09 -5.48239e-08 1 7.70372e-19 -4.03701e-10 4.35648e-09 -5.48239e-08 1 -4.03701e-10 4.35648e-09 -5.48239e-08 3975.55 -2.25702 14.8286 3999.79 3.93566 3926.42 +EDGE_SE3:QUAT 869 870 -1.27531 11.6719 -0.159875 -0.0781158 -0.0282496 0.0837108 0.993022 1 1.20371e-20 1.20371e-20 6.04743e-10 -6.88842e-09 -5.67555e-10 1 1.20371e-20 6.04743e-10 -6.88842e-09 -5.67555e-10 1 6.04743e-10 -6.88842e-09 -5.67555e-10 3980.55 5.39149 -143.806 3999.27 -5.66323 3976.93 +EDGE_SE3:QUAT 870 871 -0.525296 11.8454 0.0761569 0.0536751 0.106145 -0.0173939 0.992749 1 4.81482e-20 4.81482e-20 -1.41014e-08 8.69417e-11 -1.52516e-09 1 4.81482e-20 -1.41014e-08 8.69417e-11 -1.52516e-09 1 -1.41014e-08 8.69417e-11 -1.52516e-09 4178.42 21.8587 892.108 3954.38 6.86347 4188.73 +EDGE_SE3:QUAT 871 872 -0.948926 12.1648 0.0343856 -0.0396617 -0.0779791 -0.0161055 0.996036 1 2.43751e-19 2.43751e-19 -1.39972e-08 -2.73749e-08 -3.43292e-09 1 2.43751e-19 -1.39972e-08 -2.73749e-08 -3.43292e-09 1 -1.39972e-08 -2.73749e-08 -3.43292e-09 4094.78 11.1766 -643.806 3975.19 -0.522785 4100.03 +EDGE_SE3:QUAT 872 873 -0.813169 12.0235 0.108189 -0.037455 -0.101689 -0.0826815 0.990667 1 1.92593e-19 1.92593e-19 3.01802e-09 5.88376e-10 -2.81233e-08 1 1.92593e-19 3.01802e-09 5.88376e-10 -2.81233e-08 1 3.01802e-09 5.88376e-10 -2.81233e-08 4177.43 -4.46296 -875.059 3955.88 30.3415 4155.7 +EDGE_SE3:QUAT 873 874 -0.561726 12.0137 0.0800443 -0.0863119 -0.00981217 0.125618 0.988268 1 7.70419e-19 7.70419e-19 -5.49158e-08 -6.53364e-09 -6.33037e-10 1 7.70419e-19 -5.49158e-08 -6.53364e-09 -6.33037e-10 1 -5.49158e-08 -6.53364e-09 -6.33037e-10 3970.42 -4.15268 52.3193 3999.42 6.05646 3937.1 +EDGE_SE3:QUAT 874 875 -0.66487 12.0671 0.0149272 -0.0659121 -0.231872 0.0968186 0.965669 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4844.7 248.783 -2048.41 3856.73 -251.393 4824.59 +EDGE_SE3:QUAT 875 876 -0.778182 11.8834 -0.0165352 -0.0796733 -0.0993429 0.0451468 0.99083 1 1.92593e-19 1.92593e-19 2.79848e-08 1.73492e-09 -2.55056e-09 1 1.92593e-19 2.79848e-08 1.73492e-09 -2.55056e-09 1 2.79848e-08 1.73492e-09 -2.55056e-09 4115.2 42.7128 -763.284 3969.21 -36.2558 4132.43 +EDGE_SE3:QUAT 876 877 -0.841374 12.2668 0.326757 0.182547 0.0391943 0.103321 0.976967 1 2.0463e-19 2.0463e-19 8.0088e-10 -1.19596e-08 -2.58194e-08 1 2.0463e-19 8.0088e-10 -1.19596e-08 -2.58194e-08 1 8.0088e-10 -1.19596e-08 -2.58194e-08 3866.33 -0.266782 72.9081 4000.28 0.558517 3956.93 +EDGE_SE3:QUAT 877 878 -0.754848 11.9621 0.31304 0.174718 0.0136392 -0.0715615 0.98192 1 1.92593e-19 1.92593e-19 1.03572e-09 4.7593e-09 2.73074e-08 1 1.92593e-19 1.03572e-09 4.7593e-09 2.73074e-08 1 1.03572e-09 4.7593e-09 2.73074e-08 3893.11 24.9328 250.83 3994.8 -7.54586 3994.73 +EDGE_SE3:QUAT 878 879 -0.410782 11.8848 -0.235107 -0.095986 -0.119222 -0.00348602 0.988211 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4195.84 53.4214 -992.453 3947.02 -32.735 4232.64 +EDGE_SE3:QUAT 879 880 -0.394534 12.0803 -0.0528818 0.107426 0.0475214 0.022885 0.992813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.51 19.4129 346.082 3993.55 8.97119 4027.58 +EDGE_SE3:QUAT 880 881 -0.453827 11.7621 -0.286638 0.0788833 -0.0256566 0.0828169 0.993107 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.53 -9.98029 -280.327 3994.41 -10.6891 3991.98 +EDGE_SE3:QUAT 881 882 -0.721256 12.0611 -0.10468 0.053646 -0.14244 0.178311 0.972131 1 7.82409e-19 7.82409e-19 -2.36692e-09 5.52815e-08 -1.15528e-09 1 7.82409e-19 -2.36692e-09 5.52815e-08 -1.15528e-09 1 -2.36692e-09 5.52815e-08 -1.15528e-09 4373.21 63.0346 -1298.8 3918.45 -113.144 4257.54 +EDGE_SE3:QUAT 882 883 -0.588248 12.2337 0.13601 0.0138878 -0.00762775 0.193024 0.981066 1 3.00927e-21 3.00927e-21 -3.40463e-09 -6.68982e-10 4.27452e-11 1 3.00927e-21 -3.40463e-09 -6.68982e-10 4.27452e-11 1 -3.40463e-09 -6.68982e-10 4.27452e-11 4001.19 -0.178485 -89.037 3999.45 -9.4864 3852.93 +EDGE_SE3:QUAT 883 884 -0.831276 12.5557 -0.12866 -0.0331323 0.0822402 0.0572216 0.994417 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4112.59 -2.38622 694.002 3971.22 15.6784 4103.89 +EDGE_SE3:QUAT 884 885 -1.04694 12.0634 0.02811 -0.0342167 -0.057791 -0.0971899 0.992997 1 1.20371e-20 1.20371e-20 -6.94399e-09 6.55221e-10 4.42159e-10 1 1.20371e-20 -6.94399e-09 6.55221e-10 4.42159e-10 1 -6.94399e-09 6.55221e-10 4.42159e-10 4057.26 0.226008 -501.683 3984.55 22.7256 4024.16 +EDGE_SE3:QUAT 885 886 -0.822391 12.2234 -0.153973 -0.0485115 0.0947753 0.197025 0.9746 1 1.92593e-19 1.92593e-19 -5.30547e-09 2.7083e-08 2.36661e-10 1 1.92593e-19 -5.30547e-09 2.7083e-08 2.36661e-10 1 -5.30547e-09 2.7083e-08 2.36661e-10 4166.79 28.5712 857.847 3961.3 83.2201 4020.93 +EDGE_SE3:QUAT 886 887 -0.566686 11.8754 0.00551914 0.0713616 0.186142 0.0651009 0.977763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4523.65 133.733 1572.75 3893.12 132.761 4527.07 +EDGE_SE3:QUAT 887 888 -0.997776 12.0284 -0.148391 -0.0368607 -0.0466743 0.0846732 0.994632 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.06 9.73342 -333.153 3994.02 -15.4146 3998.82 +EDGE_SE3:QUAT 888 889 -0.92402 12.012 0.026212 0.257935 -0.0343523 0.138545 0.95556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3838.62 -88.3099 -663.353 3967.19 -23.694 4027.96 +EDGE_SE3:QUAT 889 890 -0.838678 11.7953 0.0408957 -0.0349487 -0.0635619 -0.110004 0.991281 1 1.20371e-20 1.20371e-20 6.94355e-09 -7.44184e-10 -4.87334e-10 1 1.20371e-20 6.94355e-09 -7.44184e-10 -4.87334e-10 1 6.94355e-09 -7.44184e-10 -4.87334e-10 4070.29 -1.88449 -553.552 3981.48 28.6544 4026.77 +EDGE_SE3:QUAT 890 891 -0.723931 12.1878 -0.222795 0.0315813 -0.0719919 0.00531774 0.996891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4080.59 -9.11538 -587.753 3979.24 2.39402 4084.46 +EDGE_SE3:QUAT 891 892 -0.543669 12.3798 0.0986355 -0.0353515 -0.255886 -0.049335 0.9648 1 1.20371e-20 1.20371e-20 7.72072e-09 -2.92735e-10 -2.06353e-09 1 1.20371e-20 7.72072e-09 -2.92735e-10 -2.06353e-09 1 7.72072e-09 -2.92735e-10 -2.06353e-09 5311.28 -29.3268 -2645.32 3735.68 34.3662 5306.55 +EDGE_SE3:QUAT 892 893 -1.03688 11.904 0.0139368 -0.00693135 -0.16301 0.0497787 0.985344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4454.1 42.1536 -1422.52 3897.5 -50.3936 4444.38 +EDGE_SE3:QUAT 893 894 -0.752702 12.6668 -0.0327382 -0.014195 0.0642497 -0.0094055 0.997789 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.58 -4.78867 519.585 3983.67 -3.97338 4066.04 +EDGE_SE3:QUAT 894 895 -0.839149 12.0412 -0.16046 -0.125567 0.0239208 0.161834 0.978504 1 1.92593e-19 1.92593e-19 2.73098e-08 4.21928e-09 1.72444e-09 1 1.92593e-19 2.73098e-08 4.21928e-09 1.72444e-09 1 2.73098e-08 4.21928e-09 1.72444e-09 3979.7 -23.3257 421.307 3985.77 34.3991 3938.01 +EDGE_SE3:QUAT 895 896 -0.623416 12.0956 -0.26796 -0.103959 -0.192027 0.184421 0.958283 1 7.70372e-19 7.70372e-19 -5.57396e-08 -1.36205e-08 7.71706e-09 1 7.70372e-19 -5.57396e-08 -1.36205e-08 7.71706e-09 1 -5.57396e-08 -1.36205e-08 7.71706e-09 4324.94 209.909 -1278.43 3972.13 -217.141 4232.13 +EDGE_SE3:QUAT 896 897 -0.641646 12.1518 -0.429746 -0.023861 0.00819114 0.343165 0.938936 1 1.20371e-20 1.20371e-20 6.51995e-09 2.37832e-09 1.50226e-10 1 1.20371e-20 6.51995e-09 2.37832e-09 1.50226e-10 1 6.51995e-09 2.37832e-09 1.50226e-10 4002.89 0.17562 144.97 3998.6 29.633 3534.12 +EDGE_SE3:QUAT 897 898 -0.701415 12.3393 -0.0184349 -0.260839 0.1635 -0.0129532 0.951348 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.85 -199.577 1211.81 3965.37 -163.952 4335.32 +EDGE_SE3:QUAT 898 899 -0.829128 11.7664 0.00895373 -0.0329735 0.105933 0.157556 0.981258 1 7.82409e-19 7.82409e-19 -1.32914e-08 -1.17822e-09 -5.6637e-08 1 7.82409e-19 -1.32914e-08 -1.17822e-09 -5.6637e-08 1 -1.32914e-08 -1.17822e-09 -5.6637e-08 4195.37 30.9514 915.841 3955.52 72.0762 4100.42 +EDGE_SE3:QUAT 899 900 -0.636601 12.4169 0.0558711 -0.0369915 0.106348 -0.0181224 0.993475 1 2.40741e-19 2.40741e-19 1.3364e-08 -2.79451e-08 3.26287e-10 1 2.40741e-19 1.3364e-08 -2.79451e-08 3.26287e-10 1 1.3364e-08 -2.79451e-08 3.26287e-10 4177.06 -23.1123 873.774 3956.7 -19.2338 4181.22 +EDGE_SE3:QUAT 900 901 -0.88806 12.3203 -0.01012 0.00870355 -0.0383777 0.23774 0.970531 1 1.98659e-21 1.98659e-21 2.74432e-09 6.724e-10 -1.07607e-10 1 1.98659e-21 2.74432e-09 6.724e-10 -1.07607e-10 1 2.74432e-09 6.724e-10 -1.07607e-10 4023.07 7.27811 -306.834 3995.62 -36.6637 3797.3 +EDGE_SE3:QUAT 901 902 -0.897305 12.318 -0.232563 -0.0828934 0.039365 0.0377295 0.995066 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.03 -13.6091 350.831 3992.12 3.29044 4024.82 +EDGE_SE3:QUAT 902 903 -0.890883 12.3385 -0.0421063 -0.194536 -0.116988 0.0383087 0.97314 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.15 95.144 -817.409 3975.43 -69.6978 4153.66 +EDGE_SE3:QUAT 903 904 -0.936721 12.1395 -0.017261 0.0916238 0.0739681 0.131296 0.984325 1 4.81482e-20 4.81482e-20 1.99143e-09 -1.36366e-08 1.50418e-09 1 4.81482e-20 1.99143e-09 -1.36366e-08 1.50418e-09 1 1.99143e-09 -1.36366e-08 1.50418e-09 4011.06 28.7126 429.443 3993.47 33.2037 3975.68 +EDGE_SE3:QUAT 904 905 -0.712577 12.2656 -0.510274 -0.11178 -0.0770155 -0.00892115 0.990704 1 1.93129e-19 1.93129e-19 -2.77181e-08 -7.21508e-11 6.97361e-10 1 1.93129e-19 -2.77181e-08 -7.21508e-11 6.97361e-10 1 -2.77181e-08 -7.21508e-11 6.97361e-10 4046.76 36.1117 -629.547 3977.47 -13.5143 4096.42 +EDGE_SE3:QUAT 905 906 -0.641815 11.7346 0.1228 0.123048 -0.0584773 0.0387742 0.989917 1 2.40741e-19 2.40741e-19 2.67829e-08 2.32492e-09 1.20046e-08 1 2.40741e-19 2.67829e-08 2.32492e-09 1.20046e-08 1 2.67829e-08 2.32492e-09 1.20046e-08 4006.11 -30.5112 -520.843 3983.47 1.20684 4060.66 +EDGE_SE3:QUAT 906 907 -0.658006 12.0949 -0.258929 0.190469 0.0220515 0.0588092 0.979682 1 7.70372e-19 7.70372e-19 -5.43813e-08 -3.48604e-09 9.27402e-11 1 7.70372e-19 -5.43813e-08 -3.48604e-09 9.27402e-11 1 -5.43813e-08 -3.48604e-09 9.27402e-11 3854.61 -1.17506 35.0591 4000.06 -0.0944035 3985.89 +EDGE_SE3:QUAT 907 908 -0.62444 12.0955 -0.55393 0.0929997 0.18619 0.141515 0.967811 1 9.62965e-19 9.62965e-19 -1.81291e-08 -5.87276e-08 3.9773e-09 1 9.62965e-19 -1.81291e-08 -5.87276e-08 3.9773e-09 1 -1.81291e-08 -5.87276e-08 3.9773e-09 4385.92 185.893 1367.77 3943.31 191.797 4340.41 +EDGE_SE3:QUAT 908 909 -0.832406 12.1784 -0.269042 -0.134755 0.0099179 0.0955629 0.98621 1 2.0463e-19 2.0463e-19 -3.45809e-10 -3.21968e-09 -2.83226e-08 1 2.0463e-19 -3.45809e-10 -3.21968e-09 -2.83226e-08 1 -3.45809e-10 -3.21968e-09 -2.83226e-08 3939.84 -17.4891 228.6 3995.36 11.434 3975.95 +EDGE_SE3:QUAT 909 910 -0.959787 11.9381 -0.472064 -0.0586392 0.116875 -0.00939428 0.99137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4208.09 -35.5697 967.796 3948.23 -25.3473 4221.49 +EDGE_SE3:QUAT 910 911 -0.375473 12.0266 -0.124067 0.0277245 -0.053664 -0.0445891 0.997178 1 1.20371e-20 1.20371e-20 -6.95642e-09 3.33155e-10 3.54943e-10 1 1.20371e-20 -6.95642e-09 3.33155e-10 3.54943e-10 1 -6.95642e-09 3.33155e-10 3.54943e-10 4039.82 -8.80451 -416.475 3989.8 11.2593 4034.94 +EDGE_SE3:QUAT 911 912 -0.933865 12.0194 0.151918 -0.0264698 0.0821056 -0.0140386 0.996173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4105.43 -11.7418 666.815 3973.76 -9.36759 4107.44 +EDGE_SE3:QUAT 912 913 -0.350521 12.3098 0.00893775 0.00490288 -0.122249 0.0164935 0.99235 1 2.04818e-19 2.04818e-19 4.50019e-10 -2.75228e-08 7.0146e-09 1 2.04818e-19 4.50019e-10 -2.75228e-08 7.0146e-09 1 4.50019e-10 -2.75228e-08 7.0146e-09 4250.49 3.44073 -1032.05 3940.19 -7.97323 4249.5 +EDGE_SE3:QUAT 913 914 -0.813507 12.1718 -0.385364 -0.123337 -0.130296 0.233896 0.955565 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.75 75.8452 -600.986 4003.46 -82.9567 3861.77 +EDGE_SE3:QUAT 914 915 -0.806013 11.9997 -0.135345 0.125387 -0.0160768 0.136122 0.982594 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3962.37 -20.6019 -324.399 3991.07 -23.0369 3951.14 +EDGE_SE3:QUAT 915 916 -0.714524 12.2389 -0.164254 0.031217 0.255791 0.0399464 0.965402 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5250.2 155.198 2566.98 3757.49 155.687 5247.72 +EDGE_SE3:QUAT 916 917 -0.323638 12.3709 -0.346726 -0.0414756 -0.0857759 0.188136 0.977511 1 4.81482e-20 4.81482e-20 -1.37016e-08 -2.76235e-09 8.93458e-10 1 4.81482e-20 -1.37016e-08 -2.76235e-09 8.93458e-10 1 -1.37016e-08 -2.76235e-09 8.93458e-10 4070.46 36.6593 -564.308 3987.95 -57.8133 3935.76 +EDGE_SE3:QUAT 917 918 -0.525428 12.4616 -0.178323 -0.0362669 -0.0731139 -0.0456965 0.995616 1 4.81482e-20 4.81482e-20 -1.06634e-09 -4.18147e-10 1.39757e-08 1 4.81482e-20 -1.06634e-09 -4.18147e-10 1.39757e-08 1 -1.06634e-09 -4.18147e-10 1.39757e-08 4086.92 5.58018 -614.187 3977.14 9.97498 4083.82 +EDGE_SE3:QUAT 918 919 -0.734146 12.4544 -0.384669 0.263631 -0.0482642 0.0227237 0.963147 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3765.44 -56.6463 -419.144 3991.79 12.3432 4041.38 +EDGE_SE3:QUAT 919 920 -0.872412 12.0442 -0.0867102 0.00069472 0.0936509 -0.0635915 0.993572 1 1.92593e-19 1.92593e-19 -1.79278e-09 -2.75754e-08 -3.14845e-10 1 1.92593e-19 -1.79278e-09 -2.75754e-08 -3.14845e-10 1 -1.79278e-09 -2.75754e-08 -3.14845e-10 4142.51 -13.5873 768.347 3966.05 -26.5001 4126.33 +EDGE_SE3:QUAT 920 921 -0.769922 12.3284 -0.284752 0.0782848 0.0234269 0.18513 0.979311 1 1.92593e-19 1.92593e-19 -2.71781e-08 -5.17659e-09 1.90954e-10 1 1.92593e-19 -2.71781e-08 -5.17659e-09 1.90954e-10 1 -2.71781e-08 -5.17659e-09 1.90954e-10 3974.58 -2.03248 6.84265 3999.86 -5.04145 3862 +EDGE_SE3:QUAT 921 922 -0.741606 12.3731 0.0988193 0.0820999 -0.0967283 0.0613199 0.990022 1 4.81482e-20 4.81482e-20 -1.48787e-09 1.00881e-09 1.40393e-08 1 4.81482e-20 -1.48787e-09 1.00881e-09 1.40393e-08 1 -1.48787e-09 1.00881e-09 1.40393e-08 4147.96 -23.4997 -854.66 3957.1 -8.05794 4159.88 +EDGE_SE3:QUAT 922 923 -0.843146 12.2039 -0.232743 -0.0330184 -0.1584 0.220834 0.961796 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4301.34 140.554 -1151.44 3961.54 -168.243 4110.63 +EDGE_SE3:QUAT 923 924 -0.779787 12.0622 -0.413045 -0.0599287 -0.00762775 0.189723 0.979977 1 4.81482e-20 4.81482e-20 -1.36016e-08 -2.62661e-09 -2.11807e-10 1 4.81482e-20 -1.36016e-08 -2.62661e-09 -2.11807e-10 1 -1.36016e-08 -2.62661e-09 -2.11807e-10 3986.57 -3.52358 75.4171 3999.08 11.5407 3856.95 +EDGE_SE3:QUAT 924 925 -0.799092 12.4563 -0.473478 -0.111569 0.0155785 0.0396999 0.992841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3957.79 -10.3389 175.009 3997.79 2.69229 4001.28 +EDGE_SE3:QUAT 925 926 -0.920919 12.318 0.099765 0.15328 0.00801069 0.189488 0.969812 1 7.82409e-19 7.82409e-19 -1.46971e-09 1.33792e-09 5.49605e-08 1 7.82409e-19 -1.46971e-09 1.33792e-09 5.49605e-08 1 -1.46971e-09 1.33792e-09 5.49605e-08 3922.35 -27.4378 -277.375 3990.67 -35.1717 3872.71 +EDGE_SE3:QUAT 926 927 -0.989528 12.261 -0.446454 0.162194 -0.0843455 0.215752 0.959182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4163.28 -28.9723 -1073.89 3930.15 -84.5158 4082.31 +EDGE_SE3:QUAT 927 928 -0.675772 12.3751 -0.223371 -0.11234 -0.0910802 0.0514523 0.988148 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4054.17 46.8702 -656.333 3978.97 -36.6235 4094.06 +EDGE_SE3:QUAT 928 929 -0.850486 12.4984 0.0576585 -0.0743217 0.0670441 0.033255 0.994422 1 1.20371e-20 1.20371e-20 4.98503e-10 -4.93233e-10 6.96912e-09 1 1.20371e-20 4.98503e-10 -4.93233e-10 6.96912e-09 1 4.98503e-10 -4.93233e-10 6.96912e-09 4057.73 -18.6271 570.705 3980.18 1.27099 4075.4 +EDGE_SE3:QUAT 929 930 -0.519588 12.3332 0.0502512 -0.0384624 -0.0216934 0.180648 0.982556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.56 1.73405 -83.2145 3999.94 -4.9036 3870.94 +EDGE_SE3:QUAT 930 931 -0.991153 12.4126 -0.110349 0.143223 0.126038 0.206748 0.959613 1 7.70372e-19 7.70372e-19 2.82874e-09 1.03938e-08 5.37859e-08 1 7.70372e-19 2.82874e-09 1.03938e-08 5.37859e-08 1 2.82874e-09 1.03938e-08 5.37859e-08 3990.1 69.3276 569.435 4002.39 73.3293 3901.18 +EDGE_SE3:QUAT 931 932 -0.799763 12.2039 -0.127817 0.0479573 -0.0423891 0.0438868 0.996984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.8 -6.99086 -364.897 3991.55 -6.02023 4025.3 +EDGE_SE3:QUAT 932 933 -0.65806 12.175 -0.0667862 0.0925796 0.0533314 -0.122017 0.986761 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.14 15.8788 555.507 3979.66 -28.0717 4015.87 +EDGE_SE3:QUAT 933 934 -0.596832 12.417 -0.0875358 0.103959 -0.0732356 0.0580587 0.990181 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.22 -28.593 -661.372 3973.32 -4.81181 4092.97 +EDGE_SE3:QUAT 934 935 -1.1197 12.118 0.0262833 -0.201839 0.0652979 0.0968661 0.972427 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.06 -68.4975 734.384 3966.41 4.93661 4092.49 +EDGE_SE3:QUAT 935 936 -0.791562 12.6378 0.0806585 0.0059489 0.0111041 -0.0985784 0.99505 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.09 -0.0359755 94.5763 3999.44 -4.74278 3963.36 +EDGE_SE3:QUAT 936 937 -0.888261 12.5122 -0.029977 -0.0762363 0.0671908 -0.088104 0.990914 1 4.81482e-20 4.81482e-20 -1.35914e-09 -1.37389e-08 -1.21311e-09 1 4.81482e-20 -1.35914e-09 -1.37389e-08 -1.21311e-09 1 -1.35914e-09 -1.37389e-08 -1.21311e-09 4026.61 -24.0232 450.633 3990.26 -25.6301 4018.8 +EDGE_SE3:QUAT 937 938 -0.890913 12.2369 0.0709721 -0.0551961 0.123121 0.216506 0.966913 1 7.82409e-19 7.82409e-19 1.85851e-08 -5.22565e-08 1.05792e-09 1 7.82409e-19 1.85851e-08 -5.22565e-08 1.05792e-09 1 1.85851e-08 -5.22565e-08 1.05792e-09 4281.87 60.6909 1123.7 3940.11 121.763 4106.56 +EDGE_SE3:QUAT 938 939 -0.642985 12.2772 -0.193262 0.00782723 0.0178884 0.0842047 0.996257 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.22 1.09807 133.827 3998.97 5.57374 3976.11 +EDGE_SE3:QUAT 939 940 -1.05676 11.8973 -0.187807 -0.136134 -0.00701547 0.0211256 0.99044 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3925.94 0.579294 -20.4568 4000 -0.129369 3998.28 +EDGE_SE3:QUAT 940 941 -0.501418 12.3167 -0.214312 0.0430314 0.100785 0.106364 0.98827 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4130.63 40.9626 756.379 3971.22 52.4542 4092.78 +EDGE_SE3:QUAT 941 942 -0.463397 12.3599 0.0809769 -0.0551297 -0.00174463 0.128911 0.990121 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.9 -2.60682 70.6348 3999.39 6.33999 3934.58 +EDGE_SE3:QUAT 942 943 -0.277078 12.1691 0.154574 0.0081794 0.108879 -0.00396833 0.994013 1 3.00927e-21 3.00927e-21 3.53249e-09 -7.99851e-12 3.87101e-10 1 3.00927e-21 3.53249e-09 -7.99851e-12 3.87101e-10 1 3.53249e-09 -7.99851e-12 3.87101e-10 4196.51 2.9875 908.747 3952.55 0.437477 4196.71 +EDGE_SE3:QUAT 943 944 -0.488986 12.5406 0.10507 0.111282 -0.0313125 0.0343872 0.9927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3971.7 -16.1929 -292.417 3994.44 -1.96177 4016.5 +EDGE_SE3:QUAT 944 945 -0.84167 11.9226 -0.0123412 0.0210901 0.0105207 0.061145 0.997851 1 1.50463e-20 1.50463e-20 7.13851e-09 -3.03479e-09 1.31627e-10 1 1.50463e-20 7.13851e-09 -3.03479e-09 1.31627e-10 1 7.13851e-09 -3.03479e-09 1.31627e-10 3999.38 0.78201 68.2195 3999.76 1.96522 3986.2 +EDGE_SE3:QUAT 945 946 -0.820177 12.4149 -0.253485 -0.0254126 -0.0569611 -0.027265 0.99768 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.58 3.97901 -468.604 3986.51 4.5809 4051.19 +EDGE_SE3:QUAT 946 947 -0.55555 12.003 -0.693621 -0.0285126 0.0347207 0.10091 0.993881 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.49 -1.14369 309.19 3993.93 15.3499 3983.01 +EDGE_SE3:QUAT 947 948 -0.90571 12.123 -0.302487 -0.0114865 0.100475 0.158746 0.982127 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4162.31 35.0103 823.435 3965.2 69.3219 4062.04 +EDGE_SE3:QUAT 948 949 -0.682457 12.3554 -0.328858 0.0871257 0.264195 0.0516832 0.959134 1 1.92593e-19 1.92593e-19 -3.05384e-08 -3.50739e-09 -7.86887e-09 1 1.92593e-19 -3.05384e-08 -3.50739e-09 -7.86887e-09 1 -3.05384e-08 -3.50739e-09 -7.86887e-09 5211.85 307.949 2552.49 3796.3 306.921 5231.53 +EDGE_SE3:QUAT 949 950 -0.958639 11.6824 -0.273133 0.0160299 0.146787 0.0679279 0.986703 1 2.0463e-19 2.0463e-19 -3.00272e-09 5.27203e-10 2.75418e-08 1 2.0463e-19 -3.00272e-09 5.27203e-10 2.75418e-08 1 -3.00272e-09 5.27203e-10 2.75418e-08 4352.32 50.0515 1240.31 3920.86 60.3896 4334.89 +EDGE_SE3:QUAT 950 951 -0.769137 12.2453 -0.0468669 0.231155 -0.118908 -0.0413225 0.964739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3931.67 -104.595 -781.607 3983.18 76.743 4138.57 +EDGE_SE3:QUAT 951 952 -0.609002 12.4335 0.0925356 -0.11352 -0.00672041 0.0311997 0.993023 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3948.43 -0.222761 -10.5383 4000 0.0461859 3996.08 +EDGE_SE3:QUAT 952 953 -0.962329 12.2187 0.0502806 -0.0909409 0.0469112 0.156901 0.982299 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4036.5 -12.699 533.844 3980.75 38.8485 3971.11 +EDGE_SE3:QUAT 953 954 -0.888029 12.2095 -0.207978 -0.0414799 0.0189893 0.072599 0.996317 1 1.92593e-19 1.92593e-19 6.87182e-10 -1.06496e-09 2.76835e-08 1 1.92593e-19 6.87182e-10 -1.06496e-09 2.76835e-08 1 6.87182e-10 -1.06496e-09 2.76835e-08 4001.78 -3.25554 186.689 3997.6 6.72855 3987.58 +EDGE_SE3:QUAT 954 955 -1.38447 12.5021 0.0917421 0.0344688 -0.0413503 0.113268 0.992105 1 1.20371e-20 1.20371e-20 6.91416e-09 7.70683e-10 -3.34353e-10 1 1.20371e-20 6.91416e-09 7.70683e-10 -3.34353e-10 1 6.91416e-09 7.70683e-10 -3.34353e-10 4029.76 -1.14572 -373.317 3991.21 -20.6192 3983.2 +EDGE_SE3:QUAT 955 956 -0.707689 12.0235 -0.308073 -0.0342752 -0.0380999 -0.0632967 0.996678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.4 3.38749 -330.434 3993.04 9.52646 4011.07 +EDGE_SE3:QUAT 956 957 -0.927207 12.1753 0.00245457 -0.061572 0.118908 -0.0300806 0.990538 1 3.85186e-19 3.85186e-19 2.69806e-08 -2.87776e-08 1.29299e-09 1 3.85186e-19 2.69806e-08 -2.87776e-08 1.29299e-09 1 2.69806e-08 -2.87776e-08 1.29299e-09 4205.79 -44.1758 965.82 3949.74 -37.8009 4217.34 +EDGE_SE3:QUAT 957 958 -1.09597 12.3307 -0.465626 -0.0735432 -0.0725185 0.0897251 0.990597 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.49 26.8886 -495.294 3988.11 -29.2201 4027.93 +EDGE_SE3:QUAT 958 959 -1.02719 12.2726 -0.0240933 0.0576211 0.0149905 0.157997 0.985643 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.38 -0.825374 7.65817 3999.96 -2.38876 3899.81 +EDGE_SE3:QUAT 959 960 -0.593391 12.3645 0.0156744 -0.0104492 -0.0277017 0.158542 0.986908 1 3.00927e-21 3.00927e-21 3.42813e-09 5.53375e-10 -7.9976e-11 1 3.00927e-21 3.42813e-09 5.53375e-10 -7.9976e-11 1 3.42813e-09 5.53375e-10 -7.9976e-11 4008.92 3.38211 -194.078 3998.15 -14.9012 3908.82 +EDGE_SE3:QUAT 960 961 -0.583062 12.3066 -0.251775 -0.0825683 0.210055 0.145981 0.963197 1 8.1852e-19 8.1852e-19 -2.1641e-08 5.177e-08 -2.22281e-09 1 8.1852e-19 -2.1641e-08 5.177e-08 -2.22281e-09 1 -2.1641e-08 5.177e-08 -2.22281e-09 4885.05 82.2361 2117.01 3812.13 115.486 4827.08 +EDGE_SE3:QUAT 961 962 -0.731705 12.6889 -0.388011 -0.0539935 0.0179322 0.293457 0.954278 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.14 -1.44345 305.515 3993.37 52.0219 3678.33 +EDGE_SE3:QUAT 962 963 -0.488349 12.5645 -0.201976 -0.0594109 -0.0569754 0.096137 0.991959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.75 16.6284 -381.521 3992.88 -21.1608 3998.89 +EDGE_SE3:QUAT 963 964 -1.00348 12.5209 -0.16157 -0.0223551 -0.108618 0.165963 0.979877 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4157.02 52.8719 -814.234 3970.06 -78.8809 4048.84 +EDGE_SE3:QUAT 964 965 -0.918498 12.5434 -0.395777 -0.157892 0.0250023 0.0151877 0.987023 1 3.00927e-21 3.00927e-21 -9.89845e-11 5.46548e-10 -3.42978e-09 1 3.00927e-21 -9.89845e-11 5.46548e-10 -3.42978e-09 1 -9.89845e-11 5.46548e-10 -3.42978e-09 3912.5 -17.9005 221.451 3997.05 -1.06694 4011.3 +EDGE_SE3:QUAT 965 966 -1.03248 12.5189 -0.264565 -0.167751 0.0116155 -0.0188854 0.98558 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3888.05 -3.18855 51.6827 3999.94 -0.589743 3999.19 +EDGE_SE3:QUAT 966 967 -0.731054 12.4333 0.158106 0.00685114 0.171454 0.0566333 0.983539 1 4.81482e-20 4.81482e-20 2.49604e-09 4.05445e-10 1.44892e-08 1 4.81482e-20 2.49604e-09 4.05445e-10 1.44892e-08 1 2.49604e-09 4.05445e-10 1.44892e-08 4505.31 52.4459 1509.15 3887.64 61.6309 4492.66 +EDGE_SE3:QUAT 967 968 -0.905455 12.0627 -0.283725 -0.0179102 -0.119927 0.140662 0.982604 1 8.1852e-19 8.1852e-19 7.74104e-09 -8.29894e-10 5.44244e-08 1 8.1852e-19 7.74104e-09 -8.29894e-10 5.44244e-08 1 7.74104e-09 -8.29894e-10 5.44244e-08 4208.45 56.7949 -940.147 3957.48 -80.353 4130.59 +EDGE_SE3:QUAT 968 969 -0.740812 12.2489 -0.0333513 -0.124742 0.0536168 0.212199 0.967748 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.69 -18.6266 718.559 3965.28 70.3432 3943.82 +EDGE_SE3:QUAT 969 970 -1.00678 12.3143 -0.267873 0.0298825 0.0796075 0.158682 0.983661 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4074.26 28.824 564.48 3985.33 49.0585 3977.11 +EDGE_SE3:QUAT 970 971 -0.699101 12.4445 0.0496593 -0.0400305 0.0577659 0.0948806 0.993005 1 1.92593e-19 1.92593e-19 -1.79484e-09 8.00928e-10 -2.7781e-08 1 1.92593e-19 -1.79484e-09 8.00928e-10 -2.7781e-08 1 -1.79484e-09 8.00928e-10 -2.7781e-08 4056.93 -1.99189 507.413 3984.07 21.9005 4027.33 +EDGE_SE3:QUAT 971 972 -0.429335 12.2502 -0.366236 0.0110753 -0.090447 0.0719573 0.993237 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4135.19 10.3549 -749.082 3967.49 -27.0699 4114.97 +EDGE_SE3:QUAT 972 973 -1.04003 12.4759 -0.153165 0.0550271 -0.061137 0.0425823 0.995701 1 9.62965e-20 9.62965e-20 -1.30204e-08 -1.20256e-09 -1.30204e-08 1 9.62965e-20 -1.30204e-08 -1.20256e-09 -1.30204e-08 1 -1.30204e-08 -1.20256e-09 -1.30204e-08 4054.72 -10.9553 -521.377 3983.2 -6.29083 4059.58 +EDGE_SE3:QUAT 973 974 -0.839778 12.4209 -0.0152427 0.118862 0.0685666 0.0895414 0.986485 1 8.1852e-19 8.1852e-19 5.36022e-08 1.94689e-08 6.65315e-10 1 8.1852e-19 5.36022e-08 1.94689e-08 6.65315e-10 1 5.36022e-08 1.94689e-08 6.65315e-10 3983.69 28.6413 406.634 3993.65 25.3165 4008.14 +EDGE_SE3:QUAT 974 975 -0.831977 12.6674 -0.110536 -0.0887672 0.0361573 0.137225 0.985892 1 1.92593e-19 1.92593e-19 2.75198e-08 3.60608e-09 1.62888e-09 1 1.92593e-19 2.75198e-08 3.60608e-09 1.62888e-09 1 2.75198e-08 3.60608e-09 1.62888e-09 4013.01 -13.2055 426.196 3987.18 27.7286 3969.21 +EDGE_SE3:QUAT 975 976 -0.347465 12.6433 -0.294099 -0.135579 0.199026 0.100226 0.965382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4761.63 -69.8436 2009.61 3821.56 -30.7373 4794.98 +EDGE_SE3:QUAT 976 977 -0.769522 12.681 0.115879 -0.0489082 -0.0291368 0.102996 0.993051 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.41 4.92269 -168.777 3998.78 -8.24634 3964.55 +EDGE_SE3:QUAT 977 978 -0.74603 12.1135 -0.180304 0.139176 -0.119329 0.273822 0.944146 1 7.70372e-19 7.70372e-19 5.54558e-08 1.41579e-08 -1.00984e-08 1 7.70372e-19 5.54558e-08 1.41579e-08 -1.00984e-08 1 5.54558e-08 1.41579e-08 -1.00984e-08 4360.93 47.3629 -1396.13 3904.73 -162.963 4138.5 +EDGE_SE3:QUAT 978 979 -0.717916 12.1379 0.179339 0.128547 0.0556743 -0.0378218 0.989417 1 8.1852e-19 8.1852e-19 5.50355e-08 -1.49995e-08 5.27896e-09 1 8.1852e-19 5.50355e-08 -1.49995e-08 5.27896e-09 1 5.50355e-08 -1.49995e-08 5.27896e-09 3994.98 30.8408 498.177 3984.86 1.40472 4055.36 +EDGE_SE3:QUAT 979 980 -0.941065 12.5854 -0.155219 -0.124893 -0.0943964 0.0645927 0.985555 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4039.74 52.3047 -649.055 3981.16 -42.7335 4085.44 +EDGE_SE3:QUAT 980 981 -0.782838 12.2677 -0.247137 -0.0347215 -0.118049 0.123188 0.984725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4190.16 56.2085 -905.046 3960.46 -72.7706 4134.28 +EDGE_SE3:QUAT 981 982 -1.14657 12.1582 -0.492169 -0.0363663 0.0486068 0.0254589 0.997831 1 4.81482e-20 4.81482e-20 1.3917e-08 3.06418e-10 7.01203e-10 1 4.81482e-20 1.3917e-08 3.06418e-10 7.01203e-10 1 1.3917e-08 3.06418e-10 7.01203e-10 4034.78 -6.04327 402.369 3989.95 3.12252 4037.48 +EDGE_SE3:QUAT 982 983 -0.792741 12.4696 -0.322496 -0.00592481 0.0449734 0.0709391 0.996449 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.84 2.41573 364.716 3991.94 12.9485 4012.85 +EDGE_SE3:QUAT 983 984 -0.547837 12.1931 -0.370076 -0.218493 -0.103293 0.0153583 0.970235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.64 89.8503 -747.885 3978.7 -55.1933 4133.66 +EDGE_SE3:QUAT 984 985 -1.07706 12.4227 -0.385376 -0.0403897 0.0603795 0.25014 0.965481 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4071.47 16.3638 564.01 3983.7 72.3926 3827.72 +EDGE_SE3:QUAT 985 986 -0.860166 12.5974 0.239626 0.0647355 -0.123078 0.0957697 0.985642 1 9.62965e-19 9.62965e-19 7.42112e-10 -5.35864e-08 3.06425e-08 1 9.62965e-19 7.42112e-10 -5.35864e-08 3.06425e-08 1 7.42112e-10 -5.35864e-08 3.06425e-08 4268.93 -1.15458 -1106.61 3931.95 -35.0778 4249.01 +EDGE_SE3:QUAT 986 987 -0.719207 12.4588 0.138066 -0.137607 0.0750886 0.106604 0.981866 1 9.62965e-19 9.62965e-19 -5.83245e-08 -1.31199e-09 -3.33954e-08 1 9.62965e-19 -5.83245e-08 -1.31199e-09 -3.33954e-08 1 -5.83245e-08 -1.31199e-09 -3.33954e-08 4068.04 -39.2422 772.937 3962.72 19.2174 4098.32 +EDGE_SE3:QUAT 987 988 -0.783792 12.1688 0.0722928 0.16655 0.0124674 -0.0841512 0.982357 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3905.28 24.6966 259.99 3994.21 -10.1017 3987.91 +EDGE_SE3:QUAT 988 989 -0.863052 12.4592 -0.0125407 -0.093308 0.166582 0.12261 0.973915 1 1.92593e-19 1.92593e-19 2.89142e-08 2.84703e-09 5.41991e-09 1 1.92593e-19 2.89142e-08 2.84703e-09 5.41991e-09 1 2.89142e-08 2.84703e-09 5.41991e-09 4530.46 6.5196 1606.58 3872.56 51.1216 4505.15 +EDGE_SE3:QUAT 989 990 -0.719035 12.2833 -0.164761 -0.0594522 0.115039 0.0813231 0.98824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4229.75 -5.20602 1017.42 3941.31 26.2493 4217.43 +EDGE_SE3:QUAT 990 991 -0.789732 12.3639 -0.201322 -0.0137455 0.0432636 0.0949408 0.994447 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.29 1.99318 359.482 3992.15 16.932 3995.99 +EDGE_SE3:QUAT 991 992 -0.848936 12.4494 -0.257467 0.100334 0.0705179 -0.0977213 0.987629 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.62 22.3652 682.001 3970.83 -20.9493 4074.69 +EDGE_SE3:QUAT 992 993 -0.618649 12.3466 -0.500643 -0.0175981 0.0938312 -0.0995915 0.990438 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4130.62 -27.5247 738.288 3970.52 -43.1391 4092.19 +EDGE_SE3:QUAT 993 994 -0.790697 12.6936 0.0909116 -0.0753842 0.214829 0.0140149 0.973637 1 1.94286e-19 1.94286e-19 3.03963e-08 -8.15737e-10 9.35072e-09 1 1.94286e-19 3.03963e-08 -8.15737e-10 9.35072e-09 1 3.03963e-08 -8.15737e-10 9.35072e-09 4830.1 -96.0827 2034.37 3821.49 -84.3443 4852.04 +EDGE_SE3:QUAT 994 995 -0.741303 12.717 -0.141798 -0.0550808 -0.0406595 0.161064 0.984566 1 6.01853e-20 6.01853e-20 -1.25379e-08 -9.11925e-09 -1.64347e-10 1 6.01853e-20 -1.25379e-08 -9.11925e-09 -1.64347e-10 1 -1.25379e-08 -9.11925e-09 -1.64347e-10 3998.08 7.96307 -206.906 3998.77 -14.7277 3906.45 +EDGE_SE3:QUAT 995 996 -0.6617 12.283 -0.193802 0.198438 0.117359 -0.079965 0.96977 1 1.54074e-18 1.54074e-18 -5.42659e-08 5.5687e-08 -1.81982e-08 1 1.54074e-18 -5.42659e-08 5.5687e-08 -1.81982e-08 1 -5.42659e-08 5.5687e-08 -1.81982e-08 4143.04 101.331 1137.11 3932.83 34.0456 4274.97 +EDGE_SE3:QUAT 996 997 -0.511891 12.5187 -0.442419 0.230868 -0.0317137 0.250616 0.93962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3972.29 -80.1812 -895.894 3937.33 -96.1635 3934.25 +EDGE_SE3:QUAT 997 998 -0.452665 12.4335 -0.113753 0.0925316 0.0754955 0.0822531 0.989431 1 1.92593e-19 1.92593e-19 2.76794e-08 2.67575e-09 1.6184e-09 1 1.92593e-19 2.76794e-08 2.67575e-09 1.6184e-09 1 2.76794e-08 2.67575e-09 1.6184e-09 4028.17 31.5216 505.13 3988.12 30.0587 4035.35 +EDGE_SE3:QUAT 998 999 -1.11638 12.8095 -0.121601 -0.0926314 0.0396357 0.0137873 0.994816 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.75 -15.1744 330.164 3993.34 -1.39098 4026.31 +EDGE_SE3:QUAT 999 1000 -0.774226 12.5893 0.102231 -0.0094892 -0.032506 0.156817 0.987047 1 1.50463e-20 1.50463e-20 2.33624e-09 7.39618e-09 3.55358e-11 1 1.50463e-20 2.33624e-09 7.39618e-09 3.55358e-11 1 2.33624e-09 7.39618e-09 3.55358e-11 4013.19 4.48547 -233.543 3997.26 -17.9785 3915.19 +EDGE_SE3:QUAT 1000 1001 -0.741814 12.4071 0.077618 -0.0626914 0.0540734 0.0957589 0.991956 1 9.62965e-20 9.62965e-20 1.5108e-08 -1.25322e-08 1.87907e-10 1 9.62965e-20 1.5108e-08 -1.25322e-08 1.87907e-10 1 1.5108e-08 -1.25322e-08 1.87907e-10 4046.46 -8.46375 502.916 3983.86 20.3888 4025.5 +EDGE_SE3:QUAT 1001 1002 -0.868965 12.3053 -0.0232873 0.128159 0.10021 0.104451 0.981134 1 1.15556e-18 1.15556e-18 5.34533e-08 3.85389e-08 2.72436e-08 1 1.15556e-18 5.34533e-08 3.85389e-08 2.72436e-08 1 5.34533e-08 3.85389e-08 2.72436e-08 4026.61 56.0123 619.29 3986.37 52.7875 4048.67 +EDGE_SE3:QUAT 1002 1003 -0.794558 12.5278 -0.320394 -0.0549852 -0.11687 0.162822 0.978165 1 1.92593e-19 1.92593e-19 -4.95201e-09 2.70739e-08 2.53542e-09 1 1.92593e-19 -4.95201e-09 2.70739e-08 2.53542e-09 1 -4.95201e-09 2.70739e-08 2.53542e-09 4145.04 67.2643 -810.842 3974.12 -84.7554 4051.09 +EDGE_SE3:QUAT 1003 1004 -0.488704 12.9579 0.324383 -0.214862 -0.0747529 -0.0101035 0.973727 1 7.70372e-19 7.70372e-19 -5.46591e-08 -1.25549e-09 4.04485e-09 1 7.70372e-19 -5.46591e-08 -1.25549e-09 4.04485e-09 1 -5.46591e-08 -1.25549e-09 4.04485e-09 3901.39 65.6145 -593.278 3983.57 -25.9125 4085.64 +EDGE_SE3:QUAT 1004 1005 -0.781691 12.2778 -0.122373 0.0520866 0.0258449 0.107976 0.992452 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.58 3.84991 135.509 3999.32 6.50101 3957.8 +EDGE_SE3:QUAT 1005 1006 -0.602991 12.5522 -0.230281 0.0401065 0.094396 0.182585 0.977826 1 4.81482e-20 4.81482e-20 -1.37444e-08 -2.70666e-09 -1.026e-09 1 4.81482e-20 -1.37444e-08 -2.70666e-09 -1.026e-09 1 -1.37444e-08 -2.70666e-09 -1.026e-09 4093.12 43.9821 641.262 3983.78 66.0596 3966.21 +EDGE_SE3:QUAT 1006 1007 -0.942425 12.4805 -0.185899 -0.0531823 0.0869508 0.0329328 0.994247 1 2.40741e-19 2.40741e-19 1.46855e-08 -2.72657e-08 -6.90621e-11 1 2.40741e-19 1.46855e-08 -2.72657e-08 -6.90621e-11 1 1.46855e-08 -2.72657e-08 -6.90621e-11 4118.84 -14.7951 733.181 3968.08 2.72605 4125.81 +EDGE_SE3:QUAT 1007 1008 -0.589052 12.5034 -0.0790355 0.0778182 0.040316 0.158704 0.983429 1 7.70372e-19 7.70372e-19 -7.44679e-10 -4.81511e-09 -5.46319e-08 1 7.70372e-19 -7.44679e-10 -4.81511e-09 -5.46319e-08 1 -7.44679e-10 -4.81511e-09 -5.46319e-08 3981.54 6.5723 162.159 3999.69 9.78795 3905.02 +EDGE_SE3:QUAT 1008 1009 -0.73622 12.0955 -0.338437 -0.0132836 0.114025 0.128083 0.985097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4214.7 35.6065 952.938 3952.04 65.1136 4149.78 +EDGE_SE3:QUAT 1009 1010 -0.815774 12.447 -0.33703 0.229411 0.0159045 0.000934996 0.973199 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3792.77 12.722 114.918 3999.43 1.27267 4003.28 +EDGE_SE3:QUAT 1010 1011 -0.602629 12.7431 -0.0956652 -0.0107235 0.0834785 0.195333 0.977119 1 1.93345e-19 1.93345e-19 3.72967e-09 -2.74605e-08 4.75444e-10 1 1.93345e-19 3.72967e-09 -2.74605e-08 4.75444e-10 1 3.72967e-09 -2.74605e-08 4.75444e-10 4108.74 29.5361 670.085 3978.15 68.0746 3956.58 +EDGE_SE3:QUAT 1011 1012 -0.765565 12.4672 -0.295448 0.104289 -0.287308 -0.0111969 0.952078 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5578.19 -336.39 -3019.69 3735.97 338.019 5621.19 +EDGE_SE3:QUAT 1012 1013 -0.689707 12.5376 -0.786288 0.211752 -0.140559 -0.0033017 0.967157 1 4.81482e-20 4.81482e-20 1.81243e-09 -3.18399e-09 -1.39122e-08 1 4.81482e-20 1.81243e-09 -3.18399e-09 -1.39122e-08 1 1.81243e-09 -3.18399e-09 -1.39122e-08 4103.95 -139.029 -1102.98 3953.42 101.453 4283.26 +EDGE_SE3:QUAT 1013 1014 -0.78301 12.5689 0.0888964 0.0784868 0.0662506 -0.0810152 0.991407 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.75 15.4198 608.368 3976.85 -16.59 4064.14 +EDGE_SE3:QUAT 1014 1015 -0.535872 12.7648 -0.115027 -0.0416046 0.0714788 0.0373805 0.995873 1 4.81482e-20 4.81482e-20 -1.04064e-09 5.12764e-10 -1.39719e-08 1 4.81482e-20 -1.04064e-09 5.12764e-10 -1.39719e-08 1 -1.04064e-09 5.12764e-10 -1.39719e-08 4080.94 -8.35467 599.324 3978.19 6.45065 4082.27 +EDGE_SE3:QUAT 1015 1016 -0.831813 12.2045 0.00998074 -0.00233667 0.0966428 0.123419 0.987635 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4147.88 27.3188 783.336 3966.96 52.2693 4086.98 +EDGE_SE3:QUAT 1016 1017 -0.553343 12.5492 -0.260098 -0.070832 -0.19969 0.239707 0.947443 1 4.62223e-18 4.62223e-18 -5.56768e-08 -8.79112e-08 1.09588e-07 1 4.62223e-18 -5.56768e-08 -8.79112e-08 1.09588e-07 1 -5.56768e-08 -8.79112e-08 1.09588e-07 4374.63 241.787 -1329.81 3984.2 -254.557 4164.86 +EDGE_SE3:QUAT 1017 1018 -0.689661 12.1864 0.0422309 0.157435 0.0208994 0.0468188 0.986197 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3901.95 3.4558 73.5639 3999.97 1.50438 3992.32 +EDGE_SE3:QUAT 1018 1019 -0.719781 12.5778 -0.233122 0.0112277 0.0630547 0.0202729 0.997741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.06 4.91912 508.233 3984.41 6.43713 4061.92 +EDGE_SE3:QUAT 1019 1020 -0.815622 12.3783 -0.244365 -0.0382559 -0.000387432 -0.0302569 0.99881 1 6.01853e-20 6.01853e-20 -1.38801e-08 1.53456e-10 6.96813e-09 1 6.01853e-20 -1.38801e-08 1.53456e-10 6.96813e-09 1 -1.38801e-08 1.53456e-10 6.96813e-09 3994.21 0.410685 -16.9567 3999.97 0.32379 3996.4 +EDGE_SE3:QUAT 1020 1021 -0.873207 12.1636 -0.093943 0.0186053 0.141883 0.235978 0.961165 1 4.81482e-20 4.81482e-20 1.37792e-08 3.59339e-09 1.6682e-09 1 4.81482e-20 1.37792e-08 3.59339e-09 1.6682e-09 1 1.37792e-08 3.59339e-09 1.6682e-09 4250.65 113.464 1038.61 3967.02 148.564 4029.3 +EDGE_SE3:QUAT 1021 1022 -0.770064 12.6529 -0.306468 0.060998 0.0480463 0.238427 0.968051 1 7.70372e-19 7.70372e-19 -7.71785e-10 -4.24965e-09 -5.3787e-08 1 7.70372e-19 -7.71785e-10 -4.24965e-09 -5.3787e-08 1 -7.71785e-10 -4.24965e-09 -5.3787e-08 3992.01 8.11241 181.977 4000.29 14.7447 3779.5 +EDGE_SE3:QUAT 1022 1023 -0.573063 12.5684 -0.0430626 0.201448 -0.0801776 0.103004 0.970763 1 9.62965e-19 9.62965e-19 5.19428e-08 8.88608e-09 2.11534e-08 1 9.62965e-19 5.19428e-08 8.88608e-09 2.11534e-08 1 5.19428e-08 8.88608e-09 2.11534e-08 4019.04 -77.0662 -872.133 3954.71 -1.36108 4138.92 +EDGE_SE3:QUAT 1023 1024 -0.475502 12.6931 -0.153147 -0.123706 0.0666737 -0.0370163 0.989384 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.22 -32.1614 470.586 3989 -19.6166 4048.96 +EDGE_SE3:QUAT 1024 1025 -1.04498 12.2482 -0.448355 -0.0677849 0.000553405 -0.0255187 0.997373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.68 0.785836 -16.2926 3999.97 0.292962 3997.45 +EDGE_SE3:QUAT 1025 1026 -1.0427 12.332 -0.131452 0.00384632 -0.0292875 0.177619 0.983656 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.35 3.20837 -232.006 3997.13 -20.6215 3887.21 +EDGE_SE3:QUAT 1026 1027 -0.696306 12.353 0.0323126 -0.0348053 -0.0644709 0.286102 0.955394 1 3.32223e-18 3.32223e-18 2.64122e-08 2.85861e-08 -1.06528e-07 1 3.32223e-18 2.64122e-08 2.85861e-08 -1.06528e-07 1 2.64122e-08 2.85861e-08 -1.06528e-07 4022.54 20.9732 -340.552 3999.11 -43.1471 3699.97 +EDGE_SE3:QUAT 1027 1028 -0.870103 12.7605 -0.127104 0.00279475 -0.0796449 0.0983588 0.991955 1 3.00927e-21 3.00927e-21 -3.48535e-09 -3.48474e-10 2.76306e-10 1 3.00927e-21 -3.48535e-09 -3.48474e-10 2.76306e-10 1 -3.48535e-09 -3.48474e-10 2.76306e-10 4101.45 14.3299 -645.18 3976.3 -33.3228 4062.79 +EDGE_SE3:QUAT 1028 1029 -1.0055 12.4719 0.207168 -0.145791 -0.06457 0.0243377 0.986906 1 4.81482e-20 4.81482e-20 7.63326e-10 2.09424e-09 -1.37879e-08 1 4.81482e-20 7.63326e-10 2.09424e-09 -1.37879e-08 1 7.63326e-10 2.09424e-09 -1.37879e-08 3967.6 35.6477 -462.461 3989.5 -18.0372 4050.25 +EDGE_SE3:QUAT 1029 1030 -0.672314 12.4534 -0.256899 -0.200104 -0.00450327 -0.079828 0.976507 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3851.1 27.4079 -219.962 3995.3 8.86876 3985.78 +EDGE_SE3:QUAT 1030 1031 -0.688709 12.7506 -0.290983 -0.198277 0.0376159 -0.0450611 0.978387 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3850.15 -14.356 178.152 3999.4 -6.27161 3999.29 +EDGE_SE3:QUAT 1031 1032 -0.788793 12.5922 -0.176091 0.0630069 -0.04735 -0.0773706 0.993882 1 4.33334e-19 4.33334e-19 2.7803e-08 1.3419e-08 2.5683e-08 1 4.33334e-19 2.7803e-08 1.3419e-08 2.5683e-08 1 2.7803e-08 1.3419e-08 2.5683e-08 4008.86 -12.6636 -316.408 3994.97 14.2356 4000.8 +EDGE_SE3:QUAT 1032 1033 -0.898978 12.1119 -0.111419 0.0238945 0.0153546 -0.0431297 0.998666 1 1.20371e-20 1.20371e-20 -6.93358e-09 2.94161e-10 -1.20387e-10 1 1.20371e-20 -6.93358e-09 2.94161e-10 -1.20387e-10 1 -6.93358e-09 2.94161e-10 -1.20387e-10 4002.26 1.38045 134.878 3998.81 -2.84566 3997.1 +EDGE_SE3:QUAT 1033 1034 -0.719125 12.6312 -0.355032 -0.145219 -0.107199 0.181972 0.966595 1 7.70372e-19 7.70372e-19 5.40258e-08 1.1623e-08 -2.38999e-09 1 7.70372e-19 5.40258e-08 1.1623e-08 -2.38999e-09 1 5.40258e-08 1.1623e-08 -2.38999e-09 3967.4 50.004 -480.372 3999.95 -52.5329 3919.3 +EDGE_SE3:QUAT 1034 1035 -0.855562 12.6979 -0.240138 -0.0949319 0.104158 0.165799 0.976038 1 1.92593e-19 1.92593e-19 2.79528e-08 4.21557e-09 3.67246e-09 1 1.92593e-19 2.79528e-08 4.21557e-09 3.67246e-09 1 2.79528e-08 4.21557e-09 3.67246e-09 4214.26 2.36403 1032.01 3939.69 67.2208 4140.35 +EDGE_SE3:QUAT 1035 1036 -0.610476 12.5031 -0.0833979 -0.200946 -0.0648672 0.0366647 0.976764 1 1.92593e-19 1.92593e-19 -1.25124e-09 -5.76362e-09 2.72508e-08 1 1.92593e-19 -1.25124e-09 -5.76362e-09 2.72508e-08 1 -1.25124e-09 -5.76362e-09 2.72508e-08 3878.13 40.3962 -403.233 3994.32 -21.0318 4034.28 +EDGE_SE3:QUAT 1036 1037 -0.749131 12.1559 -0.043499 0.157767 0.10419 0.0642061 0.979863 1 3.85186e-19 3.85186e-19 -4.48199e-10 3.1999e-08 2.281e-08 1 3.85186e-19 -4.48199e-10 3.1999e-08 2.281e-08 1 -4.48199e-10 3.1999e-08 2.281e-08 4015.57 68.2289 691.428 3981.5 53.9864 4098.64 +EDGE_SE3:QUAT 1037 1038 -0.717989 12.3863 -0.0182354 -0.230952 0.0950879 0.0759697 0.965323 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.05 -104.619 943.846 3953.3 -29.6758 4188.32 +EDGE_SE3:QUAT 1038 1039 -0.527152 12.6985 -0.0979366 0.156596 -0.107376 0.15555 0.969408 1 7.70372e-19 7.70372e-19 -8.41961e-09 6.93204e-09 5.5976e-08 1 7.70372e-19 -8.41961e-09 6.93204e-09 5.5976e-08 1 -8.41961e-09 6.93204e-09 5.5976e-08 4216.24 -42.8948 -1165.95 3922.19 -41.6665 4217.55 +EDGE_SE3:QUAT 1039 1040 -0.787807 12.657 -0.369232 -0.0481069 -0.0430262 -0.0251221 0.997599 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.84 7.73826 -359.746 3991.91 2.3755 4029.57 +EDGE_SE3:QUAT 1040 1041 -0.812024 12.3842 0.139612 0.0738983 0.0430956 -0.0863378 0.992586 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.34 11.4553 418.387 3988.42 -15.0237 4013.37 +EDGE_SE3:QUAT 1041 1042 -0.285198 12.2822 -0.0968641 -0.144809 0.101789 0.0468584 0.983094 1 9.62965e-19 9.62965e-19 -5.63711e-08 2.6388e-08 -2.4701e-09 1 9.62965e-19 -5.63711e-08 2.6388e-08 -2.4701e-09 1 -5.63711e-08 2.6388e-08 -2.4701e-09 4111.57 -61.051 905.591 3954.53 -18.4242 4186.67 +EDGE_SE3:QUAT 1042 1043 -0.674771 12.1632 -0.00600443 0.0248902 -0.123627 0.137772 0.982403 1 7.77143e-19 7.77143e-19 1.92612e-09 -1.66569e-10 -5.56588e-08 1 7.77143e-19 1.92612e-09 -1.66569e-10 -5.56588e-08 1 1.92612e-09 -1.66569e-10 -5.56588e-08 4260.8 40.8023 -1059.46 3941.71 -75.4406 4187.35 +EDGE_SE3:QUAT 1043 1044 -0.685699 12.5578 0.00753458 -0.17674 -0.12642 -0.12529 0.968031 1 1.92593e-19 1.92593e-19 -4.64537e-09 -4.25594e-09 2.8211e-08 1 1.92593e-19 -4.64537e-09 -4.25594e-09 2.8211e-08 1 -4.64537e-09 -4.25594e-09 2.8211e-08 4268.41 75.1511 -1315.39 3907.36 2.1221 4330.57 +EDGE_SE3:QUAT 1044 1045 -0.986223 12.7956 -0.155839 0.0608544 0.0322942 0.131146 0.988966 1 2.0463e-19 2.0463e-19 -2.84008e-08 3.12995e-09 -8.86229e-10 1 2.0463e-19 -2.84008e-08 3.12995e-09 -8.86229e-10 1 -2.84008e-08 3.12995e-09 -8.86229e-10 3990.93 5.29267 155.846 3999.29 8.74149 3936.94 +EDGE_SE3:QUAT 1045 1046 -0.498311 12.2242 -0.251501 0.0154009 -0.0131416 -0.0460847 0.998732 1 1.50463e-20 1.50463e-20 6.77084e-09 -3.78761e-09 -2.35183e-11 1 1.50463e-20 6.77084e-09 -3.78761e-09 -2.35183e-11 1 6.77084e-09 -3.78761e-09 -2.35183e-11 4001.37 -0.886996 -96.3017 3999.46 2.21019 3993.82 +EDGE_SE3:QUAT 1046 1047 -0.431907 12.388 -0.0343108 0.155652 -0.211617 0.0337481 0.964288 1 7.80951e-19 7.80951e-19 6.04551e-08 -3.2305e-09 -1.98339e-08 1 7.80951e-19 6.04551e-08 -3.2305e-09 -1.98339e-08 1 6.04551e-08 -3.2305e-09 -1.98339e-08 4731.14 -188.185 -1999.59 3842.76 163.195 4823.5 +EDGE_SE3:QUAT 1047 1048 -1.00286 12.7196 -0.22305 0.228082 -0.141807 0.124591 0.955168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4303.96 -136.554 -1520.57 3888.85 48.9082 4449.96 +EDGE_SE3:QUAT 1048 1049 -0.728204 12.5029 0.0172547 0.0136455 0.103445 0.0172158 0.994393 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4174.58 11.1171 855.589 3957.81 11.8552 4174.14 +EDGE_SE3:QUAT 1049 1050 -0.877657 12.6044 0.0312547 -0.0435793 0.0702601 0.136227 0.987222 1 4.81482e-20 4.81482e-20 1.38681e-08 1.8412e-09 1.11346e-09 1 4.81482e-20 1.38681e-08 1.8412e-09 1.11346e-09 1 1.38681e-08 1.8412e-09 1.11346e-09 4089 4.45384 629.178 3976.48 40.4395 4022.37 +EDGE_SE3:QUAT 1050 1051 -0.650793 12.3688 -0.0801587 0.0997215 -0.026028 -0.00767876 0.994645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3969.83 -9.76632 -196.372 3997.8 2.23103 4009.38 +EDGE_SE3:QUAT 1051 1052 -0.0908463 12.6404 -0.379175 -0.049092 -0.152873 0.109375 0.980947 1 7.70372e-19 7.70372e-19 5.67448e-08 7.48558e-09 -7.92341e-09 1 7.70372e-19 5.67448e-08 7.48558e-09 -7.92341e-09 1 5.67448e-08 7.48558e-09 -7.92341e-09 4327.91 96.4027 -1210.8 3934 -107.111 4289.7 +EDGE_SE3:QUAT 1052 1053 -0.685791 12.9296 -0.270556 0.0597948 0.0198191 -0.0074936 0.997986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.35 4.87396 163.297 3998.33 -0.0289579 4006.43 +EDGE_SE3:QUAT 1053 1054 -0.979499 12.4505 -0.185324 0.0670691 0.111667 0.244776 0.96079 1 1.92593e-19 1.92593e-19 2.69957e-08 7.37585e-09 1.80688e-09 1 1.92593e-19 2.69957e-08 7.37585e-09 1.80688e-09 1 2.69957e-08 7.37585e-09 1.80688e-09 4074.07 64.1902 625.12 3994.7 84.0243 3852.4 +EDGE_SE3:QUAT 1054 1055 -0.791179 12.4668 -0.425249 0.0359205 -0.0855994 -0.00090519 0.995681 1 2.40741e-19 2.40741e-19 1.38247e-08 -2.77354e-08 -1.85303e-10 1 2.40741e-19 1.38247e-08 -2.77354e-08 -1.85303e-10 1 1.38247e-08 -2.77354e-08 -1.85303e-10 4114.08 -13.7151 -700.852 3971.06 6.86566 4119.24 +EDGE_SE3:QUAT 1055 1056 -0.675954 12.1983 0.0128173 0.00133532 0.1 -0.0244696 0.994686 1 4.70198e-23 4.70198e-23 -4.40178e-10 1.09296e-11 -4.42284e-11 1 4.70198e-23 -4.40178e-10 1.09296e-11 -4.42284e-11 1 -4.40178e-10 1.09296e-11 -4.42284e-11 4164.79 -5.55317 828.448 3960.15 -10.8724 4162.4 +EDGE_SE3:QUAT 1056 1057 -0.609848 12.9391 0.217737 -0.0898491 0.0267022 0.115573 0.988867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.76 -12.7955 331.949 3991.87 18.5354 3973.62 +EDGE_SE3:QUAT 1057 1058 -0.482278 12.7626 -0.357773 0.0795193 -0.189495 -0.0285608 0.97824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4573.91 -118.503 -1660.25 3876.65 110.429 4595.94 +EDGE_SE3:QUAT 1058 1059 -0.919651 12.7075 -0.259351 -0.0484046 0.224661 -0.0972891 0.968359 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4822.09 -211.753 2004.96 3851.9 -216.679 4793.6 +EDGE_SE3:QUAT 1059 1060 -0.700354 12.4335 -0.100037 -0.00644412 0.195845 0.0987755 0.975626 1 3.00927e-21 3.00927e-21 3.66283e-09 3.91708e-10 7.24912e-10 1 3.00927e-21 3.66283e-09 3.91708e-10 7.24912e-10 1 3.66283e-09 3.91708e-10 7.24912e-10 4676.45 100.884 1778.9 3859.34 117.233 4637.59 +EDGE_SE3:QUAT 1060 1061 -0.699349 12.4282 -0.406457 -0.0861309 -0.0224884 0.116205 0.989228 1 3.88195e-19 3.88195e-19 2.78205e-08 -2.6164e-09 2.71011e-08 1 3.88195e-19 2.78205e-08 -2.6164e-09 2.71011e-08 1 2.78205e-08 -2.6164e-09 2.71011e-08 3970.66 0.894383 -55.7734 4000.04 -1.02718 3946.32 +EDGE_SE3:QUAT 1061 1062 -0.660157 12.7169 -0.0899727 0.0955465 -0.0519324 0.17592 0.978379 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.13 -11.9202 -600.455 3976.08 -49.0875 3963.86 +EDGE_SE3:QUAT 1062 1063 -0.399068 12.6665 -0.0718705 -0.0455039 0.101444 -0.010917 0.99374 1 1.20371e-20 1.20371e-20 -7.07983e-10 3.44823e-10 -7.0375e-09 1 1.20371e-20 -7.07983e-10 3.44823e-10 -7.0375e-09 1 -7.07983e-10 3.44823e-10 -7.0375e-09 4157.8 -23.692 831.833 3960.5 -16.6389 4165.61 +EDGE_SE3:QUAT 1063 1064 -0.808397 12.2178 0.0486947 -0.135462 -0.0534644 0.101441 0.984125 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3940.82 16.0634 -247.504 3998.67 -13.8878 3973.06 +EDGE_SE3:QUAT 1064 1065 -0.590883 12.4724 -0.0838326 0.0823613 0.0386777 0.12787 0.987608 1 1.92593e-19 1.92593e-19 2.74362e-08 3.6869e-09 4.44625e-10 1 1.92593e-19 2.74362e-08 3.6869e-09 4.44625e-10 1 2.74362e-08 3.6869e-09 4.44625e-10 3979.88 7.3566 174.201 3999.29 9.59774 3941.61 +EDGE_SE3:QUAT 1065 1066 -0.815043 12.7388 0.0821241 0.0351504 -0.220508 0.0644942 0.972616 1 7.70372e-19 7.70372e-19 -3.03422e-09 5.40244e-08 -4.43137e-10 1 7.70372e-19 -3.03422e-09 5.40244e-08 -4.43137e-10 1 -3.03422e-09 5.40244e-08 -4.43137e-10 4922.42 40.4585 -2137.63 3803.64 -52.8874 4910.72 +EDGE_SE3:QUAT 1066 1067 -0.880841 12.3598 -0.0366723 0.162912 0.0516903 -0.00355142 0.985279 1 7.71124e-19 7.71124e-19 5.48945e-08 4.57353e-10 1.07644e-09 1 7.71124e-19 5.48945e-08 4.57353e-10 1.07644e-09 1 5.48945e-08 4.57353e-10 1.07644e-09 3934.93 33.6458 407.602 3991.12 9.6004 4041.04 +EDGE_SE3:QUAT 1067 1068 -1.30175 12.6083 -0.0134215 0.024471 0.221323 0.0826114 0.971387 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4855.91 156.906 2042.21 3832.29 163.54 4831 +EDGE_SE3:QUAT 1068 1069 -1.19739 12.4696 -0.165913 0.125417 0.0657074 -0.0231755 0.989654 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.16 34.442 556.867 3981.88 7.43918 4073.93 +EDGE_SE3:QUAT 1069 1070 -0.849673 12.8639 -0.0250179 0.107076 0.0784633 0.156518 0.978714 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.57 29.9853 398.241 3996.46 34.4775 3939.44 +EDGE_SE3:QUAT 1070 1071 -0.579757 12.3276 -0.0635745 -0.0740851 0.097211 0.0516781 0.991156 1 4.81482e-20 4.81482e-20 -1.46573e-09 9.21434e-10 -1.40487e-08 1 4.81482e-20 -1.46573e-09 9.21434e-10 -1.40487e-08 1 -1.46573e-09 9.21434e-10 -1.40487e-08 4149.42 -21.8122 845.558 3958.12 5.41916 4160.69 +EDGE_SE3:QUAT 1071 1072 -0.623948 12.4459 -0.0279986 -0.0049524 0.132327 -0.0485885 0.990002 1 3.00927e-21 3.00927e-21 -3.55805e-09 1.85775e-10 -4.71422e-10 1 3.00927e-21 -3.55805e-09 1.85775e-10 -4.71422e-10 1 -3.55805e-09 1.85775e-10 -4.71422e-10 4291.45 -25.3263 1118.57 3932.08 -34.4214 4282.1 +EDGE_SE3:QUAT 1072 1073 -0.895438 12.4827 0.0694879 0.198072 -0.100637 -0.105418 0.969292 1 1.92593e-19 1.92593e-19 1.36398e-09 -6.08942e-09 -2.71124e-08 1 1.92593e-19 1.36398e-09 -6.08942e-09 -2.71124e-08 1 1.36398e-09 -6.08942e-09 -2.71124e-08 3901.95 -55.9008 -503.194 3996.91 47.4892 4014.43 +EDGE_SE3:QUAT 1073 1074 -1.06557 12.7246 -0.223389 0.128493 -0.00623167 0.0496518 0.990447 1 4.81482e-20 4.81482e-20 2.58742e-10 -1.76701e-09 -1.37517e-08 1 4.81482e-20 2.58742e-10 -1.76701e-09 -1.37517e-08 1 2.58742e-10 -1.76701e-09 -1.37517e-08 3937.67 -9.37962 -124.154 3998.66 -3.14646 3993.85 +EDGE_SE3:QUAT 1074 1075 -0.746013 12.5017 0.246824 0.0079892 -0.141 0.0122019 0.989902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4338.42 0.558674 -1212.2 3920.36 -4.7597 4338.08 +EDGE_SE3:QUAT 1075 1076 -0.790881 12.7347 -0.030067 0.14055 -0.0649052 0.129271 0.97945 1 7.70372e-19 7.70372e-19 5.52582e-08 6.06254e-09 -5.4307e-09 1 7.70372e-19 5.52582e-08 6.06254e-09 -5.4307e-09 1 5.52582e-08 6.06254e-09 -5.4307e-09 4048.35 -36.3914 -726.912 3965.62 -29.6807 4060.52 +EDGE_SE3:QUAT 1076 1077 -1.19721 12.7467 -0.334047 0.00650075 -0.108815 0.0630438 0.99204 1 7.34684e-23 7.34684e-23 -5.50874e-10 -3.5059e-11 6.03954e-11 1 7.34684e-23 -5.50874e-10 -3.5059e-11 6.03954e-11 1 -5.50874e-10 -3.5059e-11 6.03954e-11 4196.11 15.6953 -907.556 3953.48 -30.2552 4180.38 +EDGE_SE3:QUAT 1077 1078 -0.818778 12.5422 0.178642 0.0477274 -0.0549301 0.0230635 0.997082 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.2 -9.56102 -455.941 3987.2 -1.81649 4049.18 +EDGE_SE3:QUAT 1078 1079 -0.463095 12.794 -0.0622119 0.018278 0.12867 0.0713386 0.988949 1 9.75002e-19 9.75002e-19 6.30006e-09 5.65046e-08 2.7161e-08 1 9.75002e-19 6.30006e-09 5.65046e-08 2.7161e-08 1 6.30006e-09 5.65046e-08 2.7161e-08 4263.33 40.9266 1062.47 3940.1 51.7417 4244.31 +EDGE_SE3:QUAT 1079 1080 -0.72785 12.379 -0.343306 -0.126631 -0.0239801 0.040779 0.990821 1 7.70372e-19 7.70372e-19 5.50282e-08 2.52862e-09 -7.1546e-10 1 7.70372e-19 5.50282e-08 2.52862e-09 -7.1546e-10 1 5.50282e-08 2.52862e-09 -7.1546e-10 3939.66 6.86555 -125.561 3999.44 -3.05223 3997.15 +EDGE_SE3:QUAT 1080 1081 -0.807814 12.3018 -0.10612 0.0804446 -0.107167 0.0985635 0.986068 1 1.92593e-19 1.92593e-19 -2.8146e-08 -2.34968e-09 3.42045e-09 1 1.92593e-19 -2.8146e-08 -2.34968e-09 3.42045e-09 1 -2.8146e-08 -2.34968e-09 3.42045e-09 4201.26 -12.4464 -980.088 3944.64 -28.9133 4188.29 +EDGE_SE3:QUAT 1081 1082 -0.793643 12.454 -0.286701 -0.100159 -0.0318463 -0.00332196 0.994456 1 4.59177e-24 4.59177e-24 4.32795e-12 1.36009e-11 -1.35051e-10 1 4.59177e-24 4.32795e-12 1.36009e-11 -1.35051e-10 1 4.32795e-12 1.36009e-11 -1.35051e-10 3976.17 12.8701 -255.823 3996.1 -2.03492 4016.25 +EDGE_SE3:QUAT 1082 1083 -0.880531 12.3362 -0.108996 0.081568 0.0334714 -0.0451405 0.995082 1 7.70372e-19 7.70372e-19 -5.54039e-08 2.18278e-09 -2.24062e-09 1 7.70372e-19 -5.54039e-08 2.18278e-09 -2.24062e-09 1 -5.54039e-08 2.18278e-09 -2.24062e-09 3997.23 11.8407 309.979 3993.69 -4.63 4015.69 +EDGE_SE3:QUAT 1083 1084 -0.39794 12.1883 0.0490005 -0.00604021 -0.106003 0.0523358 0.992969 1 4.81482e-20 4.81482e-20 -1.48663e-09 -2.47151e-10 1.40922e-08 1 4.81482e-20 -1.48663e-09 -2.47151e-10 1.40922e-08 1 -1.48663e-09 -2.47151e-10 1.40922e-08 4182.5 17.6641 -874.047 3956.73 -27.2137 4171.69 +EDGE_SE3:QUAT 1084 1085 -1.06761 12.672 -0.322633 -0.0810146 0.0304646 0.0694836 0.993821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.29 -11.252 308.396 3993.48 8.95348 4004.23 +EDGE_SE3:QUAT 1085 1086 -0.680059 12.1884 -0.086805 0.0259535 0.0969058 -0.0449492 0.993939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4156.52 0.807874 813.774 3961.28 -13.9501 4151.14 +EDGE_SE3:QUAT 1086 1087 -0.526326 12.7211 -0.174793 -0.102253 0.166158 0.262861 0.944902 1 3.27408e-18 3.27408e-18 -5.08507e-09 -7.94668e-09 1.07647e-07 1 3.27408e-18 -5.08507e-09 -7.94668e-09 1.07647e-07 1 -5.08507e-09 -7.94668e-09 1.07647e-07 4588.73 138.611 1708.76 3884.62 214.931 4354.17 +EDGE_SE3:QUAT 1087 1088 -0.144906 12.488 -0.112558 0.00436618 -0.123356 0.144757 0.981738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4242.21 52.7845 -1014 3948.9 -82.9993 4158.47 +EDGE_SE3:QUAT 1088 1089 -1.0808 12.5991 0.344943 0.00158115 -0.0877423 -0.0104356 0.996087 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4125.96 -2.61682 -720.924 3969.26 4.3703 4125.53 +EDGE_SE3:QUAT 1089 1090 -0.661645 12.5111 -0.34378 -0.0664643 -0.0213437 -0.0240413 0.997271 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.23 6.20355 -188.976 3997.67 1.50165 4006.59 +EDGE_SE3:QUAT 1090 1091 -0.647415 12.3855 0.290046 -0.17996 -0.0530324 0.0887767 0.978223 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3880.19 15.0228 -211.717 3999.75 -10.8555 3978.21 +EDGE_SE3:QUAT 1091 1092 -1.15098 12.2314 0.184964 0.117795 -0.209119 -0.0186372 0.970591 1 4.81482e-20 4.81482e-20 -2.98845e-09 2.07282e-09 1.46697e-08 1 4.81482e-20 -2.98845e-09 2.07282e-09 1.46697e-08 1 -2.98845e-09 2.07282e-09 1.46697e-08 4675.73 -182.251 -1860.42 3862.8 169.544 4729.84 +EDGE_SE3:QUAT 1092 1093 -0.719534 12.6944 0.0267365 -0.00994051 -0.0157144 -0.109533 0.993809 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.26 -0.0450296 -136.55 3998.83 7.62911 3956.66 +EDGE_SE3:QUAT 1093 1094 -0.806562 12.3011 -0.15764 -0.0306541 -0.0245244 0.0768057 0.996273 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.11 3.27064 -166.268 3998.54 -6.37559 3983.27 +EDGE_SE3:QUAT 1094 1095 -1.24605 12.4216 -0.114841 0.109285 0.0124039 -0.0858107 0.990222 1 1.92593e-19 1.92593e-19 8.47954e-10 2.93561e-09 2.75209e-08 1 1.92593e-19 8.47954e-10 2.93561e-09 2.75209e-08 1 8.47954e-10 2.93561e-09 2.75209e-08 3962.73 12.3204 208.039 3996.41 -9.13915 3981.04 +EDGE_SE3:QUAT 1095 1096 -0.928097 12.0497 -0.426009 -0.0527062 0.0236315 0.136814 0.988911 1 7.70372e-19 7.70372e-19 -2.05333e-09 2.47053e-09 -5.50212e-08 1 7.70372e-19 -2.05333e-09 2.47053e-09 -5.50212e-08 1 -2.05333e-09 2.47053e-09 -5.50212e-08 4006.83 -4.59623 269.523 3994.85 19.18 3943.07 +EDGE_SE3:QUAT 1096 1097 -0.573768 12.252 -0.0202986 0.102026 -0.0442308 0.131779 0.985022 1 7.70372e-19 7.70372e-19 -3.82942e-09 4.89306e-09 5.51164e-08 1 7.70372e-19 -3.82942e-09 4.89306e-09 5.51164e-08 1 -3.82942e-09 4.89306e-09 5.51164e-08 4020.84 -18.0369 -505.592 3982.39 -29.0379 3993.02 +EDGE_SE3:QUAT 1097 1098 -1.05183 12.4321 0.129404 -0.00878792 0.0885328 0.00519413 0.996021 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4128.28 -2.4515 728.617 3968.6 0.330244 4128.48 +EDGE_SE3:QUAT 1098 1099 -0.8637 12.8429 -0.20442 -0.068162 -0.0218896 0.0549261 0.995921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.47 4.25846 -128.475 3999.25 -3.60467 3991.99 +EDGE_SE3:QUAT 1099 1100 -0.929378 12.1965 0.0712707 0.105987 0.0159055 0.147918 0.983175 1 1.92593e-19 1.92593e-19 2.72886e-08 4.10532e-09 -4.4362e-10 1 1.92593e-19 2.72886e-08 4.10532e-09 -4.4362e-10 1 2.72886e-08 4.10532e-09 -4.4362e-10 3955.08 -6.77524 -63.0145 3998.98 -9.4562 3912.49 +EDGE_SE3:QUAT 1100 1101 -0.755699 12.2872 0.000997249 0.0235977 0.145765 0.225573 0.962971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4263.24 117.707 1067.46 3964.3 149.921 4061.93 +EDGE_SE3:QUAT 1101 1102 -0.782758 12.6714 -0.164263 0.190877 0.00253341 0.0440261 0.980623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3855.58 -10.7485 -79.1761 3999.22 -2.25872 3993.56 +EDGE_SE3:QUAT 1102 1103 -0.916501 12.0232 0.115771 -0.0183117 -0.0557462 0.118162 0.991259 1 2.52778e-19 2.52778e-19 -6.62887e-09 -1.54613e-08 2.75774e-08 1 2.52778e-19 -6.62887e-09 -1.54613e-08 2.75774e-08 1 -6.62887e-09 -1.54613e-08 2.75774e-08 4041.06 11.7129 -414.269 3990.79 -25.7376 3986.55 +EDGE_SE3:QUAT 1103 1104 -0.877662 12.734 -0.436946 -0.0554028 0.0354096 0.104999 0.992296 1 1.92593e-19 1.92593e-19 -1.28168e-09 1.30781e-09 -2.76467e-08 1 1.92593e-19 -1.28168e-09 1.30781e-09 -2.76467e-08 1 -1.28168e-09 1.30781e-09 -2.76467e-08 4017.86 -5.99975 349.036 3991.86 17.4218 3986.04 +EDGE_SE3:QUAT 1104 1105 -0.721348 12.3887 -0.70178 -0.0765762 0.0329579 0.00284472 0.996515 1 2.93874e-24 2.93874e-24 3.58632e-12 -8.31839e-12 1.08279e-10 1 2.93874e-24 3.58632e-12 -8.31839e-12 1.08279e-10 1 3.58632e-12 -8.31839e-12 1.08279e-10 3994.02 -10.1904 264.961 3995.75 -1.63487 4017.44 +EDGE_SE3:QUAT 1105 1106 -0.694772 12.3917 -0.249121 0.0150844 0.0225095 0.102172 0.994398 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.39 2.18296 159.032 3998.64 7.9499 3964.54 +EDGE_SE3:QUAT 1106 1107 -0.935383 12.4966 -0.108033 -0.0711402 0.00776244 0.281651 0.956845 1 3.08149e-18 3.08149e-18 4.98834e-09 -6.19927e-09 1.06505e-07 1 3.08149e-18 4.98834e-09 -6.19927e-09 1.06505e-07 1 4.98834e-09 -6.19927e-09 1.06505e-07 3998.7 -6.81015 282.788 3992.92 49.4218 3701.63 +EDGE_SE3:QUAT 1107 1108 -0.777006 12.1782 -0.0296195 -0.222438 0.0813349 0.107753 0.965554 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.82 -91.0241 912.542 3951.29 -3.23467 4151.29 +EDGE_SE3:QUAT 1108 1109 -0.856825 12.4682 0.213138 -0.0854732 -0.044584 -0.0029868 0.995338 1 2.40753e-19 2.40753e-19 -2.76817e-08 -1.39615e-08 2.67879e-10 1 2.40753e-19 -2.76817e-08 -1.39615e-08 2.67879e-10 1 -2.76817e-08 -1.39615e-08 2.67879e-10 4002.62 15.4783 -358.298 3992.34 -3.57087 4031.8 +EDGE_SE3:QUAT 1109 1110 -0.827741 12.2018 0.129629 0.0303038 -0.127072 0.0464379 0.990342 1 4.81482e-20 4.81482e-20 -1.42157e-08 -5.74646e-10 1.85448e-09 1 4.81482e-20 -1.42157e-08 -5.74646e-10 1.85448e-09 1 -1.42157e-08 -5.74646e-10 1.85448e-09 4275.02 0.424493 -1092 3933.74 -16.8874 4270.07 +EDGE_SE3:QUAT 1110 1111 -0.481445 12.5325 -0.104879 -0.0749281 0.120005 0.0114015 0.989876 1 1.93345e-19 1.93345e-19 -2.85129e-08 3.25047e-10 -5.20917e-09 1 1.93345e-19 -2.85129e-08 3.25047e-10 -5.20917e-09 1 -2.85129e-08 3.25047e-10 -5.20917e-09 4219.47 -39.5905 1013.05 3943.41 -21.3168 4241.41 +EDGE_SE3:QUAT 1111 1112 -0.827891 12.9061 0.149033 0.0167051 -0.0851262 -0.035198 0.995608 1 2.0463e-19 2.0463e-19 5.93729e-09 -2.79017e-08 4.83078e-11 1 2.0463e-19 5.93729e-09 -2.79017e-08 4.83078e-11 1 5.93729e-09 -2.79017e-08 4.83078e-11 4114.3 -12.3837 -689.202 3972.24 15.9453 4110.46 +EDGE_SE3:QUAT 1112 1113 -0.648381 12.4537 0.062519 0.0605815 -0.0391543 0.150553 0.985967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.3 -5.06825 -412.818 3988.66 -30.7281 3951.32 +EDGE_SE3:QUAT 1113 1114 -0.71809 12.4604 -0.402817 -0.019116 0.0328142 0.247879 0.968046 1 3.13265e-18 3.13265e-18 2.57207e-09 -1.24635e-08 -1.07665e-07 1 3.13265e-18 2.57207e-09 -1.24635e-08 -1.07665e-07 1 2.57207e-09 -1.24635e-08 -1.07665e-07 4020.12 4.9733 294.618 3995.54 37.7085 3775.81 +EDGE_SE3:QUAT 1114 1115 -0.546478 12.494 -0.088992 -0.00744949 0.0269435 0.165279 0.985851 1 1.88079e-22 1.88079e-22 -8.56436e-10 -1.4344e-10 -2.4237e-11 1 1.88079e-22 -8.56436e-10 -1.4344e-10 -2.4237e-11 1 -8.56436e-10 -1.4344e-10 -2.4237e-11 4012.05 2.21309 221.881 3997.22 18.5059 3903 +EDGE_SE3:QUAT 1115 1116 -1.00423 12.8138 -0.0802313 -0.237606 0.115631 0.226795 0.93741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4324.78 -83.6772 1586.71 3866.89 63.3954 4344.86 +EDGE_SE3:QUAT 1116 1117 -0.797692 12.5136 -0.380797 0.0214599 -0.132619 0.0658532 0.988744 1 3.00927e-21 3.00927e-21 3.55847e-09 2.24514e-10 -4.8316e-10 1 3.00927e-21 3.55847e-09 2.24514e-10 -4.8316e-10 1 3.55847e-09 2.24514e-10 -4.8316e-10 4301.06 16.2562 -1141.64 3929.06 -34.806 4285.55 +EDGE_SE3:QUAT 1117 1118 -0.510972 12.6743 -0.0771931 0.0493947 -0.107276 0.0180958 0.992837 1 1.95602e-19 1.95602e-19 1.72769e-10 2.7395e-08 -4.82068e-09 1 1.95602e-19 1.72769e-10 2.7395e-08 -4.82068e-09 1 1.72769e-10 2.7395e-08 -4.82068e-09 4184.37 -19.732 -902.336 3953.32 5.46419 4192.82 +EDGE_SE3:QUAT 1118 1119 -0.76173 12.4524 -0.147521 0.0440624 -0.0997734 0.0386529 0.993282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4163.61 -10.7217 -845.503 3958.29 -6.76548 4165.4 +EDGE_SE3:QUAT 1119 1120 -0.676092 12.4948 0.105065 0.0450838 0.0211179 0.105689 0.993152 1 4.81482e-20 4.81482e-20 -1.37877e-08 -1.48857e-09 -1.53886e-10 1 4.81482e-20 -1.37877e-08 -1.48857e-09 -1.53886e-10 1 -1.37877e-08 -1.48857e-09 -1.53886e-10 3994.73 2.60184 108.947 3999.57 4.96038 3958.18 +EDGE_SE3:QUAT 1120 1121 -1.03234 12.3763 0.0992403 -0.105233 -0.0545563 0.174377 0.977518 1 9.62965e-19 9.62965e-19 -2.79301e-08 -1.162e-08 5.47029e-08 1 9.62965e-19 -2.79301e-08 -1.162e-08 5.47029e-08 1 -2.79301e-08 -1.162e-08 5.47029e-08 3963.31 10.0589 -194.581 4000.16 -12.4135 3885.98 +EDGE_SE3:QUAT 1121 1122 -0.930035 12.5235 -0.0110967 0.179274 -0.078313 0.0578179 0.978971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.09 -62.9747 -737.742 3968.8 10.6272 4118.28 +EDGE_SE3:QUAT 1122 1123 -0.652082 12.6812 -0.301847 0.0693126 -0.14201 0.0529313 0.986016 1 1.92593e-19 1.92593e-19 2.85965e-08 9.9875e-10 -4.27665e-09 1 1.92593e-19 2.85965e-08 9.9875e-10 -4.27665e-09 1 2.85965e-08 9.9875e-10 -4.27665e-09 4345.76 -24.098 -1262.22 3914.45 -2.10576 4353.77 +EDGE_SE3:QUAT 1123 1124 -0.944819 12.6679 -0.153383 0.0664379 -0.0613489 -0.00281451 0.995899 1 8.19273e-19 8.19273e-19 -5.56482e-08 1.45523e-08 4.18602e-09 1 8.19273e-19 -5.56482e-08 1.45523e-08 4.18602e-09 1 -5.56482e-08 1.45523e-08 4.18602e-09 4041.87 -17.1657 -491.576 3985.68 6.73337 4059.49 +EDGE_SE3:QUAT 1124 1125 -0.80076 12.5755 -0.136839 -0.0443055 -0.0431389 -0.0326718 0.997551 1 4.81482e-20 4.81482e-20 1.39006e-08 -4.01894e-10 -6.37944e-10 1 4.81482e-20 1.39006e-08 -4.01894e-10 -6.37944e-10 1 1.39006e-08 -4.01894e-10 -6.37944e-10 4024.92 6.75468 -363.557 3991.7 4.00175 4028.5 +EDGE_SE3:QUAT 1125 1126 -0.784258 12.6984 -0.198033 0.00767194 -0.121881 0.162256 0.979162 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4235.81 56.1676 -1000.18 3951.56 -90.4872 4130.74 +EDGE_SE3:QUAT 1126 1127 -0.764945 12.7936 -0.0253236 0.0995793 -0.0415511 0.0867425 0.99037 1 4.33334e-19 4.33334e-19 -2.71193e-08 9.05195e-09 -2.73162e-08 1 4.33334e-19 -2.71193e-08 9.05195e-09 -2.73162e-08 1 -2.71193e-08 9.05195e-09 -2.73162e-08 4006.07 -18.1115 -431.091 3987.42 -14.2613 4015.64 +EDGE_SE3:QUAT 1127 1128 -1.02475 12.0713 0.13541 0.167599 0.0028251 0.168292 0.971381 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3908.45 -31.8177 -306.639 3989.56 -31.9782 3907.51 +EDGE_SE3:QUAT 1128 1129 -0.918957 12.2547 -0.0140527 0.0343196 -0.0569317 0.0350567 0.997172 1 4.81482e-20 4.81482e-20 -1.39343e-08 -4.37163e-10 8.25559e-10 1 4.81482e-20 -1.39343e-08 -4.37163e-10 8.25559e-10 1 -1.39343e-08 -4.37163e-10 8.25559e-10 4050.69 -5.59641 -474.027 3986.14 -5.83983 4050.49 +EDGE_SE3:QUAT 1129 1130 -0.816675 12.169 0.0021645 0.0510889 -0.097201 0.108923 0.987966 1 4.81482e-20 4.81482e-20 -1.40153e-08 -1.42645e-09 1.49887e-09 1 4.81482e-20 -1.40153e-08 -1.42645e-09 1.49887e-09 1 -1.40153e-08 -1.42645e-09 1.49887e-09 4166.87 4.09467 -860.701 3957.16 -39.3684 4129.85 +EDGE_SE3:QUAT 1130 1131 -0.629237 12.675 -0.113545 0.0874926 0.15246 0.0888305 0.980413 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4284.39 107.262 1167.21 3941.34 107.489 4283.45 +EDGE_SE3:QUAT 1131 1132 -0.902676 12.3712 -0.188344 0.0916329 -0.00668069 0.00831825 0.995736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.37 -2.9546 -61.8776 3999.75 -0.144991 4000.68 +EDGE_SE3:QUAT 1132 1133 -0.829421 12.2546 -0.649405 -0.0367969 -0.00976943 0.119083 0.992154 1 4.89006e-20 4.89006e-20 1.35618e-08 3.37925e-09 5.53566e-11 1 4.89006e-20 1.35618e-08 3.37925e-09 5.53566e-11 1 1.35618e-08 3.37925e-09 5.53566e-11 3994.65 0.170611 -24.2963 4000 -0.384646 3943.34 +EDGE_SE3:QUAT 1133 1134 -0.780701 12.5125 -0.229649 0.163652 -0.0333612 0.166032 0.971874 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3971.2 -40.5455 -571.626 3974.86 -41.6006 3968.06 +EDGE_SE3:QUAT 1134 1135 -0.842191 12.3285 -0.483731 -0.155148 0.0404285 0.0874867 0.983179 1 8.1852e-19 8.1852e-19 5.59533e-08 -9.6791e-09 1.582e-09 1 8.1852e-19 5.59533e-08 -9.6791e-09 1.582e-09 1 5.59533e-08 -9.6791e-09 1.582e-09 3958.76 -35.2126 474.3 3984.43 12.0599 4024.43 +EDGE_SE3:QUAT 1135 1136 -0.375574 12.3867 -0.114098 0.148488 0.161974 -0.0228157 0.975292 1 7.7056e-19 7.7056e-19 5.70467e-08 1.41895e-09 8.57281e-09 1 7.7056e-19 5.70467e-08 1.41895e-09 8.57281e-09 1 5.70467e-08 1.41895e-09 8.57281e-09 4365.43 119.486 1421.46 3906.45 86.7324 4451.55 +EDGE_SE3:QUAT 1136 1137 -0.536204 12.5336 0.171817 -0.272675 -0.0205184 0.0923959 0.95744 1 3.08149e-18 3.08149e-18 1.06336e-07 9.92326e-09 3.45809e-09 1 3.08149e-18 1.06336e-07 9.92326e-09 3.45809e-09 1 1.06336e-07 9.92326e-09 3.45809e-09 3705.24 -33.807 141.541 3996.16 11.0078 3968.5 +EDGE_SE3:QUAT 1137 1138 -0.921312 12.5523 -0.174717 0.00906953 0.0736509 0.0915388 0.993033 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4082.61 14.4717 581.993 3980.8 29.0162 4049.42 +EDGE_SE3:QUAT 1138 1139 -0.983012 12.7401 -0.264909 -0.00302567 0.176955 0.118226 0.977088 1 1.92593e-19 1.92593e-19 5.09804e-09 1.19679e-09 2.88862e-08 1 1.92593e-19 5.09804e-09 1.19679e-09 2.88862e-08 1 5.09804e-09 1.19679e-09 2.88862e-08 4529.88 98.2444 1549.48 3890.67 119.392 4474 +EDGE_SE3:QUAT 1139 1140 -0.695965 12.1503 0.116196 0.0085117 0.009007 0.0447175 0.998923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.84 0.358193 67.2866 3999.73 1.48484 3993.13 +EDGE_SE3:QUAT 1140 1141 -1.18875 12.5959 0.078831 0.0608122 0.0427193 -0.0712657 0.994685 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.31 8.79648 392.502 3989.99 -11.5483 4017.79 +EDGE_SE3:QUAT 1141 1142 -0.548233 12.5008 0.6377 -0.170728 -0.0642298 0.0175402 0.983066 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3935.62 40.6707 -460.749 3990.02 -18.519 4050.98 +EDGE_SE3:QUAT 1142 1143 -0.843925 12.5877 -0.395419 -0.0285216 0.046468 0.0782218 0.995444 1 1.20371e-20 1.20371e-20 -6.94129e-09 -5.28551e-10 -3.50692e-10 1 1.20371e-20 -6.94129e-09 -5.28551e-10 -3.50692e-10 1 -6.94129e-09 -5.28551e-10 -3.50692e-10 4035.97 -1.40633 398.081 3990.11 14.6037 4014.75 +EDGE_SE3:QUAT 1143 1144 -0.66969 12.6809 -0.201174 0.0506774 -0.128596 0.116035 0.983581 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4296.2 19.4206 -1148.86 3928.84 -56.4129 4252.61 +EDGE_SE3:QUAT 1144 1145 -0.589235 12.5917 -0.374702 -0.161945 -0.0798893 0.0113232 0.983495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.96 52.2633 -603.277 3982.1 -26.4934 4088.35 +EDGE_SE3:QUAT 1145 1146 -0.813013 12.4652 -0.265773 0.0254392 -0.00571262 0.00568341 0.999644 1 7.52316e-22 7.52316e-22 1.03986e-11 -4.40206e-11 -1.73423e-09 1 7.52316e-22 1.03986e-11 -4.40206e-11 -1.73423e-09 1 1.03986e-11 -4.40206e-11 -1.73423e-09 3997.97 -0.605503 -47.3946 3999.86 -0.115233 4000.43 +EDGE_SE3:QUAT 1146 1147 -0.484691 12.6969 -0.346789 0.168066 -0.112368 0.318226 0.926207 1 3.08149e-18 3.08149e-18 -2.21252e-08 8.3556e-09 1.09802e-07 1 3.08149e-18 -2.21252e-08 8.3556e-09 1.09802e-07 1 -2.21252e-08 8.3556e-09 1.09802e-07 4383.88 55.6997 -1496.9 3893.62 -205.202 4091.8 +EDGE_SE3:QUAT 1147 1148 -0.810185 12.8046 -0.321701 -0.105961 -0.00403272 -0.00765652 0.994333 1 1.93345e-19 1.93345e-19 -2.76094e-08 4.67423e-13 1.87918e-09 1 1.93345e-19 -2.76094e-08 4.67423e-13 1.87918e-09 1 -2.76094e-08 4.67423e-13 1.87918e-09 3955.51 2.35079 -41.3838 3999.88 0.10829 4000.19 +EDGE_SE3:QUAT 1148 1149 -0.704403 12.4387 -0.0505512 0.154905 -0.0522311 0.149291 0.975186 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4014.53 -39.9901 -677.473 3968.3 -36.9325 4021.36 +EDGE_SE3:QUAT 1149 1150 -0.639084 12.7787 -0.293108 0.012021 -0.0617328 0.0134163 0.99793 1 5.11575e-20 5.11575e-20 3.65591e-09 -1.38073e-08 -7.18989e-11 1 5.11575e-20 3.65591e-09 -1.38073e-08 -7.18989e-11 1 3.65591e-09 -1.38073e-08 -7.18989e-11 4061.54 -1.8872 -502.306 3984.63 -2.3829 4061.39 +EDGE_SE3:QUAT 1150 1151 -1.07716 12.158 -0.31669 -0.0397649 -0.0358604 0.10259 0.993281 1 4.81482e-20 4.81482e-20 -1.38081e-08 -1.46436e-09 3.73352e-10 1 4.81482e-20 -1.38081e-08 -1.46436e-09 3.73352e-10 1 -1.38081e-08 -1.46436e-09 3.73352e-10 4007.18 6.66646 -233.657 3997.33 -12.0901 3971.41 +EDGE_SE3:QUAT 1151 1152 -0.671085 12.6821 -0.390357 0.0125985 -0.0330147 0.0450178 0.998361 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.66 -0.513382 -271.149 3995.41 -5.87641 4010.19 +EDGE_SE3:QUAT 1152 1153 -0.903346 12.1365 -0.0222402 0.0308236 0.103908 0.0618276 0.992185 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4161.84 30.0351 830.74 3962 36.1776 4150.35 +EDGE_SE3:QUAT 1153 1154 -0.704324 12.4795 0.303799 -0.14755 0.0987504 -0.0495831 0.982863 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.82 -61.9876 689.373 3979.24 -46.0016 4105.07 +EDGE_SE3:QUAT 1154 1155 -0.404945 12.6481 -0.161704 -0.00189084 0.137681 -0.02916 0.990046 1 7.82409e-19 7.82409e-19 7.2182e-10 5.50295e-08 -6.57213e-09 1 7.82409e-19 7.2182e-10 5.50295e-08 -6.57213e-09 1 7.2182e-10 5.50295e-08 -6.57213e-09 4320.12 -15.8638 1176.02 3924.92 -21.5472 4316.73 +EDGE_SE3:QUAT 1155 1156 -1.03231 12.8705 -0.628708 0.170474 0.0430498 -0.0151879 0.984304 1 7.71124e-19 7.71124e-19 -5.49482e-08 -3.0371e-10 -4.25905e-09 1 7.71124e-19 -5.49482e-08 -3.0371e-10 -4.25905e-09 1 -5.49482e-08 -3.0371e-10 -4.25905e-09 3916.35 31.2622 362.54 3992.6 5.47722 4031.67 +EDGE_SE3:QUAT 1156 1157 -1.18151 12.3088 -0.0313544 0.013905 0.000396554 0.0719766 0.997309 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.24 -0.0882348 -8.82015 3999.99 -0.461614 3979.29 +EDGE_SE3:QUAT 1157 1158 -1.05935 12.4061 0.0787104 -0.125505 0.0982599 -0.0152355 0.987097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.84 -55.3482 766.777 3969.6 -34.4202 4140.92 +EDGE_SE3:QUAT 1158 1159 -0.798664 12.8435 -0.112713 -0.0711579 -0.0483705 0.0307139 0.995818 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.8 14.2773 -359.689 3992.7 -9.0738 4028.28 +EDGE_SE3:QUAT 1159 1160 -0.892664 12.6251 -0.0863866 -0.0367319 0.0217327 -0.0682963 0.996752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.64 -3.00534 142.433 3998.95 -4.83059 3986.38 +EDGE_SE3:QUAT 1160 1161 -0.839983 12.6965 -0.046996 0.0888219 -0.125534 0.033397 0.987541 1 7.70372e-19 7.70372e-19 6.22559e-10 -5.48473e-08 4.61102e-09 1 7.70372e-19 6.22559e-10 -5.48473e-08 4.61102e-09 1 6.22559e-10 -5.48473e-08 4.61102e-09 4246.03 -42.9081 -1089.68 3934.94 16.4104 4273.12 +EDGE_SE3:QUAT 1161 1162 -0.675195 12.4217 0.122192 0.12092 0.00753674 0.0150313 0.99252 1 7.82409e-19 7.82409e-19 -5.51239e-08 -1.75089e-09 -7.09293e-09 1 7.82409e-19 -5.51239e-08 -1.75089e-09 -7.09293e-09 1 -5.51239e-08 -1.75089e-09 -7.09293e-09 3941.85 1.80294 37.3611 3999.95 0.304737 3999.43 +EDGE_SE3:QUAT 1162 1163 -0.782533 12.3055 -0.479297 -0.0445403 0.148077 -0.156134 0.975557 1 1.92593e-19 1.92593e-19 2.80698e-08 -5.05594e-09 3.60941e-09 1 1.92593e-19 2.80698e-08 -5.05594e-09 3.60941e-09 1 2.80698e-08 -5.05594e-09 3.60941e-09 4281.4 -104.956 1115.86 3950.22 -123.707 4191.83 +EDGE_SE3:QUAT 1163 1164 -0.470268 12.4761 -0.167155 -0.145585 -0.00676926 -0.0475605 0.988179 1 7.70372e-19 7.70372e-19 5.48854e-08 -2.4219e-09 -1.11858e-09 1 7.70372e-19 5.48854e-08 -2.4219e-09 -1.11858e-09 1 5.48854e-08 -2.4219e-09 -1.11858e-09 3919.56 11.5107 -134.206 3998.44 3.09325 3995.29 +EDGE_SE3:QUAT 1164 1165 -0.779124 12.61 0.0465334 -0.0982711 0.0133985 0.0936086 0.990657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3972.5 -11.0425 213.906 3996.25 10.3943 3976.08 +EDGE_SE3:QUAT 1165 1166 -0.851427 12.6922 0.0381607 0.00431918 0.13232 0.0321993 0.990675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4293.46 17.552 1122.62 3930.99 23.393 4289.38 +EDGE_SE3:QUAT 1166 1167 -1.06567 12.3632 -0.258541 -0.158392 -0.0607418 0.0820575 0.982084 1 1.92593e-19 1.92593e-19 -8.65156e-10 -4.64926e-09 2.7339e-08 1 1.92593e-19 -8.65156e-10 -4.64926e-09 2.7339e-08 1 -8.65156e-10 -4.64926e-09 2.7339e-08 3922.57 24.2365 -310.506 3997.46 -17.9265 3995.99 +EDGE_SE3:QUAT 1167 1168 -0.730411 12.4818 -0.0323778 0.02966 -0.0499409 -0.0262342 0.997967 1 4.81482e-20 4.81482e-20 -4.06422e-10 -1.38484e-08 4.49508e-10 1 4.81482e-20 -4.06422e-10 -1.38484e-08 4.49508e-10 1 -4.06422e-10 -1.38484e-08 4.49508e-10 4034.62 -7.44394 -392.438 3990.78 6.95983 4035.38 +EDGE_SE3:QUAT 1168 1169 -0.915926 12.2981 -0.283676 0.144613 0.101414 0.125302 0.976269 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.39 55.0632 558.367 3992.32 52.9193 4011.24 +EDGE_SE3:QUAT 1169 1170 -0.773787 12.3985 -0.112158 -0.0268989 0.11552 0.0714938 0.990364 1 1.20371e-20 1.20371e-20 -7.06813e-09 -4.78567e-10 -8.42888e-10 1 1.20371e-20 -7.06813e-09 -4.78567e-10 -8.42888e-10 1 -7.06813e-09 -4.78567e-10 -8.42888e-10 4227.41 9.93815 987.051 3945.23 31.1178 4209.86 +EDGE_SE3:QUAT 1170 1171 -0.701201 12.3246 -0.360253 -0.0938282 0.112125 0.109884 0.983133 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4224.4 -16.0551 1051.9 3936.94 32.2693 4211.32 +EDGE_SE3:QUAT 1171 1172 -0.92842 12.3471 0.146008 -0.121222 0.137224 0.174339 0.967512 1 7.70372e-19 7.70372e-19 5.67385e-08 8.4026e-09 9.84665e-09 1 7.70372e-19 5.67385e-08 8.4026e-09 9.84665e-09 1 5.67385e-08 8.4026e-09 9.84665e-09 4387.66 5.67829 1409.52 3896.86 78.4914 4324.86 +EDGE_SE3:QUAT 1172 1173 -0.783623 12.9455 -0.0207649 -0.0362289 -0.197053 0.0294148 0.979281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4677.09 78.4682 -1787.48 3853.37 -77.4128 4678.88 +EDGE_SE3:QUAT 1173 1174 -0.987146 12.3248 -0.352447 -0.0695011 0.054707 0.175478 0.980502 1 7.70372e-19 7.70372e-19 4.20279e-09 -2.62091e-09 5.49822e-08 1 7.70372e-19 4.20279e-09 -2.62091e-09 5.49822e-08 1 4.20279e-09 -2.62091e-09 5.49822e-08 4059.67 -2.67195 568.503 3979.61 48.0164 3955.82 +EDGE_SE3:QUAT 1174 1175 -0.673234 12.5843 -0.0958019 0.119511 -0.0219088 0.0482952 0.991416 1 2.0463e-19 2.0463e-19 -2.78572e-08 5.7198e-09 9.5617e-11 1 2.0463e-19 -2.78572e-08 5.7198e-09 9.5617e-11 1 -2.78572e-08 5.7198e-09 9.5617e-11 3957.16 -14.8298 -240.287 3995.92 -4.0667 4004.96 +EDGE_SE3:QUAT 1175 1176 -0.6478 12.5788 0.185296 0.045692 0.0966184 0.246888 0.963132 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4071.34 49.355 577.259 3992.9 74.6284 3835.88 +EDGE_SE3:QUAT 1176 1177 -0.768959 12.5697 0.024865 0.070698 -0.00140586 0.205605 0.976077 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.39 -6.81887 -179.738 3996.66 -23.9121 3838.29 +EDGE_SE3:QUAT 1177 1178 -0.589051 12.669 -0.301852 0.0548717 0.0707985 -0.0593863 0.994208 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4079.58 10.0052 612.347 3977.04 -12.1047 4077.51 +EDGE_SE3:QUAT 1178 1179 -0.735279 12.5265 0.105142 -0.189992 0.109948 0.0655796 0.973403 1 8.1852e-19 8.1852e-19 5.75658e-08 -1.37775e-09 2.11616e-08 1 8.1852e-19 5.75658e-08 -1.37775e-09 2.11616e-08 1 5.75658e-08 -1.37775e-09 2.11616e-08 4105.43 -91.2941 1030.48 3944.08 -31.2835 4232.61 +EDGE_SE3:QUAT 1179 1180 -0.706442 12.2536 -0.269404 0.0566305 0.0557966 0.0750574 0.994005 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4025.23 15.5148 392.567 3991.9 17.9232 4015.52 +EDGE_SE3:QUAT 1180 1181 -0.51721 12.3738 -0.153203 -0.0843341 -0.0274988 -0.0328278 0.995517 1 2.0463e-19 2.0463e-19 2.79122e-08 -1.99308e-10 -7.82731e-09 1 2.0463e-19 2.79122e-08 -1.99308e-10 -7.82731e-09 1 2.79122e-08 -1.99308e-10 -7.82731e-09 3987.25 10.3869 -251.271 3995.87 2.43646 4011.39 +EDGE_SE3:QUAT 1181 1182 -0.754484 12.5221 -0.0795221 0.128782 -0.0294362 0.0252836 0.990913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3951.68 -17.5763 -269.215 3995.41 -0.245396 4015.46 +EDGE_SE3:QUAT 1182 1183 -0.770035 12.638 -0.252851 -0.0398118 -0.0551481 -0.0390487 0.99692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4046.59 6.56776 -463.202 3986.7 6.32294 4046.83 +EDGE_SE3:QUAT 1183 1184 -0.556943 12.3642 -0.0446753 -0.0510253 -0.0301889 0.165725 0.984388 1 8.30557e-19 8.30557e-19 -1.3151e-08 -1.23916e-08 5.44311e-08 1 8.30557e-19 -1.3151e-08 -1.23916e-08 5.44311e-08 1 -1.3151e-08 -1.23916e-08 5.44311e-08 3993.5 3.91885 -131.188 3999.68 -8.28028 3894.06 +EDGE_SE3:QUAT 1184 1185 -0.75561 12.3849 -0.541865 -0.047611 -0.0298869 0.138334 0.988789 1 1.20371e-20 1.20371e-20 9.76087e-10 -6.85882e-09 -3.74852e-10 1 1.20371e-20 9.76087e-10 -6.85882e-09 -3.74852e-10 1 9.76087e-10 -6.85882e-09 -3.74852e-10 3996.59 4.54221 -153.588 3999.23 -9.21732 3929.11 +EDGE_SE3:QUAT 1185 1186 -0.904107 12.171 -0.15546 0.248591 -0.0290135 -0.107913 0.962141 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3752.36 26.7902 99.2364 3997.1 -11.6732 3952.97 +EDGE_SE3:QUAT 1186 1187 -1.11719 12.2205 -0.336552 -0.0916093 0.152718 0.152977 0.972051 1 7.70372e-19 7.70372e-19 -7.232e-09 5.41429e-08 2.45952e-09 1 7.70372e-19 -7.232e-09 5.41429e-08 2.45952e-09 1 -7.232e-09 5.41429e-08 2.45952e-09 4455.37 25.8194 1481.67 3889.93 80.0929 4395.33 +EDGE_SE3:QUAT 1187 1188 -0.795163 12.2455 -0.707075 0.066704 -0.033857 0.0798655 0.993995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.51 -8.86404 -332.15 3992.56 -11.717 4001.8 +EDGE_SE3:QUAT 1188 1189 -0.908305 12.2966 -0.290238 -0.208324 0.0433901 0.135488 0.967658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3930.38 -64.4959 658.356 3968.96 25.9602 4030.54 +EDGE_SE3:QUAT 1189 1190 -0.946947 12.2102 0.0242508 0.036241 2.562e-05 -0.159337 0.986559 1 4.81482e-20 4.81482e-20 1.36931e-08 -2.20571e-09 1.58479e-10 1 4.81482e-20 1.36931e-08 -2.20571e-09 1.58479e-10 1 1.36931e-08 -2.20571e-09 1.58479e-10 3995.79 1.48682 68.276 3999.49 -7.24182 3899.49 +EDGE_SE3:QUAT 1190 1191 -0.292293 12.278 -0.103399 0.0733503 0.0827425 0.144605 0.983292 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4043.07 34.5966 515.82 3989.75 44.0097 3980.95 +EDGE_SE3:QUAT 1191 1192 -0.75493 12.6831 -0.117872 0.0530262 0.052106 -0.138994 0.987499 1 4.81482e-20 4.81482e-20 -1.85524e-09 -1.37145e-08 5.12506e-10 1 4.81482e-20 -1.85524e-09 -1.37145e-08 5.12506e-10 1 -1.85524e-09 -1.37145e-08 5.12506e-10 4049.61 2.24773 497.507 3984.43 -32.9371 3983.58 +EDGE_SE3:QUAT 1192 1193 -0.606892 12.2416 0.0977038 -0.0305805 -0.0362824 0.0167201 0.998734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.44 4.89276 -284.828 3995.08 -3.33288 4019.06 +EDGE_SE3:QUAT 1193 1194 -0.598494 12.6299 0.00259686 -0.080515 -0.0204091 -0.165513 0.982704 1 1.92593e-19 1.92593e-19 -2.73596e-08 4.4646e-09 1.26019e-09 1 1.92593e-19 -2.73596e-08 4.4646e-09 1.26019e-09 1 -2.73596e-08 4.4646e-09 1.26019e-09 3997.97 9.84501 -313.349 3992.34 27.9868 3914.33 +EDGE_SE3:QUAT 1194 1195 -0.908318 12.4952 0.199041 0.00689699 -0.150748 0.142429 0.978234 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4372.3 79.3513 -1276.39 3923.29 -108.345 4291.34 +EDGE_SE3:QUAT 1195 1196 -0.627264 12.4017 -0.193712 0.0651093 -0.00122219 0.278402 0.958254 1 3.09352e-18 3.09352e-18 -2.06052e-09 -6.09211e-10 1.06919e-07 1 3.09352e-18 -2.06052e-09 -6.09211e-10 1.06919e-07 1 -2.06052e-09 -6.09211e-10 1.06919e-07 3993.66 -6.22006 -214.875 3995.35 -39.2719 3700.58 +EDGE_SE3:QUAT 1196 1197 -0.924386 12.3959 0.0156587 -0.16567 -0.0489182 0.0703323 0.982453 1 7.70372e-19 7.70372e-19 5.4629e-08 4.59826e-09 -1.26235e-09 1 7.70372e-19 5.4629e-08 4.59826e-09 -1.26235e-09 1 5.4629e-08 4.59826e-09 -1.26235e-09 3903.25 17.3472 -235.622 3998.71 -11.1185 3993.25 +EDGE_SE3:QUAT 1197 1198 -0.704175 12.768 -0.41029 -0.0325036 -0.034764 0.043761 0.997908 1 1.92593e-19 1.92593e-19 -2.77562e-08 -1.28031e-09 8.81939e-10 1 1.92593e-19 -2.77562e-08 -1.28031e-09 8.81939e-10 1 -2.77562e-08 -1.28031e-09 8.81939e-10 4012.69 5.33824 -260.742 3996.04 -6.49288 4009.25 +EDGE_SE3:QUAT 1198 1199 -0.893263 12.309 0.00978985 0.011481 -0.092967 0.201068 0.975088 1 6.77085e-21 6.77085e-21 5.16304e-09 1.07235e-09 -4.76091e-10 1 6.77085e-21 5.16304e-09 1.07235e-09 -4.76091e-10 1 5.16304e-09 1.07235e-09 -4.76091e-10 4134.46 38.0822 -747.425 3973.65 -79.0821 3973.28 +EDGE_SE3:QUAT 1199 1200 -1.00657 12.3721 0.0621134 0.0834186 -0.0889515 -0.0210607 0.992313 1 1.92593e-19 1.92593e-19 -2.79518e-08 1.01556e-09 2.36738e-09 1 1.92593e-19 -2.79518e-08 1.01556e-09 2.36738e-09 1 -2.79518e-08 1.01556e-09 2.36738e-09 4091.06 -35.0326 -699.917 3972.9 23.3065 4117.12 +EDGE_SE3:QUAT 1200 1201 -0.815345 12.5312 -0.332255 -0.0453493 -0.0774995 0.147509 0.984976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4059.17 28.4594 -525.206 3987.72 -43.3823 3980.36 +EDGE_SE3:QUAT 1201 1202 -0.536809 12.3877 -0.404077 -0.117022 0.105401 0.190003 0.969069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4234.44 -0.347269 1114.8 3930.18 80.7044 4144.81 +EDGE_SE3:QUAT 1202 1203 -0.646073 12.2351 -0.1666 -0.039717 -0.00441386 0.020908 0.998982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.85 0.44081 -25.2532 3999.97 -0.240182 3998.41 +EDGE_SE3:QUAT 1203 1204 -0.558868 12.4088 -0.114126 -0.0471488 -0.0668565 0.0750001 0.993822 1 7.70372e-19 7.70372e-19 -3.28163e-09 -3.19161e-09 5.55811e-08 1 7.70372e-19 -3.28163e-09 -3.19161e-09 5.55811e-08 1 -3.28163e-09 -3.19161e-09 5.55811e-08 4050.68 18.809 -492.142 3986.88 -23.0906 4037.08 +EDGE_SE3:QUAT 1204 1205 -0.548352 12.329 0.0308702 0.124521 -0.0282792 0.125904 0.98379 1 1.92593e-19 1.92593e-19 2.74451e-08 3.21822e-09 -1.60273e-09 1 1.92593e-19 2.74451e-08 3.21822e-09 -1.60273e-09 1 2.74451e-08 3.21822e-09 -1.60273e-09 3977.72 -22.9608 -404.117 3987.57 -23.356 3976.33 +EDGE_SE3:QUAT 1205 1206 -1.2563 12.505 -0.647057 0.0179274 -0.0915133 0.125801 0.987663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4139.86 19.6182 -764.539 3967.55 -48.8298 4077.84 +EDGE_SE3:QUAT 1206 1207 -0.975715 12.4312 -0.326745 -0.0478334 -0.0285201 0.0671084 0.99619 1 4.81482e-20 4.81482e-20 -1.38401e-08 -9.67232e-10 3.01787e-10 1 4.81482e-20 -1.38401e-08 -9.67232e-10 3.01787e-10 1 -1.38401e-08 -9.67232e-10 3.01787e-10 3999.59 5.17263 -187.774 3998.19 -6.58283 3990.73 +EDGE_SE3:QUAT 1207 1208 -0.622605 12.1923 0.015323 0.054604 -0.0594946 -0.0380291 0.996008 1 4.81482e-20 4.81482e-20 1.39099e-08 -6.22562e-10 -7.65098e-10 1 4.81482e-20 1.39099e-08 -6.22562e-10 -7.65098e-10 1 1.39099e-08 -6.22562e-10 -7.65098e-10 4038.63 -15.5251 -452.648 3988.29 13.025 4044.77 +EDGE_SE3:QUAT 1208 1209 -1.17935 12.3507 -0.302031 0.158816 0.0265688 0.170801 0.972059 1 1.54074e-18 1.54074e-18 5.23492e-08 1.825e-08 5.23492e-08 1 1.54074e-18 5.23492e-08 1.825e-08 5.23492e-08 1 5.23492e-08 1.825e-08 5.23492e-08 3899.7 -18.4273 -118.338 3996.62 -19.8261 3883.9 +EDGE_SE3:QUAT 1209 1210 -0.76904 12.5701 -0.00520452 -0.20135 -0.0685039 0.0418407 0.976225 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3880.29 42.24 -417.885 3994.19 -23.4827 4035.46 +EDGE_SE3:QUAT 1210 1211 -0.924592 12.0693 0.0767293 -0.0688336 -0.0418596 0.00287946 0.996745 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.43 11.7024 -332.083 3993.39 -3.34587 4027.35 +EDGE_SE3:QUAT 1211 1212 -0.845887 12.1622 -0.139435 -0.111897 -0.0338818 0.179108 0.976858 1 1.92593e-19 1.92593e-19 -2.71072e-08 -5.0558e-09 -2.32584e-10 1 1.92593e-19 -2.71072e-08 -5.0558e-09 -2.32584e-10 1 -2.71072e-08 -5.0558e-09 -2.32584e-10 3948.21 -3.4249 -19.4659 3999.85 5.79489 3869.97 +EDGE_SE3:QUAT 1212 1213 -0.881086 12.3849 0.00348383 0.0218548 0.118294 0.110196 0.986603 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4207.62 48.193 939.436 3955.06 65.5214 4160.96 +EDGE_SE3:QUAT 1213 1214 -0.565338 12.3984 -0.320187 0.0109756 0.118842 0.0877892 0.988964 1 3.97223e-19 3.97223e-19 7.75376e-09 2.90221e-08 2.81361e-08 1 3.97223e-19 7.75376e-09 2.90221e-08 2.81361e-08 1 7.75376e-09 2.90221e-08 2.81361e-08 4223.5 36.8266 972.74 3949.43 52.4969 4193.15 +EDGE_SE3:QUAT 1214 1215 -0.606638 12.2305 -0.125756 0.0307487 -0.0933394 0.123568 0.987458 1 1.92593e-19 1.92593e-19 -2.77192e-09 2.02625e-10 2.79395e-08 1 1.92593e-19 -2.77192e-09 2.02625e-10 2.79395e-08 1 -2.77192e-09 2.02625e-10 2.79395e-08 4150.58 15.2054 -800.81 3963.78 -47.72 4093.29 +EDGE_SE3:QUAT 1215 1216 -0.888143 12.2175 -0.0284548 -0.120367 -0.056371 0.0305109 0.990658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.54 25.6287 -399.976 3991.83 -13.6922 4035.77 +EDGE_SE3:QUAT 1216 1217 -0.635044 12.5871 -0.161996 -0.0146805 0.0121671 0.121574 0.992399 1 3.00927e-21 3.00927e-21 3.44455e-09 4.20707e-10 5.32658e-11 1 3.00927e-21 3.44455e-09 4.20707e-10 5.32658e-11 1 3.44455e-09 4.20707e-10 5.32658e-11 4002.52 -0.32513 116.455 3999.1 7.41223 3944.26 +EDGE_SE3:QUAT 1217 1218 -0.71557 12.3169 -0.165274 -0.0944589 -0.0127281 -0.0130675 0.995362 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.62 5.60333 -115.252 3999.13 0.335299 4002.63 +EDGE_SE3:QUAT 1218 1219 -0.747037 12.4113 -0.30671 0.00122099 -0.0697777 0.0374434 0.996859 1 4.70198e-23 4.70198e-23 -4.36566e-10 -1.64842e-11 3.05124e-11 1 4.70198e-23 -4.36566e-10 -1.64842e-11 3.05124e-11 1 -4.36566e-10 -1.64842e-11 3.05124e-11 4078.87 4.11149 -567.207 3980.7 -11.0147 4073.27 +EDGE_SE3:QUAT 1219 1220 -0.818953 12.0036 0.238385 0.0144232 -0.18333 0.140009 0.972923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4579.13 116.099 -1629.95 3884.12 -142.01 4501.56 +EDGE_SE3:QUAT 1220 1221 -0.603169 12.3524 -0.129144 0.0187078 0.0565885 -0.0630851 0.996227 1 4.81482e-20 4.81482e-20 -8.16951e-10 -1.60979e-10 -1.39195e-08 1 4.81482e-20 -8.16951e-10 -1.60979e-10 -1.39195e-08 1 -8.16951e-10 -1.60979e-10 -1.39195e-08 4052.97 -0.551265 469.527 3986.53 -13.9236 4038.45 +EDGE_SE3:QUAT 1221 1222 -0.93367 12.2054 -0.542039 0.184194 -0.0796685 0.146489 0.968641 1 9.62965e-19 9.62965e-19 -5.83146e-08 2.07431e-08 2.72449e-09 1 9.62965e-19 -5.83146e-08 2.07431e-08 2.72449e-09 1 -5.83146e-08 2.07431e-08 2.72449e-09 4075.99 -62.5004 -946.797 3944.35 -29.9571 4125.86 +EDGE_SE3:QUAT 1222 1223 -0.543535 12.1223 -0.218805 -0.0145326 -0.016861 0.0255973 0.999424 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.4 1.10449 -130.369 3998.97 -1.74761 4001.62 +EDGE_SE3:QUAT 1223 1224 -0.9568 12.2483 -0.102967 -0.0157366 0.0543629 0.124906 0.990553 1 3.00927e-21 3.00927e-21 3.45872e-09 4.3265e-10 1.97487e-10 1 3.00927e-21 3.45872e-09 4.3265e-10 1.97487e-10 1 3.45872e-09 4.3265e-10 1.97487e-10 4049.69 5.78308 453.071 3987.98 28.303 3988.27 +EDGE_SE3:QUAT 1224 1225 -0.970203 12.2085 -0.122503 -0.150927 0.159741 0.217674 0.950958 1 1.92593e-19 1.92593e-19 -2.86709e-08 -5.20436e-09 -6.16079e-09 1 1.92593e-19 -2.86709e-08 -5.20436e-09 -6.16079e-09 1 -2.86709e-08 -5.20436e-09 -6.16079e-09 4586.69 33.3057 1781.42 3852.68 120.42 4488.28 +EDGE_SE3:QUAT 1225 1226 -0.787238 12.6052 -0.0557914 -0.126828 0.0998809 0.168238 0.972437 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4199.13 -17.919 1061.08 3934.53 60.1846 4150.25 +EDGE_SE3:QUAT 1226 1227 -0.815383 12.3526 0.0992824 0.000994771 -0.0139359 0.107467 0.99411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.07 0.444524 -110.909 3999.27 -5.95521 3956.88 +EDGE_SE3:QUAT 1227 1228 -0.921902 12.2018 0.087057 0.204819 0.0713986 0.0236663 0.975905 1 3.08149e-18 3.08149e-18 1.09155e-07 5.67129e-09 6.22635e-09 1 3.08149e-18 1.09155e-07 5.67129e-09 6.22635e-09 1 1.09155e-07 5.67129e-09 6.22635e-09 3889.39 50.81 483.586 3990.81 25.4393 4054.95 +EDGE_SE3:QUAT 1228 1229 -0.781949 12.5529 0.303856 0.0393472 0.180194 0.145058 0.97208 1 9.62965e-19 9.62965e-19 1.92211e-08 5.87192e-08 -5.42081e-10 1 9.62965e-19 1.92211e-08 5.87192e-08 -5.42081e-10 1 1.92211e-08 5.87192e-08 -5.42081e-10 4464.35 152.064 1451.76 3918.64 167.983 4386.38 +EDGE_SE3:QUAT 1229 1230 -1.20771 12.5534 0.433535 -0.0289959 -0.0281348 0.115959 0.992432 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.7 4.00232 -180.544 3998.44 -10.0585 3954.28 +EDGE_SE3:QUAT 1230 1231 -0.833931 12.5409 -0.138269 -0.0376734 -0.0200332 0.122956 0.991494 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.78 2.14516 -101.341 3999.65 -5.21005 3941.99 +EDGE_SE3:QUAT 1231 1232 -1.22093 12.1852 -0.0911572 0.128196 -0.16683 0.027838 0.97722 1 6.77085e-21 6.77085e-21 9.29491e-10 -6.96172e-10 -5.39532e-09 1 6.77085e-21 9.29491e-10 -6.96172e-10 -5.39532e-09 1 9.29491e-10 -6.96172e-10 -5.39532e-09 4427.84 -103.274 -1489.28 3894.64 73.5428 4490.47 +EDGE_SE3:QUAT 1232 1233 -0.640635 12.0863 -0.311739 0.155485 -0.085752 0.107085 0.978266 1 1.15556e-18 1.15556e-18 -5.45343e-08 1.89691e-08 -2.51744e-08 1 1.15556e-18 -5.45343e-08 1.89691e-08 -2.51744e-08 1 -5.45343e-08 1.89691e-08 -2.51744e-08 4089.58 -51.7677 -884.102 3952.84 -13.9353 4140.42 +EDGE_SE3:QUAT 1233 1234 -0.828574 12.5655 -0.179148 0.0254023 0.048781 -0.125657 0.990548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.62 -2.5477 422.846 3989.19 -26.25 3981.04 +EDGE_SE3:QUAT 1234 1235 -0.597548 12.1749 0.00591554 -0.0843976 0.0444786 0.0517941 0.994091 1 4.81482e-20 4.81482e-20 6.07849e-10 -1.38011e-08 -1.10664e-09 1 4.81482e-20 6.07849e-10 -1.38011e-08 -1.10664e-09 1 6.07849e-10 -1.38011e-08 -1.10664e-09 4012.38 -15.2024 406.639 3989.35 6.23869 4030.14 +EDGE_SE3:QUAT 1235 1236 -0.698273 12.3408 -0.223078 0.0547485 -0.0384329 0.182143 0.980994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.85 -1.98736 -412.082 3988.95 -38.3622 3909.13 +EDGE_SE3:QUAT 1236 1237 -0.725929 12.4978 -0.214993 -0.162027 0.0503363 0.107449 0.979627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.53 -43.0607 596.934 3975.84 17.9982 4040.36 +EDGE_SE3:QUAT 1237 1238 -0.689268 12.3018 0.115561 0.123144 0.050432 -0.0241133 0.990813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.85 26.3737 433.831 3988.67 2.98198 4044.18 +EDGE_SE3:QUAT 1238 1239 -0.927051 12.447 0.0145646 0.0160745 -0.011127 -0.0499703 0.998559 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.53 -0.733145 -79.0509 3999.65 1.93384 3991.57 +EDGE_SE3:QUAT 1239 1240 -0.809496 12.0835 -0.0431347 -0.0603324 0.0995445 -0.037537 0.992493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4134.77 -34.5537 787.28 3965.9 -30.1245 4143.69 +EDGE_SE3:QUAT 1240 1241 -0.826395 12.4664 0.0362975 -0.099469 -0.116593 0.139487 0.978292 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4092.4 70.4788 -743.291 3980.97 -76.1877 4054.15 +EDGE_SE3:QUAT 1241 1242 -0.90704 12.3679 -0.288383 -0.0257858 0.0339708 0.0405771 0.998266 1 6.01853e-20 6.01853e-20 -7.48375e-09 1.35843e-08 6.94575e-11 1 6.01853e-20 -7.48375e-09 1.35843e-08 6.94575e-11 1 -7.48375e-09 1.35843e-08 6.94575e-11 4017.49 -2.55841 284.651 3994.88 5.1597 4013.57 +EDGE_SE3:QUAT 1242 1243 -0.764703 12.3213 0.0769442 -0.0747396 0.182809 0.26315 0.944324 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4645.73 193.253 1766.2 3892.61 251.788 4391.08 +EDGE_SE3:QUAT 1243 1244 -0.562299 12.66 -0.0296235 -0.059779 -0.135296 -0.0410357 0.988149 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4309.08 22.1908 -1182.41 3923.72 -0.542909 4316.64 +EDGE_SE3:QUAT 1244 1245 -1.10346 12.256 -0.024576 -0.0397139 0.0485941 0.0278322 0.997641 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4034.13 -6.63795 404.256 3989.84 3.43537 4037.35 +EDGE_SE3:QUAT 1245 1246 -1.14171 11.948 -0.118875 -0.07344 -0.129021 0.0620369 0.986971 1 3.85186e-19 3.85186e-19 2.48682e-08 -2.54099e-10 2.48682e-08 1 3.85186e-19 2.48682e-08 -2.54099e-10 2.48682e-08 1 2.48682e-08 -2.54099e-10 2.48682e-08 4219.32 66.4243 -1011.2 3949.21 -64.2521 4225.5 +EDGE_SE3:QUAT 1246 1247 -1.07901 12.3105 -0.230078 -0.0808855 0.0206646 0.0881489 0.992603 1 1.92593e-19 1.92593e-19 -2.76029e-08 -2.32963e-09 -9.52425e-10 1 1.92593e-19 -2.76029e-08 -2.32963e-09 -9.52425e-10 1 -2.76029e-08 -2.32963e-09 -9.52425e-10 3988.92 -9.44491 247.488 3995.46 10.5937 3984.01 +EDGE_SE3:QUAT 1247 1248 -0.81213 12.1208 -0.219617 -0.00276623 0.0924983 0.139626 0.985871 1 3.00927e-21 3.00927e-21 -3.47833e-09 -4.99422e-10 -3.16157e-10 1 3.00927e-21 -3.47833e-09 -4.99422e-10 -3.16157e-10 1 -3.47833e-09 -4.99422e-10 -3.16157e-10 4133.83 27.9668 744.006 3970.75 55.6444 4055.88 +EDGE_SE3:QUAT 1248 1249 -0.875705 12.4242 -0.154425 -0.0830972 -0.0809205 -0.0673309 0.990966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4099.23 20.5865 -723.688 3968.27 11.3422 4108.71 +EDGE_SE3:QUAT 1249 1250 -0.414918 12.2643 -0.190972 0.028875 0.162562 0.0232818 0.986001 1 1.20371e-20 1.20371e-20 -1.17591e-09 -2.80518e-10 -7.21714e-09 1 1.20371e-20 -1.17591e-09 -2.80518e-10 -7.21714e-09 1 -1.17591e-09 -2.80518e-10 -7.21714e-09 4446.81 42.7463 1415.35 3898.03 41.6699 4447.97 +EDGE_SE3:QUAT 1250 1251 -0.741691 12.3571 -0.385115 -0.0459232 0.105342 0.109127 0.987363 1 4.81482e-20 4.81482e-20 -1.40517e-08 -1.44414e-09 -1.60198e-09 1 4.81482e-20 -1.40517e-08 -1.44414e-09 -1.60198e-09 1 -1.40517e-08 -1.44414e-09 -1.60198e-09 4195.45 9.30998 925.843 3951.4 43.5756 4156.25 +EDGE_SE3:QUAT 1251 1252 -1.06476 12.3516 -0.171873 0.0119247 0.0172489 0.0146132 0.999673 1 3.00927e-21 3.00927e-21 5.86254e-11 4.31533e-11 3.47031e-09 1 3.00927e-21 5.86254e-11 4.31533e-11 3.47031e-09 1 5.86254e-11 4.31533e-11 3.47031e-09 4004.05 0.910815 135.962 3998.86 1.07441 4003.76 +EDGE_SE3:QUAT 1252 1253 -0.648853 12.2539 -0.503012 -0.0266478 0.0108981 0.0805519 0.996335 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.28 -1.26119 111.966 3999.12 4.73683 3977.16 +EDGE_SE3:QUAT 1253 1254 -0.584115 12.1714 -0.164082 -0.0379224 -0.0440654 0.0799169 0.995105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.64 8.92164 -313.686 3994.68 -13.7002 3998.85 +EDGE_SE3:QUAT 1254 1255 -0.733439 12.1968 -0.210469 -0.0371308 -0.0298809 0.131179 0.990212 1 7.70372e-19 7.70372e-19 -1.06123e-09 -2.42709e-09 5.50203e-08 1 7.70372e-19 -1.06123e-09 -2.42709e-09 5.50203e-08 1 -1.06123e-09 -2.42709e-09 5.50203e-08 4001.98 4.63537 -174.849 3998.73 -10.6201 3938.66 +EDGE_SE3:QUAT 1255 1256 -0.795177 12.5942 0.0972009 -0.017223 -0.0442805 0.0872613 0.995052 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4026.49 6.62958 -334.011 3993.67 -15.2724 3997.22 +EDGE_SE3:QUAT 1256 1257 -0.918566 12.2244 -0.193608 0.0829553 0.25002 0.190592 0.945665 1 2.31112e-18 2.31112e-18 5.50574e-08 7.885e-08 5.87777e-08 1 2.31112e-18 5.50574e-08 7.885e-08 5.87777e-08 1 5.50574e-08 7.885e-08 5.87777e-08 4732.98 400.255 1912.05 3956.55 401.966 4615.2 +EDGE_SE3:QUAT 1257 1258 -0.695754 12.0831 -0.149943 0.0017178 0.0655714 0.00705487 0.997821 1 1.88079e-22 1.88079e-22 -8.72974e-10 -6.42402e-12 -5.73396e-11 1 1.88079e-22 -8.72974e-10 -6.42402e-12 -5.73396e-11 1 -8.72974e-10 -6.42402e-12 -5.73396e-11 4069.63 1.22087 532.364 3982.82 2.14364 4069.44 +EDGE_SE3:QUAT 1258 1259 -0.677632 12.5342 -0.237579 0.0604701 0.140356 0.0587736 0.986503 1 1.92593e-19 1.92593e-19 3.76635e-09 2.28487e-09 2.83972e-08 1 1.92593e-19 3.76635e-09 2.28487e-09 2.83972e-08 1 3.76635e-09 2.28487e-09 2.83972e-08 4285.05 68.8112 1135.4 3935.59 68.4841 4285.86 +EDGE_SE3:QUAT 1259 1260 -0.431465 12.5622 -0.012274 -0.0817501 0.0853013 0.114215 0.986405 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4127.74 -11.2976 801.475 3961.3 33.3154 4102.29 +EDGE_SE3:QUAT 1260 1261 -0.801705 12.1334 -0.27919 0.100872 -0.153203 0.0414073 0.98216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4385.15 -60.3909 -1372.87 3903.39 30.999 4418.99 +EDGE_SE3:QUAT 1261 1262 -0.816091 12.4293 0.0352554 0.11625 0.0192072 0.0103219 0.992981 1 3.00927e-21 3.00927e-21 -5.65784e-11 -4.05122e-10 -3.44712e-09 1 3.00927e-21 -5.65784e-11 -4.05122e-10 -3.44712e-09 1 -5.65784e-11 -4.05122e-10 -3.44712e-09 3950.58 7.69047 136.383 3999.01 1.53851 4004.21 +EDGE_SE3:QUAT 1262 1263 -0.793131 12.1979 -0.129738 0.0488442 0.0429668 0.0895748 0.993853 1 4.81482e-20 4.81482e-20 -1.3828e-08 -1.30272e-09 -4.63704e-10 1 4.81482e-20 -1.3828e-08 -1.30272e-09 -4.63704e-10 1 -1.3828e-08 -1.30272e-09 -4.63704e-10 4010.87 9.68834 287.267 3995.84 13.8586 3988.32 +EDGE_SE3:QUAT 1263 1264 -0.72053 12.1592 0.0996682 -0.22079 -0.0926445 0.110188 0.964639 1 7.70372e-19 7.70372e-19 5.37894e-08 7.84366e-09 -1.85414e-09 1 7.70372e-19 5.37894e-08 7.84366e-09 -1.85414e-09 1 5.37894e-08 7.84366e-09 -1.85414e-09 3838.69 41.2212 -391.812 4000.84 -34.564 3985.12 +EDGE_SE3:QUAT 1264 1265 -0.736068 12.562 -0.339164 0.0838738 0.0847402 0.125352 0.984922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.73 37.0467 536.335 3988.4 42.7061 4007.02 +EDGE_SE3:QUAT 1265 1266 -0.735476 12.2394 -0.26241 0.0562113 -0.0438368 0.215745 0.973844 1 7.70372e-19 7.70372e-19 -3.53586e-09 1.82932e-09 5.44469e-08 1 7.70372e-19 -3.53586e-09 1.82932e-09 5.44469e-08 1 -3.53586e-09 1.82932e-09 5.44469e-08 4042.16 1.60745 -472.175 3986.18 -52.4942 3868.61 +EDGE_SE3:QUAT 1266 1267 -0.985088 12.2772 -0.00393282 0.118959 0.0107275 0.110514 0.986671 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3944.03 -7.46354 -72.5488 3999.01 -6.92672 3951.79 +EDGE_SE3:QUAT 1267 1268 -0.842126 12.6348 -0.0740059 0.253225 -0.0681062 -0.14003 0.954793 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3738.23 10.1884 -73.5273 4000.76 -3.76714 3916.29 +EDGE_SE3:QUAT 1268 1269 -0.504483 12.1958 -0.0523078 -0.084425 -0.0363307 0.236361 0.967309 1 1.92593e-19 1.92593e-19 -2.68423e-08 -6.63763e-09 -1.93003e-10 1 1.92593e-19 -2.68423e-08 -6.63763e-09 -1.93003e-10 1 -2.68423e-08 -6.63763e-09 -1.93003e-10 3969.86 -1.69668 -33.8288 4000.05 6.32448 3774.9 +EDGE_SE3:QUAT 1269 1270 -0.673317 12.4779 0.00614784 0.0414146 -0.183765 0.0835356 0.978538 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4616.92 34.5949 -1698.31 3862.03 -56.7753 4595.87 +EDGE_SE3:QUAT 1270 1271 -0.885386 12.3936 -0.198321 -0.0518663 0.0749069 -0.0308117 0.995364 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4073.63 -19.9153 587.166 3980.19 -16.2074 4080.59 +EDGE_SE3:QUAT 1271 1272 -0.385418 12.4147 -0.0503649 -0.0176404 -0.0143813 0.0894879 0.995728 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.99 1.10987 -94.8159 3999.54 -4.01121 3970.2 +EDGE_SE3:QUAT 1272 1273 -0.742905 12.3883 -0.443219 0.039425 -0.189009 -0.0171403 0.981034 1 6.01853e-20 6.01853e-20 1.60389e-08 -8.77323e-10 -1.01106e-08 1 6.01853e-20 1.60389e-08 -8.77323e-10 -1.01106e-08 1 1.60389e-08 -8.77323e-10 -1.01106e-08 4620.49 -63.7498 -1702.84 3862.85 60.0505 4625.53 +EDGE_SE3:QUAT 1273 1274 -0.96943 12.2897 0.0189549 0.10071 -0.0536349 0.145946 0.982691 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.47 -16.7732 -594.536 3976.49 -37.3432 4000.84 +EDGE_SE3:QUAT 1274 1275 -1.18083 12.1926 -0.0113569 0.143906 0.0310196 0.12109 0.981665 1 7.73381e-19 7.73381e-19 -5.40522e-08 -1.03389e-08 8.12951e-10 1 7.73381e-19 -5.40522e-08 -1.03389e-08 8.12951e-10 1 -5.40522e-08 -1.03389e-08 8.12951e-10 3916.05 -2.8755 30.6877 3999.98 -2.33147 3940.23 +EDGE_SE3:QUAT 1275 1276 -0.860904 12.0294 -0.408911 0.0430395 0.106957 0.0416571 0.992458 1 4.81482e-20 4.81482e-20 1.40765e-08 7.34781e-10 1.45365e-09 1 4.81482e-20 1.40765e-08 7.34781e-10 1.45365e-09 1 1.40765e-08 7.34781e-10 1.45365e-09 4169.99 32.0209 860.926 3959.02 31.7438 4170.46 +EDGE_SE3:QUAT 1276 1277 -0.687992 12.1036 -0.294461 -0.219717 0.0740022 0.10039 0.967559 1 1.92593e-19 1.92593e-19 3.08471e-09 -5.7792e-09 2.7433e-08 1 1.92593e-19 3.08471e-09 -5.7792e-09 2.7433e-08 1 3.08471e-09 -5.7792e-09 2.7433e-08 3971.51 -84.0483 829.44 3958.94 -1.59409 4124.3 +EDGE_SE3:QUAT 1277 1278 -0.772889 12.5315 -0.221941 -0.0941953 0.0207986 0.125887 0.987344 1 4.33334e-19 4.33334e-19 -2.79449e-08 7.97542e-09 2.74756e-08 1 4.33334e-19 -2.79449e-08 7.97542e-09 2.74756e-08 1 -2.79449e-08 7.97542e-09 2.74756e-08 3986.76 -12.9825 301.986 3992.88 19.4217 3958.86 +EDGE_SE3:QUAT 1278 1279 -1.06171 12.5799 -0.126885 0.142278 -0.165384 0.12806 0.967474 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4529.2 -44.1672 -1677.54 3862.62 -14.3138 4544.57 +EDGE_SE3:QUAT 1279 1280 -0.979658 12.0095 0.0853589 0.101739 -0.00128728 -0.105291 0.989223 1 1.92593e-19 1.92593e-19 5.54241e-10 2.76966e-09 2.74669e-08 1 1.92593e-19 5.54241e-10 2.76966e-09 2.74669e-08 1 5.54241e-10 2.76966e-09 2.74669e-08 3961.58 7.8246 116.827 3998.44 -8.11883 3958.64 +EDGE_SE3:QUAT 1280 1281 -0.939794 12.4514 -0.218301 0.069799 -0.0880814 0.0808652 0.990369 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4129.39 -12.7459 -786.084 3963.04 -20.0371 4122.72 +EDGE_SE3:QUAT 1281 1282 -0.532785 11.9872 0.0888926 0.0135864 0.0654322 0.0110773 0.997703 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4068.1 4.90712 529.232 3983.08 4.47582 4068.35 +EDGE_SE3:QUAT 1282 1283 -0.798136 12.2505 -0.0150221 -0.0378824 0.0859565 0.193099 0.976672 1 7.70372e-19 7.70372e-19 5.30133e-09 -1.51338e-10 5.51839e-08 1 7.70372e-19 5.30133e-09 -1.51338e-10 5.51839e-08 1 5.30133e-09 -1.51338e-10 5.51839e-08 4132.89 24.4758 757.467 3969.68 73.2128 3989.48 +EDGE_SE3:QUAT 1283 1284 -0.456157 12.112 -0.168148 0.0887975 -0.0807977 0.124197 0.984968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4115.4 -12.964 -781.159 3962.78 -36.1323 4085.24 +EDGE_SE3:QUAT 1284 1285 -0.851022 11.8996 -0.039671 0.130397 0.138449 0.209848 0.959058 1 1.92593e-19 1.92593e-19 -6.73899e-09 2.64025e-08 -4.9587e-09 1 1.92593e-19 -6.73899e-09 2.64025e-08 -4.9587e-09 1 -6.73899e-09 2.64025e-08 -4.9587e-09 4041.49 91.7514 692.915 3999.89 97.9095 3933.36 +EDGE_SE3:QUAT 1285 1286 -1.0188 11.8838 -0.261092 -0.0445537 0.123173 -0.0508542 0.990079 1 4.81482e-20 4.81482e-20 -1.67562e-09 8.3509e-10 -1.41412e-08 1 4.81482e-20 -1.67562e-09 8.3509e-10 -1.41412e-08 1 -1.67562e-09 8.3509e-10 -1.41412e-08 4227.66 -44.3027 999.069 3946.83 -45.5707 4225.26 +EDGE_SE3:QUAT 1286 1287 -0.782844 12.3906 -0.29293 -0.0227405 -0.0489658 0.0674842 0.996259 1 1.20371e-20 1.20371e-20 -6.94282e-09 -4.8753e-10 3.163e-10 1 1.20371e-20 -6.94282e-09 -4.8753e-10 3.163e-10 1 -6.94282e-09 -4.8753e-10 3.163e-10 4032.41 7.86793 -373.059 3991.97 -13.8609 4016.26 +EDGE_SE3:QUAT 1287 1288 -1.04327 12.436 0.557283 -0.0527112 -0.137058 -0.0694743 0.986717 1 8.1852e-19 8.1852e-19 1.74344e-08 5.39933e-08 -1.30321e-10 1 8.1852e-19 1.74344e-08 5.39933e-08 -1.30321e-10 1 1.74344e-08 5.39933e-08 -1.30321e-10 4328.17 2.65344 -1213.39 3920.08 23.8074 4319.98 +EDGE_SE3:QUAT 1288 1289 -1.11547 12.5386 -0.0529811 -0.0721752 0.0247675 0.15223 0.985395 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.47 -8.22994 321.25 3992.38 25.5173 3932.61 +EDGE_SE3:QUAT 1289 1290 -0.723455 12.4578 -0.117884 0.154706 0.23268 0.0382665 0.959407 1 1.92593e-19 1.92593e-19 6.30693e-09 5.86316e-09 2.93701e-08 1 1.92593e-19 6.30693e-09 5.86316e-09 2.93701e-08 1 6.30693e-09 5.86316e-09 2.93701e-08 4740.31 296.01 2012.74 3878.98 287.134 4830.19 +EDGE_SE3:QUAT 1290 1291 -0.806501 12.2567 -0.666324 0.0485263 0.00324912 -0.0635405 0.996793 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.52 1.74614 62.6027 3999.65 -2.32492 3984.79 +EDGE_SE3:QUAT 1291 1292 -1.0455 12.4496 -0.356932 0.0262487 -0.0174977 0.295539 0.95481 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.21 1.31657 -210.161 3997.41 -34.4498 3661.59 +EDGE_SE3:QUAT 1292 1293 -0.720647 12.0981 0.159193 -0.114908 -0.0260813 0.0617446 0.991112 1 2.0463e-19 2.0463e-19 -2.70618e-08 -8.71124e-09 -5.05615e-10 1 2.0463e-19 -2.70618e-08 -8.71124e-09 -5.05615e-10 1 -2.70618e-08 -8.71124e-09 -5.05615e-10 3950.49 5.58589 -119.144 3999.61 -3.59464 3988.06 +EDGE_SE3:QUAT 1293 1294 -0.768276 12.1658 -0.0631529 0.056604 -0.0539315 0.167038 0.982846 1 2.40741e-19 2.40741e-19 1.8236e-08 -2.50512e-08 2.91264e-11 1 2.40741e-19 1.8236e-08 -2.50512e-08 2.91264e-11 1 1.8236e-08 -2.50512e-08 2.91264e-11 4056.49 -0.0977533 -531.579 3982.47 -43.2146 3957.7 +EDGE_SE3:QUAT 1294 1295 -0.689764 11.7017 -0.247357 -0.127335 -0.0288317 0.0138133 0.991344 1 1.20371e-20 1.20371e-20 1.69453e-10 8.91273e-10 -6.88792e-09 1 1.20371e-20 1.69453e-10 8.91273e-10 -6.88792e-09 1 1.69453e-10 8.91273e-10 -6.88792e-09 3945.55 12.7836 -204.537 3997.82 -3.49021 4009.64 +EDGE_SE3:QUAT 1295 1296 -0.791481 12.0035 -0.249158 0.0413522 0.0973778 0.0934696 0.989985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4125.61 36.0318 740.248 3971.49 45.6042 4097.51 +EDGE_SE3:QUAT 1296 1297 -0.548815 12.4659 -0.278156 -0.181141 -0.141155 0.0469676 0.972141 1 1.54074e-18 1.54074e-18 5.02574e-08 5.93239e-08 4.61438e-09 1 1.54074e-18 5.02574e-08 5.93239e-08 4.61438e-09 1 5.02574e-08 5.93239e-08 4.61438e-09 4109.92 123.354 -1014.32 3963.02 -101.83 4232.35 +EDGE_SE3:QUAT 1297 1298 -0.713222 12.0479 -0.519412 -0.0322485 0.037763 0.105019 0.99323 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.38 -1.42049 339.241 3992.69 17.408 3984.43 +EDGE_SE3:QUAT 1298 1299 -0.784122 12.2932 -0.294732 -0.00983082 0.0912869 -0.0785484 0.992673 1 1.20371e-20 1.20371e-20 -7.00026e-09 5.75892e-10 -6.24459e-10 1 1.20371e-20 -7.00026e-09 5.75892e-10 -6.24459e-10 1 -7.00026e-09 5.75892e-10 -6.24459e-10 4130.13 -19.7215 734.27 3969.62 -33.1003 4105.83 +EDGE_SE3:QUAT 1299 1300 -0.666228 12.2517 -0.283539 -0.0490991 0.274485 0.037901 0.959589 1 3.27408e-18 3.27408e-18 -3.29934e-08 1.0615e-07 -5.26398e-09 1 3.27408e-18 -3.29934e-08 1.0615e-07 -5.26398e-09 1 -3.29934e-08 1.0615e-07 -5.26398e-09 5559.86 -31.6519 2956.57 3695.81 -29.9111 5563.75 +EDGE_SE3:QUAT 1300 1301 -0.9703 11.9324 0.072848 0.0481763 0.100394 0.00439498 0.993771 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4154.66 23.08 826.244 3960.87 14.1269 4163.87 +EDGE_SE3:QUAT 1301 1302 -1.09561 12.1802 -0.147001 0.11109 0.0527364 0.0871164 0.988579 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3971.8 17.7861 295.356 3996.76 15.6395 3990.81 +EDGE_SE3:QUAT 1302 1303 -0.666469 11.8444 -0.333347 0.117936 0.0456867 -0.0437387 0.991005 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.46 23.8504 422.529 3988.67 -2.40428 4036.44 +EDGE_SE3:QUAT 1303 1304 -0.877854 12.3345 -0.407535 0.0524839 0.134699 0.0501466 0.988224 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4271.23 56.2911 1099.53 3937.49 55.8273 4272.19 +EDGE_SE3:QUAT 1304 1305 -0.610658 12.159 -0.247506 0.0951661 -0.0326108 0.119965 0.987668 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.16 -15.0265 -390.385 3989.04 -21.7135 3979.82 +EDGE_SE3:QUAT 1305 1306 -0.789027 12.1491 0.334126 -0.0413701 -0.10742 -0.0346182 0.992749 1 4.81482e-20 4.81482e-20 -1.41144e-08 3.73792e-10 1.56002e-09 1 4.81482e-20 -1.41144e-08 3.73792e-10 1.56002e-09 1 -1.41144e-08 3.73792e-10 1.56002e-09 4190.85 10.8648 -910.968 3952.19 5.35455 4192.9 +EDGE_SE3:QUAT 1306 1307 -1.07713 11.9719 0.10756 -0.013338 0.0514863 0.0621349 0.99665 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4043.62 1.20666 423.448 3989.04 12.7234 4028.89 +EDGE_SE3:QUAT 1307 1308 -0.632614 12.1118 -0.156349 0.0824044 0.0933172 0.0204504 0.99201 1 1.20371e-20 1.20371e-20 6.24334e-10 6.1801e-10 6.99694e-09 1 1.20371e-20 6.24334e-10 6.1801e-10 6.99694e-09 1 6.24334e-10 6.1801e-10 6.99694e-09 4104.77 36.9378 738.452 3969.91 25.0566 4130.26 +EDGE_SE3:QUAT 1308 1309 -1.13933 12.149 0.189742 -0.189199 -0.0536569 -0.017321 0.980319 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3906.75 43.1284 -449.705 3989.14 -10.2236 4048.73 +EDGE_SE3:QUAT 1309 1310 -0.829695 11.9831 -0.2693 0.0910024 0.0128619 0.0083885 0.995732 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3969.01 4.0869 92.5383 3999.52 0.682218 4001.85 +EDGE_SE3:QUAT 1310 1311 -1.17075 12.4462 0.0864288 -0.0219564 0.0642586 0.113469 0.991218 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4070.25 5.96483 542.162 3982.64 30.1793 4020.68 +EDGE_SE3:QUAT 1311 1312 -1.17368 11.8695 0.411308 0.0143822 -0.0316124 0.021397 0.999168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.65 -1.35118 -257.273 3995.87 -2.43995 4014.65 +EDGE_SE3:QUAT 1312 1313 -0.857734 11.9865 0.176251 -0.00456797 0.050945 0.0528026 0.997294 1 4.81482e-20 4.81482e-20 -7.13476e-10 -1.15418e-11 -1.39131e-08 1 4.81482e-20 -7.13476e-10 -1.15418e-11 -1.39131e-08 1 -7.13476e-10 -1.15418e-11 -1.39131e-08 4042.01 2.38178 412.511 3989.65 10.9108 4030.95 +EDGE_SE3:QUAT 1313 1314 -0.853931 12.1399 0.0327752 0.0970297 -0.0843263 0.0155875 0.99158 1 1.93345e-19 1.93345e-19 2.80841e-08 -1.95259e-10 -4.16111e-09 1 1.93345e-19 2.80841e-08 -1.95259e-10 -4.16111e-09 1 2.80841e-08 -1.95259e-10 -4.16111e-09 4081.63 -33.9432 -700.977 3971.68 11.676 4118.31 +EDGE_SE3:QUAT 1314 1315 -0.804661 11.8615 0.0941821 0.0324881 0.0122177 -0.0119188 0.999326 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.39 1.64238 102.269 3999.33 -0.494372 4002.04 +EDGE_SE3:QUAT 1315 1316 -0.928729 11.7086 -0.121638 -0.059588 0.0678234 0.0143399 0.995813 1 3.00927e-21 3.00927e-21 -2.41806e-10 2.03744e-10 -3.488e-09 1 3.00927e-21 -2.41806e-10 2.03744e-10 -3.488e-09 1 -2.41806e-10 2.03744e-10 -3.488e-09 4062.47 -15.8971 559.093 3981.19 -2.66043 4075.85 +EDGE_SE3:QUAT 1316 1317 -0.665863 12.0229 -0.37698 -0.0284628 -0.0235772 0.112949 0.992913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.07 2.93136 -146.68 3999 -7.78205 3954.28 +EDGE_SE3:QUAT 1317 1318 -0.678122 12.2732 0.0889284 0.039864 0.0836735 0.218054 0.971526 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4060.38 36.0316 525.058 3991.4 59.6598 3876.55 +EDGE_SE3:QUAT 1318 1319 -1.18814 11.6045 -0.362383 0.20897 0.0704652 0.139933 0.96529 1 4.81482e-20 4.81482e-20 -2.17342e-09 1.33605e-08 -3.05987e-09 1 4.81482e-20 -2.17342e-09 1.33605e-08 -3.05987e-09 1 -2.17342e-09 1.33605e-08 -3.05987e-09 3827.98 7.56329 172.302 4001.69 7.91789 3924.33 +EDGE_SE3:QUAT 1319 1320 -0.930748 12.2831 -0.252838 -0.207635 0.271799 0.188547 0.920577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5912.37 -74.4044 3561.94 3633.99 -66.3721 5942.62 +EDGE_SE3:QUAT 1320 1321 -0.79442 12.1582 -0.336363 -0.0888629 -0.0868744 -0.0726191 0.989587 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4116.64 23.0547 -784.339 3963.09 12.3829 4127.13 +EDGE_SE3:QUAT 1321 1322 -0.725334 12.1242 0.0602156 -0.070183 0.0937926 0.150801 0.981599 1 1.92593e-19 1.92593e-19 -3.86804e-09 2.72917e-08 1.11236e-09 1 1.92593e-19 -3.86804e-09 2.72917e-08 1.11236e-09 1 -3.86804e-09 2.72917e-08 1.11236e-09 4165.89 5.69684 881.645 3955.23 57.1246 4094.63 +EDGE_SE3:QUAT 1322 1323 -0.683286 11.6697 0.167494 0.0202234 0.120264 -0.0870426 0.988712 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4245.6 -21.1297 1024.73 3942.29 -44.0508 4216.93 +EDGE_SE3:QUAT 1323 1324 -0.817601 12.5643 -0.374916 0.103578 -0.0551849 0.151043 0.981536 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4049.7 -17.3066 -617.379 3974.73 -40.0018 4001.36 +EDGE_SE3:QUAT 1324 1325 -0.641803 11.8067 0.114062 0.0316981 0.0339662 0.184738 0.981689 1 6.01853e-20 6.01853e-20 -1.2343e-08 -9.40497e-09 1.24127e-11 1 6.01853e-20 -1.2343e-08 -9.40497e-09 1.24127e-11 1 -1.2343e-08 -9.40497e-09 1.24127e-11 4004.65 5.59176 189.069 3998.84 15.5108 3872.16 +EDGE_SE3:QUAT 1325 1326 -1.22329 12.3075 -0.146379 -0.0299356 0.0569234 0.0402735 0.997117 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.79 -4.07899 473.909 3986.15 7.49185 4048.89 +EDGE_SE3:QUAT 1326 1327 -0.467378 12.0742 -0.14305 -0.0446934 0.0459012 0.0382518 0.997212 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.49 -6.92128 389.059 3990.49 5.26207 4031.63 +EDGE_SE3:QUAT 1327 1328 -1.17741 12.0141 -0.0482014 0.0103036 -0.0150524 0.222769 0.974701 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.35 0.802044 -138.342 3998.93 -16.0593 3806.27 +EDGE_SE3:QUAT 1328 1329 -1.07618 12.1972 0.0618084 -0.0532522 -0.0704374 -0.0352478 0.99547 1 2.40741e-19 2.40741e-19 -1.47372e-08 -2.72455e-08 -3.18133e-10 1 2.40741e-19 -1.47372e-08 -2.72455e-08 -3.18133e-10 1 -1.47372e-08 -2.72455e-08 -3.18133e-10 4074.94 12.2996 -593.815 3978.56 4.28128 4081.32 +EDGE_SE3:QUAT 1329 1330 -1.23764 11.9011 -0.0712136 0.0304597 0.0401805 -0.0056716 0.998712 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.51 4.81783 324.914 3993.48 0.2608 4026.09 +EDGE_SE3:QUAT 1330 1331 -0.509633 11.8534 -0.140543 0.00958254 -0.05209 -0.034112 0.998014 1 5.11575e-20 5.11575e-20 4.19678e-09 -3.06957e-10 -1.41031e-08 1 5.11575e-20 4.19678e-09 -3.06957e-10 -1.41031e-08 1 4.19678e-09 -3.06957e-10 -1.41031e-08 4042.4 -4.2532 -415.836 3989.54 7.88722 4038.12 +EDGE_SE3:QUAT 1331 1332 -1.00918 12.0263 -0.329556 0.085347 0.0024824 0.146074 0.985582 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.38 -7.10725 -127.846 3998.07 -12.719 3918.17 +EDGE_SE3:QUAT 1332 1333 -0.704445 11.8109 -0.369734 -0.0444094 0.0277908 0.126084 0.990635 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.12 -3.34955 284.203 3994.54 18.1761 3956.42 +EDGE_SE3:QUAT 1333 1334 -0.715877 12.0411 0.22622 0.254921 -0.0152656 0.0646186 0.964679 1 3.08149e-18 3.08149e-18 -1.07413e-07 -5.42925e-09 5.00758e-09 1 3.08149e-18 -1.07413e-07 -5.42925e-09 5.00758e-09 1 -1.07413e-07 -5.42925e-09 5.00758e-09 3761.84 -44.7048 -300.029 3992.92 -5.02766 4005.08 +EDGE_SE3:QUAT 1334 1335 -0.750493 11.6979 -0.389794 -0.00576138 0.025483 0.0322295 0.999139 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.47 -0.0885315 206.244 3997.35 3.26531 4006.45 +EDGE_SE3:QUAT 1335 1336 -0.600604 12.2024 -0.21593 -0.0828319 0.193267 0.0290137 0.977213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4657.41 -73.0264 1791.21 3851.4 -54.6908 4681.48 +EDGE_SE3:QUAT 1336 1337 -0.698193 11.8246 -0.305119 0.103689 0.0808659 0.157703 0.978693 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.22 32.2054 421.944 3995.71 37.4253 3942.75 +EDGE_SE3:QUAT 1337 1338 -0.752102 11.5652 0.0377902 -0.122331 0.0277426 0.186055 0.974499 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.88 -22.5189 476.731 3982.25 45.0915 3916.27 +EDGE_SE3:QUAT 1338 1339 -0.861877 12.0148 -0.170675 0.0812207 -0.0165551 -0.118058 0.989541 1 3.85938e-19 3.85938e-19 2.7171e-08 -7.32362e-09 -2.72341e-08 1 3.85938e-19 2.7171e-08 -7.32362e-09 -2.72341e-08 1 2.7171e-08 -7.32362e-09 -2.72341e-08 3973.28 0.943891 -14.8561 3999.98 -1.42275 3943.91 +EDGE_SE3:QUAT 1339 1340 -0.775482 12.2069 -0.0400841 0.0987999 0.0803786 0.0467195 0.990755 1 4.81482e-20 4.81482e-20 -9.69306e-10 -1.50222e-09 -1.38949e-08 1 4.81482e-20 -9.69306e-10 -1.50222e-09 -1.38949e-08 1 -9.69306e-10 -1.50222e-09 -1.38949e-08 4044.89 35.9187 586.104 3982.34 27.3495 4075.21 +EDGE_SE3:QUAT 1340 1341 -0.549192 12.3047 0.429737 -0.100841 -0.192346 0.123543 0.968283 1 7.70372e-19 7.70372e-19 9.10485e-09 9.07819e-09 -5.69151e-08 1 7.70372e-19 9.10485e-09 9.07819e-09 -5.69151e-08 1 9.10485e-09 9.07819e-09 -5.69151e-08 4426.93 196.665 -1449.08 3934.04 -199.371 4406.55 +EDGE_SE3:QUAT 1341 1342 -0.817041 11.9508 0.291099 0.0647299 0.0305708 -0.0119343 0.997363 1 2.40741e-19 2.40741e-19 -2.78474e-08 -1.3622e-08 3.89041e-12 1 2.40741e-19 -2.78474e-08 -1.3622e-08 3.89041e-12 1 -2.78474e-08 -1.3622e-08 3.89041e-12 3999.19 8.07634 253.125 3996.01 -0.00695567 4015.38 +EDGE_SE3:QUAT 1342 1343 -0.696889 11.8493 -0.244472 -0.1063 -0.0663888 0.205493 0.970601 1 7.70372e-19 7.70372e-19 9.11056e-10 6.92281e-09 -5.39568e-08 1 7.70372e-19 9.11056e-10 6.92281e-09 -5.39568e-08 1 9.11056e-10 6.92281e-09 -5.39568e-08 3965.67 14.2845 -234.646 4000.74 -17.7063 3841.96 +EDGE_SE3:QUAT 1343 1344 -1.10014 12.1992 -0.316999 -0.24366 0.00176073 -0.0103643 0.969804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3762.56 3.26175 -16.2549 3999.96 0.130892 3999.61 +EDGE_SE3:QUAT 1344 1345 -0.70537 11.7783 -0.269643 -0.200905 0.0183389 0.0694859 0.976971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3860.6 -33.9134 301.144 3992.93 6.90205 4002.74 +EDGE_SE3:QUAT 1345 1346 -0.859128 11.8634 -0.190036 -0.0368069 -0.0488798 -0.0486145 0.996942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.02 4.89585 -414.232 3989.26 8.18566 4032.98 +EDGE_SE3:QUAT 1346 1347 -0.895114 11.6988 -0.241821 -0.134952 0.0722665 0.0404494 0.987385 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.11 -40.9937 640.264 3975.84 -5.87537 4093.41 +EDGE_SE3:QUAT 1347 1348 -0.892283 12.0859 -0.0486565 -0.0438144 0.0663108 0.0837392 0.993313 1 4.81482e-20 4.81482e-20 -1.39264e-08 -1.0988e-09 -1.01653e-09 1 4.81482e-20 -1.39264e-08 -1.0988e-09 -1.01653e-09 1 -1.39264e-08 -1.0988e-09 -1.01653e-09 4074.1 -3.46413 577.852 3979.52 20.6518 4053.73 +EDGE_SE3:QUAT 1348 1349 -0.7597 12.0192 -0.121099 0.0371996 0.222628 -0.0504702 0.972885 1 1.20371e-20 1.20371e-20 -7.50943e-09 2.93447e-10 -1.73636e-09 1 1.20371e-20 -7.50943e-09 2.93447e-10 -1.73636e-09 1 -7.50943e-09 2.93447e-10 -1.73636e-09 4941.08 -16.2114 2163.93 3798.98 -26.8577 4936.43 +EDGE_SE3:QUAT 1349 1350 -0.875809 11.7665 -0.0849328 -0.109615 0.0657185 0.0668816 0.989542 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4043.67 -27.9467 613.006 3976.57 7.93744 4073.84 +EDGE_SE3:QUAT 1350 1351 -0.769571 12.1523 -0.461299 -0.0417446 -0.0160049 -0.0463826 0.997923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.68 2.94224 -150.672 3998.46 3.34714 3997.05 +EDGE_SE3:QUAT 1351 1352 -0.784731 11.995 0.0740601 -0.0433011 0.243011 -0.0701443 0.966515 1 1.15556e-18 1.15556e-18 3.17895e-08 -5.93666e-08 3.26915e-08 1 1.15556e-18 3.17895e-08 -5.93666e-08 3.26915e-08 1 3.17895e-08 -5.93666e-08 3.26915e-08 5046.81 -208.466 2308.68 3804.96 -210.482 5034.63 +EDGE_SE3:QUAT 1352 1353 -0.807904 11.9779 0.00763288 -0.0323216 -0.0633441 -0.089696 0.993427 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4068.29 -0.312199 -543.289 3982.04 22.4194 4040.28 +EDGE_SE3:QUAT 1353 1354 -0.612133 12.0075 -0.224149 -0.116211 -0.111953 0.214508 0.9633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.32 56.369 -527.879 3999.64 -63.9335 3879.28 +EDGE_SE3:QUAT 1354 1355 -0.650906 12.0605 0.346322 -0.0528946 0.00226024 0.043513 0.997649 1 9.62965e-20 9.62965e-20 -1.39408e-08 1.31394e-10 -1.39408e-08 1 9.62965e-20 -1.39408e-08 1.31394e-10 -1.39408e-08 1 -1.39408e-08 1.31394e-10 -1.39408e-08 3989.31 -1.42052 45.4937 3999.81 1.15864 3992.92 +EDGE_SE3:QUAT 1355 1356 -0.795045 11.4842 -0.544725 0.0624663 -0.134753 -0.053663 0.987451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4260.28 -63.2368 -1086.36 3940.1 61.5188 4264.37 +EDGE_SE3:QUAT 1356 1357 -0.781837 11.6897 0.0426935 -0.105052 0.101716 -0.138764 0.979471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.96 -53.912 612.717 3987.7 -58.3094 4013.08 +EDGE_SE3:QUAT 1357 1358 -0.738519 11.8723 0.212522 0.0671346 -0.0767673 0.0316611 0.994282 1 2.40741e-19 2.40741e-19 -5.3373e-10 -2.672e-08 1.57225e-08 1 2.40741e-19 -5.3373e-10 -2.672e-08 1.57225e-08 1 -5.3373e-10 -2.672e-08 1.57225e-08 4084.67 -18.5644 -649.132 3974.69 -0.718242 4098.69 +EDGE_SE3:QUAT 1358 1359 -0.810564 11.4581 -0.100949 -0.1301 0.00617006 0.160137 0.978464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3951.93 -20.9465 290.663 3991.8 27.2167 3917.06 +EDGE_SE3:QUAT 1359 1360 -0.84236 11.8085 0.000632829 -0.137848 0.208418 -0.11046 0.961956 1 7.70372e-19 7.70372e-19 9.65419e-09 5.2876e-08 1.06846e-08 1 7.70372e-19 9.65419e-09 5.2876e-08 1.06846e-08 1 9.65419e-09 5.2876e-08 1.06846e-08 4445.52 -247.658 1541.44 3941.26 -245.198 4472.72 +EDGE_SE3:QUAT 1360 1361 -0.59134 11.9688 0.125646 0.0262909 0.0262321 0.090931 0.995164 1 1.92593e-19 1.92593e-19 -5.83284e-10 -8.51338e-10 -2.7649e-08 1 1.92593e-19 -5.83284e-10 -8.51338e-10 -2.7649e-08 1 -5.83284e-10 -8.51338e-10 -2.7649e-08 4005.18 3.40646 178.784 3998.32 8.04089 3974.87 +EDGE_SE3:QUAT 1361 1362 -0.533321 11.7553 -0.254269 0.0338336 -0.206202 0.186531 0.95997 1 7.82409e-19 7.82409e-19 -5.09702e-09 -1.38452e-09 5.68021e-08 1 7.82409e-19 -5.09702e-09 -1.38452e-09 5.68021e-08 1 -5.09702e-09 -1.38452e-09 5.68021e-08 4762.24 190.872 -1912.2 3864.38 -220.779 4627.64 +EDGE_SE3:QUAT 1362 1363 -0.858149 11.5296 0.178223 0.089198 0.191025 0.0574008 0.975837 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4535.66 151.676 1610.6 3892 146.989 4554.3 +EDGE_SE3:QUAT 1363 1364 -0.842469 11.7074 -0.224625 -0.0826985 -0.0327511 0.103795 0.990613 1 1.92593e-19 1.92593e-19 4.0396e-10 2.43837e-09 -2.75143e-08 1 1.92593e-19 4.0396e-10 2.43837e-09 -2.75143e-08 1 4.0396e-10 2.43837e-09 -2.75143e-08 3978.15 6.08952 -153.282 3999.33 -7.07991 3962.41 +EDGE_SE3:QUAT 1364 1365 -0.372632 11.8034 -0.0528796 -0.202684 0.210623 -0.0576659 0.954584 1 7.70372e-19 7.70372e-19 5.66943e-08 -8.71208e-09 9.78044e-09 1 7.70372e-19 5.66943e-08 -8.71208e-09 9.78044e-09 1 5.66943e-08 -8.71208e-09 9.78044e-09 4380.89 -276.703 1580.5 3947.2 -264.213 4531.91 +EDGE_SE3:QUAT 1365 1366 -0.544846 11.9821 -0.0746945 0.0104346 0.0208821 -0.00768123 0.999698 1 1.57986e-20 1.57986e-20 3.48525e-09 6.89407e-09 -1.73292e-09 1 1.57986e-20 3.48525e-09 6.89407e-09 -1.73292e-09 1 3.48525e-09 6.89407e-09 -1.73292e-09 4006.63 0.802134 168.237 3998.23 -0.539907 4006.83 +EDGE_SE3:QUAT 1366 1367 -0.658746 11.9177 0.0560803 -0.15537 -0.187965 0.129902 0.96107 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4249.69 200.926 -1236.87 3971.71 -198.544 4278.75 +EDGE_SE3:QUAT 1367 1368 -0.579707 11.8599 -0.615649 0.111801 -0.0165312 0.0493337 0.992368 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3959.42 -11.5356 -195.301 3997.19 -3.97369 3999.68 +EDGE_SE3:QUAT 1368 1369 -0.927112 11.9638 -0.0351762 -0.0770593 0.0672124 -0.0372912 0.994059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.67 -23.4065 503.81 3986.01 -17.1277 4056.86 +EDGE_SE3:QUAT 1369 1370 -1.00917 11.8509 -0.112832 0.0606736 -0.046315 -0.0113528 0.997018 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.89 -11.7041 -362.673 3992.19 5.1083 4032.1 +EDGE_SE3:QUAT 1370 1371 -0.92796 12.1011 -0.400094 0.033411 -0.0605803 0.232213 0.970201 1 1.20371e-20 1.20371e-20 -6.79653e-09 -1.60894e-09 4.84035e-10 1 1.20371e-20 -6.79653e-09 -1.60894e-09 4.84035e-10 1 -6.79653e-09 -1.60894e-09 4.84035e-10 4068.27 15.3727 -544.276 3984.69 -64.5215 3857.04 +EDGE_SE3:QUAT 1371 1372 -0.75062 11.8142 -0.0678859 0.109887 0.186466 -0.0178311 0.976134 1 1.94286e-19 1.94286e-19 -2.96528e-08 -1.03652e-09 -8.27528e-09 1 1.94286e-19 -2.96528e-08 -1.03652e-09 -8.27528e-09 1 -2.96528e-08 -1.03652e-09 -8.27528e-09 4568.85 110.342 1688.08 3870.12 88.8159 4615.88 +EDGE_SE3:QUAT 1372 1373 -0.705054 12.0098 -0.221823 0.0434529 -0.0578697 -0.0706189 0.994875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.11 -14.2259 -425.301 3990.05 18.0767 4024.71 +EDGE_SE3:QUAT 1373 1374 -0.865793 12.0069 -0.136549 -0.139449 0.00798072 0.153322 0.978255 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3944.8 -23.8705 310.862 3990.84 26.9725 3928.56 +EDGE_SE3:QUAT 1374 1375 -0.838827 11.6948 0.282295 0.121635 -0.0149954 -0.0959988 0.987808 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3940.38 4.28821 22.23 3999.69 -3.38741 3962.7 +EDGE_SE3:QUAT 1375 1376 -0.388565 11.8253 -0.016288 0.0243335 -0.0874744 0.189367 0.9777 1 7.77143e-19 7.77143e-19 -8.10246e-11 -4.32585e-10 -5.47139e-08 1 7.77143e-19 -8.10246e-11 -4.32585e-10 -5.47139e-08 1 -8.10246e-11 -4.32585e-10 -5.47139e-08 4129.18 28.4263 -737.27 3972.19 -71.4774 3988.11 +EDGE_SE3:QUAT 1376 1377 -0.854107 12.106 -0.121698 -0.165538 0.0403741 0.0781519 0.982273 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.37 -37.8167 464.986 3985.26 8.67555 4028.55 +EDGE_SE3:QUAT 1377 1378 -0.894704 11.8962 -0.117982 -0.191192 0.0416733 0.0191524 0.980481 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3886.04 -35.0745 360.671 3992.76 -5.56945 4030.79 +EDGE_SE3:QUAT 1378 1379 -0.549141 11.8376 -0.386527 -0.0830045 -0.00329263 -0.0965512 0.991855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.86 5.98476 -120.943 3998.57 7.07124 3966.13 +EDGE_SE3:QUAT 1379 1380 -0.754313 11.5103 -0.174536 -0.0561008 -0.260724 -0.0376451 0.963046 1 2.40741e-19 2.40741e-19 3.52563e-08 3.46524e-10 -2.39823e-08 1 2.40741e-19 3.52563e-08 3.46524e-10 -2.39823e-08 1 3.52563e-08 3.46524e-10 -2.39823e-08 5369.47 46.5784 -2727.33 3725.59 -41.9395 5376.39 +EDGE_SE3:QUAT 1380 1381 -1.05896 11.9294 -0.247476 -0.00152287 0.0715197 0.0851741 0.993795 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4081.72 10.1572 577.605 3980.61 25.6676 4052.72 +EDGE_SE3:QUAT 1381 1382 -0.691177 11.8758 -0.106356 0.072575 0.0181681 0.0516847 0.995857 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.31 3.26129 98.8622 3999.59 2.48263 3991.69 +EDGE_SE3:QUAT 1382 1383 -0.827881 11.8735 0.083847 0.148362 0.0134077 0.154434 0.976708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3916.96 -18.7278 -166.748 3995.82 -19.5446 3909.6 +EDGE_SE3:QUAT 1383 1384 -0.960499 11.7295 -0.463139 0.0438395 0.182445 0.0969108 0.977446 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4512.68 127.804 1534.21 3898.24 136.24 4482.8 +EDGE_SE3:QUAT 1384 1385 -0.774218 12.2295 0.0900989 0.0303836 -0.026303 -0.119817 0.991982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.83 -3.59219 -162.535 3998.8 9.16423 3949.09 +EDGE_SE3:QUAT 1385 1386 -0.398492 11.805 -0.398346 0.121161 0.0838756 -0.040906 0.988237 1 2.0463e-19 2.0463e-19 -2.72381e-08 1.37793e-09 4.39982e-09 1 2.0463e-19 -2.72381e-08 1.37793e-09 4.39982e-09 1 -2.72381e-08 1.37793e-09 4.39982e-09 4072.03 41.0528 734.962 3968.51 7.08689 4124.05 +EDGE_SE3:QUAT 1386 1387 -1.0194 11.8679 0.0325159 -0.0288541 0.0555304 0.124007 0.990306 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.99 3.13314 482.285 3986 29.2015 3995.81 +EDGE_SE3:QUAT 1387 1388 -0.684841 11.439 -0.157851 0.115079 0.0289636 0.216255 0.969098 1 9.63153e-19 9.63153e-19 2.54402e-08 1.33281e-08 5.3054e-08 1 9.63153e-19 2.54402e-08 1.33281e-08 5.3054e-08 1 2.54402e-08 1.33281e-08 5.3054e-08 3945.9 -10.5855 -75.6304 3997.93 -19.7689 3811.81 +EDGE_SE3:QUAT 1388 1389 -1.1695 12.0802 -0.122664 -0.0951465 -0.0699913 -0.123289 0.985316 1 1.92593e-19 1.92593e-19 2.77575e-08 -3.07586e-09 -2.53708e-09 1 1.92593e-19 2.77575e-08 -3.07586e-09 -2.53708e-09 1 2.77575e-08 -3.07586e-09 -2.53708e-09 4081.81 16.7028 -697.956 3969.35 32.4692 4057.22 +EDGE_SE3:QUAT 1389 1390 -1.15803 11.7674 -0.187289 0.0361103 -0.0166564 0.00683982 0.999186 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.41 -2.43346 -136.082 3998.84 -0.221282 4004.44 +EDGE_SE3:QUAT 1390 1391 -0.961634 11.6714 -0.128021 -0.0612735 0.0451947 0.160847 0.984038 1 7.70372e-19 7.70372e-19 3.46758e-09 -2.46022e-09 5.50019e-08 1 7.70372e-19 3.46758e-09 -2.46022e-09 5.50019e-08 1 3.46758e-09 -2.46022e-09 5.50019e-08 4038.78 -3.7727 467.812 3985.82 36.9131 3950.31 +EDGE_SE3:QUAT 1391 1392 -0.877875 12.0444 -0.0799373 -0.120711 -0.0280661 0.15928 0.979424 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3940.18 -5.69315 13.5208 3999.48 7.53764 3896.98 +EDGE_SE3:QUAT 1392 1393 -0.571837 11.5521 0.0605181 0.17812 0.0673419 0.134417 0.972456 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3881.86 14.3722 219.32 4000.9 13.2697 3936.5 +EDGE_SE3:QUAT 1393 1394 -0.30515 11.7381 -0.169421 -0.00761513 -0.0144997 0.148481 0.98878 1 7.76391e-19 7.76391e-19 -3.56086e-09 -4.58746e-09 5.49056e-08 1 7.76391e-19 -3.56086e-09 -4.58746e-09 5.49056e-08 1 -3.56086e-09 -4.58746e-09 5.49056e-08 4002.2 0.947482 -98.8486 3999.52 -6.95021 3914.24 +EDGE_SE3:QUAT 1394 1395 -0.756818 11.8372 0.0289138 0.0158957 -0.0239197 0.0325937 0.999056 1 1.50463e-20 1.50463e-20 3.69144e-09 -6.82186e-09 1.29006e-11 1 1.50463e-20 3.69144e-09 -6.82186e-09 1.29006e-11 1 3.69144e-09 -6.82186e-09 1.29006e-11 4008.73 -1.12521 -197.622 3997.53 -3.04288 4005.49 +EDGE_SE3:QUAT 1395 1396 -0.490351 11.8601 -0.151985 0.0504109 0.141805 -0.118367 0.981499 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4362.55 -28.2539 1276.65 3914.96 -64.7514 4316.68 +EDGE_SE3:QUAT 1396 1397 -0.440808 11.6621 -0.257244 0.153324 -0.0763963 0.150265 0.973692 1 7.70372e-19 7.70372e-19 6.5393e-09 -7.1576e-09 -5.53249e-08 1 7.70372e-19 6.5393e-09 -7.1576e-09 -5.53249e-08 1 6.5393e-09 -7.1576e-09 -5.53249e-08 4088.98 -41.816 -877.159 3951.5 -39.4511 4092.7 +EDGE_SE3:QUAT 1397 1398 -1.00703 11.5905 -0.192561 -0.173301 -0.0132677 0.0823569 0.98133 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3880.18 -10.8864 66.7428 3999.01 5.14906 3973.18 +EDGE_SE3:QUAT 1398 1399 -0.914357 11.4839 -0.59627 0.00339182 0.0134841 -0.0266448 0.999548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.92 0.0675615 108.911 3999.26 -1.44303 4000.12 +EDGE_SE3:QUAT 1399 1400 -0.606999 11.3406 -0.478036 0.0354094 0.0773642 0.0522396 0.995004 1 1.92593e-19 1.92593e-19 1.61596e-09 -2.76077e-08 1.21446e-09 1 1.92593e-19 1.61596e-09 -2.76077e-08 1.21446e-09 1 1.61596e-09 -2.76077e-08 1.21446e-09 4084.24 18.4168 604.245 3979.19 21.4071 4078.34 +EDGE_SE3:QUAT 1400 1401 -0.813246 11.7949 0.0970941 -0.132141 0.0477306 0.126738 0.981936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.38 -29.839 570.857 3977.48 27.4982 4014.98 +EDGE_SE3:QUAT 1401 1402 -0.876622 11.9155 -0.260463 -0.0618175 0.0481603 0.109602 0.990882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.38 -7.29155 462.48 3986.14 22.8246 4004.62 +EDGE_SE3:QUAT 1402 1403 -0.796753 11.701 -0.265499 0.0798635 0.0359852 -0.0271474 0.995786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.74 12.0087 312.454 3993.81 -1.57997 4021.3 +EDGE_SE3:QUAT 1403 1404 -0.780579 11.7398 0.00924302 0.0885432 0.0215458 0.0357727 0.995197 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3972.96 5.55146 132.318 3999.17 2.79867 3999.2 +EDGE_SE3:QUAT 1404 1405 -1.14117 11.9058 0.186211 -0.24344 -0.0242777 0.183067 0.952173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3784.33 -60.3806 335.483 3983.63 43.4749 3887.33 +EDGE_SE3:QUAT 1405 1406 -0.647918 11.7203 -0.0443341 -0.0331395 -0.0389833 0.0567698 0.997075 1 4.81482e-20 4.81482e-20 1.38731e-08 8.26384e-10 -4.85274e-10 1 4.81482e-20 1.38731e-08 8.26384e-10 -4.85274e-10 1 1.38731e-08 8.26384e-10 -4.85274e-10 4016.29 6.55441 -288.54 3995.24 -9.15047 4007.8 +EDGE_SE3:QUAT 1406 1407 -0.863845 11.6125 0.0435487 -0.0184821 -0.045099 0.220211 0.974234 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.06 10.2993 -288.403 3997.03 -30.1623 3826.46 +EDGE_SE3:QUAT 1407 1408 -0.86746 11.6055 -0.140219 -0.0588623 -0.0549181 -0.237314 0.968092 1 2.40741e-19 2.40741e-19 -2.0003e-08 -2.36668e-08 3.04683e-10 1 2.40741e-19 -2.0003e-08 -2.36668e-08 3.04683e-10 1 -2.0003e-08 -2.36668e-08 3.04683e-10 4066.48 -8.07539 -573.093 3981.04 69.4971 3855.07 +EDGE_SE3:QUAT 1408 1409 -0.86622 11.5264 -0.677457 0.111378 -0.061085 0.142382 0.981627 1 1.92593e-19 1.92593e-19 2.76237e-08 3.56509e-09 -2.49346e-09 1 1.92593e-19 2.76237e-08 3.56509e-09 -2.49346e-09 1 2.76237e-08 3.56509e-09 -2.49346e-09 4058.85 -21.2654 -669.146 3970.75 -37.7436 4027.38 +EDGE_SE3:QUAT 1409 1410 -0.642989 11.5008 0.0593539 -0.0438418 -0.0476123 0.0440281 0.996932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.06 10.0117 -357.911 3992.63 -10.0358 4024 +EDGE_SE3:QUAT 1410 1411 -0.976086 11.653 -0.0424417 -0.0153441 0.083352 0.0304989 0.995935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4114.17 -0.361607 688.247 3971.8 8.61866 4111.39 +EDGE_SE3:QUAT 1411 1412 -0.936858 11.8051 0.167332 0.107383 -0.0894009 -0.0339894 0.989606 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.9 -43.8642 -672.911 3976.53 30.8298 4105.41 +EDGE_SE3:QUAT 1412 1413 -0.75068 11.9434 -0.175362 0.191498 -0.0380063 0.232945 0.952691 1 7.70372e-19 7.70372e-19 -6.61094e-09 8.76931e-09 5.39535e-08 1 7.70372e-19 -6.61094e-09 8.76931e-09 5.39535e-08 1 -6.61094e-09 8.76931e-09 5.39535e-08 4002.99 -54.1871 -798.366 3951.85 -82.7588 3932.62 +EDGE_SE3:QUAT 1413 1414 -0.585498 11.8092 -0.195793 -0.000930179 0.15256 -0.0953787 0.983681 1 1.20371e-20 1.20371e-20 7.1516e-09 -7.29388e-10 1.08662e-09 1 1.20371e-20 7.1516e-09 -7.29388e-10 1.08662e-09 1 7.1516e-09 -7.29388e-10 1.08662e-09 4387.31 -59.326 1303.62 3915.09 -77.8855 4350.92 +EDGE_SE3:QUAT 1414 1415 -0.780416 11.7157 -0.186194 0.00737312 -0.0639553 -0.00600077 0.997907 1 7.52316e-22 7.52316e-22 -1.74534e-09 1.22403e-11 1.11681e-10 1 7.52316e-22 -1.74534e-09 1.22403e-11 1.11681e-10 1 -1.74534e-09 1.22403e-11 1.11681e-10 4065.88 -2.59252 -518.42 3983.7 2.35878 4065.95 +EDGE_SE3:QUAT 1415 1416 -0.707036 11.5217 -0.287263 0.0329965 -0.0209811 0.268565 0.962468 1 4.81482e-20 4.81482e-20 1.33852e-08 3.71301e-09 -4.86651e-10 1 4.81482e-20 1.33852e-08 3.71301e-09 -4.86651e-10 1 1.33852e-08 3.71301e-09 -4.86651e-10 4011.37 1.0381 -251.967 3996.07 -37.3013 3727.22 +EDGE_SE3:QUAT 1416 1417 -1.04748 11.4493 0.116663 0.0488864 0.0367022 -0.044194 0.997151 1 4.81482e-20 4.81482e-20 5.62417e-10 1.38404e-08 -6.32798e-10 1 4.81482e-20 5.62417e-10 1.38404e-08 -6.32798e-10 1 5.62417e-10 1.38404e-08 -6.32798e-10 4015.77 6.49378 319.42 3993.46 -5.54054 4017.52 +EDGE_SE3:QUAT 1417 1418 -0.539967 11.733 -0.0157161 -0.0629626 0.0955006 0.0667608 0.99119 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4151.52 -12.7179 835.246 3958.89 15.4474 4149.55 +EDGE_SE3:QUAT 1418 1419 -0.967907 11.4697 -0.408962 0.220168 0.120585 0.0397121 0.967165 1 1.92593e-19 1.92593e-19 2.56452e-09 6.65871e-09 2.73976e-08 1 1.92593e-19 2.56452e-09 6.65871e-09 2.73976e-08 1 2.56452e-09 6.65871e-09 2.73976e-08 3963.53 105.48 813.332 3979.72 77.9063 4151.12 +EDGE_SE3:QUAT 1419 1420 -1.02075 11.6301 -0.124687 0.104962 0.0358537 0.101716 0.988611 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3961.09 6.84215 151.249 3999.54 6.70947 3963.77 +EDGE_SE3:QUAT 1420 1421 -0.849694 11.8343 -0.156504 0.00328204 0.00273271 0.100282 0.99495 1 1.88079e-22 1.88079e-22 -8.6299e-10 -8.69966e-11 -1.75446e-12 1 1.88079e-22 -8.6299e-10 -8.69966e-11 -1.75446e-12 1 -8.6299e-10 -8.69966e-11 -1.75446e-12 4000.03 0.0395528 17.6096 3999.98 0.811875 3959.85 +EDGE_SE3:QUAT 1421 1422 -0.777751 11.7835 -0.448561 -0.0588177 -0.0950287 0.00391902 0.993728 1 4.81482e-20 4.81482e-20 -1.40407e-08 -2.15836e-10 1.32653e-09 1 4.81482e-20 -1.40407e-08 -2.15836e-10 1.32653e-09 1 -1.40407e-08 -2.15836e-10 1.32653e-09 4131.92 25.8433 -777.374 3965.33 -14.8166 4145.7 +EDGE_SE3:QUAT 1422 1423 -0.452856 11.2252 0.146936 -0.0814365 -0.137998 -0.0267272 0.986717 1 7.70372e-19 7.70372e-19 -2.42333e-10 -5.47933e-08 -4.2771e-09 1 7.70372e-19 -2.42333e-10 -5.47933e-08 -4.2771e-09 1 -2.42333e-10 -5.47933e-08 -4.2771e-09 4305.88 45.4609 -1200.05 3923.02 -22.5625 4329.55 +EDGE_SE3:QUAT 1423 1424 -0.908857 11.25 -0.233025 -0.0376842 0.0542529 0.23805 0.969004 1 8.30557e-19 8.30557e-19 6.37962e-09 -1.13402e-08 -5.39008e-08 1 8.30557e-19 6.37962e-09 -1.13402e-08 -5.39008e-08 1 6.37962e-09 -1.13402e-08 -5.39008e-08 4057.84 11.7856 508.102 3986.24 62.0798 3836.85 +EDGE_SE3:QUAT 1424 1425 -0.556917 11.181 0.15026 -0.101574 -0.167942 0.0330872 0.979992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4399.12 114.364 -1398.78 3910.92 -102.391 4436.01 +EDGE_SE3:QUAT 1425 1426 -0.525769 11.7846 0.173986 -0.13228 0.00567537 0.123192 0.983511 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3942.92 -18.147 235.289 3994.64 16.6523 3952.2 +EDGE_SE3:QUAT 1426 1427 -1.01377 11.4554 -0.355423 -0.0180318 -0.101233 0.00256815 0.994696 1 2.0463e-19 2.0463e-19 6.87059e-09 2.76527e-08 -1.90362e-10 1 2.0463e-19 6.87059e-09 2.76527e-08 -1.90362e-10 1 6.87059e-09 2.76527e-08 -1.90362e-10 4167.43 9.04193 -838.682 3959.21 -5.84794 4168.7 +EDGE_SE3:QUAT 1427 1428 -0.659785 11.782 -0.318306 0.035687 0.0550902 0.081172 0.994536 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.28 12.373 404.191 3991.04 18.6177 4014.02 +EDGE_SE3:QUAT 1428 1429 -0.69495 11.3061 -0.424842 -0.010304 0.0758412 -0.0698554 0.994617 1 1.92593e-19 1.92593e-19 2.00411e-09 2.76015e-08 5.82251e-10 1 1.92593e-19 2.00411e-09 2.76015e-08 5.82251e-10 1 2.00411e-09 2.76015e-08 5.82251e-10 4089.08 -12.8771 605.02 3978.84 -23.6507 4069.98 +EDGE_SE3:QUAT 1429 1430 -0.855398 11.506 -0.0461569 0.279726 0.175343 0.181538 0.926311 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3742.28 92.4939 576.497 4031.63 96.8001 3923.44 +EDGE_SE3:QUAT 1430 1431 -0.884768 11.6401 -0.230654 -0.0388257 -0.0632652 0.236405 0.968815 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.9 20.0608 -358.421 3997 -39.7848 3807.38 +EDGE_SE3:QUAT 1431 1432 -0.84099 11.9162 -0.00697878 -0.0182671 0.159477 0.0183482 0.986862 1 1.20371e-20 1.20371e-20 -7.21673e-09 -9.69838e-11 -1.1698e-09 1 1.20371e-20 -7.21673e-09 -9.69838e-11 -1.1698e-09 1 -7.21673e-09 -9.69838e-11 -1.1698e-09 4441.12 -3.55995 1402 3897.78 3.68885 4441.11 +EDGE_SE3:QUAT 1432 1433 -0.841839 11.5642 -0.00090714 -0.0683344 -0.20414 -0.047996 0.975374 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4769.77 36.3343 -1943.05 3828.7 -18.7452 4779.23 +EDGE_SE3:QUAT 1433 1434 -0.427458 11.6622 -0.391146 -0.0469252 -0.107081 0.080508 0.989874 1 3.85186e-19 3.85186e-19 -2.5484e-08 -3.00565e-08 9.62867e-10 1 3.85186e-19 -2.5484e-08 -3.00565e-08 9.62867e-10 1 -2.5484e-08 -3.00565e-08 9.62867e-10 4155.49 42.1924 -827.498 3964.31 -48.5743 4138.37 +EDGE_SE3:QUAT 1434 1435 -0.965809 11.2915 -0.563643 0.0134676 0.016347 0.0791022 0.996641 1 3.00927e-21 3.00927e-21 3.45928e-09 2.7612e-10 4.86323e-11 1 3.00927e-21 3.45928e-09 2.7612e-10 4.86323e-11 1 3.45928e-09 2.7612e-10 4.86323e-11 4002.68 1.18538 116.864 3999.24 4.52111 3978.38 +EDGE_SE3:QUAT 1435 1436 -0.801406 11.1768 -0.0425545 -0.125459 -0.0697131 0.00855101 0.989609 1 1.20371e-20 1.20371e-20 -4.57437e-10 -8.95125e-10 6.92893e-09 1 1.20371e-20 -4.57437e-10 -8.95125e-10 6.92893e-09 1 -4.57437e-10 -8.95125e-10 6.92893e-09 4008.57 35.9384 -539.838 3984.22 -16.3822 4071.24 +EDGE_SE3:QUAT 1436 1437 -0.930705 10.9631 -0.0198899 0.0105369 -0.200348 0.198235 0.959402 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4655.38 207.083 -1748.46 3895.13 -234.96 4498.64 +EDGE_SE3:QUAT 1437 1438 -0.437539 11.5849 -0.168648 0.0106804 0.0983271 0.0723072 0.992466 1 1.92593e-19 1.92593e-19 2.10415e-09 -2.75392e-08 6.98253e-10 1 1.92593e-19 2.10415e-09 -2.75392e-08 6.98253e-10 1 2.10415e-09 -2.75392e-08 6.98253e-10 4152.28 21.7202 796.459 3964.4 34.0247 4131.83 +EDGE_SE3:QUAT 1438 1439 -0.833341 11.384 -0.160375 0.0158131 -0.222505 0.139203 0.964813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4894.92 184.217 -2094.57 3833.02 -201.594 4818.41 +EDGE_SE3:QUAT 1439 1440 -0.6312 11.3132 0.0405857 0.006412 0.162971 0.0312125 0.986116 1 4.81482e-20 4.81482e-20 -2.37636e-09 -2.54235e-10 -1.4448e-08 1 4.81482e-20 -2.37636e-09 -2.54235e-10 -1.4448e-08 1 -2.37636e-09 -2.54235e-10 -1.4448e-08 4457.66 28.4662 1428.6 3895.51 33.2684 4453.92 +EDGE_SE3:QUAT 1440 1441 -0.780016 11.4811 0.134645 0.098549 -0.00945326 0.120436 0.987772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3972.06 -11.3402 -213.646 3995.94 -14.4742 3952.89 +EDGE_SE3:QUAT 1441 1442 -0.856117 11.041 -0.197342 -0.128407 -0.0942449 -0.0151093 0.987118 1 1.88079e-22 1.88079e-22 -8.39088e-11 -1.12961e-10 8.72126e-10 1 1.88079e-22 -8.39088e-11 -1.12961e-10 8.72126e-10 1 -8.39088e-11 -1.12961e-10 8.72126e-10 4081.85 51.7931 -783.008 3966.38 -22.6233 4146.89 +EDGE_SE3:QUAT 1442 1443 -0.446768 11.3634 -0.00507972 0.199342 -0.277775 -0.0371371 0.939002 1 7.70372e-19 7.70372e-19 5.96283e-08 -1.0322e-08 -1.48034e-08 1 7.70372e-19 5.96283e-08 -1.0322e-08 -1.48034e-08 1 5.96283e-08 -1.0322e-08 -1.48034e-08 5002.57 -518.42 -2453.88 3912.72 522.418 5156 +EDGE_SE3:QUAT 1443 1444 -0.908044 11.2755 -0.42075 0.0261313 0.0784113 0.0557891 0.995016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4090.65 16.5354 618.308 3978.07 21.8978 4080.93 +EDGE_SE3:QUAT 1444 1445 -0.810804 11.3379 -0.0221282 0.109542 0.0202016 0.206216 0.972146 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3953.19 -11.2119 -112.687 3997.32 -21.3151 3831.09 +EDGE_SE3:QUAT 1445 1446 -0.856292 11.3007 0.0640337 0.0290303 0.0230231 0.0278949 0.998924 1 2.40741e-20 2.40741e-20 -5.45653e-11 7.14161e-09 6.72777e-09 1 2.40741e-20 -5.45653e-11 7.14161e-09 6.72777e-09 1 -5.45653e-11 7.14161e-09 6.72777e-09 4004.21 2.8201 174.305 3998.19 2.73583 4004.47 +EDGE_SE3:QUAT 1446 1447 -0.997344 11.3829 -0.177959 -0.0182696 -0.036897 0.222516 0.974059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.25 6.86013 -226.643 3998.29 -23.2469 3814.54 +EDGE_SE3:QUAT 1447 1448 -0.614506 11.2917 0.163546 0.104443 -0.0781292 0.216158 0.967607 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4137.38 1.07125 -871.404 3954.97 -84.8534 3994.11 +EDGE_SE3:QUAT 1448 1449 -0.908523 11.1493 -0.27704 -0.185041 -0.00998177 -0.123154 0.974933 1 2.40741e-19 2.40741e-19 5.61334e-11 8.61512e-09 2.96187e-08 1 2.40741e-19 5.61334e-11 8.61512e-09 2.96187e-08 1 5.61334e-11 8.61512e-09 2.96187e-08 3890.36 36.3082 -340.957 3989.28 21.0062 3966.65 +EDGE_SE3:QUAT 1449 1450 -0.797609 11.7971 0.314283 -0.117226 0.108235 0.126333 0.979073 1 5.77779e-19 5.77779e-19 2.71108e-08 -2.18114e-08 -2.67873e-08 1 5.77779e-19 2.71108e-08 -2.18114e-08 -2.67873e-08 1 2.71108e-08 -2.18114e-08 -2.67873e-08 4211.42 -25.5865 1066.68 3934.62 34.9657 4202.55 +EDGE_SE3:QUAT 1450 1451 -0.754246 11.2665 -0.203515 0.0599129 0.0822882 0.138527 0.985114 1 7.70372e-19 7.70372e-19 3.46358e-09 4.54108e-09 5.51889e-08 1 7.70372e-19 3.46358e-09 4.54108e-09 5.51889e-08 1 3.46358e-09 4.54108e-09 5.51889e-08 4057.86 33.0861 544.438 3987.24 44.434 3995.46 +EDGE_SE3:QUAT 1451 1452 -1.16826 11.3334 -0.0236488 -0.0805266 0.00880158 -0.0839503 0.993172 1 1.92593e-19 1.92593e-19 -1.35064e-10 -2.24433e-09 2.75655e-08 1 1.92593e-19 -1.35064e-10 -2.24433e-09 2.75655e-08 1 -1.35064e-10 -2.24433e-09 2.75655e-08 3973.91 1.56868 -11.4069 3999.91 1.63527 3971.66 +EDGE_SE3:QUAT 1452 1453 -0.843345 11.0944 -0.115928 -0.0488356 0.0068435 0.272135 0.960995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.06 -3.13717 200.472 3996.54 33.7469 3713.37 +EDGE_SE3:QUAT 1453 1454 -1.07737 11.173 -0.00863676 0.00141198 -0.0519034 -0.0768625 0.995689 1 4.89006e-20 4.89006e-20 -6.61998e-10 1.39524e-08 -4.12487e-11 1 4.89006e-20 -6.61998e-10 1.39524e-08 -4.12487e-11 1 -6.61998e-10 1.39524e-08 -4.12487e-11 4042.4 -5.25409 -414.035 3989.83 16.3866 4018.77 +EDGE_SE3:QUAT 1454 1455 -0.741914 11.4024 -0.43653 0.0487908 -0.155205 0.0308045 0.986196 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4414.98 -21.8445 -1370.49 3901.78 5.71058 4420.71 +EDGE_SE3:QUAT 1455 1456 -0.72549 11.0362 -0.332904 0.0831324 -0.0912897 0.326601 0.937063 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4192.3 58.568 -963.486 3960.8 -161.933 3793.27 +EDGE_SE3:QUAT 1456 1457 -0.743298 11.298 -0.250727 0.00289362 -0.0371919 -0.120282 0.992039 1 7.52316e-22 7.52316e-22 -1.72542e-09 2.10145e-10 6.16025e-11 1 7.52316e-22 -1.72542e-09 2.10145e-10 6.16025e-11 1 -1.72542e-09 2.10145e-10 6.16025e-11 4020.62 -4.24392 -288.23 3995.3 17.4572 3962.78 +EDGE_SE3:QUAT 1457 1458 -0.987365 11.4132 -0.180793 -0.144417 -0.15741 0.0380664 0.976175 1 9.62965e-19 9.62965e-19 -6.05782e-08 -9.65817e-09 3.63071e-08 1 9.62965e-19 -6.05782e-08 -9.65817e-09 3.63071e-08 1 -6.05782e-08 -9.65817e-09 3.63071e-08 4265.75 130.413 -1233.56 3936.76 -112.342 4343.38 +EDGE_SE3:QUAT 1458 1459 -0.935642 10.956 -0.205974 0.0492773 0.114338 0.187711 0.974301 1 1.15556e-18 1.15556e-18 2.68431e-08 3.77673e-08 5.50562e-08 1 1.15556e-18 2.68431e-08 3.77673e-08 5.50562e-08 1 2.68431e-08 3.77673e-08 5.50562e-08 4133.67 66.5301 774.152 3978.55 88.1322 4002.44 +EDGE_SE3:QUAT 1459 1460 -0.416157 11.1497 -0.264188 -0.00365335 0.0191995 0.0941141 0.99537 1 1.9264e-19 1.9264e-19 -1.10863e-10 4.05786e-11 -2.76397e-08 1 1.9264e-19 -1.10863e-10 4.05786e-11 -2.76397e-08 1 -1.10863e-10 4.05786e-11 -2.76397e-08 4006.01 0.568382 155.868 3998.53 7.36312 3970.63 +EDGE_SE3:QUAT 1460 1461 -0.911391 11.4255 -0.11047 -0.217224 -0.0305526 -0.0514947 0.974284 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3843.04 41.6373 -359.135 3991.5 1.09915 4021.18 +EDGE_SE3:QUAT 1461 1462 -0.645793 11.2532 -0.118781 -0.0247348 -0.127182 -0.00967544 0.991524 1 1.27894e-20 1.27894e-20 -6.88253e-09 6.66929e-11 -8.63398e-10 1 1.27894e-20 -6.88253e-09 6.66929e-11 -8.63398e-10 1 -6.88253e-09 6.66929e-11 -8.63398e-10 4270.55 11.5929 -1080.06 3935.12 -4.30351 4272.62 +EDGE_SE3:QUAT 1462 1463 -0.685568 11.401 0.150094 0.0211199 -0.218498 0.0919137 0.971269 1 4.23178e-22 4.23178e-22 1.39847e-09 1.32038e-10 -3.1472e-10 1 4.23178e-22 1.39847e-09 1.32038e-10 -3.1472e-10 1 1.39847e-09 1.32038e-10 -3.1472e-10 4889.17 101.677 -2087.5 3816.81 -115.827 4857.16 +EDGE_SE3:QUAT 1463 1464 -0.771922 11.3623 -0.263855 -0.0548064 0.0772734 0.0126856 0.995422 1 3.00927e-21 3.00927e-21 -2.74617e-10 1.87842e-10 -3.49619e-09 1 3.00927e-21 -2.74617e-10 1.87842e-10 -3.49619e-09 1 -2.74617e-10 1.87842e-10 -3.49619e-09 4087.04 -16.7261 637.2 3975.83 -3.90323 4098.41 +EDGE_SE3:QUAT 1464 1465 -0.978873 11.4115 -0.136335 0.00367019 0.0710117 -0.0668255 0.995228 1 1.88079e-22 1.88079e-22 -8.72029e-10 5.86911e-11 -6.20924e-11 1 1.88079e-22 -8.72029e-10 5.86911e-11 -6.20924e-11 1 -8.72029e-10 5.86911e-11 -6.20924e-11 4081.61 -7.17169 577.356 3980.28 -19.8558 4063.8 +EDGE_SE3:QUAT 1465 1466 -1.14272 10.8813 -0.27748 -0.061506 -0.0922031 -0.057561 0.992171 1 4.81482e-20 4.81482e-20 -1.40328e-08 6.60458e-10 1.38726e-09 1 4.81482e-20 -1.40328e-08 6.60458e-10 1.38726e-09 1 -1.40328e-08 6.60458e-10 1.38726e-09 4138.54 14.0247 -799.003 3962.2 11.3657 4140.42 +EDGE_SE3:QUAT 1466 1467 -0.901569 11.2315 -0.290935 -0.106054 -0.0524781 0.0296576 0.992532 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.22 21.3926 -377.354 3992.47 -11.4967 4031.69 +EDGE_SE3:QUAT 1467 1468 -0.655011 11.3146 -0.174995 0.0812862 0.160712 -0.0966518 0.978888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4475.05 4.92226 1502.54 3885.21 -32.0902 4464.11 +EDGE_SE3:QUAT 1468 1469 -0.627427 11.6103 -0.10505 -0.0611084 0.0151578 0.172918 0.982922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.1 -5.60063 240.057 3995.44 23.2951 3894.44 +EDGE_SE3:QUAT 1469 1470 -0.493205 11.4147 0.0163236 0.142918 0.101832 -0.0513362 0.983143 1 4.81482e-20 4.81482e-20 1.59247e-09 1.9189e-09 1.39861e-08 1 4.81482e-20 1.59247e-09 1.9189e-09 1.39861e-08 1 1.59247e-09 1.9189e-09 1.39861e-08 4117.12 59.4412 913.756 3953.38 15.8193 4188.28 +EDGE_SE3:QUAT 1470 1471 -1.00623 10.964 0.0901595 -0.0766552 0.105312 0.0371884 0.990783 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4171.88 -28.267 905.404 3952.95 -3.66339 4189.85 +EDGE_SE3:QUAT 1471 1472 -1.03094 11.3746 -0.150045 -0.140668 0.122993 0.0269421 0.982018 1 3.00927e-21 3.00927e-21 4.50062e-10 -4.95508e-10 3.51919e-09 1 3.00927e-21 4.50062e-10 -4.95508e-10 3.51919e-09 1 4.50062e-10 -4.95508e-10 3.51919e-09 4183.11 -76.2837 1057.28 3941.95 -40.4526 4259.36 +EDGE_SE3:QUAT 1472 1473 -1.06602 10.5204 -0.549289 0.0951927 0.0817073 0.0211491 0.991874 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.5 34.8482 633.06 3978.04 21.5727 4095.96 +EDGE_SE3:QUAT 1473 1474 -0.792047 11.0482 -0.0509574 0.0726809 0.169178 0.081363 0.979529 1 1.92593e-19 1.92593e-19 2.86089e-08 3.23328e-09 4.44785e-09 1 1.92593e-19 2.86089e-08 3.23328e-09 4.44785e-09 1 2.86089e-08 3.23328e-09 4.44785e-09 4401.2 119.513 1367.4 3918.25 120.96 4395.85 +EDGE_SE3:QUAT 1474 1475 -0.42737 11.2163 -0.0331223 0.0685845 -0.0755814 0.0648112 0.992665 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4089.06 -14.5461 -665.816 3972.94 -12.5766 4091.08 +EDGE_SE3:QUAT 1475 1476 -0.782015 10.6666 -0.00265538 0.220146 0.0519252 0.0464059 0.972978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3822.92 25.6879 265.974 3998.6 12.6035 4008.17 +EDGE_SE3:QUAT 1476 1477 -0.851719 11.2183 -0.312702 -0.0249523 0.0999696 0.154954 0.982534 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4169.74 29.112 847.704 3961.81 66.861 4076.19 +EDGE_SE3:QUAT 1477 1478 -0.565498 11.0968 -0.115667 -0.105264 0.0810113 0.138443 0.981423 1 7.70372e-19 7.70372e-19 -5.96502e-09 4.55871e-09 -5.56023e-08 1 7.70372e-19 -5.96502e-09 4.55871e-09 -5.56023e-08 1 -5.96502e-09 4.55871e-09 -5.56023e-08 4117.69 -17.8524 822.09 3958.55 41.2156 4085.35 +EDGE_SE3:QUAT 1478 1479 -0.820304 10.698 -0.1928 0.0389842 0.130871 -0.00700646 0.990608 1 4.70198e-23 4.70198e-23 -5.88414e-11 -1.72841e-11 -4.44896e-10 1 4.70198e-23 -5.88414e-11 -1.72841e-11 -4.44896e-10 1 -5.88414e-11 -1.72841e-11 -4.44896e-10 4283.24 22.5574 1114 3931.77 12.8585 4289.13 +EDGE_SE3:QUAT 1479 1480 -0.662467 11.0745 -0.401253 0.147996 -0.122495 0.115382 0.974566 1 1.92593e-19 1.92593e-19 4.30269e-09 -3.49396e-09 -2.82239e-08 1 1.92593e-19 4.30269e-09 -3.49396e-09 -2.82239e-08 1 4.30269e-09 -3.49396e-09 -2.82239e-08 4256.55 -53.5109 -1223.33 3917.71 -12.1078 4290.91 +EDGE_SE3:QUAT 1480 1481 -0.979444 10.9732 -0.127935 0.0103153 -0.101951 -0.110432 0.988587 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4158.74 -32.0958 -813.761 3964.71 51.7815 4110.38 +EDGE_SE3:QUAT 1481 1482 -0.602418 11.2414 -0.211614 0.0279743 0.0188434 0.0854491 0.995771 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.47 2.0674 120.463 3999.28 4.89706 3974.39 +EDGE_SE3:QUAT 1482 1483 -0.676337 11.2797 -0.0364581 -0.0278372 -0.000547532 0.124001 0.991891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.19 -0.668673 36.7041 3999.84 3.12615 3938.79 +EDGE_SE3:QUAT 1483 1484 -0.868023 11.4778 0.0730646 0.0648847 0.136059 0.0273842 0.988194 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4278.23 55.9753 1125.85 3933.86 48.4358 4292.07 +EDGE_SE3:QUAT 1484 1485 -0.777677 10.8449 -0.397525 0.0351636 -0.0648335 0.03223 0.996755 1 1.20371e-20 1.20371e-20 -4.67812e-10 2.18361e-10 6.9779e-09 1 1.20371e-20 -4.67812e-10 2.18361e-10 6.9779e-09 1 -4.67812e-10 2.18361e-10 6.9779e-09 4066.38 -6.5321 -538.907 3982.26 -5.3862 4067.18 +EDGE_SE3:QUAT 1485 1486 -0.547742 11.4938 -0.263545 0.0743244 -0.012169 0.0279263 0.996769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.57 -4.67453 -121.345 3998.98 -1.43336 4000.54 +EDGE_SE3:QUAT 1486 1487 -0.937242 11.2823 -0.278347 0.110083 0.136546 -0.140046 0.974487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4359.39 7.82679 1341.21 3904.41 -51.7994 4329.41 +EDGE_SE3:QUAT 1487 1488 -0.69809 11.2305 -0.260248 0.0969339 0.103545 0.0861981 0.98613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4089.16 54.7813 724.857 3976.13 53.0058 4097.02 +EDGE_SE3:QUAT 1488 1489 -0.395414 11.0963 -0.0653089 -0.0118723 0.0530472 0.206543 0.976926 1 1.17549e-21 1.17549e-21 2.13099e-09 4.50381e-10 1.16293e-10 1 1.17549e-21 2.13099e-09 4.50381e-10 1.16293e-10 1 2.13099e-09 4.50381e-10 1.16293e-10 4045.21 11.9105 430.408 3990.67 45.0512 3875.13 +EDGE_SE3:QUAT 1489 1490 -1.14456 11.0694 -0.346924 -0.183289 -0.0107164 0.00682867 0.982977 1 1.20371e-20 1.20371e-20 5.22838e-11 1.27314e-09 -6.82174e-09 1 1.20371e-20 5.22838e-11 1.27314e-09 -6.82174e-09 1 5.22838e-11 1.27314e-09 -6.82174e-09 3866.72 5.54384 -66.7704 3999.82 -0.557148 4000.91 +EDGE_SE3:QUAT 1490 1491 -0.548936 10.7286 -0.111842 -0.039766 0.0647749 -0.0069559 0.997083 1 5.11575e-20 5.11575e-20 1.37286e-08 -2.68875e-11 -2.5925e-09 1 5.11575e-20 1.37286e-08 -2.68875e-11 -2.5925e-09 1 1.37286e-08 -2.68875e-11 -2.5925e-09 4060.44 -11.4894 521.066 3983.74 -5.91891 4066.57 +EDGE_SE3:QUAT 1491 1492 -0.63952 11.1944 -0.143553 -0.0527948 0.0202107 -0.034762 0.997795 1 4.81482e-20 4.81482e-20 1.38555e-08 -5.09966e-10 2.2749e-10 1 4.81482e-20 1.38555e-08 -5.09966e-10 2.2749e-10 1 1.38555e-08 -5.09966e-10 2.2749e-10 3993.65 -3.74731 138.876 3998.95 -2.70009 3999.97 +EDGE_SE3:QUAT 1492 1493 -0.984574 10.8308 -0.103456 -0.0853995 0.167065 0.182421 0.965152 1 4.81482e-20 4.81482e-20 -1.43716e-08 -2.41443e-09 -2.76394e-09 1 4.81482e-20 -1.43716e-08 -2.41443e-09 -2.76394e-09 1 -1.43716e-08 -2.41443e-09 -2.76394e-09 4554.34 71.1115 1635.46 3876.61 126.232 4450.4 +EDGE_SE3:QUAT 1493 1494 -0.506426 10.6882 -0.140082 -0.0945229 -0.112702 0.0632129 0.987101 1 5.77779e-19 5.77779e-19 -3.31019e-08 2.18064e-08 3.38036e-08 1 5.77779e-19 -3.31019e-08 2.18064e-08 3.38036e-08 1 -3.31019e-08 2.18064e-08 3.38036e-08 4133.28 60.4722 -840.259 3965.72 -54.7972 4153.03 +EDGE_SE3:QUAT 1494 1495 -0.644007 10.7447 -0.266109 0.0486894 -0.0577531 0.0122965 0.997067 1 4.81482e-20 4.81482e-20 1.39325e-08 9.32839e-11 -8.19765e-10 1 4.81482e-20 1.39325e-08 9.32839e-11 -8.19765e-10 1 1.39325e-08 9.32839e-11 -8.19765e-10 4045.72 -10.9541 -473.154 3986.36 1.01679 4054.6 +EDGE_SE3:QUAT 1495 1496 -0.964286 10.9026 -0.284024 -0.00493572 -0.00560627 0.300782 0.953664 1 9.40395e-22 9.40395e-22 1.39344e-09 1.34903e-09 3.24357e-12 1 9.40395e-22 1.39344e-09 1.34903e-09 3.24357e-12 1 1.39344e-09 1.34903e-09 3.24357e-12 4000.01 0.119563 -22.1611 4000.01 -2.11928 3638.22 +EDGE_SE3:QUAT 1496 1497 -1.02943 10.9043 -0.352332 -0.00302896 0.0429761 -0.00725416 0.999045 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.63 -0.857643 345.741 3992.63 -1.4133 4029.45 +EDGE_SE3:QUAT 1497 1498 -0.563392 10.8535 -0.159985 -0.00192114 0.0173237 0.0189678 0.999668 1 1.20371e-20 1.20371e-20 1.20699e-10 -8.77292e-12 6.94078e-09 1 1.20371e-20 1.20699e-10 -8.77292e-12 6.94078e-09 1 1.20699e-10 -8.77292e-12 6.94078e-09 4004.82 0.00324703 139.099 3998.79 1.3106 4003.39 +EDGE_SE3:QUAT 1498 1499 -0.786828 10.8235 0.0124464 -0.147454 -0.0624608 0.287537 0.944287 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3905.23 -18.3851 51.4341 3996.6 35.857 3661.49 +EDGE_SE3:QUAT 1499 1500 -0.886064 10.9269 -0.194487 0.0366168 0.197092 0.16471 0.965756 1 9.62965e-19 9.62965e-19 1.84783e-08 -5.28624e-10 -5.22691e-08 1 9.62965e-19 1.84783e-08 -5.28624e-10 -5.22691e-08 1 1.84783e-08 -5.28624e-10 -5.22691e-08 4555.14 198.708 1600.81 3913.12 214.976 4451.98 +EDGE_SE3:QUAT 1500 1501 -0.873644 10.4971 0.110134 -0.117177 0.0395695 0.0680493 0.989986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.81 -22.2211 406.498 3988.89 8.52784 4022.21 +EDGE_SE3:QUAT 1501 1502 -0.631154 10.9302 -0.0209157 -0.145387 0.0744482 0.286506 0.944052 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4167.46 3.0213 1038.8 3936.87 137.39 3923.67 +EDGE_SE3:QUAT 1502 1503 -0.519229 11.2247 -0.220322 0.00202894 -0.116069 -0.00588392 0.993222 1 1.88079e-22 1.88079e-22 8.85327e-10 -5.81845e-12 -1.0343e-10 1 1.88079e-22 8.85327e-10 -5.81845e-12 -1.0343e-10 1 8.85327e-10 -5.81845e-12 -1.0343e-10 4224.47 -3.16114 -973.828 3946.16 3.97562 4224.35 +EDGE_SE3:QUAT 1503 1504 -1.077 11.0556 -0.419469 -0.136361 0.0106799 0.232272 0.962986 1 7.70372e-19 7.70372e-19 3.92055e-09 -6.53362e-09 5.37854e-08 1 7.70372e-19 3.92055e-09 -6.53362e-09 5.37854e-08 1 3.92055e-09 -6.53362e-09 5.37854e-08 3971.56 -27.1812 443.48 3981.97 59.6155 3830.14 +EDGE_SE3:QUAT 1504 1505 -0.759874 11.0814 -0.27174 0.196131 0.0753869 0.0867165 0.973822 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3876.94 34.6164 363.917 3998.02 25.7783 4000.73 +EDGE_SE3:QUAT 1505 1506 -0.967555 10.6785 -0.450004 -0.0416368 0.0445348 -0.0887548 0.994186 1 4.81482e-20 4.81482e-20 -1.38381e-08 1.2871e-09 -5.05066e-10 1 4.81482e-20 -1.38381e-08 1.2871e-09 -5.05066e-10 1 -1.38381e-08 1.2871e-09 -5.05066e-10 4016.63 -9.59377 308.437 3995.03 -14.7931 3992.05 +EDGE_SE3:QUAT 1506 1507 -0.818437 10.8161 -0.207428 -0.164614 -0.166514 0.00466841 0.97219 1 4.81482e-20 4.81482e-20 -2.27259e-09 -2.57246e-09 1.42241e-08 1 4.81482e-20 -2.27259e-09 -2.57246e-09 1.42241e-08 1 -2.27259e-09 -2.57246e-09 1.42241e-08 4324.28 148.833 -1385.54 3919.86 -121.091 4432.59 +EDGE_SE3:QUAT 1507 1508 -0.778857 10.7258 -0.169524 0.0312315 0.219807 0.0235173 0.97476 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4880.52 83.9446 2078.45 3814.51 82.9975 4882.21 +EDGE_SE3:QUAT 1508 1509 -0.875093 10.8725 0.144768 0.0948656 0.141927 0.0780335 0.982226 1 1.92593e-19 1.92593e-19 -3.50216e-09 -3.44495e-09 -2.81868e-08 1 1.92593e-19 -3.50216e-09 -3.44495e-09 -2.81868e-08 1 -3.50216e-09 -3.44495e-09 -2.81868e-08 4234.64 94.0143 1076.29 3948.47 91.0635 4246.28 +EDGE_SE3:QUAT 1509 1510 -0.714562 11.4598 -1.06119 0.112959 -0.0194545 0.0275279 0.993028 1 7.82409e-19 7.82409e-19 -5.53427e-08 5.64205e-09 6.1953e-10 1 7.82409e-19 -5.53427e-08 5.64205e-09 6.1953e-10 1 -5.53427e-08 5.64205e-09 6.1953e-10 3957.93 -11.0776 -189.887 3997.58 -1.36747 4005.94 +EDGE_SE3:QUAT 1510 1511 -0.658597 10.7297 -0.134692 -0.113283 0.0597946 -0.0280157 0.991366 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.31 -26.6451 434.861 3990.06 -14.518 4043.5 +EDGE_SE3:QUAT 1511 1512 -0.343219 11.0592 -0.462067 0.216815 0.149224 0.11701 0.957618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3959.44 121.449 801.149 3997.39 112.93 4092.71 +EDGE_SE3:QUAT 1512 1513 -0.500618 10.7389 -0.259942 -0.0433835 -0.00109287 0.0399537 0.998259 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.5 -0.411457 12.0544 3999.98 0.378804 3993.64 +EDGE_SE3:QUAT 1513 1514 -0.545255 10.9701 -0.0164965 0.0496774 0.101996 0.101571 0.988338 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4129.76 43.0272 760.945 3971.07 52.3868 4098.36 +EDGE_SE3:QUAT 1514 1515 -0.899822 10.9462 -0.143184 0.0563769 0.143294 0.197155 0.968204 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4213.31 109.476 982.092 3970.61 130.178 4070.54 +EDGE_SE3:QUAT 1515 1516 -0.786381 10.7526 0.0784025 -0.0477555 -0.133074 -0.0190373 0.989772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4294.26 23.6083 -1142.62 3928.5 -9.45601 4301.93 +EDGE_SE3:QUAT 1516 1517 -0.80201 10.7526 0.00352348 0.086402 -0.0900275 0.151989 0.980474 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4154.9 -3.15957 -879.86 3954.39 -54.088 4092.36 +EDGE_SE3:QUAT 1517 1518 -0.90989 10.9639 -0.167258 0.156423 -0.114023 0.174175 0.965502 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4265.15 -33.5372 -1260.03 3911.37 -57.0073 4241.67 +EDGE_SE3:QUAT 1518 1519 -0.857059 10.7596 -0.193515 0.0262767 -0.0879333 -0.0298841 0.995331 1 1.20371e-20 1.20371e-20 -7.01166e-09 2.46408e-10 6.06187e-10 1 1.20371e-20 -7.01166e-09 2.46408e-10 6.06187e-10 1 -7.01166e-09 2.46408e-10 6.06187e-10 4119.75 -15.6543 -710.683 3970.67 16.3546 4118.94 +EDGE_SE3:QUAT 1519 1520 -0.265097 11.3616 0.023334 -0.106154 0.0404334 0.0535888 0.992081 1 1.92593e-19 1.92593e-19 2.76651e-08 1.22779e-09 1.41198e-09 1 1.92593e-19 2.76651e-08 1.22779e-09 1.41198e-09 1 2.76651e-08 1.22779e-09 1.41198e-09 3992.08 -19.2965 387.734 3990.15 5.58557 4025.67 +EDGE_SE3:QUAT 1520 1521 -0.757803 11.0558 -0.247844 0.0531785 -0.115167 -0.0905485 0.98778 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4173.75 -52.7412 -880.604 3961.25 59.7451 4152.26 +EDGE_SE3:QUAT 1521 1522 -0.885055 10.554 -0.00223309 -0.129748 -0.115964 -0.0990456 0.979749 1 1.92593e-19 1.92593e-19 2.81824e-08 -1.96383e-09 -3.90961e-09 1 1.92593e-19 2.81824e-08 -1.96383e-09 -3.90961e-09 1 2.81824e-08 -1.96383e-09 -3.90961e-09 4222.07 44.6368 -1114.56 3930.2 10.8022 4250.17 +EDGE_SE3:QUAT 1522 1523 -0.762548 10.7872 -0.192667 -0.0239513 -0.0801659 0.0952714 0.991929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4090.52 21.5713 -616.552 3979.26 -34.1495 4056.51 +EDGE_SE3:QUAT 1523 1524 -0.637994 10.8546 -0.379232 0.0127417 0.0140062 0.0266766 0.999465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.26 0.798241 107.893 3999.29 1.47975 4000.06 +EDGE_SE3:QUAT 1524 1525 -0.707802 10.6349 -0.25428 -0.0550682 0.053944 -0.00828456 0.99699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.2 -12.6489 428.233 3989.05 -5.61705 4045.05 +EDGE_SE3:QUAT 1525 1526 -0.456832 10.6511 -0.24121 -0.0349614 0.0294352 0.162101 0.985715 1 4.81482e-20 4.81482e-20 1.37172e-08 2.22666e-09 5.42985e-10 1 4.81482e-20 1.37172e-08 2.22666e-09 5.42985e-10 1 1.37172e-08 2.22666e-09 5.42985e-10 4016.57 -0.67766 294.166 3994.41 24.6575 3916.35 +EDGE_SE3:QUAT 1526 1527 -0.948503 10.7288 -0.22477 -0.0345315 -0.0407132 0.0760685 0.995672 1 1.92593e-19 1.92593e-19 9.70899e-10 1.12499e-09 -2.77091e-08 1 1.92593e-19 9.70899e-10 1.12499e-09 -2.77091e-08 1 9.70899e-10 1.12499e-09 -2.77091e-08 4016.41 7.48811 -292.131 3995.32 -12.0041 3998.04 +EDGE_SE3:QUAT 1527 1528 -0.996362 10.8984 -0.0115558 -0.102157 -0.00112119 0.13985 0.984888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3963.89 -10.3079 159.668 3997.14 14.6115 3927.4 +EDGE_SE3:QUAT 1528 1529 -1.03188 10.9627 0.104673 0.0384551 -0.059172 -0.0440241 0.996535 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.29 -12.4051 -455.519 3987.98 13.2555 4043.45 +EDGE_SE3:QUAT 1529 1530 -0.596921 10.2383 -0.0697666 0.0118161 -0.0302099 -0.0323838 0.998949 1 1.50463e-20 1.50463e-20 3.24188e-09 -7.04663e-09 -6.53029e-12 1 1.50463e-20 3.24188e-09 -7.04663e-09 -6.53029e-12 1 3.24188e-09 -7.04663e-09 -6.53029e-12 4013.48 -2.09554 -237.375 3996.57 4.10413 4009.84 +EDGE_SE3:QUAT 1530 1531 -0.836615 10.7272 0.0662992 0.111591 -0.111877 0.113348 0.980909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4221.12 -26.4153 -1076.13 3933.95 -28.2509 4219.54 +EDGE_SE3:QUAT 1531 1532 -0.858133 10.6016 -0.274504 0.0113469 0.172572 0.0161401 0.984799 1 1.50463e-20 1.50463e-20 4.90113e-09 2.10377e-10 7.89877e-09 1 1.50463e-20 4.90113e-09 2.10377e-10 7.89877e-09 1 4.90113e-09 2.10377e-10 7.89877e-09 4519.53 24.8223 1533.17 3882.04 25.7125 4519 +EDGE_SE3:QUAT 1532 1533 -0.819183 10.7425 -0.0144553 -0.300491 -0.00971665 0.0143294 0.953627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3638.8 -0.30175 -18.863 4000.04 -0.0951203 3999.16 +EDGE_SE3:QUAT 1533 1534 -0.871064 10.84 0.202041 0.0063959 0.14254 0.102666 0.984429 1 1.92593e-19 1.92593e-19 -3.98697e-09 -1.05586e-09 -2.84371e-08 1 1.92593e-19 -3.98697e-09 -1.05586e-09 -2.84371e-08 1 -3.98697e-09 -1.05586e-09 -2.84371e-08 4328.71 58.0839 1193.28 3928.36 77.2598 4286.71 +EDGE_SE3:QUAT 1534 1535 -0.940537 10.982 -0.0735643 0.0400901 -0.131697 0.105891 0.984802 1 1.20371e-20 1.20371e-20 -7.098e-09 -7.11289e-10 9.87592e-10 1 1.20371e-20 -7.098e-09 -7.11289e-10 9.87592e-10 1 -7.098e-09 -7.11289e-10 9.87592e-10 4305.58 22.9083 -1159.92 3927.85 -54.6499 4267.16 +EDGE_SE3:QUAT 1535 1536 -0.663263 10.8514 -0.20352 -0.104802 0.0541338 0.103453 0.987615 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.1 -21.5437 557.705 3979.52 20.9827 4033.22 +EDGE_SE3:QUAT 1536 1537 -0.835178 10.4801 -0.0434107 0.0529026 -0.134365 0.0974943 0.984704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4321.46 11.1581 -1200.57 3922.21 -44.1959 4294.63 +EDGE_SE3:QUAT 1537 1538 -0.445638 10.6767 0.0739086 0.0219738 0.0693236 0.0942352 0.99289 1 1.20371e-20 1.20371e-20 -6.94922e-09 -6.86485e-10 -4.46831e-10 1 1.20371e-20 -6.94922e-09 -6.86485e-10 -4.46831e-10 1 -6.94922e-09 -6.86485e-10 -4.46831e-10 4066.96 16.128 529.603 3984.49 27.9959 4033.37 +EDGE_SE3:QUAT 1538 1539 -0.858787 10.2921 0.23678 0.071408 -0.020826 -0.0533742 0.9958 1 2.0463e-19 2.0463e-19 2.72638e-08 -8.45913e-09 1.50248e-10 1 2.0463e-19 2.72638e-08 -8.45913e-09 1.50248e-10 1 2.72638e-08 -8.45913e-09 1.50248e-10 3983.08 -4.03761 -119.177 3999.37 3.21714 3992.09 +EDGE_SE3:QUAT 1539 1540 -0.703439 11.0191 -0.379699 0.0966302 0.0319177 0.108432 0.988881 1 3.97223e-19 3.97223e-19 -2.69491e-08 -1.28007e-08 -2.70276e-08 1 3.97223e-19 -2.69491e-08 -1.28007e-08 -2.70276e-08 1 -2.69491e-08 -1.28007e-08 -2.70276e-08 3965.92 4.76772 123.193 3999.78 5.13198 3956.24 +EDGE_SE3:QUAT 1540 1541 -0.545032 10.7123 -0.0599996 -0.0469643 0.0706336 0.138301 0.986751 1 4.81482e-20 4.81482e-20 1.38666e-08 1.86326e-09 1.13283e-09 1 4.81482e-20 1.38666e-08 1.86326e-09 1.13283e-09 1 1.38666e-08 1.86326e-09 1.13283e-09 4090.61 3.80671 638.6 3975.71 41.3787 4022.92 +EDGE_SE3:QUAT 1541 1542 -0.395398 10.6009 -0.196113 0.100685 0.10944 0.0975611 0.984057 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4095.04 61.8026 751.094 3975.88 61.2995 4097.51 +EDGE_SE3:QUAT 1542 1543 -0.595917 10.6167 -0.155337 -0.0290399 -0.0600638 -0.00612706 0.997753 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4055.35 6.82406 -488.217 3985.5 -1.01843 4058.58 +EDGE_SE3:QUAT 1543 1544 -0.755844 10.8015 -0.0717857 -0.0666811 0.0426902 -0.0567499 0.995244 1 4.81482e-20 4.81482e-20 4.79543e-10 -9.92294e-10 1.38489e-08 1 4.81482e-20 4.79543e-10 -9.92294e-10 1.38489e-08 1 4.79543e-10 -9.92294e-10 1.38489e-08 4003.57 -11.3726 293.57 3995.47 -10.319 4008.47 +EDGE_SE3:QUAT 1544 1545 -0.997278 10.647 0.138133 -0.0604473 0.0199794 0.0255731 0.997644 1 7.22224e-20 7.22224e-20 -1.38593e-08 6.19095e-09 7.02352e-09 1 7.22224e-20 -1.38593e-08 6.19095e-09 7.02352e-09 1 -1.38593e-08 6.19095e-09 7.02352e-09 3993.25 -5.281 177.628 3997.93 1.67193 4005.25 +EDGE_SE3:QUAT 1545 1546 -0.272685 10.5613 -0.212791 0.0823924 0.230745 0.12853 0.960962 1 9.62965e-19 9.62965e-19 1.91675e-08 5.83986e-08 -2.456e-09 1 9.62965e-19 1.91675e-08 5.83986e-08 -2.456e-09 1 1.91675e-08 5.83986e-08 -2.456e-09 4729.3 290.768 1899.97 3898.72 294.095 4690.38 +EDGE_SE3:QUAT 1546 1547 -1.02001 10.5745 -0.0663893 0.0398904 -0.0807171 0.0493015 0.994717 1 1.92593e-19 1.92593e-19 1.20263e-09 -2.76167e-08 8.94244e-10 1 1.92593e-19 1.20263e-09 -2.76167e-08 8.94244e-10 1 1.20263e-09 -2.76167e-08 8.94244e-10 4106.8 -6.33917 -682.259 3972.05 -11.4098 4103.44 +EDGE_SE3:QUAT 1547 1548 -0.614492 10.2811 -0.290533 0.0490123 -0.0333291 0.0808205 0.994965 1 2.88889e-19 2.88889e-19 1.37925e-08 -1.15342e-08 2.77326e-08 1 2.88889e-19 1.37925e-08 -1.15342e-08 2.77326e-08 1 1.37925e-08 -1.15342e-08 2.77326e-08 4014.56 -5.34489 -312.127 3993.56 -11.7038 3998.04 +EDGE_SE3:QUAT 1548 1549 -0.567869 10.4913 0.156112 0.0685807 -0.153168 -0.0494745 0.984575 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4345.58 -82.0137 -1261.34 3922.56 78.429 4354.6 +EDGE_SE3:QUAT 1549 1550 -0.95858 10.3867 -0.426447 0.0815277 0.131168 0.0981012 0.98312 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4194.97 80.2682 968.554 3958.26 83.1589 4183.06 +EDGE_SE3:QUAT 1550 1551 -0.880685 10.6217 -0.0660325 -0.230633 0.145749 0.0290992 0.961623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4140.78 -160.143 1241.21 3939.19 -109.663 4350.16 +EDGE_SE3:QUAT 1551 1552 -0.935696 10.496 -0.265461 0.0838241 -0.143628 0.0703348 0.983564 1 1.92593e-19 1.92593e-19 -2.86039e-08 -1.38762e-09 4.43241e-09 1 1.92593e-19 -2.86039e-08 -1.38762e-09 4.43241e-09 1 -2.86039e-08 -1.38762e-09 4.43241e-09 4359.4 -26.2926 -1303.98 3909.35 -7.25593 4367.72 +EDGE_SE3:QUAT 1552 1553 -0.566266 11.1612 -0.0973956 0.0534372 0.123976 -0.131926 0.982023 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4278.3 -22.6683 1114.86 3933.09 -64.3112 4220.1 +EDGE_SE3:QUAT 1553 1554 -0.686713 10.5295 -0.374532 -0.0389648 -0.104434 0.172557 0.978672 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4124.02 52.6656 -734.971 3977.68 -74.783 4010.99 +EDGE_SE3:QUAT 1554 1555 -0.706665 10.7118 0.103822 0.131246 0.11273 0.198936 0.96462 1 7.70372e-19 7.70372e-19 -2.6644e-09 -9.36644e-09 -5.39875e-08 1 7.70372e-19 -2.6644e-09 -9.36644e-09 -5.39875e-08 1 -2.6644e-09 -9.36644e-09 -5.39875e-08 3992.81 56.4943 522.347 3999.77 61.475 3903.41 +EDGE_SE3:QUAT 1555 1556 -0.543814 10.3177 0.0834316 -0.111752 0.0186695 0.273265 0.955243 1 1.92593e-19 1.92593e-19 2.67132e-08 7.35337e-09 2.06614e-09 1 1.92593e-19 2.67132e-08 7.35337e-09 2.06614e-09 1 2.67132e-08 7.35337e-09 2.06614e-09 4005.5 -16.0978 482.749 3980.95 75.7841 3756.75 +EDGE_SE3:QUAT 1556 1557 -0.630439 10.4752 -0.0546852 0.0885782 -0.109203 -0.0725919 0.9874 1 5.77779e-19 5.77779e-19 -2.80086e-08 3.2971e-08 2.76474e-08 1 5.77779e-19 -2.80086e-08 3.2971e-08 2.76474e-08 1 -2.80086e-08 3.2971e-08 2.76474e-08 4123.67 -56.5501 -803.596 3968.8 53.7037 4133.97 +EDGE_SE3:QUAT 1557 1558 -0.74977 10.4662 -0.0314185 -0.0511728 0.0791007 -0.0155263 0.995431 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4087.5 -19.4906 633.668 3976.62 -12.8929 4097.01 +EDGE_SE3:QUAT 1558 1559 -1.18129 10.2543 -0.314775 0.00178392 0.0600102 0.0808774 0.994914 1 2.41494e-19 2.41494e-19 2.25197e-09 1.42705e-08 2.7754e-08 1 2.41494e-19 2.25197e-09 1.42705e-08 2.7754e-08 1 2.25197e-09 1.42705e-08 2.7754e-08 4056.66 7.42773 479.479 3986.5 20.1858 4030.5 +EDGE_SE3:QUAT 1559 1560 -0.482876 10.6456 -0.0127901 -0.047281 0.0803752 0.119019 0.988503 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4114.66 3.21695 714.015 3969.83 38.1086 4066.93 +EDGE_SE3:QUAT 1560 1561 -0.564278 10.4211 0.306098 0.0206266 0.0887743 -0.213207 0.972747 1 1.94286e-19 1.94286e-19 -3.33793e-09 -2.7564e-08 -2.73856e-10 1 1.94286e-19 -3.33793e-09 -2.7564e-08 -2.73856e-10 1 -3.33793e-09 -2.7564e-08 -2.73856e-10 4128.69 -35.0204 734.03 3974.35 -81.083 3948.56 +EDGE_SE3:QUAT 1561 1562 -1.05081 10.2893 0.122605 -0.10723 -0.0190916 0.0827298 0.990602 1 1.92593e-19 1.92593e-19 -2.74952e-08 -2.35693e-09 2.22629e-11 1 1.92593e-19 -2.74952e-08 -2.35693e-09 2.22629e-11 1 -2.74952e-08 -2.35693e-09 2.22629e-11 3954.13 0.485213 -43.3439 4000.03 -0.446535 3972.75 +EDGE_SE3:QUAT 1562 1563 -1.14078 10.1231 -0.504493 -0.0690985 -0.0332777 0.0918461 0.992815 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.3 6.95708 -185.626 3998.61 -8.42095 3974.65 +EDGE_SE3:QUAT 1563 1564 -0.639854 10.3394 0.039429 -0.0142244 0.0825372 0.167016 0.98239 1 7.70637e-19 7.70637e-19 5.67679e-09 9.54102e-10 5.53962e-08 1 7.70637e-19 5.67679e-09 9.54102e-10 5.53962e-08 1 5.67679e-09 9.54102e-10 5.53962e-08 4110.66 23.5131 677.032 3975.93 58.3135 3999.89 +EDGE_SE3:QUAT 1564 1565 -0.71268 9.99147 -0.0865111 0.0110641 -0.00455129 0.200492 0.979622 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.4 -0.146236 -60.1485 3999.74 -6.83248 3840.1 +EDGE_SE3:QUAT 1565 1566 -0.778641 10.2648 0.0676253 0.00627587 -0.0661999 0.124996 0.989926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4070.06 11.662 -534.645 3983.88 -34.2371 4007.73 +EDGE_SE3:QUAT 1566 1567 -0.448142 10.5452 -0.39427 -0.0435374 -0.122332 0.00969005 0.991486 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4238.65 29.4185 -1022.53 3942.16 -22.339 4245.86 +EDGE_SE3:QUAT 1567 1568 -1.02864 10.3824 -0.0332222 0.00129199 -0.0673243 0.0674595 0.995447 1 1.88079e-22 1.88079e-22 8.71269e-10 5.94319e-11 -5.85384e-11 1 1.88079e-22 8.71269e-10 5.94319e-11 -5.85384e-11 1 8.71269e-10 5.94319e-11 -5.85384e-11 4072.78 7.09286 -544.481 3982.45 -19.0698 4054.59 +EDGE_SE3:QUAT 1568 1569 -0.78981 10.5501 -0.0363024 -0.00930596 0.135406 -0.0687944 0.988355 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4300.3 -38.6933 1137.12 3931.52 -50.8888 4281.71 +EDGE_SE3:QUAT 1569 1570 -0.382943 10.3565 0.231861 -0.000552817 -0.148027 -0.0367295 0.988301 1 7.52316e-22 7.52316e-22 1.79281e-09 -6.93758e-11 -2.67846e-10 1 7.52316e-22 1.79281e-09 -6.93758e-11 -2.67846e-10 1 1.79281e-09 -6.93758e-11 -2.67846e-10 4373.57 -21.044 -1278.21 3913.4 28.647 4368.17 +EDGE_SE3:QUAT 1570 1571 -0.720896 10.061 -0.258832 0.020198 -0.0151764 0.110244 0.993583 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.66 -0.739507 -145.816 3998.58 -8.3608 3956.68 +EDGE_SE3:QUAT 1571 1572 -0.619774 10.6884 -0.139976 -0.0476848 0.203479 0.131655 0.969015 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4781.52 101.077 1946.15 3837.47 128.016 4721.28 +EDGE_SE3:QUAT 1572 1573 -0.685151 10.2617 -0.124138 0.0435597 0.0915461 0.0859005 0.991132 1 4.81482e-20 4.81482e-20 -1.39561e-08 -1.33778e-09 -1.1577e-09 1 4.81482e-20 -1.39561e-08 -1.33778e-09 -1.1577e-09 1 -1.39561e-08 -1.33778e-09 -1.1577e-09 4109.18 31.8697 693.697 3974.57 39.5127 4087.25 +EDGE_SE3:QUAT 1573 1574 -1.07105 10.5627 -0.042074 -0.0994953 0.101787 0.130233 0.981213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4190.18 -13.8902 986.36 3943.41 42.0703 4161.93 +EDGE_SE3:QUAT 1574 1575 -0.977374 10.3313 -0.209624 -0.0216989 0.00669562 0.132023 0.990986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.95 -0.743593 86.1413 3999.44 6.36457 3932.11 +EDGE_SE3:QUAT 1575 1576 -0.466227 10.4687 -0.168591 -0.0110375 0.0117581 0.0859611 0.996168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.23 -0.258811 104.402 3999.29 4.59928 3973.16 +EDGE_SE3:QUAT 1576 1577 -1.02471 10.0182 0.178758 0.0636143 -0.0499734 0.178889 0.980538 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.17 -1.82093 -520.255 3982.85 -45.8062 3938.35 +EDGE_SE3:QUAT 1577 1578 -0.856996 10.2547 0.0644382 0.0263331 0.0750387 -0.0032092 0.996828 1 4.70198e-23 4.70198e-23 -3.29426e-11 -1.1469e-11 -4.37239e-10 1 4.70198e-23 -3.29426e-11 -1.1469e-11 -4.37239e-10 1 -3.29426e-11 -1.1469e-11 -4.37239e-10 4088.99 8.1033 612.747 3977.5 2.62066 4091.72 +EDGE_SE3:QUAT 1578 1579 -0.602388 10.4212 -0.104362 0.0768999 -0.0573924 0.0994287 0.990407 1 1.92593e-19 1.92593e-19 1.98553e-09 -1.80855e-09 -2.77454e-08 1 1.92593e-19 1.98553e-09 -1.80855e-09 -2.77454e-08 1 1.98553e-09 -1.80855e-09 -2.77454e-08 4050.13 -12.5907 -548.749 3980.7 -21.7121 4034.24 +EDGE_SE3:QUAT 1579 1580 -0.702095 10.0539 -0.220975 0.00971231 0.184911 0.109805 0.976553 1 1.92593e-19 1.92593e-19 -5.27926e-09 -1.56553e-09 -2.90001e-08 1 1.92593e-19 -5.27926e-09 -1.56553e-09 -2.90001e-08 1 -5.27926e-09 -1.56553e-09 -2.90001e-08 4570.42 112.973 1615.43 3884.3 129.333 4522.56 +EDGE_SE3:QUAT 1580 1581 -1.01251 10.4987 -0.282957 0.052345 0.119137 0.226447 0.965292 1 1.92593e-19 1.92593e-19 6.72966e-09 -2.6684e-08 2.80993e-09 1 1.92593e-19 6.72966e-09 -2.6684e-08 2.80993e-09 1 6.72966e-09 -2.6684e-08 2.80993e-09 4124.53 76.0262 754.958 3985.54 100.124 3930.38 +EDGE_SE3:QUAT 1581 1582 -0.689519 10.2614 0.0941297 -0.115842 0.14667 0.1179 0.975278 1 9.62965e-19 9.62965e-19 2.38333e-08 5.68354e-08 9.50508e-09 1 9.62965e-19 2.38333e-08 5.68354e-08 9.50508e-09 1 2.38333e-08 5.68354e-08 9.50508e-09 4401.85 -25.0603 1424.93 3894.11 28.3881 4399.93 +EDGE_SE3:QUAT 1582 1583 -0.431324 10.3955 -0.304815 0.0105746 -0.097806 0.0090567 0.995108 1 1.92593e-19 1.92593e-19 -1.9798e-10 2.76202e-08 -2.49302e-10 1 1.92593e-19 -1.9798e-10 2.76202e-08 -2.49302e-10 1 -1.9798e-10 2.76202e-08 -2.49302e-10 4157.51 -2.53814 -810.42 3961.63 -1.4945 4157.63 +EDGE_SE3:QUAT 1583 1584 -0.829056 10.3362 -0.270833 -0.0466242 -0.009571 0.106835 0.993137 1 2.40741e-19 2.40741e-19 -1.37662e-08 -2.80963e-09 2.75568e-08 1 2.40741e-19 -1.37662e-08 -2.80963e-09 2.75568e-08 1 -1.37662e-08 -2.80963e-09 2.75568e-08 3991.26 -0.0764323 -15.7738 4000 0.235406 3954.3 +EDGE_SE3:QUAT 1584 1585 -0.911566 10.3183 -0.224575 -0.0456863 0.0926199 0.0188828 0.994474 1 4.81482e-20 4.81482e-20 1.40478e-08 1.49322e-10 1.32671e-09 1 4.81482e-20 1.40478e-08 1.49322e-10 1.32671e-09 1 1.40478e-08 1.49322e-10 1.32671e-09 4135.6 -15.199 772.347 3964.99 -2.00107 4142.52 +EDGE_SE3:QUAT 1585 1586 -0.494289 10.1895 -0.332892 -0.00376542 0.0271364 0.139535 0.989838 1 4.59177e-26 4.59177e-26 1.3435e-11 1.89393e-12 3.68095e-13 1 4.59177e-26 1.3435e-11 1.89393e-12 3.68095e-13 1 1.3435e-11 1.89393e-12 3.68095e-13 4011.74 2.08491 217.567 3997.29 15.2288 3933.92 +EDGE_SE3:QUAT 1586 1587 -0.862384 10.5083 -0.176437 -0.150262 0.014851 -0.0472631 0.987404 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3909.7 -0.0947738 30.5757 4000.02 -0.15284 3991.07 +EDGE_SE3:QUAT 1587 1588 -0.751088 10.2391 -0.0796643 0.0478642 -0.0776259 0.0706027 0.993327 1 4.33334e-19 4.33334e-19 1.33984e-08 -2.56472e-08 2.7802e-08 1 4.33334e-19 1.33984e-08 -2.56472e-08 2.7802e-08 1 1.33984e-08 -2.56472e-08 2.7802e-08 4100.36 -5.92012 -670.956 3972.78 -17.9048 4089.59 +EDGE_SE3:QUAT 1588 1589 -0.571096 9.99665 -0.426135 -0.0963938 0.0513916 0.0233409 0.993742 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.92 -20.3752 436.543 3988.37 -1.40148 4044.9 +EDGE_SE3:QUAT 1589 1590 -0.433041 9.96775 0.0674952 -0.00849025 0.0819459 0.19252 0.977829 1 1.93345e-19 1.93345e-19 -7.09634e-09 2.67928e-08 -7.85812e-10 1 1.93345e-19 -7.09634e-09 2.67928e-08 -7.85812e-10 1 -7.09634e-09 2.67928e-08 -7.85812e-10 4103.55 28.3843 653.028 3979.21 65.4233 3955.58 +EDGE_SE3:QUAT 1590 1591 -0.949392 10.0123 -0.488238 0.0456866 -0.0742223 0.157572 0.983654 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4101.45 8.64458 -671.866 3973.82 -50.7615 4010.48 +EDGE_SE3:QUAT 1591 1592 -1.13434 10.2297 -0.257623 0.0464157 0.0313921 0.174951 0.982981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.15 4.35003 143.528 3999.58 9.90825 3882.34 +EDGE_SE3:QUAT 1592 1593 -0.382971 10.243 -0.0784825 -0.0899667 0.197276 0.00933249 0.976167 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4662.08 -105.113 1805.6 3853.74 -89.7271 4694.11 +EDGE_SE3:QUAT 1593 1594 -0.776898 10.1735 -0.129003 -0.127992 -0.0108105 0.229082 0.964895 1 1.20371e-20 1.20371e-20 1.55713e-09 -6.70292e-09 -8.28663e-10 1 1.20371e-20 1.55713e-09 -6.70292e-09 -8.28663e-10 1 1.55713e-09 -6.70292e-09 -8.28663e-10 3948.3 -21.3865 258.837 3991.42 41.8566 3803.91 +EDGE_SE3:QUAT 1594 1595 -0.683154 10.3864 -0.0451114 0.215519 -0.0698602 0.0428988 0.973052 1 7.82409e-19 7.82409e-19 5.41499e-08 2.03156e-09 2.26667e-09 1 7.82409e-19 5.41499e-08 2.03156e-09 2.26667e-09 1 5.41499e-08 2.03156e-09 2.26667e-09 3914.56 -69.5985 -641.512 3977.87 16.8828 4092.99 +EDGE_SE3:QUAT 1595 1596 -0.527961 10.0877 -0.190044 0.111251 0.00677229 -0.0303734 0.993305 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3952.63 5.84696 93.3429 3999.31 -1.31826 3998.45 +EDGE_SE3:QUAT 1596 1597 -0.374139 10.4219 -0.464148 -0.0882165 -0.0330447 0.342509 0.93478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.55 -11.2718 116.139 3995.96 43.5591 3530.43 +EDGE_SE3:QUAT 1597 1598 -0.565708 10.0292 0.22384 -0.0255536 -0.267008 0.124838 0.955232 1 3.08149e-18 3.08149e-18 -1.76983e-08 1.05479e-07 1.1366e-08 1 3.08149e-18 -1.76983e-08 1.05479e-07 1.1366e-08 1 -1.76983e-08 1.05479e-07 1.1366e-08 5269.35 342.036 -2590.36 3802.96 -344.129 5209.62 +EDGE_SE3:QUAT 1598 1599 -0.693079 9.97207 0.0235633 0.0438002 -0.032857 0.106207 0.992835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.91 -3.68167 -314.878 3993.45 -16.3377 3979.46 +EDGE_SE3:QUAT 1599 1600 -0.806147 9.99284 0.348979 0.127629 0.0273452 0.0284677 0.991036 1 7.70372e-19 7.70372e-19 -5.50636e-08 -1.91701e-09 -1.06637e-09 1 7.70372e-19 -5.50636e-08 -1.91701e-09 -1.06637e-09 1 -5.50636e-08 -1.91701e-09 -1.06637e-09 3942 10.2334 170.256 3998.68 3.78323 4003.91 +EDGE_SE3:QUAT 1600 1601 -0.607117 10.0796 0.250629 -0.143136 0.198654 0.152597 0.957477 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4831.61 -10.8972 2118.98 3805.8 40.1 4820.42 +EDGE_SE3:QUAT 1601 1602 -0.664263 10.0889 -0.649086 -0.0316454 -0.00324445 0.158244 0.986887 1 8.1852e-19 8.1852e-19 -1.33182e-08 -3.91949e-09 5.46901e-08 1 8.1852e-19 -1.33182e-08 -3.91949e-09 5.46901e-08 1 -1.33182e-08 -3.91949e-09 5.46901e-08 3996.19 -0.838166 34.1021 3999.82 4.30513 3900.03 +EDGE_SE3:QUAT 1602 1603 -0.647222 10.0896 -0.110254 0.0380377 0.0249804 0.244567 0.968564 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.11 1.54779 74.5837 4000.16 3.96418 3761.64 +EDGE_SE3:QUAT 1603 1604 -0.932847 10.0929 0.230004 0.133048 -0.0364095 0.17457 0.974935 1 4.81482e-20 4.81482e-20 -2.22117e-09 1.35645e-08 -1.57277e-09 1 4.81482e-20 -2.22117e-09 1.35645e-08 -1.57277e-09 1 -2.22117e-09 1.35645e-08 -1.57277e-09 4002.42 -27.3942 -550.94 3977.42 -44.851 3951.33 +EDGE_SE3:QUAT 1604 1605 -0.724919 9.8151 -0.238908 0.0155084 -0.0237764 0.0386703 0.998849 1 1.20371e-20 1.20371e-20 -2.63401e-10 6.93109e-09 -9.46566e-11 1 1.20371e-20 -2.63401e-10 6.93109e-09 -9.46566e-11 1 -2.63401e-10 6.93109e-09 -9.46566e-11 4008.75 -1.00109 -197.334 3997.54 -3.65943 4003.73 +EDGE_SE3:QUAT 1605 1606 -0.875226 10.2153 -0.322051 -0.0375349 0.129199 0.0631976 0.988891 1 1.20371e-20 1.20371e-20 7.11012e-09 3.97672e-10 9.54067e-10 1 1.20371e-20 7.11012e-09 3.97672e-10 9.54067e-10 1 7.11012e-09 3.97672e-10 9.54067e-10 4287.72 3.47263 1122.27 3930.53 25.2397 4277.38 +EDGE_SE3:QUAT 1606 1607 -1.0205 10.2187 0.0614024 0.026812 0.0506952 0.0162103 0.998223 1 9.62965e-20 9.62965e-20 -1.36591e-08 -1.41174e-08 -2.96813e-10 1 9.62965e-20 -1.36591e-08 -1.41174e-08 -2.96813e-10 1 -1.36591e-08 -1.41174e-08 -2.96813e-10 4037.37 6.51359 403.229 3990.16 4.97702 4039.19 +EDGE_SE3:QUAT 1607 1608 -0.7649 9.99966 -0.0688723 0.0658942 -0.0100436 0.148742 0.986627 1 1.92593e-19 1.92593e-19 -2.7416e-08 -4.06263e-09 8.02002e-10 1 1.92593e-19 -2.7416e-08 -4.06263e-09 8.02002e-10 1 -2.7416e-08 -4.06263e-09 8.02002e-10 3991.63 -6.05045 -193.186 3996.82 -16.5486 3920.5 +EDGE_SE3:QUAT 1608 1609 -0.951838 10.0792 -0.152904 -0.0930327 0.135474 -0.0811736 0.983058 1 1.92593e-19 1.92593e-19 3.30397e-09 -3.3604e-09 2.81155e-08 1 1.92593e-19 3.30397e-09 -3.3604e-09 2.81155e-08 1 3.30397e-09 -3.3604e-09 2.81155e-08 4207.75 -86.1926 1015.28 3953.74 -84.104 4216.02 +EDGE_SE3:QUAT 1609 1610 -0.942482 10.0048 -0.0195092 -0.131044 0.0348156 -0.00166578 0.990764 1 7.70372e-19 7.70372e-19 5.5125e-08 -5.93933e-10 1.84625e-09 1 7.70372e-19 5.5125e-08 -5.93933e-10 1.84625e-09 1 5.5125e-08 -5.93933e-10 1.84625e-09 3949.42 -17.7309 269.834 3995.92 -3.88323 4018.1 +EDGE_SE3:QUAT 1610 1611 -0.70121 10.2212 0.058785 0.0512825 -0.0945177 0.26109 0.959306 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4169.19 45.9471 -866.688 3965.66 -115.605 3907.04 +EDGE_SE3:QUAT 1611 1612 -0.83214 9.91317 -0.210431 0.110326 0.000654639 0.165608 0.980001 1 2.0463e-19 2.0463e-19 -2.83578e-08 2.31036e-09 2.52962e-10 1 2.0463e-19 -2.83578e-08 2.31036e-09 2.52962e-10 1 -2.83578e-08 2.31036e-09 2.52962e-10 3961.07 -13.9617 -209.052 3995.22 -22.3214 3900.05 +EDGE_SE3:QUAT 1612 1613 -1.17084 9.75198 -0.230064 0.0962255 0.0753862 0.143031 0.98214 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.53 29.1096 416.005 3994.69 34.0048 3959.73 +EDGE_SE3:QUAT 1613 1614 -0.909421 9.92984 -0.292478 0.0523381 -0.139422 0.0925658 0.984507 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4345.99 10.7719 -1247.1 3916.8 -42.2269 4322.67 +EDGE_SE3:QUAT 1614 1615 -0.850248 10.4038 -0.258254 0.110993 -0.0324124 0.145634 0.982558 1 1.92593e-19 1.92593e-19 -2.74381e-08 -3.78119e-09 1.73506e-09 1 1.92593e-19 -2.74381e-08 -3.78119e-09 1.73506e-09 1 -2.74381e-08 -3.78119e-09 1.73506e-09 3998.19 -19.5156 -441.512 3985.55 -30.4946 3962.63 +EDGE_SE3:QUAT 1615 1616 -0.703054 10.093 -0.323305 0.0260908 -0.0369965 0.0172006 0.998827 1 7.22224e-20 7.22224e-20 6.89945e-09 -1.35824e-08 7.03243e-09 1 7.22224e-20 6.89945e-09 -1.35824e-08 7.03243e-09 1 6.89945e-09 -1.35824e-08 7.03243e-09 4020.01 -3.44083 -302.437 3994.3 -1.76746 4021.55 +EDGE_SE3:QUAT 1616 1617 -1.07288 9.82073 -0.0995392 -0.0291188 0.0660442 -0.0488205 0.996196 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4062.04 -12.6687 515.825 3984.53 -15.9229 4055.9 +EDGE_SE3:QUAT 1617 1618 -0.745273 9.9691 0.0578221 0.0318737 0.114069 -0.0208013 0.992743 1 2.0463e-19 2.0463e-19 7.46139e-09 2.74584e-08 4.68444e-11 1 2.0463e-19 7.46139e-09 2.74584e-08 4.68444e-11 1 7.46139e-09 2.74584e-08 4.68444e-11 4215.63 10.5112 962.835 3947.21 -0.695363 4217.96 +EDGE_SE3:QUAT 1618 1619 -0.402538 9.71836 -0.427335 -0.175046 0.102123 0.0887092 0.975223 1 1.92593e-19 1.92593e-19 -1.38064e-09 2.71445e-08 4.41009e-09 1 1.92593e-19 -1.38064e-09 2.71445e-08 4.41009e-09 1 -1.38064e-09 2.71445e-08 4.41009e-09 4116.72 -73.5322 1007.68 3942.91 -8.36428 4207.81 +EDGE_SE3:QUAT 1619 1620 -0.712523 9.82193 -0.072389 0.0647387 -0.0586247 0.0958281 0.991559 1 4.81482e-20 4.81482e-20 -1.38858e-08 -1.23472e-09 9.73073e-10 1 4.81482e-20 -1.38858e-08 -1.23472e-09 9.73073e-10 1 -1.38858e-08 -1.23472e-09 9.73073e-10 4055.45 -9.05128 -542.613 3981.37 -21.4227 4035.48 +EDGE_SE3:QUAT 1620 1621 -0.766438 9.39477 -0.0196936 -0.0665035 0.19713 -0.1555 0.965679 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4494.5 -207.274 1523.58 3928.13 -217.672 4415.47 +EDGE_SE3:QUAT 1621 1622 -0.762948 9.69778 -0.46162 -0.015698 -0.0218278 0.142425 0.98944 1 7.70372e-19 7.70372e-19 9.16549e-10 1.17933e-09 -5.49605e-08 1 7.70372e-19 9.16549e-10 1.17933e-09 -5.49605e-08 1 9.16549e-10 1.17933e-09 -5.49605e-08 4004.08 2.25377 -142.933 3999.04 -9.58686 3923.92 +EDGE_SE3:QUAT 1622 1623 -0.791202 10.1354 -0.139041 -0.0718478 -0.0988229 0.109895 0.986405 1 1.92593e-19 1.92593e-19 -2.77785e-08 -3.52051e-09 2.23412e-09 1 1.92593e-19 -2.77785e-08 -3.52051e-09 2.23412e-09 1 -2.77785e-08 -3.52051e-09 2.23412e-09 4094.82 46.7499 -690.915 3978.13 -52.9922 4067.16 +EDGE_SE3:QUAT 1623 1624 -0.760459 9.86547 -0.195371 0.025995 0.083872 0.0707092 0.993625 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4102.6 20.605 657.603 3975.73 28.8284 4085.31 +EDGE_SE3:QUAT 1624 1625 -0.663131 10.0236 0.0805615 -0.0313254 0.0554535 -0.0164815 0.997834 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4044.15 -8.29694 441.135 3988.29 -6.02098 4046.98 +EDGE_SE3:QUAT 1625 1626 -0.815459 10.2817 -0.0078472 0.169152 -0.150102 0.161121 0.960675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4459.94 -48.2926 -1621.83 3868.5 -32.4348 4470.55 +EDGE_SE3:QUAT 1626 1627 -1.08067 10.3428 -0.2889 0.0201875 0.119422 0.0288444 0.992219 1 1.92593e-19 1.92593e-19 9.59798e-10 -2.75345e-08 7.70854e-10 1 1.92593e-19 9.59798e-10 -2.75345e-08 7.70854e-10 1 9.59798e-10 -2.75345e-08 7.70854e-10 4232 21.9482 994.54 3944.87 23.7566 4230.3 +EDGE_SE3:QUAT 1627 1628 -0.7024 9.94168 -0.256819 0.0107111 -0.00108302 0.0414224 0.999084 1 4.70198e-23 4.70198e-23 -1.795e-11 4.33284e-10 -4.59041e-12 1 4.70198e-23 -1.795e-11 4.33284e-10 -4.59041e-12 1 -1.795e-11 4.33284e-10 -4.59041e-12 3999.59 -0.0816825 -13.9582 3999.98 -0.325033 3993.18 +EDGE_SE3:QUAT 1628 1629 -0.629794 9.88461 0.141743 0.0215736 -0.0970854 -0.0640302 0.99298 1 2.40741e-19 2.40741e-19 1.2105e-08 -2.85316e-08 -3.65286e-10 1 2.40741e-19 1.2105e-08 -2.85316e-08 -3.65286e-10 1 1.2105e-08 -2.85316e-08 -3.65286e-10 4144.26 -23.635 -778.409 3966.06 31.9893 4129.72 +EDGE_SE3:QUAT 1629 1630 -0.811575 9.98982 0.271669 -0.168144 0.0633745 0.0316867 0.983213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3963.12 -46.694 557.386 3982.29 -9.54602 4072.19 +EDGE_SE3:QUAT 1630 1631 -0.431912 9.9213 -0.509953 -0.0843028 0.0458547 0.025479 0.995058 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.54 -15.7763 391.595 3990.48 0.477395 4035.37 +EDGE_SE3:QUAT 1631 1632 -0.427696 9.424 -0.242942 -0.0563866 -0.0196956 -0.0714649 0.995653 1 4.81482e-20 4.81482e-20 -1.38355e-08 9.56916e-10 3.808e-10 1 4.81482e-20 -1.38355e-08 9.56916e-10 3.808e-10 1 -1.38355e-08 9.56916e-10 3.808e-10 3997.63 5.21641 -204.226 3997.06 7.09458 3989.92 +EDGE_SE3:QUAT 1632 1633 -0.721996 9.96289 -0.219804 -0.147286 0.0457802 -0.120943 0.980604 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3916.35 -6.02367 137.239 4000.26 -5.57669 3944.61 +EDGE_SE3:QUAT 1633 1634 -0.722112 9.76116 -0.300731 -0.0721885 0.0869988 0.0918814 0.989332 1 1.92593e-19 1.92593e-19 2.79734e-08 2.2563e-09 2.77176e-09 1 1.92593e-19 2.79734e-08 2.2563e-09 2.77176e-09 1 2.79734e-08 2.2563e-09 2.77176e-09 4128.44 -11.5497 787.24 3962.84 24.5568 4115.52 +EDGE_SE3:QUAT 1634 1635 -0.571102 9.65199 0.448408 0.147688 -0.0495747 0.12262 0.980151 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.18 -36.8106 -600.308 3975.22 -25.2067 4027.28 +EDGE_SE3:QUAT 1635 1636 -0.893163 9.65198 -0.1707 -0.00385673 0.012392 0.0641381 0.997857 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.52 0.0482218 101.541 3999.36 3.27213 3986.12 +EDGE_SE3:QUAT 1636 1637 -0.865918 9.77697 0.175703 0.0183215 0.0361213 0.137347 0.989695 1 7.82409e-19 7.82409e-19 -5.22741e-09 5.64804e-10 5.48423e-08 1 7.82409e-19 -5.22741e-09 5.64804e-10 5.48423e-08 1 -5.22741e-09 5.64804e-10 5.48423e-08 4014.37 5.72446 251.623 3996.82 17.0682 3940.25 +EDGE_SE3:QUAT 1637 1638 -0.723238 9.87863 -0.113606 0.0351791 0.0443428 0.0571085 0.996762 1 9.62965e-20 9.62965e-20 1.3043e-08 1.467e-08 -1.27069e-12 1 9.62965e-20 1.3043e-08 1.467e-08 -1.27069e-12 1 1.3043e-08 1.467e-08 -1.27069e-12 4022.09 8.17705 330.122 3993.78 10.8407 4013.99 +EDGE_SE3:QUAT 1638 1639 -0.682287 9.56356 -0.0267881 0.100955 -0.0308592 0.0739499 0.991659 1 1.92593e-19 1.92593e-19 -2.76189e-08 -1.84991e-09 1.24625e-09 1 1.92593e-19 -2.76189e-08 -1.84991e-09 1.24625e-09 1 -2.76189e-08 -1.84991e-09 1.24625e-09 3986.45 -15.6829 -332.025 3992.3 -9.75842 4005.34 +EDGE_SE3:QUAT 1639 1640 -0.560871 9.90843 -0.142319 -0.0626908 0.174694 0.148213 0.971383 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4576.76 68.3077 1649.54 3873.36 108.617 4504.61 +EDGE_SE3:QUAT 1640 1641 -0.476713 9.61333 0.0374033 -0.0109593 0.0630668 0.036196 0.997292 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4064.89 0.615182 515.519 3983.86 8.66743 4060.13 +EDGE_SE3:QUAT 1641 1642 -0.499992 9.65385 -0.136946 0.0534083 0.0326524 0.116238 0.991247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.59 5.89216 181.284 3998.72 9.84313 3953.95 +EDGE_SE3:QUAT 1642 1643 -0.994778 9.76611 -0.151229 0.0637556 0.158266 0.247119 0.953844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4212.38 142.593 994.502 3986.73 163.177 3984.37 +EDGE_SE3:QUAT 1643 1644 -0.622017 9.77826 0.347117 -0.093834 -0.116572 0.0212695 0.988511 1 4.81482e-20 4.81482e-20 1.56959e-09 1.44307e-09 -1.40738e-08 1 4.81482e-20 1.56959e-09 1.44307e-09 -1.40738e-08 1 1.56959e-09 1.44307e-09 -1.40738e-08 4172.59 56.368 -935.273 3954.09 -41.9113 4206 +EDGE_SE3:QUAT 1644 1645 -0.684553 9.50463 -0.531515 0.105587 -0.0617282 0.0882923 0.988557 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4044.19 -24.0719 -603.166 3976.74 -16.1261 4057.6 +EDGE_SE3:QUAT 1645 1646 -0.658457 9.47904 -0.340032 0.0663899 -0.0262015 -0.0786259 0.994346 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.43 -4.82212 -144.158 3999.15 5.45778 3980.33 +EDGE_SE3:QUAT 1646 1647 -1.05504 9.99007 -0.322597 0.107917 -0.102131 0.108075 0.982977 1 1.15556e-18 1.15556e-18 -5.505e-08 1.99943e-08 -2.35343e-08 1 1.15556e-18 -5.505e-08 1.99943e-08 -2.35343e-08 1 -5.505e-08 1.99943e-08 -2.35343e-08 4178.9 -25.9168 -976.544 3944.32 -26.0596 4178.76 +EDGE_SE3:QUAT 1647 1648 -0.867449 9.83031 -0.238696 -0.0626477 0.101334 0.0444052 0.991884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4165.66 -18.4836 870.846 3955.89 4.55199 4173.47 +EDGE_SE3:QUAT 1648 1649 -0.600565 9.73614 0.00957722 0.0259559 0.162456 0.037281 0.98567 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4442.88 49.6911 1407.45 3899.86 51.8578 4440.02 +EDGE_SE3:QUAT 1649 1650 -0.706277 9.37105 -0.235849 0.0377156 -0.00307521 0.217124 0.97541 1 4.81482e-20 4.81482e-20 1.35424e-08 3.00299e-09 -2.60362e-10 1 4.81482e-20 1.35424e-08 3.00299e-09 -2.60362e-10 1 1.35424e-08 3.00299e-09 -2.60362e-10 3997.59 -2.04403 -118.021 3998.69 -16.1745 3814.71 +EDGE_SE3:QUAT 1650 1651 -0.809344 9.74715 0.0352996 -0.0365097 -0.0525381 0.25497 0.96483 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.28 13.2649 -272.646 3998.94 -30.1144 3757.57 +EDGE_SE3:QUAT 1651 1652 -0.340857 9.51991 -0.194526 -0.0980647 0.0374186 -0.0519141 0.99312 1 1.92593e-19 1.92593e-19 -2.76116e-08 1.62216e-09 -7.32448e-10 1 1.92593e-19 -2.76116e-08 1.62216e-09 -7.32448e-10 1 -2.76116e-08 1.62216e-09 -7.32448e-10 3975 -11.7039 233.722 3997.45 -7.83597 4002.69 +EDGE_SE3:QUAT 1652 1653 -0.710323 9.76846 0.18331 0.19972 0.0448478 -0.0203352 0.978615 1 3.13265e-18 3.13265e-18 1.09363e-07 1.4144e-08 6.14515e-09 1 3.13265e-18 1.09363e-07 1.4144e-08 6.14515e-09 1 1.09363e-07 1.4144e-08 6.14515e-09 3877.76 39.444 388.123 3991.77 6.98477 4035.66 +EDGE_SE3:QUAT 1653 1654 -0.609812 9.73114 0.388984 0.0771396 -0.0680225 0.184864 0.977368 1 1.15556e-18 1.15556e-18 -2.72707e-08 1.95706e-08 -5.38519e-08 1 1.15556e-18 -2.72707e-08 1.95706e-08 -5.38519e-08 1 -2.72707e-08 1.95706e-08 -5.38519e-08 4094.41 0.413778 -698.519 3970.39 -60.271 3981.51 +EDGE_SE3:QUAT 1654 1655 -0.343175 9.44492 0.178783 -0.134289 -0.0803442 0.0282096 0.987277 1 7.70372e-19 7.70372e-19 5.53953e-08 2.75496e-09 -3.90843e-09 1 7.70372e-19 5.53953e-08 2.75496e-09 -3.90843e-09 1 5.53953e-08 2.75496e-09 -3.90843e-09 4012.78 44.4525 -589.593 3982.68 -26.8931 4081.73 +EDGE_SE3:QUAT 1655 1656 -0.80526 9.75235 -0.179098 0.181866 0.129177 0.127965 0.966366 1 7.70372e-19 7.70372e-19 -5.44333e-08 -9.54805e-09 -3.88571e-09 1 7.70372e-19 -5.44333e-08 -9.54805e-09 -3.88571e-09 1 -5.44333e-08 -9.54805e-09 -3.88571e-09 3979.24 88.5383 692.125 3993.85 83.2442 4046.04 +EDGE_SE3:QUAT 1656 1657 -0.616744 8.93586 0.0743341 -0.221736 -0.117414 0.127436 0.959587 1 7.70372e-19 7.70372e-19 -5.36979e-08 -9.42064e-09 2.54765e-09 1 7.70372e-19 -5.36979e-08 -9.42064e-09 2.54765e-09 1 -5.36979e-08 -9.42064e-09 2.54765e-09 3863.29 64.6808 -520.288 4002.25 -58.7672 3995 +EDGE_SE3:QUAT 1657 1658 -0.504191 9.52797 0.0532889 -0.185764 0.104798 -0.0833186 0.973431 1 7.70372e-19 7.70372e-19 -5.46669e-08 6.60775e-09 -3.64386e-09 1 7.70372e-19 -5.46669e-08 6.60775e-09 -3.64386e-09 1 -5.46669e-08 6.60775e-09 -3.64386e-09 3951.47 -68.2301 612.464 3990.08 -55.6044 4061.74 +EDGE_SE3:QUAT 1658 1659 -0.725441 9.27536 0.110748 0.0251972 0.202808 -0.0927018 0.974495 1 7.71124e-19 7.71124e-19 -3.15936e-09 -5.42793e-08 -3.33388e-10 1 7.71124e-19 -3.15936e-09 -5.42793e-08 -3.33388e-10 1 -3.15936e-09 -5.42793e-08 -3.33388e-10 4754.65 -79.512 1897.93 3839.93 -97.17 4722.82 +EDGE_SE3:QUAT 1659 1660 -0.875103 9.63446 0.182516 -0.026246 0.0879636 0.0589582 0.994031 1 4.81482e-20 4.81482e-20 -1.27475e-09 2.25769e-10 -1.40218e-08 1 4.81482e-20 -1.27475e-09 2.25769e-10 -1.40218e-08 1 -1.27475e-09 2.25769e-10 -1.40218e-08 4129.38 1.19931 738.937 3967.75 18.5162 4118.23 +EDGE_SE3:QUAT 1660 1661 -0.777557 9.58355 0.29864 -0.0228133 0.0226808 0.0229886 0.999218 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.72 -1.87773 187.82 3997.76 1.89675 4006.68 +EDGE_SE3:QUAT 1661 1662 -0.58939 9.53234 -0.176292 -0.029715 0.0884094 0.288817 0.95283 1 7.52316e-22 7.52316e-22 1.68241e-09 5.08989e-10 1.58961e-10 1 7.52316e-22 1.68241e-09 5.08989e-10 1.58961e-10 1 1.68241e-09 5.08989e-10 1.58961e-10 4128.45 48.3016 739.021 3979.52 110.857 3798.33 +EDGE_SE3:QUAT 1662 1663 -0.459586 9.31879 0.151699 0.0851383 -0.0594824 0.159841 0.981664 1 1.92593e-19 1.92593e-19 2.75808e-08 4.18293e-09 -2.32069e-09 1 1.92593e-19 2.75808e-08 4.18293e-09 -2.32069e-09 1 2.75808e-08 4.18293e-09 -2.32069e-09 4066.72 -8.79455 -627.234 3974.83 -45.1745 3993.52 +EDGE_SE3:QUAT 1663 1664 -0.456835 9.60833 0.0257712 -0.00278259 -0.056208 0.0351555 0.997796 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.54 3.33892 -452.588 3987.58 -8.42014 4045.63 +EDGE_SE3:QUAT 1664 1665 -0.749758 9.32412 -0.0274421 0.298241 0.0534793 0.199605 0.931853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3654.57 -84.0392 -306.074 3979.7 -55.0997 3850.99 +EDGE_SE3:QUAT 1665 1666 -0.767321 9.47522 0.0660324 0.178832 0.0987766 0.0935057 0.974433 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3944.26 58.3012 550.774 3992.61 48.6457 4037.21 +EDGE_SE3:QUAT 1666 1667 -1.03696 9.33854 -0.0703214 -0.0766828 0.0776997 -0.164688 0.980286 1 1.92593e-19 1.92593e-19 2.73764e-08 -4.92094e-09 1.32236e-09 1 1.92593e-19 2.73764e-08 -4.92094e-09 1.32236e-09 1 2.73764e-08 -4.92094e-09 1.32236e-09 4024.25 -30.2033 445.161 3993.73 -40.1087 3939.29 +EDGE_SE3:QUAT 1667 1668 -0.468081 9.66645 -0.372321 -0.0147961 -0.0495471 0.247147 0.967597 1 9.62965e-20 9.62965e-20 -1.00112e-08 -1.68953e-08 -5.44134e-12 1 9.62965e-20 -1.00112e-08 -1.68953e-08 -5.44134e-12 1 -1.00112e-08 -1.68953e-08 -5.44134e-12 4024.19 13.018 -319.751 3996.74 -37.6265 3780.74 +EDGE_SE3:QUAT 1668 1669 -0.811657 9.5169 -0.0471733 0.0413501 -0.0829497 0.0148911 0.995584 1 2.40741e-19 2.40741e-19 1.37875e-08 2.77495e-08 -2.27475e-09 1 2.40741e-19 1.37875e-08 2.77495e-08 -2.27475e-09 1 1.37875e-08 2.77495e-08 -2.27475e-09 4107.51 -12.6827 -685.902 3972.04 1.66756 4113.46 +EDGE_SE3:QUAT 1669 1670 -0.443308 9.53462 -0.332213 0.0705463 0.0320071 0.0162622 0.996862 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.56 8.76717 241.047 3996.63 3.52028 4013.41 +EDGE_SE3:QUAT 1670 1671 -0.941901 9.26793 0.0835568 -0.185475 -0.0122334 0.0645045 0.980453 1 1.92593e-19 1.92593e-19 3.38332e-10 -5.15471e-09 2.72118e-08 1 1.92593e-19 3.38332e-10 -5.15471e-09 2.72118e-08 1 3.38332e-10 -5.15471e-09 2.72118e-08 3862.39 -9.03201 47.6226 3999.41 3.14164 3983.35 +EDGE_SE3:QUAT 1671 1672 -0.260006 9.92097 -0.540171 -0.00927548 -0.00710036 -0.0354226 0.999304 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.57 0.239805 -60.6406 3999.76 1.0848 3995.9 +EDGE_SE3:QUAT 1672 1673 -0.436796 9.43293 -0.273547 -0.07786 0.0468084 0.228851 0.969213 1 1.92593e-19 1.92593e-19 -6.12792e-09 2.6953e-08 1.36933e-09 1 1.92593e-19 -6.12792e-09 2.6953e-08 1.36933e-09 1 -6.12792e-09 2.6953e-08 1.36933e-09 4051.86 -1.38061 558.672 3980.05 65.3515 3866.62 +EDGE_SE3:QUAT 1673 1674 -0.895632 9.51194 -0.0423395 -0.106597 0.00917903 -0.00849161 0.994224 1 1.95602e-19 1.95602e-19 -2.7563e-08 3.73376e-09 1.7137e-10 1 1.95602e-19 -2.7563e-08 3.73376e-09 1.7137e-10 1 -2.7563e-08 3.73376e-09 1.7137e-10 3955.49 -3.07287 61.4071 3999.81 -0.408661 4000.65 +EDGE_SE3:QUAT 1674 1675 -0.461838 9.2788 0.0210525 -0.202672 0.0606572 -0.0499933 0.976087 1 7.70372e-19 7.70372e-19 5.43771e-08 -3.91715e-09 1.9699e-09 1 7.70372e-19 5.43771e-08 -3.91715e-09 1.9699e-09 1 5.43771e-08 -3.91715e-09 1.9699e-09 3862.99 -32.4151 336.684 3996.9 -17.9278 4017.3 +EDGE_SE3:QUAT 1675 1676 -0.771576 9.40223 -0.218104 0.162098 0.116916 0.134558 0.970541 1 9.62965e-19 9.62965e-19 -4.98801e-08 -3.62333e-08 1.76896e-09 1 9.62965e-19 -4.98801e-08 -3.62333e-08 1.76896e-09 1 -4.98801e-08 -3.62333e-08 1.76896e-09 3985.82 71.24 622.96 3993.5 68.436 4018.5 +EDGE_SE3:QUAT 1676 1677 -0.653404 9.34943 -0.540006 0.0137808 -0.0226045 0.0403002 0.998837 1 1.50463e-20 1.50463e-20 3.74472e-09 -6.79309e-09 6.8885e-13 1 1.50463e-20 3.74472e-09 -6.79309e-09 6.8885e-13 1 3.74472e-09 -6.79309e-09 6.8885e-13 4008 -0.789825 -187.368 3997.78 -3.65939 4002.26 +EDGE_SE3:QUAT 1677 1678 -0.614264 9.54482 0.0933201 0.145526 0.033464 0.0683515 0.986423 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3919.68 7.81991 139.967 3999.66 4.88054 3985.7 +EDGE_SE3:QUAT 1678 1679 -0.68433 9.40618 -0.470488 0.0815703 0.0424358 0.0203406 0.995556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.44 13.6605 317.703 3994.27 6.3995 4023.4 +EDGE_SE3:QUAT 1679 1680 -0.826722 9.11066 -0.474142 0.0866641 0.0633612 -0.089086 0.990221 1 1.92593e-19 1.92593e-19 -2.77882e-08 2.17688e-09 -2.15741e-09 1 1.92593e-19 -2.77882e-08 2.17688e-09 -2.15741e-09 1 -2.77882e-08 2.17688e-09 -2.15741e-09 4057.69 17.271 599.311 3977.26 -18.3717 4055.99 +EDGE_SE3:QUAT 1680 1681 -0.79959 9.3222 -0.421476 0.0500094 -0.0400345 0.0665592 0.995724 1 4.81482e-20 4.81482e-20 1.3874e-08 8.70236e-10 -6.42897e-10 1 4.81482e-20 1.3874e-08 8.70236e-10 -6.42897e-10 1 1.3874e-08 8.70236e-10 -6.42897e-10 4022 -6.3919 -359.402 3991.66 -10.2891 4014.28 +EDGE_SE3:QUAT 1681 1682 -0.702884 9.37704 0.175445 -0.0908824 -0.241326 0.0152126 0.966059 1 7.70372e-19 7.70372e-19 -3.592e-09 5.35133e-08 6.13525e-09 1 7.70372e-19 -3.592e-09 5.35133e-08 6.13525e-09 1 -3.592e-09 5.35133e-08 6.13525e-09 5027.68 199.458 -2317.07 3800.82 -193.417 5059.79 +EDGE_SE3:QUAT 1682 1683 -0.74009 9.14109 -0.161275 0.0302897 -0.0504809 -0.0708937 0.995745 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.57 -9.61854 -377.282 3991.96 15.0275 4015.14 +EDGE_SE3:QUAT 1683 1684 -0.755361 9.32595 -0.0659167 -0.0730279 0.00918186 0.124059 0.989541 1 1.92593e-19 1.92593e-19 2.74922e-08 3.3742e-09 7.42877e-10 1 1.92593e-19 2.74922e-08 3.3742e-09 7.42877e-10 1 2.74922e-08 3.3742e-09 7.42877e-10 3986.36 -6.71166 178.766 3997.24 12.657 3946.13 +EDGE_SE3:QUAT 1684 1685 -0.42162 9.45726 0.298523 -0.00307852 0.0113771 -0.0988771 0.99503 1 1.92593e-19 1.92593e-19 2.92845e-10 -1.45982e-10 2.76241e-08 1 1.92593e-19 2.92845e-10 -1.45982e-10 2.76241e-08 1 2.92845e-10 -1.45982e-10 2.76241e-08 4001.81 -0.413274 86.0884 3999.57 -4.188 3962.74 +EDGE_SE3:QUAT 1685 1686 -0.489758 9.39873 -0.0222075 0.00457282 -0.0781991 0.0762174 0.99401 1 1.88079e-22 1.88079e-22 8.72859e-10 6.71256e-11 -6.84773e-11 1 1.88079e-22 8.72859e-10 6.71256e-11 -6.84773e-11 1 8.72859e-10 6.71256e-11 -6.84773e-11 4099.17 9.96901 -637.863 3976.27 -25.177 4076.02 +EDGE_SE3:QUAT 1686 1687 -0.949596 9.35468 -0.0418509 -0.107485 -0.0131226 -0.0281067 0.993723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3958.6 7.92956 -139.166 3998.63 1.41977 4001.65 +EDGE_SE3:QUAT 1687 1688 -0.851274 9.04919 0.457859 0.1535 -0.0652659 0.218142 0.961557 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4094.58 -29.0313 -893.637 3948.04 -80.5647 3998.48 +EDGE_SE3:QUAT 1688 1689 -0.768781 9.57195 -0.286319 -0.0733052 -0.18951 0.0137601 0.979042 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4596.57 99.2899 -1689.52 3869 -89.6243 4617.31 +EDGE_SE3:QUAT 1689 1690 -0.88277 9.34849 0.0133875 -0.215363 0.163964 0.0944171 0.958029 1 4.81482e-20 4.81482e-20 2.79393e-09 -2.88737e-09 1.42867e-08 1 4.81482e-20 2.79393e-09 -2.88737e-09 1.42867e-08 1 2.79393e-09 -2.88737e-09 1.42867e-08 4402.8 -156.871 1643.07 3880.3 -91.2874 4552.67 +EDGE_SE3:QUAT 1690 1691 -0.776122 9.41367 -0.303577 0.0269709 0.0242183 0.0683351 0.997004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.32 2.99503 170.377 3998.4 5.89491 3988.55 +EDGE_SE3:QUAT 1691 1692 -0.540651 9.48628 0.0317454 0.17267 -0.0272049 0.150481 0.973037 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.07 -42.2586 -510.166 3979.22 -33.6808 3971.75 +EDGE_SE3:QUAT 1692 1693 -1.21392 8.61783 -0.164971 -0.0539661 -0.0873175 0.113451 0.988227 1 3.85186e-19 3.85186e-19 -2.43202e-08 -3.08731e-08 -2.67479e-12 1 3.85186e-19 -2.43202e-08 -3.08731e-08 -2.67479e-12 1 -2.43202e-08 -3.08731e-08 -2.67479e-12 4081.99 34.5133 -620.177 3981.41 -44.2127 4042.15 +EDGE_SE3:QUAT 1693 1694 -0.713284 9.39014 0.0125476 0.122587 -0.139192 0.019327 0.982458 1 1.92781e-19 1.92781e-19 2.82656e-08 -3.34499e-10 -3.1491e-09 1 1.92781e-19 2.82656e-08 -3.34499e-10 -3.1491e-09 1 2.82656e-08 -3.34499e-10 -3.1491e-09 4271.01 -78.9767 -1197.57 3927.03 49.5631 4329.63 +EDGE_SE3:QUAT 1694 1695 -0.761725 8.88161 0.103145 -0.0703493 -0.109746 -0.087851 0.987567 1 4.33334e-19 4.33334e-19 8.63738e-09 -2.99644e-08 2.50539e-08 1 4.33334e-19 8.63738e-09 -2.99644e-08 2.50539e-08 1 8.63738e-09 -2.99644e-08 2.50539e-08 4209.19 9.92639 -984.171 3944.47 25.9379 4198.11 +EDGE_SE3:QUAT 1695 1696 -0.900095 9.21745 0.00850321 -0.0139438 -0.0325259 -0.152475 0.987674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.37 -2.33279 -277.451 3995.47 21.4285 3926.16 +EDGE_SE3:QUAT 1696 1697 -0.724879 9.30903 -0.319755 0.000513868 -0.0628522 -0.0110963 0.997961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.92 -1.20832 -509.678 3984.22 2.9948 4063.43 +EDGE_SE3:QUAT 1697 1698 -0.896425 9.09989 -0.171549 -0.096264 -0.0210062 -0.0544065 0.993646 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.81 11.0661 -228.056 3996.3 5.11621 4001.04 +EDGE_SE3:QUAT 1698 1699 -0.372334 9.09967 -0.127171 0.128738 0.0198104 0.176747 0.975599 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3935.12 -13.4856 -117.141 3997.2 -18.6183 3876.46 +EDGE_SE3:QUAT 1699 1700 -0.968815 9.53547 0.0537589 0.104639 0.19817 -0.0306203 0.974085 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4680.31 103.389 1849.53 3847.16 82.229 4720.35 +EDGE_SE3:QUAT 1700 1701 -0.704202 8.9967 -0.234418 -0.0140586 0.0150599 0.0996175 0.994813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.79 -0.33448 135.494 3998.81 6.92348 3964.89 +EDGE_SE3:QUAT 1701 1702 -0.463627 8.81333 -0.297556 -0.126462 0.218526 0.0915552 0.963261 1 1.92593e-19 1.92593e-19 -7.23713e-09 2.96656e-09 -2.99502e-08 1 1.92593e-19 -7.23713e-09 2.96656e-09 -2.99502e-08 1 -7.23713e-09 2.96656e-09 -2.99502e-08 4935.77 -73.9395 2235.77 3792.24 -45.029 4966.21 +EDGE_SE3:QUAT 1702 1703 -0.526512 9.17218 -0.130339 0.172796 -0.234842 0.241875 0.925466 1 9.62965e-19 9.62965e-19 4.90807e-08 2.17983e-09 -7.02924e-08 1 9.62965e-19 4.90807e-08 2.17983e-09 -7.02924e-08 1 4.90807e-08 2.17983e-09 -7.02924e-08 5405.54 159.055 -2902.93 3723.39 -202.233 5290.96 +EDGE_SE3:QUAT 1703 1704 -0.461915 9.30388 -0.22119 0.222502 0.0764585 0.133451 0.962724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3807.5 12.2892 207.355 4002.19 12.0506 3934.29 +EDGE_SE3:QUAT 1704 1705 -0.86181 9.21109 0.0399317 0.0018453 0.00669912 0.0744589 0.9972 1 1.92781e-19 1.92781e-19 -1.04129e-09 -1.4289e-10 -2.76857e-08 1 1.92781e-19 -1.04129e-09 -1.4289e-10 -2.76857e-08 1 -1.04129e-09 -1.4289e-10 -2.76857e-08 4000.65 0.122534 51.5122 3999.84 1.89449 3978.49 +EDGE_SE3:QUAT 1705 1706 -0.904281 9.29122 -0.223442 -0.0352683 -0.0904028 0.124808 0.987424 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4103.04 34.0125 -666.837 3977.94 -49.52 4045.71 +EDGE_SE3:QUAT 1706 1707 -0.291405 9.11947 -0.355 -0.128021 -0.0152943 0.0629984 0.98965 1 7.52316e-22 7.52316e-22 -1.12437e-10 1.71657e-09 2.23649e-10 1 7.52316e-22 -1.12437e-10 1.71657e-09 2.23649e-10 1 -1.12437e-10 1.71657e-09 2.23649e-10 3934.3 -0.618702 -23.14 4000.01 0.234768 3983.98 +EDGE_SE3:QUAT 1707 1708 -0.448754 9.09126 0.0331623 -0.0150549 0.00535142 0.0593522 0.998109 1 3.00927e-21 3.00927e-21 3.46319e-09 2.053e-10 2.46185e-11 1 3.00927e-21 3.46319e-09 2.053e-10 2.46185e-11 1 3.46319e-09 2.053e-10 2.46185e-11 3999.8 -0.369623 53.2757 3999.8 1.67065 3986.62 +EDGE_SE3:QUAT 1708 1709 -0.697133 9.07288 -0.682525 -0.029695 0.0411509 0.165262 0.984943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.55 2.47106 376.32 3991.46 31.4874 3925.83 +EDGE_SE3:QUAT 1709 1710 -0.959954 9.17996 -0.0616286 0.116221 0.0244848 0.0129363 0.992837 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3953.53 9.91061 174.254 3998.38 2.49177 4006.89 +EDGE_SE3:QUAT 1710 1711 -0.59743 8.70396 -0.314904 0.0201811 -0.0754003 0.0351963 0.996328 1 1.20371e-20 1.20371e-20 -6.99497e-09 -2.28235e-10 5.37714e-10 1 1.20371e-20 -6.99497e-09 -2.28235e-10 5.37714e-10 1 -6.99497e-09 -2.28235e-10 5.37714e-10 4093.16 -1.65829 -622.998 3976.65 -8.78642 4089.83 +EDGE_SE3:QUAT 1711 1712 -0.899996 8.91304 -0.0411668 -0.00629644 -0.0386468 -0.0429766 0.998308 1 7.52316e-22 7.52316e-22 -1.73707e-09 7.41515e-11 6.79357e-11 1 7.52316e-22 -1.73707e-09 7.41515e-11 6.79357e-11 1 -1.73707e-09 7.41515e-11 6.79357e-11 4024.22 -0.567746 -313.216 3993.95 6.62408 4016.99 +EDGE_SE3:QUAT 1712 1713 -0.694825 9.21721 0.0517766 -0.0777322 -0.122062 0.00837955 0.989438 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4216.17 48.2997 -1009.56 3945.07 -34.0028 4240.06 +EDGE_SE3:QUAT 1713 1714 -0.592267 9.0173 -0.0093867 -0.0466992 0.0867453 -0.0655072 0.992977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4098.91 -27.4327 665.144 3975.83 -30.8313 4090.47 +EDGE_SE3:QUAT 1714 1715 -1.04696 9.33547 -0.346919 0.000689802 -0.0662364 0.183119 0.980857 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4064.4 18.3732 -511.901 3987.02 -48.1404 3930.27 +EDGE_SE3:QUAT 1715 1716 -0.470048 8.90605 0.232256 -0.102547 0.0378227 0.148128 0.98291 1 1.92593e-19 1.92593e-19 -2.74726e-08 -3.85557e-09 -1.82749e-09 1 1.92593e-19 -2.74726e-08 -3.85557e-09 -1.82749e-09 1 -2.74726e-08 -3.85557e-09 -1.82749e-09 4012.54 -17.1433 473.009 3984.04 32.7633 3966.84 +EDGE_SE3:QUAT 1716 1717 -0.614282 8.88878 -0.406413 0.0359163 0.0440783 0.0161284 0.998252 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.73 7.04413 347.076 3992.74 4.46745 4028.85 +EDGE_SE3:QUAT 1717 1718 -0.851473 8.89056 -0.31895 -0.10735 0.0725712 -0.116459 0.984706 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.14 -28.8981 413.121 3994.1 -29.8887 3986.99 +EDGE_SE3:QUAT 1718 1719 -0.630616 8.98603 -0.318261 -0.0456237 0.0548868 0.0233696 0.997176 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.84 -9.02433 455.278 3987.23 2.05023 4048.98 +EDGE_SE3:QUAT 1719 1720 -0.705037 8.79274 -0.201517 0.0457448 0.19011 -0.00166548 0.980695 1 7.52316e-22 7.52316e-22 -3.54101e-10 -9.09299e-11 -1.83333e-09 1 7.52316e-22 -3.54101e-10 -9.09299e-11 -1.83333e-09 1 -3.54101e-10 -9.09299e-11 -1.83333e-09 4635.42 53.3216 1729.05 3858.23 45.4402 4643.78 +EDGE_SE3:QUAT 1720 1721 -0.887145 8.76463 -0.113402 0.0201352 0.100044 0.0643542 0.992695 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4154.45 24.4471 805.43 3963.76 33.2386 4139.5 +EDGE_SE3:QUAT 1721 1722 -0.649653 8.91699 -0.0900797 0.0686091 0.0253444 0.00884977 0.997282 1 2.0463e-19 2.0463e-19 2.76279e-08 7.2602e-09 1.84128e-10 1 2.0463e-19 2.76279e-08 7.2602e-09 1.84128e-10 1 2.76279e-08 7.2602e-09 1.84128e-10 3990.6 6.74066 194.424 3997.77 1.84616 4009.11 +EDGE_SE3:QUAT 1722 1723 -0.825958 9.00914 -0.146729 0.0145145 -0.0817751 0.292063 0.952786 1 3.0845e-18 3.0845e-18 -1.18814e-08 -4.85232e-09 1.07449e-07 1 3.0845e-18 -1.18814e-08 -4.85232e-09 1.07449e-07 1 -1.18814e-08 -4.85232e-09 1.07449e-07 4096.68 41.6124 -633.387 3986.71 -95.1026 3756.32 +EDGE_SE3:QUAT 1723 1724 -0.766034 8.6371 -0.240093 0.0475031 0.00932724 0.301249 0.952316 1 3.08224e-18 3.08224e-18 -1.66181e-09 3.25913e-09 1.05829e-07 1 3.08224e-18 -1.66181e-09 3.25913e-09 1.05829e-07 1 -1.66181e-09 3.25913e-09 1.05829e-07 3992.6 -3.34516 -96.6555 3998.5 -23.6416 3638.62 +EDGE_SE3:QUAT 1724 1725 -0.692422 8.6104 -0.411783 -0.0886654 0.126662 0.0766067 0.985001 1 7.70372e-19 7.70372e-19 5.67577e-08 3.17749e-09 7.9023e-09 1 7.70372e-19 5.67577e-08 3.17749e-09 7.9023e-09 1 5.67577e-08 3.17749e-09 7.9023e-09 4274.92 -25.706 1148.73 3926.96 11.7547 4282.89 +EDGE_SE3:QUAT 1725 1726 -0.837199 8.66704 0.055834 0.0463284 -0.204449 -0.00961472 0.977733 1 6.01853e-20 6.01853e-20 1.63218e-08 -8.77633e-10 -1.04579e-08 1 6.01853e-20 1.63218e-08 -8.77633e-10 -1.04579e-08 1 1.63218e-08 -8.77633e-10 -1.04579e-08 4741.99 -75.3269 -1888.32 3839.16 69.9625 4750.21 +EDGE_SE3:QUAT 1726 1727 -0.666553 8.60263 -0.202108 -0.0537577 0.155993 0.0715841 0.983693 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4433.1 1.29593 1405.85 3897.37 27.1043 4424.16 +EDGE_SE3:QUAT 1727 1728 -1.0129 8.61362 -0.347029 -0.00288412 -0.059266 0.0839089 0.994705 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4054.85 7.7322 -471.774 3986.99 -20.6472 4026.72 +EDGE_SE3:QUAT 1728 1729 -0.911676 8.91045 -0.247266 -0.0611819 0.19089 -0.012648 0.979621 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4619.9 -85.8955 1715.42 3863.62 -78.0219 4634.23 +EDGE_SE3:QUAT 1729 1730 -0.514994 9.29341 -0.059949 -0.104827 0.00557132 0.172894 0.97933 1 1.92593e-19 1.92593e-19 2.72352e-08 4.67195e-09 1.12978e-09 1 1.92593e-19 2.72352e-08 4.67195e-09 1.12978e-09 1 2.72352e-08 4.67195e-09 1.12978e-09 3971.11 -14.306 254.442 3993.72 26.5606 3895.5 +EDGE_SE3:QUAT 1730 1731 -0.527408 9.03168 -0.0575734 0.0746899 -0.106544 0.0182861 0.99133 1 3.00927e-21 3.00927e-21 3.83855e-10 -2.5734e-10 -3.5215e-09 1 3.00927e-21 3.83855e-10 -2.5734e-10 -3.5215e-09 1 3.83855e-10 -2.5734e-10 -3.5215e-09 4169.92 -32.3768 -897.706 3954.29 12.7189 4190.89 +EDGE_SE3:QUAT 1731 1732 -0.347306 8.67653 -0.284272 0.0305908 0.0053753 0.0789884 0.996392 1 2.0463e-19 2.0463e-19 -6.92727e-09 -1.41134e-09 -2.76588e-08 1 2.0463e-19 -6.92727e-09 -1.41134e-09 -2.76588e-08 1 -6.92727e-09 -1.41134e-09 -2.76588e-08 3996.28 0.0708668 13.6822 4000 0.157133 3975.07 +EDGE_SE3:QUAT 1732 1733 -0.564736 8.68739 -0.186076 -0.19603 0.0889237 0.0783657 0.973408 1 1.92593e-19 1.92593e-19 -1.08886e-09 2.7083e-08 5.10473e-09 1 1.92593e-19 -1.08886e-09 2.7083e-08 5.10473e-09 1 -1.08886e-09 2.7083e-08 5.10473e-09 4031.98 -79.211 882.081 3956.09 -12.8088 4161.12 +EDGE_SE3:QUAT 1733 1734 -0.90735 8.63567 0.149224 0.146074 0.0620772 0.0485373 0.98613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3953.45 30.7114 397.796 3993.22 18.8865 4029.37 +EDGE_SE3:QUAT 1734 1735 -0.679269 8.89137 -0.429417 -0.0506884 0.0727049 0.130286 0.987507 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4095.43 1.89434 658.961 3973.98 39.1928 4037.81 +EDGE_SE3:QUAT 1735 1736 -0.865725 8.76124 -0.28058 0.0354413 -0.18738 0.194773 0.962131 1 3.00927e-21 3.00927e-21 -3.59912e-09 -7.32368e-10 6.9731e-10 1 3.00927e-21 -3.59912e-09 -7.32368e-10 6.9731e-10 1 -3.59912e-09 -7.32368e-10 6.9731e-10 4619.42 157.805 -1699.63 3887.11 -195.053 4472.7 +EDGE_SE3:QUAT 1736 1737 -0.718697 8.63395 -0.311683 0.063227 0.0207025 0.100696 0.99269 1 3.88195e-19 3.88195e-19 2.741e-08 8.12605e-09 2.75364e-08 1 3.88195e-19 2.741e-08 8.12605e-09 2.75364e-08 1 2.741e-08 8.12605e-09 2.75364e-08 3985.69 2.30273 86.4103 3999.83 3.27425 3961.12 +EDGE_SE3:QUAT 1737 1738 -0.222944 9.18565 -0.31993 0.0618471 -0.179594 0.0719421 0.979155 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4589.37 -1.72748 -1668.64 3864.19 -22.9527 4583.96 +EDGE_SE3:QUAT 1738 1739 -0.652262 8.94198 0.159669 -0.0784784 -0.052315 0.197474 0.97576 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.89 10.4097 -209.547 3999.85 -15.835 3853.55 +EDGE_SE3:QUAT 1739 1740 -0.687865 8.38605 0.0205892 -0.00855026 -0.0687356 0.0696313 0.995165 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4073.22 10.275 -547.242 3982.54 -20.816 4054.12 +EDGE_SE3:QUAT 1740 1741 -0.752419 8.60957 -0.118894 -0.142351 0.129777 0.255261 0.947489 1 9.62965e-19 9.62965e-19 4.02846e-08 -4.6582e-08 1.74226e-09 1 9.62965e-19 4.02846e-08 -4.6582e-08 1.74226e-09 1 4.02846e-08 -4.6582e-08 1.74226e-09 4411.27 43.6266 1488.27 3892.19 151.173 4231.7 +EDGE_SE3:QUAT 1741 1742 -0.780445 8.96263 -0.129493 0.0399449 -0.126611 -0.0748797 0.988315 1 2.40741e-19 2.40741e-19 -1.1707e-08 2.86521e-08 2.76204e-11 1 2.40741e-19 -1.1707e-08 2.86521e-08 2.76204e-11 1 -1.1707e-08 2.86521e-08 2.76204e-11 4236.57 -52.1227 -1015.51 3946.77 59.0122 4220.52 +EDGE_SE3:QUAT 1742 1743 -0.533681 8.86346 0.0541868 -0.035244 0.0028577 -0.0590719 0.997627 1 9.62965e-20 9.62965e-20 -1.38632e-08 3.3017e-10 1.38632e-08 1 9.62965e-20 -1.38632e-08 3.3017e-10 1.38632e-08 1 -1.38632e-08 3.3017e-10 1.38632e-08 3995.02 0.186487 -2.20497 3999.99 0.31265 3986.03 +EDGE_SE3:QUAT 1743 1744 -0.784259 8.59873 0.0223731 0.0135434 0.179332 -0.070172 0.981189 1 5.75992e-22 5.75992e-22 1.59236e-09 -1.13441e-10 2.91203e-10 1 5.75992e-22 1.59236e-09 -1.13441e-10 2.91203e-10 1 1.59236e-09 -1.13441e-10 2.91203e-10 4568.95 -49.1596 1613.47 3874.09 -64.1283 4549.98 +EDGE_SE3:QUAT 1744 1745 -0.939583 8.88864 -0.0805273 0.0150935 0.0399568 0.136637 0.9897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.58 6.59953 287.358 3995.73 19.6492 3945.81 +EDGE_SE3:QUAT 1745 1746 -0.519833 8.52434 -0.282499 0.0363579 0.0026757 -0.0354108 0.998708 1 4.81482e-20 4.81482e-20 1.38604e-08 -4.87459e-10 7.26337e-11 1 4.81482e-20 1.38604e-08 -4.87459e-10 7.26337e-11 1 1.38604e-08 -4.87459e-10 7.26337e-11 3995.04 0.746537 36.7492 3999.89 -0.726312 3995.32 +EDGE_SE3:QUAT 1746 1747 -0.767165 8.84786 -0.160053 0.11477 0.0585172 0.191112 0.973078 1 1.92593e-19 1.92593e-19 2.70271e-08 5.55468e-09 2.68145e-10 1 1.92593e-19 2.70271e-08 5.55468e-09 2.68145e-10 1 2.70271e-08 5.55468e-09 2.68145e-10 3952.58 8.79792 177.846 4000.74 10.1927 3859.17 +EDGE_SE3:QUAT 1747 1748 -0.560951 8.76058 -0.277711 0.101866 -0.0959577 -0.0359186 0.989508 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4087.2 -46.8782 -729.376 3972.41 34.808 4123.55 +EDGE_SE3:QUAT 1748 1749 -0.144396 8.40502 -0.0505151 0.00490739 0.00531325 0.189375 0.981878 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.11 0.135884 29.3539 3999.97 2.35601 3856.76 +EDGE_SE3:QUAT 1749 1750 -0.339126 8.39883 -0.143722 -0.00995619 -0.0631204 0.0337297 0.997386 1 3.00927e-21 3.00927e-21 -3.48765e-09 -1.23283e-10 2.17798e-10 1 3.00927e-21 -3.48765e-09 -1.23283e-10 2.17798e-10 1 -3.48765e-09 -1.23283e-10 2.17798e-10 4062.83 5.8586 -506.86 3984.58 -9.83133 4058.68 +EDGE_SE3:QUAT 1750 1751 -0.976587 8.23882 -0.00148037 0.0193928 -0.0605619 0.288769 0.955285 1 4.70198e-23 4.70198e-23 -4.17683e-10 -1.26199e-10 2.67426e-11 1 4.70198e-23 -4.17683e-10 -1.26199e-10 2.67426e-11 1 -4.17683e-10 -1.26199e-10 2.67426e-11 4058.79 22.3805 -495.2 3990.51 -72.8639 3726.75 +EDGE_SE3:QUAT 1751 1752 -0.724863 8.94085 -0.0337066 -0.210044 0.0285248 0.0306937 0.976794 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3844.33 -32.0265 289.512 3994.87 -1.32295 4017.03 +EDGE_SE3:QUAT 1752 1753 -0.546889 8.1457 -0.0943046 0.11524 -0.0404719 -0.0304215 0.992046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3965.77 -16.1449 -276.177 3996.15 7.58891 4015.19 +EDGE_SE3:QUAT 1753 1754 -0.62086 8.66922 -0.123921 -0.135652 -0.058842 0.0141331 0.988907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.98 31.04 -439.185 3989.88 -13.3343 4046.79 +EDGE_SE3:QUAT 1754 1755 -0.707242 8.74239 -0.221255 -0.0677297 -0.0258968 -0.0197184 0.997173 1 1.92593e-19 1.92593e-19 -2.77198e-08 4.465e-10 7.86912e-10 1 1.92593e-19 -2.77198e-08 4.465e-10 7.86912e-10 1 -2.77198e-08 4.465e-10 7.86912e-10 3993.95 7.39225 -222.231 3996.85 1.03634 4010.75 +EDGE_SE3:QUAT 1755 1756 0.0151313 8.49221 -0.219469 0.12457 -0.015357 0.114932 0.985412 1 1.92593e-19 1.92593e-19 -2.74207e-08 -2.99676e-09 1.18884e-09 1 1.92593e-19 -2.74207e-08 -2.99676e-09 1.18884e-09 1 -2.74207e-08 -2.99676e-09 1.18884e-09 3957.87 -18.7728 -287.65 3993.04 -16.8778 3967.1 +EDGE_SE3:QUAT 1756 1757 -0.797317 8.38002 -0.218202 -0.091886 -0.151705 0.0418951 0.983253 1 4.81482e-20 4.81482e-20 2.03206e-09 1.57738e-09 -1.4236e-08 1 4.81482e-20 2.03206e-09 1.57738e-09 -1.4236e-08 1 2.03206e-09 1.57738e-09 -1.4236e-08 4315.46 92.5415 -1232.83 3927.74 -83.2795 4342.21 +EDGE_SE3:QUAT 1757 1758 -0.219492 8.06171 -0.311052 -0.0300084 0.0675557 0.0437256 0.996305 1 1.20371e-20 1.20371e-20 -6.98039e-09 -2.80107e-10 -4.89203e-10 1 1.20371e-20 -6.98039e-09 -2.80107e-10 -4.89203e-10 1 -6.98039e-09 -2.80107e-10 -4.89203e-10 4074.26 -3.84096 563.509 3980.66 9.52956 4070.22 +EDGE_SE3:QUAT 1758 1759 -0.791192 8.49694 -0.0223129 0.252757 0.0119473 0.0169212 0.967308 1 1.27894e-20 1.27894e-20 -2.09151e-11 3.43383e-09 6.27332e-09 1 1.27894e-20 -2.09151e-11 3.43383e-09 6.27332e-09 1 -2.09151e-11 3.43383e-09 6.27332e-09 3744.7 2.17971 37.3883 4000.04 0.383673 3999.1 +EDGE_SE3:QUAT 1759 1760 -0.574233 8.4112 0.14778 0.109975 -0.0160544 0.0654722 0.991646 1 1.92593e-19 1.92593e-19 2.7562e-08 1.67966e-09 -8.28904e-10 1 1.92593e-19 2.7562e-08 1.67966e-09 -8.28904e-10 1 2.7562e-08 1.67966e-09 -8.28904e-10 3962.59 -12.2891 -211.361 3996.57 -6.31882 3993.82 +EDGE_SE3:QUAT 1760 1761 -0.81194 8.49571 -0.207689 0.123675 -0.00898069 -0.147874 0.981202 1 1.95602e-19 1.95602e-19 -2.77533e-08 6.35293e-10 -3.46265e-10 1 1.95602e-19 -2.77533e-08 6.35293e-10 -3.46265e-10 1 -2.77533e-08 6.35293e-10 -3.46265e-10 3942.92 13.1376 146.277 3997.01 -15.8943 3916.64 +EDGE_SE3:QUAT 1761 1762 -0.79124 8.44504 -0.212422 -0.0776303 -0.159665 0.165562 0.970088 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4264.13 134.657 -1116.41 3960.92 -146.959 4178.59 +EDGE_SE3:QUAT 1762 1763 -1.00612 8.36581 0.497003 -0.152258 -0.0439117 0.268277 0.950219 1 3.08149e-18 3.08149e-18 1.05487e-07 2.98145e-08 4.68987e-09 1 3.08149e-18 1.05487e-07 2.98145e-08 4.68987e-09 1 1.05487e-07 2.98145e-08 4.68987e-09 3906.71 -25.8037 157.033 3992.86 45.3744 3711.55 +EDGE_SE3:QUAT 1763 1764 -0.699053 8.33489 0.0588386 -0.0384467 0.032818 0.00888865 0.998682 1 4.81482e-20 4.81482e-20 -8.82096e-11 1.38598e-08 5.26542e-10 1 4.81482e-20 -8.82096e-11 1.38598e-08 5.26542e-10 1 -8.82096e-11 1.38598e-08 5.26542e-10 4011.84 -4.97957 267.072 3995.56 0.185123 4017.44 +EDGE_SE3:QUAT 1764 1765 -0.450904 8.1061 0.145697 0.0988219 0.0744642 0.0464565 0.991227 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.81 32.1668 537.758 3985.11 23.9203 4062.24 +EDGE_SE3:QUAT 1765 1766 -0.788732 8.62482 -0.0526261 -0.00791556 -0.00485841 0.0221859 0.999711 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.09 0.154103 -36.7309 3999.92 -0.403746 3998.37 +EDGE_SE3:QUAT 1766 1767 -0.510857 8.45627 -0.101561 0.16711 0.124155 0.196496 0.958149 1 7.70372e-19 7.70372e-19 2.33875e-09 1.14964e-08 5.35908e-08 1 7.70372e-19 2.33875e-09 1.14964e-08 5.35908e-08 1 2.33875e-09 1.14964e-08 5.35908e-08 3944.34 61.5004 512.011 4004.6 62.8529 3901.6 +EDGE_SE3:QUAT 1767 1768 -0.826661 8.59857 -0.172042 0.105673 0.0505569 0.0502652 0.991842 1 2.40741e-19 2.40741e-19 -2.6793e-08 -1.54286e-08 4.6143e-10 1 2.40741e-19 -2.6793e-08 -1.54286e-08 4.6143e-10 1 -2.6793e-08 -1.54286e-08 4.6143e-10 3982.95 19.1167 334.597 3994.57 12.8753 4017.52 +EDGE_SE3:QUAT 1768 1769 -0.698852 8.45781 -0.152525 0.0885784 -0.035112 0.0335325 0.994885 1 1.92593e-19 1.92593e-19 -2.76989e-08 -7.48646e-10 1.12517e-09 1 1.92593e-19 -2.76989e-08 -7.48646e-10 1.12517e-09 1 -2.76989e-08 -7.48646e-10 1.12517e-09 3993.15 -13.4131 -314.364 3993.65 -2.38877 4020.04 +EDGE_SE3:QUAT 1769 1770 -0.7627 8.41373 -0.0584048 0.0934596 0.00025435 0.218559 0.971338 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.48 -12.038 -234.772 3994.11 -33.4721 3821.34 +EDGE_SE3:QUAT 1770 1771 -0.674578 8.31228 -0.012231 -0.106651 -0.205528 0.0102733 0.972768 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4679.71 155.22 -1851.36 3857.22 -141.982 4724.79 +EDGE_SE3:QUAT 1771 1772 -0.719556 8.12329 -0.219802 0.105329 -0.0300385 0.0648855 0.991864 1 1.92593e-19 1.92593e-19 -2.76169e-08 -1.59533e-09 1.18939e-09 1 1.92593e-19 -2.76169e-08 -1.59533e-09 1.18939e-09 1 -2.76169e-08 -1.59533e-09 1.18939e-09 3980.61 -16.105 -317.981 3992.98 -7.69242 4008.15 +EDGE_SE3:QUAT 1772 1773 -0.886932 8.33613 -0.110768 0.0937037 0.0824485 0.0188998 0.992 1 1.92593e-19 1.92593e-19 -2.78814e-08 -9.65525e-10 -2.17362e-09 1 1.92593e-19 -2.78814e-08 -9.65525e-10 -2.17362e-09 1 -2.78814e-08 -9.65525e-10 -2.17362e-09 4065.6 34.6767 642.802 3977.23 21.113 4099.29 +EDGE_SE3:QUAT 1773 1774 -0.581645 8.47112 -0.215031 0.0173687 0.030688 -0.192732 0.980618 1 6.01853e-20 6.01853e-20 -9.48521e-09 -1.22755e-08 -1.80944e-10 1 6.01853e-20 -9.48521e-09 -1.22755e-08 -1.80944e-10 1 -9.48521e-09 -1.22755e-08 -1.80944e-10 4017.23 -2.75363 272.206 3995.77 -26.9027 3869.85 +EDGE_SE3:QUAT 1774 1775 -0.942565 8.32088 -0.15609 0.0194938 0.126308 0.156352 0.979398 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4225.76 68.5358 980.966 3956.25 94.187 4129.49 +EDGE_SE3:QUAT 1775 1776 -1.00481 8.26437 0.0542644 0.103815 0.0386592 0.0460915 0.992776 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3971.95 13.06 246.974 3997.1 7.93621 4006.56 +EDGE_SE3:QUAT 1776 1777 -0.572283 8.2453 -0.135306 0.0862774 0.0652041 -0.0475155 0.992999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.78 20.9396 573.454 3979.74 -4.4108 4071.53 +EDGE_SE3:QUAT 1777 1778 -0.879557 8.05825 -0.179659 0.0831774 0.00749867 0.198863 0.976462 1 1.92593e-19 1.92593e-19 -2.71153e-08 -5.47885e-09 7.08068e-10 1 1.92593e-19 -2.71153e-08 -5.47885e-09 7.08068e-10 1 -2.71153e-08 -5.47885e-09 7.08068e-10 3976 -7.85409 -136.598 3997.46 -20.0373 3845.49 +EDGE_SE3:QUAT 1778 1779 -0.741356 8.28233 -0.00344944 0.0094198 0.016553 0.0647093 0.997722 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.51 0.961598 124.381 3999.09 4.00335 3987.11 +EDGE_SE3:QUAT 1779 1780 -0.786803 8.3735 -0.295316 0.0109683 0.0431803 -0.135773 0.989738 1 7.52316e-22 7.52316e-22 1.72378e-09 -2.3569e-10 7.75674e-11 1 7.52316e-22 1.72378e-09 -2.3569e-10 7.75674e-11 1 1.72378e-09 -2.3569e-10 7.75674e-11 4030.96 -4.41289 356.026 3992.64 -24.3334 3957.7 +EDGE_SE3:QUAT 1780 1781 -0.101774 7.94269 0.442077 0.0708795 0.0520256 -0.0201301 0.995924 1 1.20371e-20 1.20371e-20 3.79145e-10 4.82421e-10 6.95098e-09 1 1.20371e-20 3.79145e-10 4.82421e-10 6.95098e-09 1 3.79145e-10 4.82421e-10 6.95098e-09 4026.53 14.6172 434.387 3988.42 0.376924 4045.01 +EDGE_SE3:QUAT 1781 1782 -0.452643 8.43695 -0.134418 -0.151371 -0.202331 0.104349 0.961904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4382.56 235.477 -1463.06 3948.76 -231.043 4430.66 +EDGE_SE3:QUAT 1782 1783 -0.423855 8.53589 -0.080997 -0.0431747 -0.0397851 0.0527173 0.996882 1 9.62965e-20 9.62965e-20 1.33858e-08 1.23216e-10 1.33858e-08 1 9.62965e-20 1.33858e-08 1.23216e-10 1.33858e-08 1 1.33858e-08 1.23216e-10 1.33858e-08 4013.44 7.88084 -290.039 3995.26 -8.92353 4009.78 +EDGE_SE3:QUAT 1783 1784 -0.795085 8.37937 -0.391812 0.127385 0.0583556 0.0393914 0.989351 1 7.70372e-19 7.70372e-19 5.5192e-08 2.96517e-09 2.57965e-09 1 7.70372e-19 5.5192e-08 2.96517e-09 2.57965e-09 1 5.5192e-08 2.96517e-09 2.57965e-09 3974.06 27.0871 397.735 3992.37 15.8096 4032.76 +EDGE_SE3:QUAT 1784 1785 -0.452215 7.94794 0.138095 0.11309 0.00809535 0.14929 0.982272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3952.44 -11.1481 -136.584 3997.41 -14.9759 3914.45 +EDGE_SE3:QUAT 1785 1786 -0.705488 8.40459 -0.071724 -0.0987752 -0.116192 0.0513654 0.986967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4147.34 63.538 -883.925 3961.55 -54.7217 4175.81 +EDGE_SE3:QUAT 1786 1787 -0.60431 8.0471 -0.154755 -0.0634846 0.0518851 -0.124076 0.98888 1 1.92593e-19 1.92593e-19 2.75295e-08 -3.6242e-09 9.5118e-10 1 1.92593e-19 2.75295e-08 -3.6242e-09 9.5118e-10 1 2.75295e-08 -3.6242e-09 9.5118e-10 4007.5 -14.1659 310.714 3996.02 -20.1391 3962.04 +EDGE_SE3:QUAT 1787 1788 -0.642754 8.29027 -0.257484 -0.00666599 0.113423 0.180799 0.976935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4199.12 53.7836 915.191 3960.59 90.9866 4068.55 +EDGE_SE3:QUAT 1788 1789 -0.599807 8.1939 0.107732 0.0435721 -0.123959 -0.077523 0.988294 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4221.46 -52.6158 -984.487 3950.22 59.2533 4205.01 +EDGE_SE3:QUAT 1789 1790 -0.6687 7.8381 0.116757 0.0493805 0.0255868 0.0289731 0.998032 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.95 4.88929 186.882 3998 3.31154 4005.34 +EDGE_SE3:QUAT 1790 1791 -0.678983 8.89114 0.0711411 0.0463414 0.0492243 0.396617 0.915491 1 3.08149e-18 3.08149e-18 -4.06548e-11 7.51636e-09 1.01638e-07 1 3.08149e-18 -4.06548e-11 7.51636e-09 1.01638e-07 1 -4.06548e-11 7.51636e-09 1.01638e-07 3991.27 4.07527 105.394 4001.88 0.119898 3370.64 +EDGE_SE3:QUAT 1791 1792 -0.330325 8.11772 -0.374617 -0.070792 -0.0437464 0.301296 0.949892 1 3.27408e-18 3.27408e-18 2.57669e-08 1.76836e-08 -1.05287e-07 1 3.27408e-18 2.57669e-08 1.76836e-08 -1.05287e-07 1 2.57669e-08 1.76836e-08 -1.05287e-07 3978.32 0.120909 -60.6122 4000.54 5.98112 3635.24 +EDGE_SE3:QUAT 1792 1793 -0.562505 8.40638 -0.0362061 -0.0449619 0.0752936 0.0355292 0.995513 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4089.38 -10.0138 631.986 3975.87 5.44285 4092.42 +EDGE_SE3:QUAT 1793 1794 -0.782072 7.89126 -0.355745 0.164263 -0.074091 0.017467 0.983475 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.48 -51.399 -614.979 3979.56 17.4321 4091.19 +EDGE_SE3:QUAT 1794 1795 -0.411814 7.83398 -0.0293514 0.0491914 0.0247557 0.1837 0.981439 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.57 1.81927 81.4836 4000.03 4.05795 3866.26 +EDGE_SE3:QUAT 1795 1796 -0.800387 8.19168 -0.300594 -0.0716945 0.0691535 0.251462 0.962728 1 4.81482e-20 4.81482e-20 -1.35872e-08 -3.41929e-09 -1.33937e-09 1 4.81482e-20 -1.35872e-08 -3.41929e-09 -1.33937e-09 1 -1.35872e-08 -3.41929e-09 -1.33937e-09 4107.35 16.0439 727.203 3970.86 91.7522 3874.98 +EDGE_SE3:QUAT 1796 1797 -0.565539 8.09459 0.201311 -0.0521122 -0.0178829 0.154264 0.986492 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.3 0.460254 -42.6043 4000.04 -0.74044 3904.97 +EDGE_SE3:QUAT 1797 1798 -0.676852 7.70435 -0.000547512 0.000292592 -0.0286222 0.0169386 0.999447 1 7.34684e-25 7.34684e-25 -5.4269e-11 -9.20351e-13 1.55381e-12 1 7.34684e-25 -5.4269e-11 -9.20351e-13 1.55381e-12 1 -5.4269e-11 -9.20351e-13 1.55381e-12 4013.14 0.300446 -229.597 3996.73 -1.95538 4011.99 +EDGE_SE3:QUAT 1798 1799 -0.405846 8.00774 0.33769 -0.0447024 -0.0679644 0.126136 0.988672 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.51 21.4184 -466.832 3989.57 -32.8726 3989.87 +EDGE_SE3:QUAT 1799 1800 -0.101959 7.98044 -0.256517 0.0657567 -0.0122857 0.0541675 0.996289 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.55 -4.72105 -139.926 3998.55 -3.75333 3993.11 +EDGE_SE3:QUAT 1800 1801 -0.573998 8.2656 0.130396 -0.0446715 0.0167038 0.132856 0.989987 1 6.01853e-20 6.01853e-20 1.46651e-08 -5.05159e-09 1.17619e-10 1 6.01853e-20 1.46651e-08 -5.05159e-09 1.17619e-10 1 1.46651e-08 -5.05159e-09 1.17619e-10 4001.94 -3.2692 200.514 3997.06 14.2929 3939.32 +EDGE_SE3:QUAT 1801 1802 -0.38133 7.81024 -0.243141 -0.0710497 0.0990845 -0.021743 0.992301 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4131.03 -35.7977 792.383 3965.19 -26.0941 4149.33 +EDGE_SE3:QUAT 1802 1803 -0.958084 8.13273 0.0839571 -0.0555876 0.134969 -0.0764137 0.986334 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4256.14 -67.5356 1070.95 3943.3 -71.5118 4245.14 +EDGE_SE3:QUAT 1803 1804 -0.881043 7.98949 0.0787863 -0.0352564 0.0619499 0.107436 0.991654 1 1.92593e-19 1.92593e-19 -1.90318e-09 5.99798e-10 -2.77722e-08 1 1.92593e-19 -1.90318e-09 5.99798e-10 -2.77722e-08 1 -1.90318e-09 5.99798e-10 -2.77722e-08 4066.62 1.19731 539.993 3982.29 27.2224 4025.43 +EDGE_SE3:QUAT 1804 1805 -0.527554 7.98442 -0.0196048 0.0831194 -0.0348865 -0.0564047 0.99433 1 2.0463e-19 2.0463e-19 -2.72129e-08 8.60758e-09 8.87796e-11 1 2.0463e-19 -2.72129e-08 8.60758e-09 8.87796e-11 1 -2.72129e-08 8.60758e-09 8.87796e-11 3984.25 -9.5178 -219.397 3997.7 7.37271 3999.16 +EDGE_SE3:QUAT 1805 1806 -0.441624 8.12948 -0.233614 0.051213 0.206207 0.00601383 0.977149 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4755.7 79.0529 1910.98 3836.46 72.5613 4766.04 +EDGE_SE3:QUAT 1806 1807 -0.926693 7.7716 -0.357252 0.108256 0.0274461 0.113877 0.987198 1 1.92593e-19 1.92593e-19 -4.74917e-11 -3.10075e-09 -2.74016e-08 1 1.92593e-19 -4.74917e-11 -3.10075e-09 -2.74016e-08 1 -4.74917e-11 -3.10075e-09 -2.74016e-08 3953.52 1.16823 65.8305 4000.08 1.1868 3948.53 +EDGE_SE3:QUAT 1807 1808 -0.368604 7.76046 -0.138287 -0.0986785 -0.101478 0.0208055 0.989713 1 9.75002e-19 9.75002e-19 -5.41879e-08 -2.90333e-08 -4.52389e-09 1 9.75002e-19 -5.41879e-08 -2.90333e-08 -4.52389e-09 1 -5.41879e-08 -2.90333e-08 -4.52389e-09 4115.11 48.025 -800.159 3965.85 -32.9392 4152.32 +EDGE_SE3:QUAT 1808 1809 -0.622865 8.10318 0.052966 0.0254338 -0.100353 -0.00730255 0.9946 1 1.92593e-19 1.92593e-19 3.5037e-10 2.76042e-08 -7.61586e-10 1 1.92593e-19 3.5037e-10 2.76042e-08 -7.61586e-10 1 3.5037e-10 2.76042e-08 -7.61586e-10 4162.21 -13.4854 -828.456 3960.29 9.76169 4164.58 +EDGE_SE3:QUAT 1809 1810 -0.495052 7.35618 0.0238588 -0.045356 -0.00256546 0.111612 0.992713 1 1.92593e-19 1.92593e-19 -2.09831e-10 1.24333e-09 -2.75544e-08 1 1.92593e-19 -2.09831e-10 1.24333e-09 -2.75544e-08 1 -2.09831e-10 1.24333e-09 -2.75544e-08 3992.07 -1.34342 40.0834 3999.77 3.36381 3950.47 +EDGE_SE3:QUAT 1810 1811 -0.602265 7.958 0.172782 -0.0435727 -0.0810933 0.171379 0.980895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4062.7 32.1029 -537.195 3988.28 -50.4303 3952.81 +EDGE_SE3:QUAT 1811 1812 -0.400186 7.96444 -0.419776 0.0344661 -0.0189442 0.0355949 0.998592 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.12 -2.59954 -165.958 3998.2 -2.70749 4001.8 +EDGE_SE3:QUAT 1812 1813 -0.722669 8.16909 0.257733 0.0251985 0.0398331 0.0591161 0.997138 1 1.20371e-20 1.20371e-20 6.93846e-09 4.2606e-10 2.54109e-10 1 1.20371e-20 6.93846e-09 4.2606e-10 2.54109e-10 1 6.93846e-09 4.2606e-10 2.54109e-10 4019.86 5.8146 300.249 3994.78 9.69334 4008.42 +EDGE_SE3:QUAT 1813 1814 -0.187135 7.92462 -0.324268 0.0838564 -0.0798661 0.051224 0.99195 1 1.01111e-18 1.01111e-18 5.57054e-08 -2.43487e-08 1.11894e-08 1 1.01111e-18 5.57054e-08 -2.43487e-08 1.11894e-08 1 5.57054e-08 -2.43487e-08 1.11894e-08 4090.64 -23.0548 -699.52 3970.52 -4.81772 4108.28 +EDGE_SE3:QUAT 1814 1815 -0.655462 7.66642 0.169302 0.0278095 0.108547 0.0961764 0.989037 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4171.32 39.5693 853.52 3961.83 52.852 4137.41 +EDGE_SE3:QUAT 1815 1816 -0.667489 7.87718 -0.2221 0.0115317 -0.114074 0.0199598 0.993205 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4217.14 0.3769 -958.166 3947.7 -7.04122 4216.08 +EDGE_SE3:QUAT 1816 1817 -0.639113 8.02018 -0.192798 0.156052 0.0749684 0.168651 0.970353 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3913.61 16.7675 245.56 4001.29 17.085 3897.25 +EDGE_SE3:QUAT 1817 1818 -0.917168 7.94448 0.516661 -0.0441194 0.00126079 0.0448692 0.998017 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.48 -0.904632 33.7214 3999.89 0.920463 3992.22 +EDGE_SE3:QUAT 1818 1819 -0.302455 7.54826 -0.0466482 0.0808136 0.0602829 0.126086 0.986883 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.1 19.299 346.811 3995.52 23.8751 3965.63 +EDGE_SE3:QUAT 1819 1820 -0.52825 8.03353 -0.0360145 0.011698 -0.0996858 0.138067 0.985324 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4161.82 29.3537 -822.15 3963.98 -59.8142 4086.12 +EDGE_SE3:QUAT 1820 1821 -0.531679 7.80904 -0.230583 -0.144575 -0.183449 -0.00529518 0.972325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4480.42 152.37 -1604.73 3890.42 -127.792 4563.91 +EDGE_SE3:QUAT 1821 1822 -0.520743 7.48389 -0.221601 -0.131876 -0.0412731 0.0470582 0.989288 1 7.70372e-19 7.70372e-19 -5.50217e-08 -3.13424e-09 1.51915e-09 1 7.70372e-19 -5.50217e-08 -3.13424e-09 1.51915e-09 1 -5.50217e-08 -3.13424e-09 1.51915e-09 3945.46 15.9375 -247.522 3997.43 -8.76237 4006.17 +EDGE_SE3:QUAT 1822 1823 -0.411832 7.66485 0.223549 -0.0977194 0.0437449 0.127864 0.985996 1 4.81482e-20 4.81482e-20 -1.63373e-09 1.3701e-08 1.16595e-09 1 4.81482e-20 -1.63373e-09 1.3701e-08 1.16595e-09 1 -1.63373e-09 1.3701e-08 1.16595e-09 4020.85 -16.7554 491.148 3983.43 27.4835 3993.65 +EDGE_SE3:QUAT 1823 1824 -0.375245 7.7909 -0.10086 0.114636 0.105452 0.102014 0.982513 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.47 60.1213 688.302 3981.38 58.2404 4072.41 +EDGE_SE3:QUAT 1824 1825 -0.742439 7.67122 -0.483672 0.172625 0.0298509 -0.07043 0.982013 1 7.70372e-19 7.70372e-19 -5.47519e-08 3.13641e-09 -2.88428e-09 1 7.70372e-19 -5.47519e-08 3.13641e-09 -2.88428e-09 1 -5.47519e-08 3.13641e-09 -2.88428e-09 3914.81 33.3698 372.29 3990.14 -7.18449 4014.16 +EDGE_SE3:QUAT 1825 1826 -0.705361 7.73687 -0.226369 0.0961282 -0.10067 0.0570452 0.988621 1 1.92593e-19 1.92593e-19 2.8092e-08 1.07018e-09 -3.10561e-09 1 1.92593e-19 2.8092e-08 1.07018e-09 -3.10561e-09 1 2.8092e-08 1.07018e-09 -3.10561e-09 4153.31 -32.5144 -893 3953.76 -1.53779 4177.25 +EDGE_SE3:QUAT 1826 1827 -0.542609 7.61241 0.239591 0.184521 0.14924 0.00753699 0.971402 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4192.47 137.073 1193.77 3941.74 105.219 4328.44 +EDGE_SE3:QUAT 1827 1828 -0.328084 7.59891 -0.0159739 0.0996881 0.017935 0.0870419 0.991042 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.26 0.155783 36.772 4000.02 0.167283 3969.71 +EDGE_SE3:QUAT 1828 1829 -0.653484 7.70192 0.0199354 -0.0222295 -0.129904 -0.205224 0.969801 1 3.00927e-21 3.00927e-21 3.48453e-09 -7.4249e-10 -4.59067e-10 1 3.00927e-21 3.48453e-09 -7.4249e-10 -4.59067e-10 1 3.48453e-09 -7.4249e-10 -4.59067e-10 4275.59 -76.4131 -1089.98 3947.54 122.481 4109.1 +EDGE_SE3:QUAT 1829 1830 -0.393374 7.80935 -0.0983473 0.057981 0.104897 -0.0533229 0.991358 1 2.88889e-19 2.88889e-19 -1.36924e-08 -2.62588e-08 1.38531e-08 1 2.88889e-19 -1.36924e-08 -2.62588e-08 1.38531e-08 1 -1.36924e-08 -2.62588e-08 1.38531e-08 4182.42 13.9882 906.589 3952.4 -10.2146 4184.5 +EDGE_SE3:QUAT 1830 1831 -0.510874 7.80287 0.0158624 0.0316202 0.0883886 0.0761084 0.992671 1 1.92593e-19 1.92593e-19 -2.31648e-09 -1.27531e-09 -2.79475e-08 1 1.92593e-19 -2.31648e-09 -1.27531e-09 -2.79475e-08 1 -2.31648e-09 -1.27531e-09 -2.79475e-08 4110.74 25.188 687.276 3974.02 33.4164 4091.57 +EDGE_SE3:QUAT 1831 1832 -0.430156 7.33615 0.129252 -0.197319 -0.0194346 -0.037728 0.97942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3857.78 25.1815 -233.921 3996.22 1.40301 4007.83 +EDGE_SE3:QUAT 1832 1833 -0.648192 7.73001 0.0767575 0.187795 0.0619315 0.0157639 0.980127 1 7.70372e-19 7.70372e-19 -5.4741e-08 -2.10703e-09 -2.88364e-09 1 7.70372e-19 -5.4741e-08 -2.10703e-09 -2.88364e-09 1 -5.4741e-08 -2.10703e-09 -2.88364e-09 3906.26 41.929 438.599 3991.4 17.9962 4046.33 +EDGE_SE3:QUAT 1833 1834 -0.162216 7.73475 -0.219912 0.00300446 0.0332233 0.127338 0.991298 1 7.70372e-19 7.70372e-19 -1.74564e-09 -6.29646e-10 -5.51418e-08 1 7.70372e-19 -1.74564e-09 -6.29646e-10 -5.51418e-08 1 -1.74564e-09 -6.29646e-10 -5.51418e-08 4016.23 3.5837 255.686 3996.34 16.3014 3951.41 +EDGE_SE3:QUAT 1834 1835 -0.846216 7.71651 -0.16825 -0.0615624 0.185818 -0.0314763 0.980148 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4566.99 -98.1074 1633.35 3876.78 -93.1449 4578.19 +EDGE_SE3:QUAT 1835 1836 -0.876059 7.72204 -0.0634509 0.0830443 -0.0930453 0.0413291 0.991331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4127.58 -27.3857 -802.993 3962.22 0.946631 4148.33 +EDGE_SE3:QUAT 1836 1837 -0.965118 7.68559 -0.0351527 -0.102441 -0.138261 -0.00873102 0.985045 1 9.63717e-19 9.63717e-19 2.75551e-08 5.54403e-08 4.24798e-11 1 9.63717e-19 2.75551e-08 5.54403e-08 4.24798e-11 1 2.75551e-08 5.54403e-08 4.24798e-11 4278.19 68.1194 -1176.11 3928.5 -45.245 4319.86 +EDGE_SE3:QUAT 1837 1838 -0.395546 7.27684 -0.0932004 0.158328 -0.0475385 0.0455781 0.985188 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3950.89 -35.7048 -455.607 3987.09 0.32213 4042.85 +EDGE_SE3:QUAT 1838 1839 -0.779566 7.64302 -0.17981 0.0830238 -0.0271082 0.0412212 0.995326 1 2.40741e-19 2.40741e-19 -2.81479e-08 1.13827e-10 1.47721e-08 1 2.40741e-19 -2.81479e-08 1.13827e-10 1.47721e-08 1 -2.81479e-08 1.13827e-10 1.47721e-08 3988.7 -10.3064 -255.913 3995.63 -3.67869 4009.48 +EDGE_SE3:QUAT 1839 1840 -0.621347 7.68068 -0.24653 0.0166937 0.00873949 0.0304341 0.999359 1 1.50463e-20 1.50463e-20 6.82877e-09 3.68034e-09 -6.20778e-12 1 1.50463e-20 6.82877e-09 3.68034e-09 -6.20778e-12 1 6.82877e-09 3.68034e-09 -6.20778e-12 3999.9 0.563223 63.7107 3999.76 0.965152 3997.31 +EDGE_SE3:QUAT 1840 1841 -0.509687 7.27334 0.00198739 -0.0511241 -0.0964179 0.0308287 0.993549 1 2.40741e-19 2.40741e-19 1.28909e-08 2.81483e-08 3.02462e-10 1 2.40741e-19 1.28909e-08 2.81483e-08 3.02462e-10 1 1.28909e-08 2.81483e-08 3.02462e-10 4133.08 28.2564 -771.252 3966.55 -24.2781 4139.73 +EDGE_SE3:QUAT 1841 1842 -0.564914 7.67369 0.0407833 -0.0254603 -0.128105 -0.040631 0.990601 1 1.20371e-20 1.20371e-20 7.11184e-09 -2.53315e-10 -9.30807e-10 1 1.20371e-20 7.11184e-09 -2.53315e-10 -9.30807e-10 1 7.11184e-09 -2.53315e-10 -9.30807e-10 4278.84 -1.14941 -1097.7 3933.15 15.2619 4274.83 +EDGE_SE3:QUAT 1842 1843 -1.06322 7.30185 -0.41055 -0.0341086 -0.0128774 0.146712 0.988507 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.64 0.487746 -40.3783 4000 -1.44591 3914.2 +EDGE_SE3:QUAT 1843 1844 -0.580247 7.34382 0.075107 -0.0651514 0.0700657 0.0799934 0.992193 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4079.09 -10.9672 627.493 3975.69 18.118 4070.48 +EDGE_SE3:QUAT 1844 1845 -0.710987 7.61579 -0.0678771 -0.0334369 0.0519571 0.0694599 0.995669 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4044.34 -2.79224 444.624 3987.69 13.7864 4029.52 +EDGE_SE3:QUAT 1845 1846 -0.465196 7.48702 -0.145416 -0.0351749 0.0737442 0.140098 0.986761 1 7.70372e-19 7.70372e-19 4.52747e-09 -7.6253e-10 5.54798e-08 1 7.70372e-19 4.52747e-09 -7.6253e-10 5.54798e-08 1 4.52747e-09 -7.6253e-10 5.54798e-08 4096.38 8.83649 644.711 3975.89 43.683 4022.82 +EDGE_SE3:QUAT 1846 1847 -0.638625 7.45628 0.235012 0.108025 -0.0138891 0.187657 0.976177 1 7.70372e-19 7.70372e-19 2.90871e-09 -5.31609e-09 -5.43855e-08 1 7.70372e-19 2.90871e-09 -5.31609e-09 -5.43855e-08 1 2.90871e-09 -5.31609e-09 -5.43855e-08 3981.11 -16.8217 -341.604 3989.84 -36.2559 3886.93 +EDGE_SE3:QUAT 1847 1848 -0.923167 7.33745 -0.162494 -0.060339 -0.0198382 0.0208688 0.997763 1 1.20371e-20 1.20371e-20 1.60437e-10 -6.92302e-09 -4.24346e-10 1 1.20371e-20 1.60437e-10 -6.92302e-09 -4.24346e-10 1 1.60437e-10 -6.92302e-09 -4.24346e-10 3990.52 4.33037 -142.809 3998.85 -1.92505 4003.34 +EDGE_SE3:QUAT 1848 1849 -1.00391 7.17794 0.233363 0.0150418 0.105082 0.125016 0.98646 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4162.81 39.1676 825.915 3965.02 60.4177 4101.2 +EDGE_SE3:QUAT 1849 1850 -1.01663 7.4444 -0.302651 -0.132628 -0.0582697 0.133062 0.980464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3941.6 14.6428 -234.117 3999.56 -14.6639 3941.14 +EDGE_SE3:QUAT 1850 1851 -1.08552 7.37013 -0.178838 0.106636 0.0716935 0.102949 0.986352 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.9 29.243 427.364 3992.98 28.8127 4001.99 +EDGE_SE3:QUAT 1851 1852 -0.831002 7.58837 -0.596033 0.0329634 -0.0884288 0.111655 0.989256 1 1.92593e-19 1.92593e-19 2.63932e-09 -3.61932e-10 -2.79386e-08 1 1.92593e-19 2.63932e-09 -3.61932e-10 -2.79386e-08 1 2.63932e-09 -3.61932e-10 -2.79386e-08 4135.26 9.66542 -760.238 3966.64 -39.8204 4089.74 +EDGE_SE3:QUAT 1852 1853 -0.420203 6.96515 0.131237 0.0598571 0.0092335 -0.0373104 0.997467 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.15 3.13686 100.091 3999.27 -1.83312 3996.92 +EDGE_SE3:QUAT 1853 1854 -0.421784 7.1154 -0.480119 -0.0909081 0.120897 -0.108347 0.982538 1 1.92593e-19 1.92593e-19 -2.71489e-09 3.33679e-09 -2.78624e-08 1 1.92593e-19 -2.71489e-09 3.33679e-09 -2.78624e-08 1 -2.71489e-09 3.33679e-09 -2.78624e-08 4138.09 -72.6808 847.151 3969.73 -75.5539 4124.19 +EDGE_SE3:QUAT 1854 1855 -0.424449 7.43776 0.0324067 -0.0569049 -0.0396869 0.116178 0.990802 1 4.81482e-20 4.81482e-20 1.37731e-08 1.67112e-09 -3.50288e-10 1 4.81482e-20 1.37731e-08 1.67112e-09 -3.50288e-10 1 1.37731e-08 1.67112e-09 -3.50288e-10 4000.16 8.58667 -231.474 3997.78 -13.2584 3959.12 +EDGE_SE3:QUAT 1855 1856 -0.606337 7.28151 0.211722 0.195212 0.0112463 0.254216 0.947175 1 3.12964e-18 3.12964e-18 6.1762e-09 -6.39494e-09 -1.0834e-07 1 3.12964e-18 6.1762e-09 -6.39494e-09 -1.0834e-07 1 6.1762e-09 -6.39494e-09 -1.0834e-07 3898.48 -54.846 -484.463 3973.03 -78.2396 3792.41 +EDGE_SE3:QUAT 1856 1857 -0.525178 7.10928 -0.0380797 -0.101304 0.0552798 0.179557 0.976955 1 7.70372e-19 7.70372e-19 -4.86337e-09 4.27338e-09 -5.49341e-08 1 7.70372e-19 -4.86337e-09 4.27338e-09 -5.49341e-08 1 -4.86337e-09 4.27338e-09 -5.49341e-08 4059.1 -13.0767 642.814 3972.8 52.6758 3971.19 +EDGE_SE3:QUAT 1857 1858 -0.35836 7.04341 -0.069041 0.0568284 -0.0463148 -0.0659751 0.995124 1 4.81482e-20 4.81482e-20 -1.3855e-08 9.89466e-10 5.3049e-10 1 4.81482e-20 -1.3855e-08 9.89466e-10 5.3049e-10 1 -1.3855e-08 9.89466e-10 5.3049e-10 4012.94 -11.6541 -323.106 3994.46 12.702 4008.44 +EDGE_SE3:QUAT 1858 1859 -0.857609 7.31969 -0.0465932 -0.106438 -0.0788121 0.217414 0.967053 1 7.70372e-19 7.70372e-19 1.33842e-09 7.27154e-09 -5.38243e-08 1 7.70372e-19 1.33842e-09 7.27154e-09 -5.38243e-08 1 1.33842e-09 7.27154e-09 -5.38243e-08 3974.54 22.7421 -306.864 4000.89 -28.0336 3830.78 +EDGE_SE3:QUAT 1859 1860 -0.381172 7.12026 0.193408 -0.00759027 0.0950515 0.120695 0.988099 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4146.06 23.9967 778.868 3966.84 49.7082 4088.02 +EDGE_SE3:QUAT 1860 1861 -0.868735 7.52494 0.0678249 0.234317 -0.0274964 0.021836 0.971526 1 3.00927e-21 3.00927e-21 -1.19664e-10 8.11414e-10 3.37828e-09 1 3.00927e-21 -1.19664e-10 8.11414e-10 3.37828e-09 1 -1.19664e-10 8.11414e-10 3.37828e-09 3797.49 -32.1563 -262.202 3996.15 2.73305 4015.2 +EDGE_SE3:QUAT 1861 1862 -0.835109 7.19193 -0.0862502 -0.0821596 0.15128 0.161942 0.971668 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4444.3 39.856 1451.77 3895.39 93.7077 4366.4 +EDGE_SE3:QUAT 1862 1863 -0.750871 6.99997 0.168346 -0.024956 0.00954197 -0.129532 0.991215 1 1.20371e-20 1.20371e-20 -6.87818e-09 9.01105e-10 -1.943e-11 1 1.20371e-20 -6.87818e-09 9.01105e-10 -1.943e-11 1 -6.87818e-09 9.01105e-10 -1.943e-11 3997.79 -0.37746 36.0065 3999.98 -1.47088 3933.16 +EDGE_SE3:QUAT 1863 1864 -0.286981 7.44577 0.165012 -0.168481 0.0333668 -0.101069 0.979942 1 7.82409e-19 7.82409e-19 5.36548e-08 -1.27052e-08 -1.33926e-09 1 7.82409e-19 5.36548e-08 -1.27052e-08 -1.33926e-09 1 5.36548e-08 -1.27052e-08 -1.33926e-09 3885.8 1.41797 52.2434 4000.13 0.471049 3958.49 +EDGE_SE3:QUAT 1864 1865 -0.411109 7.25564 -0.219849 -0.0263798 -0.202964 0.0858182 0.975061 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4695.15 133.225 -1810.97 3860.38 -141.586 4668.48 +EDGE_SE3:QUAT 1865 1866 -0.372099 7.17296 -0.0573416 0.0921877 0.0927068 -0.0168942 0.991273 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4110.76 35.446 774.572 3965.67 13.144 4143.61 +EDGE_SE3:QUAT 1866 1867 -0.548981 7.10721 0.0654662 0.102203 -0.0154734 0.131835 0.985868 1 1.55278e-18 1.55278e-18 5.34408e-08 5.43981e-09 5.3223e-08 1 1.55278e-18 5.34408e-08 5.43981e-09 5.3223e-08 1 5.34408e-08 5.43981e-09 5.3223e-08 3976.98 -14.0382 -278.743 3993.53 -19.6431 3949.24 +EDGE_SE3:QUAT 1867 1868 -0.701843 7.09362 0.438835 -0.121477 -0.0543199 0.0100486 0.991056 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.35 26.0604 -414.051 3990.61 -10.1339 4041.97 +EDGE_SE3:QUAT 1868 1869 -0.58235 6.9241 0.0371845 0.282395 -0.0284244 0.0128129 0.958791 1 3.09428e-18 3.09428e-18 -1.06638e-07 -6.62863e-09 3.72088e-09 1 3.09428e-18 -1.06638e-07 -6.62863e-09 3.72088e-09 1 -1.06638e-07 -6.62863e-09 3.72088e-09 3695.67 -34.9981 -242.649 3997.42 4.71452 4014 +EDGE_SE3:QUAT 1869 1870 -0.53028 7.07304 -0.329435 0.0603532 0.033509 0.188834 0.97958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.28 3.70862 119.042 4000.02 7.00433 3860.22 +EDGE_SE3:QUAT 1870 1871 -0.646224 6.96457 -0.13386 0.0361242 -0.0602626 0.105739 0.991909 1 3.97223e-19 3.97223e-19 7.91307e-09 -2.61889e-08 2.79372e-08 1 3.97223e-19 7.91307e-09 -2.61889e-08 2.79372e-08 1 7.91307e-09 -2.61889e-08 2.79372e-08 4062.96 0.480225 -526.755 3983.06 -26.0527 4023.46 +EDGE_SE3:QUAT 1871 1872 -0.508988 6.97472 -0.0502363 0.196429 0.0182272 0.109084 0.974261 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3847.11 -19.8372 -113.6 3997.43 -10.8865 3953.85 +EDGE_SE3:QUAT 1872 1873 -0.809221 7.1038 0.134556 -0.165346 0.142127 0.0980729 0.971001 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4330.37 -83.5789 1397.52 3900.03 -22.0261 4401.25 +EDGE_SE3:QUAT 1873 1874 -0.673074 7.10616 -0.244245 -0.141499 -0.0499555 0.00151645 0.988676 1 7.73381e-19 7.73381e-19 -5.49776e-08 -3.68827e-10 -7.96182e-10 1 7.73381e-19 -5.49776e-08 -3.68827e-10 -7.96182e-10 1 -5.49776e-08 -3.68827e-10 -7.96182e-10 3957.23 27.914 -388.242 3991.77 -8.47343 4037.31 +EDGE_SE3:QUAT 1874 1875 -0.275613 6.7162 0.235254 0.153492 -0.0841765 0.106072 0.978828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4085.04 -50.2734 -866.593 3954.49 -14.257 4134.27 +EDGE_SE3:QUAT 1875 1876 -0.420585 6.9549 -0.127828 -0.0866553 0.0595916 0.146143 0.983657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.41 -11.0705 619.532 3975.33 39.5285 4008.02 +EDGE_SE3:QUAT 1876 1877 -0.951429 7.10023 -0.301001 -0.0332562 -0.105442 0.14028 0.983919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4143.67 47.7595 -784.662 3970.93 -66.993 4069.38 +EDGE_SE3:QUAT 1877 1878 -0.354627 6.85662 -0.144393 -0.0288665 -0.0239449 0.195912 0.979904 1 4.81482e-20 4.81482e-20 1.36043e-08 2.73657e-09 -1.5224e-10 1 4.81482e-20 1.36043e-08 2.73657e-09 -1.5224e-10 1 1.36043e-08 2.73657e-09 -1.5224e-10 3999.73 2.55573 -114.304 3999.72 -8.83132 3849.54 +EDGE_SE3:QUAT 1878 1879 -0.7529 6.98009 -0.272601 -0.105051 -0.0146748 -0.0788684 0.991226 1 1.92593e-19 1.92593e-19 8.50734e-10 2.82167e-09 -2.75509e-08 1 1.92593e-19 8.50734e-10 2.82167e-09 -2.75509e-08 1 8.50734e-10 2.82167e-09 -2.75509e-08 3966.97 11.8495 -213.278 3996.38 8.25879 3986.23 +EDGE_SE3:QUAT 1879 1880 -0.923737 6.69462 -0.243784 0.0488698 0.275905 -0.032766 0.959382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5576.16 45.4649 2976.12 3693.75 44.0954 5581.41 +EDGE_SE3:QUAT 1880 1881 -0.915651 7.13806 -0.0146325 -0.104763 0.0276671 0.163519 0.980572 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.71 -16.891 413.912 3986.92 34.251 3934.66 +EDGE_SE3:QUAT 1881 1882 -0.51128 6.77984 -0.416243 -0.180485 0.0598858 -0.0228171 0.981488 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3911.11 -37.5747 410.281 3992.63 -16.9999 4039.32 +EDGE_SE3:QUAT 1882 1883 -0.301655 6.92948 -0.251177 0.0815127 0.114678 0.0692821 0.987626 1 1.92593e-19 1.92593e-19 2.84872e-09 2.80629e-09 2.80252e-08 1 1.92593e-19 2.84872e-09 2.80629e-09 2.80252e-08 1 2.84872e-09 2.80629e-09 2.80252e-08 4151.86 58.5415 864.18 3963.25 56.2925 4159.23 +EDGE_SE3:QUAT 1883 1884 -0.853077 7.18609 0.0475779 0.0503028 -0.0586509 0.104797 0.991487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4059.11 -3.82478 -530.975 3982.42 -24.8711 4025.3 +EDGE_SE3:QUAT 1884 1885 -0.541943 6.90642 -0.45182 -0.0163397 0.0337602 0.29221 0.955618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.08 6.94896 291.649 3996.37 43.6865 3679.6 +EDGE_SE3:QUAT 1885 1886 0.023516 7.01083 -0.502263 0.115256 0.0608374 -0.0818096 0.98809 1 1.92593e-19 1.92593e-19 2.77265e-08 -1.86176e-09 2.16773e-09 1 1.92593e-19 2.77265e-08 -1.86176e-09 2.16773e-09 1 2.77265e-08 -1.86176e-09 2.16773e-09 4033.67 27.9069 596.279 3977.29 -12.7673 4060.04 +EDGE_SE3:QUAT 1886 1887 -0.457034 6.5075 -0.141995 0.0241171 -0.149471 0.208639 0.966202 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4367.89 105.692 -1272.42 3932.85 -150.555 4196.09 +EDGE_SE3:QUAT 1887 1888 -0.746216 6.39585 -0.158013 0.0531276 0.0279045 0.166738 0.984173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.27 2.99531 108.835 3999.87 6.22202 3891.35 +EDGE_SE3:QUAT 1888 1889 -0.845014 6.95014 -0.0292859 -0.0697045 0.196846 0.141942 0.967598 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4752.41 78.4649 1919.16 3838.35 113.157 4691.26 +EDGE_SE3:QUAT 1889 1890 -0.620725 6.86384 -0.169816 0.0280727 0.0929068 0.0863528 0.991526 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4123.75 28.0498 723.874 3971.57 38.995 4097.08 +EDGE_SE3:QUAT 1890 1891 -0.289366 7.0453 0.0293112 -0.0341391 -0.050213 -0.00436712 0.998145 1 1.88079e-22 1.88079e-22 4.39322e-11 2.95286e-11 -8.7017e-10 1 1.88079e-22 4.39322e-11 2.95286e-11 -8.7017e-10 1 4.39322e-11 2.95286e-11 -8.7017e-10 4036.21 6.85908 -406.388 3989.89 -1.18957 4040.79 +EDGE_SE3:QUAT 1891 1892 -0.202162 6.87634 -0.0900568 -0.0858815 0.0225622 0.0809917 0.992752 1 1.92593e-19 1.92593e-19 9.94884e-10 -2.2595e-09 2.76128e-08 1 1.92593e-19 9.94884e-10 -2.2595e-09 2.76128e-08 1 9.94884e-10 -2.2595e-09 2.76128e-08 3987.25 -10.6267 260.549 3995.05 9.8106 3990.51 +EDGE_SE3:QUAT 1892 1893 -0.49932 7.08459 0.210569 -0.0403638 0.0182564 0.0675593 0.996731 1 6.01853e-20 6.01853e-20 -1.43035e-08 6.00123e-09 -6.53722e-11 1 6.01853e-20 -1.43035e-08 6.00123e-09 -6.53722e-11 1 -1.43035e-08 6.00123e-09 -6.53722e-11 4001.33 -3.07277 177.625 3997.84 5.93862 3989.59 +EDGE_SE3:QUAT 1893 1894 -0.601911 6.79385 -0.596772 -0.0220201 0.117492 0.103553 0.987415 1 1.95602e-19 1.95602e-19 -1.12753e-10 -2.88537e-10 2.77872e-08 1 1.95602e-19 -1.12753e-10 -2.88537e-10 2.77872e-08 1 -1.12753e-10 -2.88537e-10 2.77872e-08 4234.71 25.0011 1001.3 3945.3 51.8522 4193.76 +EDGE_SE3:QUAT 1894 1895 -0.427171 6.78188 -0.245302 0.0280348 0.018063 0.0540397 0.997982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.79 2.01999 125.659 3999.13 3.41167 3992.25 +EDGE_SE3:QUAT 1895 1896 -0.27747 6.89999 0.051343 0.00296659 0.135218 0.0721945 0.988178 1 3.00927e-21 3.00927e-21 -3.55644e-09 -2.72629e-10 -4.79763e-10 1 3.00927e-21 -3.55644e-09 -2.72629e-10 -4.79763e-10 1 -3.55644e-09 -2.72629e-10 -4.79763e-10 4302.53 36.1746 1140.98 3930.88 50.4505 4281.71 +EDGE_SE3:QUAT 1896 1897 -0.368965 6.89676 -0.176973 0.235158 0.141271 0.173393 0.945874 1 3.27408e-18 3.27408e-18 -9.96159e-08 -5.09364e-08 3.59903e-09 1 3.27408e-18 -9.96159e-08 -5.09364e-08 3.59903e-09 1 -9.96159e-08 -5.09364e-08 3.59903e-09 3829.18 68.9743 511.732 4012.65 68.3993 3930.12 +EDGE_SE3:QUAT 1897 1898 -0.72962 6.31129 -0.285334 -0.133669 0.0347799 0.196243 0.970779 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.57 -26.722 569.862 3975.55 54.3161 3924 +EDGE_SE3:QUAT 1898 1899 -0.912732 6.46059 0.0638677 -0.167045 -0.0363104 -0.0282055 0.984877 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3916.35 28.6058 -335.788 3993.14 -1.71283 4024.79 +EDGE_SE3:QUAT 1899 1900 -0.437348 6.67191 -0.21521 -0.0462643 0.0189441 0.142553 0.988524 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.95 -3.45722 225.163 3996.34 17.1447 3931.23 +EDGE_SE3:QUAT 1900 1901 -0.745193 6.69781 -0.286138 0.0549331 0.183321 0.0668312 0.979239 1 7.70372e-19 7.70372e-19 5.10867e-09 -5.42451e-08 4.65126e-09 1 7.70372e-19 5.10867e-09 -5.42451e-08 4.65126e-09 1 5.10867e-09 -5.42451e-08 4.65126e-09 4527.74 116.577 1565.75 3890.33 118.503 4521.94 +EDGE_SE3:QUAT 1901 1902 -0.516388 6.69852 0.111392 0.0505042 -0.0678408 0.0506646 0.995128 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.13 -9.42532 -579.81 3979.38 -9.49457 4072.07 +EDGE_SE3:QUAT 1902 1903 -0.672175 6.42862 -0.254384 -0.0558669 -0.1094 0.107478 0.98659 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4144.54 51.8055 -808.85 3968.54 -61.0467 4110.82 +EDGE_SE3:QUAT 1903 1904 -0.679274 6.61539 -0.493309 0.0199311 -0.00823189 0.304721 0.952198 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.29 0.060161 -125.347 3998.95 -22.219 3632.46 +EDGE_SE3:QUAT 1904 1905 -0.285222 6.73956 0.0240471 0.0468043 0.0734938 0.0411394 0.995347 1 1.92593e-19 1.92593e-19 1.34058e-09 -2.76175e-08 1.4768e-09 1 1.92593e-19 1.34058e-09 -2.76175e-08 1.4768e-09 1 1.34058e-09 -2.76175e-08 1.4768e-09 4071.1 18.9712 570.908 3981.38 17.9931 4073.09 +EDGE_SE3:QUAT 1905 1906 -0.82342 6.74468 -0.242912 0.149734 -0.0867501 0.0824567 0.981456 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4080.39 -51.9936 -842.665 3957.9 -2.89971 4142.87 +EDGE_SE3:QUAT 1906 1907 -0.866245 6.68633 -0.0100457 -0.0672547 0.0400239 0.0502811 0.995664 1 2.40741e-19 2.40741e-19 2.8366e-08 -1.25779e-08 4.11901e-10 1 2.40741e-19 2.8366e-08 -1.25779e-08 4.11901e-10 1 2.8366e-08 -1.25779e-08 4.11901e-10 4014 -10.4273 359.904 3991.63 6.42249 4021.98 +EDGE_SE3:QUAT 1907 1908 -0.642672 6.76363 -0.14812 -0.08217 0.075435 0.161875 0.980487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4110.48 -3.45641 754.928 3965.42 53.3124 4032.67 +EDGE_SE3:QUAT 1908 1909 -0.537424 6.55319 -0.265024 0.144056 0.106749 0.0340342 0.983206 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4067.37 69.4446 791.003 3970.89 49.7783 4145.74 +EDGE_SE3:QUAT 1909 1910 -0.578993 6.40958 -0.197354 0.13229 0.0525175 0.140905 0.979738 1 7.70372e-19 7.70372e-19 -5.44295e-08 -8.33966e-09 -6.56692e-10 1 7.70372e-19 -5.44295e-08 -8.33966e-09 -6.56692e-10 1 -5.44295e-08 -8.33966e-09 -6.56692e-10 3936.09 9.26412 177.85 4000.18 9.51013 3926.67 +EDGE_SE3:QUAT 1910 1911 -0.689679 6.53255 -0.0494443 -0.111347 0.0502602 -0.21879 0.968094 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3949.19 -0.475506 84.6518 4000.58 1.78422 3807.31 +EDGE_SE3:QUAT 1911 1912 -0.518896 6.41229 0.0650327 0.0779961 0.0489939 0.258214 0.961687 1 3.08149e-18 3.08149e-18 3.2214e-10 1.02358e-08 1.06786e-07 1 3.08149e-18 3.2214e-10 1.02358e-08 1.06786e-07 1 3.2214e-10 1.02358e-08 1.06786e-07 3976.87 4.01775 119.104 4000.87 4.08724 3734.51 +EDGE_SE3:QUAT 1912 1913 -0.650511 6.55052 0.289966 0.0879713 0.0575862 0.110885 0.988256 1 1.92593e-19 1.92593e-19 -2.75237e-08 -3.33765e-09 -9.9743e-10 1 1.92593e-19 -2.75237e-08 -3.33765e-09 -9.9743e-10 1 -2.75237e-08 -3.33765e-09 -9.9743e-10 3995.93 18.5182 332.433 3995.75 20.7893 3977.7 +EDGE_SE3:QUAT 1913 1914 -0.717285 6.4527 -0.23115 0.0219028 -0.00520871 0.0780372 0.996696 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.02 -0.653225 -61.6956 3999.71 -2.64284 3976.58 +EDGE_SE3:QUAT 1914 1915 -0.442164 6.73926 -0.0948804 -0.0722748 -0.00814948 -0.0902649 0.993258 1 1.92593e-19 1.92593e-19 2.75854e-08 -2.4488e-09 -5.80317e-10 1 1.92593e-19 2.75854e-08 -2.4488e-09 -5.80317e-10 1 2.75854e-08 -2.4488e-09 -5.80317e-10 3983.97 5.52898 -141.665 3998.3 7.14183 3972.27 +EDGE_SE3:QUAT 1915 1916 -0.658542 6.91487 0.234743 -0.12388 0.0204753 0.0800494 0.988851 1 1.92593e-19 1.92593e-19 -2.7512e-08 -2.02175e-09 -1.09142e-09 1 1.92593e-19 -2.7512e-08 -2.02175e-09 -1.09142e-09 1 -2.7512e-08 -2.02175e-09 -1.09142e-09 3957.43 -17.7428 277.131 3994.12 9.733 3993.18 +EDGE_SE3:QUAT 1916 1917 -0.386413 6.47625 0.0235989 0.0698494 0.0776282 0.0245498 0.994229 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4070.47 25.6058 606.739 3979.16 17.5425 4087.57 +EDGE_SE3:QUAT 1917 1918 -0.267603 6.74415 -0.2822 0.201049 0.0671472 -0.0753677 0.974367 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3956 67.0502 696.927 3970.94 3.64875 4094.97 +EDGE_SE3:QUAT 1918 1919 -0.269869 6.39594 -0.0309726 0.014497 -0.0707836 0.0449394 0.996373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4082.31 1.17288 -582.682 3979.55 -12.0212 4075.07 +EDGE_SE3:QUAT 1919 1920 -0.10183 6.59294 0.0486062 0.0386676 -0.0347905 0.00882987 0.998607 1 7.52316e-22 7.52316e-22 -6.15016e-11 6.63295e-11 1.73662e-09 1 7.52316e-22 -6.15016e-11 6.63295e-11 1.73662e-09 1 -6.15016e-11 6.63295e-11 1.73662e-09 4013.94 -5.30122 -283.001 3995.03 -0.117882 4019.61 +EDGE_SE3:QUAT 1920 1921 -0.451673 6.58038 0.0913362 0.0653036 -0.0934875 0.147318 0.982493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4163.14 6.8334 -868.143 3956.66 -55.6616 4093.39 +EDGE_SE3:QUAT 1921 1922 -0.332457 6.30016 -0.228191 -0.150288 -0.0245745 0.0706261 0.98581 1 7.70372e-19 7.70372e-19 -5.47269e-08 -4.15073e-09 1.25678e-10 1 7.70372e-19 -5.47269e-08 -4.15073e-09 1.25678e-10 1 -5.47269e-08 -4.15073e-09 1.25678e-10 3910.14 1.59797 -63.381 4000.06 -1.12231 3980.53 +EDGE_SE3:QUAT 1922 1923 -0.746307 6.2508 -0.24761 -0.00523899 -0.0368033 -0.0779453 0.996264 1 1.88079e-22 1.88079e-22 -8.66519e-10 6.76417e-11 3.23291e-11 1 1.88079e-22 -8.66519e-10 6.76417e-11 3.23291e-11 1 -8.66519e-10 6.76417e-11 3.23291e-11 4021.98 -1.79441 -298.062 3994.61 11.639 3997.79 +EDGE_SE3:QUAT 1923 1924 -0.469253 6.36856 0.0208312 -0.126616 -0.000822921 0.123766 0.9842 1 1.92593e-19 1.92593e-19 8.35491e-10 -3.41523e-09 2.73419e-08 1 1.92593e-19 8.35491e-10 -3.41523e-09 2.73419e-08 1 8.35491e-10 -3.41523e-09 2.73419e-08 3942.92 -14.3976 178.161 3996.48 14.0336 3945.78 +EDGE_SE3:QUAT 1924 1925 -0.434693 6.30452 -0.342884 0.00145973 0.0729748 0.105426 0.991745 1 1.92593e-19 1.92593e-19 -1.99194e-09 -4.73032e-10 -2.78142e-08 1 1.92593e-19 -1.99194e-09 -4.73032e-10 -2.78142e-08 1 -1.99194e-09 -4.73032e-10 -2.78142e-08 4083.09 13.9145 582.55 3980.82 32.3964 4038.64 +EDGE_SE3:QUAT 1925 1926 -0.523442 6.48835 -0.194506 0.224428 -0.109692 0.0873165 0.964352 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4081.28 -113.557 -1100.76 3937.51 35.6622 4252.25 +EDGE_SE3:QUAT 1926 1927 -0.119395 6.4113 -0.036738 -0.0551792 0.110611 -0.1066 0.986589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4149.55 -52.5278 821.305 3967.48 -61.7907 4116.28 +EDGE_SE3:QUAT 1927 1928 -0.447346 6.23854 -0.00165844 -0.00756924 0.0957764 0.153632 0.983446 1 1.93345e-19 1.93345e-19 2.56553e-09 -2.7564e-08 4.49179e-10 1 1.93345e-19 2.56553e-09 -2.7564e-08 4.49179e-10 1 2.56553e-09 -2.7564e-08 4.49179e-10 4145.31 31.6029 776.858 3968.74 63.4504 4051.12 +EDGE_SE3:QUAT 1928 1929 -0.409046 6.41654 -0.0320207 -0.099915 -0.064063 0.0194692 0.992741 1 1.92593e-19 1.92593e-19 2.77569e-08 8.95951e-10 -1.64446e-09 1 1.92593e-19 2.77569e-08 8.95951e-10 -1.64446e-09 1 2.77569e-08 8.95951e-10 -1.64446e-09 4018.52 26.5856 -487.217 3986.89 -13.969 4056.93 +EDGE_SE3:QUAT 1929 1930 -0.506253 6.60265 -0.110091 -0.177793 -0.156345 0.15727 0.958756 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.85 125.386 -829.408 3997.87 -123.792 4058.36 +EDGE_SE3:QUAT 1930 1931 -0.790168 6.07883 -0.271889 0.132031 0.0328717 0.0836716 0.987161 1 9.62965e-19 9.62965e-19 -5.50817e-08 -8.73844e-09 -2.79322e-08 1 9.62965e-19 -5.50817e-08 -8.73844e-09 -2.79322e-08 1 -5.50817e-08 -8.73844e-09 -2.79322e-08 3933.45 5.75653 122.814 3999.84 4.34836 3975.18 +EDGE_SE3:QUAT 1931 1932 -0.331587 6.44575 -0.319243 -0.104557 0.0501246 0.0929709 0.988894 1 1.92593e-19 1.92593e-19 -2.76714e-08 -2.26824e-09 -1.88997e-09 1 1.92593e-19 -2.76714e-08 -2.26824e-09 -1.88997e-09 1 -2.76714e-08 -2.26824e-09 -1.88997e-09 4020.67 -21.2569 512.52 3982.6 16.9395 4029.82 +EDGE_SE3:QUAT 1932 1933 -0.233725 6.5162 0.188722 0.0365921 0.013202 0.104787 0.993734 1 3.00927e-21 3.00927e-21 -3.65975e-10 3.44745e-09 -1.33728e-10 1 3.00927e-21 -3.65975e-10 3.44745e-09 -1.33728e-10 1 -3.65975e-10 3.44745e-09 -1.33728e-10 3995.42 0.954705 58.0302 3999.91 2.26979 3956.85 +EDGE_SE3:QUAT 1933 1934 -0.313177 6.1976 -0.353466 -0.020133 -0.0172528 0.169966 0.985093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.41 1.43644 -91.7534 3999.73 -6.55408 3886.48 +EDGE_SE3:QUAT 1934 1935 -0.542409 5.88481 0.0598224 -0.102302 -0.0952481 0.183963 0.972944 1 1.92593e-19 1.92593e-19 2.72077e-08 5.64863e-09 -1.37498e-09 1 1.92593e-19 2.72077e-08 5.64863e-09 -1.37498e-09 1 2.72077e-08 5.64863e-09 -1.37498e-09 4015.52 43.637 -493.888 3995.54 -51.6498 3922.01 +EDGE_SE3:QUAT 1935 1936 -0.598753 6.32329 -0.249887 -0.00866575 -0.103851 0.130244 0.98599 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4162.65 37.3355 -823.849 3965.01 -61.0621 4095.1 +EDGE_SE3:QUAT 1936 1937 -0.74056 5.99196 0.0928115 -0.0282908 -0.0746916 0.0776779 0.993774 1 4.81482e-20 4.81482e-20 1.39312e-08 1.1586e-09 -9.70343e-10 1 4.81482e-20 1.39312e-08 1.1586e-09 -9.70343e-10 1 1.39312e-08 1.1586e-09 -9.70343e-10 4077.69 18.233 -574.701 3981.56 -26.7092 4056.76 +EDGE_SE3:QUAT 1937 1938 -0.442179 6.17091 0.114232 0.0245285 0.105987 0.0764877 0.991118 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4169.55 32.0146 847.104 3960.99 42.3172 4148.56 +EDGE_SE3:QUAT 1938 1939 -0.815128 6.27385 -0.138459 0.107107 0.0352938 -0.085925 0.989899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.99 18.6761 387.06 3989.56 -13.0764 4007.35 +EDGE_SE3:QUAT 1939 1940 -0.772363 6.34878 -0.300414 0.0550756 0.0242897 0.0584875 0.996472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.75 4.47558 154.093 3998.82 4.68256 3992.2 +EDGE_SE3:QUAT 1940 1941 -0.0847828 6.29749 -0.131564 -0.0363468 -0.0775497 -0.0171766 0.996178 1 3.00927e-21 3.00927e-21 2.75959e-10 1.19726e-10 -3.49917e-09 1 3.00927e-21 2.75959e-10 1.19726e-10 -3.49917e-09 1 2.75959e-10 1.19726e-10 -3.49917e-09 4094.67 9.82419 -640.18 3975.44 0.377473 4098.78 +EDGE_SE3:QUAT 1941 1942 -0.682232 6.24776 0.220787 0.000745383 0.0191801 0.197701 0.980074 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.09 1.64675 142.963 3999.01 13.8271 3848.75 +EDGE_SE3:QUAT 1942 1943 -0.49362 6.01582 0.31171 0.146524 0.0716692 -0.176788 0.970639 1 9.62965e-19 9.62965e-19 -2.34049e-09 2.05619e-08 -5.83202e-08 1 9.62965e-19 -2.34049e-09 2.05619e-08 -5.83202e-08 1 -2.34049e-09 2.05619e-08 -5.83202e-08 4093.08 32.8555 867.584 3951.84 -55.9229 4053.94 +EDGE_SE3:QUAT 1943 1944 -0.551456 6.17883 0.138431 0.11384 -0.0644151 0.0453811 0.990369 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.39 -29.9732 -575.91 3979.74 -0.555703 4072.99 +EDGE_SE3:QUAT 1944 1945 -0.729221 6.05522 -0.0137933 0.0168424 -0.0942507 0.00792774 0.995374 1 7.52316e-22 7.52316e-22 -1.66832e-10 2.76076e-11 1.75805e-09 1 7.52316e-22 -1.66832e-10 2.76076e-11 1.75805e-09 1 -1.66832e-10 2.76076e-11 1.75805e-09 4145.37 -5.41554 -779.417 3964.35 0.378321 4146.26 +EDGE_SE3:QUAT 1945 1946 -0.365311 5.96171 -0.300116 0.0558909 0.011009 0.282807 0.957484 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.21 -4.34525 -101.88 3998.26 -23.7932 3681.78 +EDGE_SE3:QUAT 1946 1947 -0.600384 6.36585 -0.081412 -0.0966606 0.0433259 0.02767 0.993989 1 1.92593e-19 1.92593e-19 -2.77106e-08 -5.26977e-10 -1.33244e-09 1 1.92593e-19 -2.77106e-08 -5.26977e-10 -1.33244e-09 1 -2.77106e-08 -5.26977e-10 -1.33244e-09 3997.7 -17.5931 376.278 3991.17 0.47347 4032.01 +EDGE_SE3:QUAT 1947 1948 -0.633504 6.20738 -0.114251 -0.0410063 -0.0237631 0.0503703 0.997605 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000 3.75726 -164.392 3998.52 -4.38845 3996.58 +EDGE_SE3:QUAT 1948 1949 -0.454274 6.26689 0.25829 0.0156982 0.015908 -0.0213616 0.999522 1 3.00927e-21 3.00927e-21 3.46965e-09 -7.24207e-11 5.74727e-11 1 3.00927e-21 3.46965e-09 -7.24207e-11 5.74727e-11 1 3.46965e-09 -7.24207e-11 5.74727e-11 4003.32 0.907229 131.278 3998.91 -1.31978 4002.48 +EDGE_SE3:QUAT 1949 1950 -0.460173 6.08669 -0.144584 0.125052 0.118378 -0.0660524 0.982846 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4210.92 53.102 1081.17 3935.36 9.15944 4256.02 +EDGE_SE3:QUAT 1950 1951 -0.534704 6.16783 -0.381232 -0.0838731 -0.0210679 0.0911248 0.992077 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3972.96 2.07121 -73.8509 3999.94 -2.19961 3967.89 +EDGE_SE3:QUAT 1951 1952 -0.27435 6.17327 0.0897548 0.0477901 0.0531628 0.0237358 0.997159 1 4.81482e-20 4.81482e-20 -1.39116e-08 -4.02546e-10 -7.05612e-10 1 4.81482e-20 -1.39116e-08 -4.02546e-10 -7.05612e-10 1 -1.39116e-08 -4.02546e-10 -7.05612e-10 4033.17 11.5836 413.579 3989.92 8.09209 4040.05 +EDGE_SE3:QUAT 1952 1953 -0.498771 6.10104 0.0628263 -0.0936086 -0.121168 0.0793818 0.985015 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4153.76 70.3877 -890.575 3963.45 -67.8753 4163.61 +EDGE_SE3:QUAT 1953 1954 -0.456575 6.07647 -0.109245 -0.123274 -0.0280597 0.0121569 0.991901 1 3.00927e-21 3.00927e-21 -8.41294e-11 -4.31111e-10 3.44578e-09 1 3.00927e-21 -8.41294e-11 -4.31111e-10 3.44578e-09 1 -8.41294e-11 -4.31111e-10 3.44578e-09 3949.36 12.2586 -201.935 3997.83 -3.18325 4009.56 +EDGE_SE3:QUAT 1954 1955 -0.0649808 6.00591 0.133081 0.0913151 0.113278 0.0471329 0.988235 1 1.92593e-19 1.92593e-19 -1.89835e-09 2.73945e-08 -2.88376e-09 1 1.92593e-19 -1.89835e-09 2.73945e-08 -2.88376e-09 1 -1.89835e-09 2.73945e-08 -2.88376e-09 4148.21 57.5124 871.792 3961.51 49.1559 4172.68 +EDGE_SE3:QUAT 1955 1956 -0.211763 5.77326 0.0900277 0.00424474 -0.176881 -0.104407 0.97867 1 1.92593e-19 1.92593e-19 5.07632e-09 -1.26999e-09 -2.89165e-08 1 1.92593e-19 5.07632e-09 -1.26999e-09 -2.89165e-08 1 5.07632e-09 -1.26999e-09 -2.89165e-08 4526.33 -93.2136 -1543.73 3890.05 110.681 4482.8 +EDGE_SE3:QUAT 1956 1957 -0.683764 5.71659 -0.121467 -0.305741 -0.0474543 -0.00294869 0.950927 1 3.08149e-18 3.08149e-18 -1.05987e-07 -2.82123e-09 4.48809e-09 1 3.08149e-18 -1.05987e-07 -2.82123e-09 4.48809e-09 1 -1.05987e-07 -2.82123e-09 4.48809e-09 3654.51 50.6389 -339.783 3996.76 -14.0781 4028.39 +EDGE_SE3:QUAT 1957 1958 -0.537842 5.49941 0.231383 0.190724 0.0240968 0.223091 0.955654 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3872.9 -43.5826 -314.124 3985.38 -52.065 3819.32 +EDGE_SE3:QUAT 1958 1959 -0.384496 5.8665 -0.0257057 0.028203 0.0337787 -0.0865338 0.995277 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.81 1.60954 297.525 3994.35 -12.5202 3992.04 +EDGE_SE3:QUAT 1959 1960 -0.579632 5.83399 -0.0705563 -0.0205385 -0.0607445 0.0777688 0.994907 1 1.92593e-19 1.92593e-19 1.58548e-09 8.35635e-10 -2.78008e-08 1 1.92593e-19 1.58548e-09 8.35635e-10 -2.78008e-08 1 1.58548e-09 8.35635e-10 -2.78008e-08 4052.18 11.3904 -467.385 3987.55 -20.2494 4029.67 +EDGE_SE3:QUAT 1960 1961 -0.12799 5.66606 -0.167435 -0.165749 0.0187506 0.105405 0.980339 1 7.70372e-19 7.70372e-19 -5.4626e-08 -5.21823e-09 -2.87612e-09 1 7.70372e-19 -5.4626e-08 -5.21823e-09 -2.87612e-09 1 -5.4626e-08 -5.21823e-09 -2.87612e-09 3919.36 -31.0514 348.401 3990.02 16.2637 3984.81 +EDGE_SE3:QUAT 1961 1962 -0.868714 5.80787 0.170543 0.0773298 -0.107715 -0.0113513 0.991105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4159.76 -40.9916 -876.673 3957.69 27.5978 4183.17 +EDGE_SE3:QUAT 1962 1963 -0.591921 5.96082 -0.0221423 -0.0453965 -0.123997 0.0358698 0.990594 1 2.40741e-19 2.40741e-19 -3.71194e-10 -2.82774e-08 1.26148e-08 1 2.40741e-19 -3.71194e-10 -2.82774e-08 1.26148e-08 1 -3.71194e-10 -2.82774e-08 1.26148e-08 4235.92 40.3064 -1018.03 3944.05 -38.3614 4239.02 +EDGE_SE3:QUAT 1963 1964 0.0442404 5.37184 -0.2466 0.0980072 -0.157564 0.124656 0.974694 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4473.2 -0.201108 -1519.47 3883.21 -48.0517 4449.46 +EDGE_SE3:QUAT 1964 1965 -0.608598 5.70953 0.241098 -0.0654481 0.0809263 0.136234 0.985194 1 4.81482e-20 4.81482e-20 1.39104e-08 1.78573e-09 1.34309e-09 1 4.81482e-20 1.39104e-08 1.78573e-09 1.34309e-09 1 1.39104e-08 1.78573e-09 1.34309e-09 4120.45 -0.289155 754.803 3966.02 44.4396 4063.35 +EDGE_SE3:QUAT 1965 1966 -0.242984 5.78615 0.235125 -0.150714 0.033719 -0.0263378 0.987651 1 1.20371e-20 1.20371e-20 -1.6866e-10 1.06016e-09 -6.8631e-09 1 1.20371e-20 -1.6866e-10 1.06016e-09 -6.8631e-09 1 -1.6866e-10 1.06016e-09 -6.8631e-09 3920.42 -15.3354 213.827 3997.98 -5.51259 4008.51 +EDGE_SE3:QUAT 1966 1967 -0.253586 5.82266 0.0897873 -0.0572032 0.158938 -0.0612819 0.983723 1 3.85186e-19 3.85186e-19 2.429e-08 -8.67035e-11 -2.429e-08 1 3.85186e-19 2.429e-08 -8.67035e-11 -2.429e-08 1 2.429e-08 -8.67035e-11 -2.429e-08 4381.43 -85.901 1316.97 3916.75 -86.6507 4379.49 +EDGE_SE3:QUAT 1967 1968 -0.498046 5.79383 -0.319296 0.0342766 0.153681 0.0936374 0.983076 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4360.41 81.6762 1262.75 3923.8 92.7304 4330.04 +EDGE_SE3:QUAT 1968 1969 -0.454086 5.85078 -0.0170369 0.0055965 -0.0095223 0.0899324 0.995887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.53 -0.0149174 -81.2904 3999.58 -3.72212 3969.3 +EDGE_SE3:QUAT 1969 1970 -0.590678 5.28209 -0.0580266 -0.186442 0.0625817 0.0828775 0.976962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3969.2 -58.2855 667.972 3972.21 3.2953 4080.77 +EDGE_SE3:QUAT 1970 1971 -0.308378 5.89595 -0.424294 0.0389685 0.00737913 0.121058 0.991853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.83 -0.338371 1.6047 3999.98 -1.07181 3941.29 +EDGE_SE3:QUAT 1971 1972 -0.481592 5.8141 0.0504884 0.0195894 0.0248791 0.0930834 0.995155 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.07 2.78004 174.842 3998.35 8.04099 3972.95 +EDGE_SE3:QUAT 1972 1973 -0.702493 5.80763 0.185832 0.0343918 0.0409132 0.0877505 0.994708 1 4.81482e-20 4.81482e-20 1.38401e-08 1.26091e-09 4.75175e-10 1 4.81482e-20 1.38401e-08 1.26091e-09 4.75175e-10 1 1.38401e-08 1.26091e-09 4.75175e-10 4015.85 7.70628 288.079 3995.56 13.3781 3989.79 +EDGE_SE3:QUAT 1973 1974 -0.700759 5.39093 -0.162834 0.268941 -0.0339049 0.101273 0.957217 1 4.81482e-20 4.81482e-20 9.66791e-10 -1.33232e-08 3.5902e-09 1 4.81482e-20 9.66791e-10 -1.33232e-08 3.5902e-09 1 9.66791e-10 -1.33232e-08 3.5902e-09 3785.98 -81.1087 -558.604 3977.94 -8.51973 4034.27 +EDGE_SE3:QUAT 1974 1975 -0.386294 5.88672 -0.198957 -0.036715 0.067274 0.0266564 0.996702 1 1.20371e-20 1.20371e-20 4.83141e-10 -2.33926e-10 6.98175e-09 1 1.20371e-20 4.83141e-10 -2.33926e-10 6.98175e-09 1 4.83141e-10 -2.33926e-10 6.98175e-09 4070.87 -7.7449 557.543 3981.09 3.63475 4073.42 +EDGE_SE3:QUAT 1975 1976 -0.578596 5.61257 -0.14984 -0.133842 -0.0933581 0.131469 0.977797 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.62 45.7305 -503.675 3993.68 -45.4784 3991.13 +EDGE_SE3:QUAT 1976 1977 -0.508286 5.34923 -0.596275 0.000256967 -0.0428696 -0.09884 0.994179 1 1.92593e-19 1.92593e-19 -1.16933e-09 2.42598e-10 2.76936e-08 1 1.92593e-19 -1.16933e-09 2.42598e-10 2.76936e-08 1 -1.16933e-09 2.42598e-10 2.76936e-08 4028.65 -4.35733 -339.742 3993.24 17.035 3989.57 +EDGE_SE3:QUAT 1977 1978 -0.498062 5.54308 0.214925 0.0978434 0.116558 0.0295969 0.987909 1 1.92593e-19 1.92593e-19 2.81105e-08 1.50713e-09 3.07583e-09 1 1.92593e-19 2.81105e-08 1.50713e-09 3.07583e-09 1 2.81105e-08 1.50713e-09 3.07583e-09 4163.29 59.8626 920.581 3956.39 46.5374 4198.08 +EDGE_SE3:QUAT 1978 1979 -0.315457 5.79171 -0.00793546 -0.174434 0.075606 0.130726 0.97302 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4056.72 -57.1564 865.547 3953.03 23.9706 4110.07 +EDGE_SE3:QUAT 1979 1980 -0.939737 5.62288 -0.297581 -0.0747519 -0.081868 0.200615 0.973377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.08 32.3858 -437.262 3995.86 -45.0593 3884.44 +EDGE_SE3:QUAT 1980 1981 -0.529965 5.67516 0.454649 -0.0525592 0.121339 0.0614625 0.989311 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4251.88 -7.96383 1058.73 3937.05 17.0671 4247.82 +EDGE_SE3:QUAT 1981 1982 -0.391713 5.6419 0.304541 -0.0476173 0.222917 -0.0801472 0.97037 1 1.92593e-19 1.92593e-19 6.41845e-09 -2.76678e-09 2.96609e-08 1 1.92593e-19 6.41845e-09 -2.76678e-09 2.96609e-08 1 6.41845e-09 -2.76678e-09 2.96609e-08 4831.13 -186.794 2017.02 3842.75 -190.285 4814.51 +EDGE_SE3:QUAT 1982 1983 -0.357626 5.9789 0.229072 0.00248271 0.0485798 0.0596156 0.997036 1 4.81482e-20 4.81482e-20 -6.68335e-10 -1.15431e-10 -1.39012e-08 1 4.81482e-20 -6.68335e-10 -1.15431e-10 -1.39012e-08 1 -6.68335e-10 -1.15431e-10 -1.39012e-08 4037.25 3.86015 387.91 3990.95 11.9496 4023.05 +EDGE_SE3:QUAT 1983 1984 -0.224249 5.81822 -0.362001 0.0267992 0.0350243 0.0782038 0.995961 1 1.20371e-20 1.20371e-20 6.92471e-09 5.57238e-10 2.11051e-10 1 1.20371e-20 6.92471e-09 5.57238e-10 2.11051e-10 1 6.92471e-09 5.57238e-10 2.11051e-10 4013.05 5.27958 253.084 3996.44 10.3207 3991.46 +EDGE_SE3:QUAT 1984 1985 -0.586702 5.34711 -0.194696 0.0903463 -0.00284989 -0.0367242 0.995229 1 1.92596e-19 1.92596e-19 2.76272e-08 -9.08983e-10 9.59156e-11 1 1.92596e-19 2.76272e-08 -9.08983e-10 9.59156e-11 1 2.76272e-08 -9.08983e-10 9.59156e-11 3967.38 1.37566 17.0878 3999.94 -0.557798 3994.63 +EDGE_SE3:QUAT 1985 1986 -0.568724 5.37044 -0.0988837 -0.0144522 -0.0624156 -0.0998909 0.992934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4064.75 -5.95256 -516.375 3984.23 25.6211 4025.67 +EDGE_SE3:QUAT 1986 1987 -0.342293 5.49325 -0.433442 0.164688 0.152332 0.0716666 0.971873 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4157.73 134.299 1069.74 3961.79 120.586 4245.67 +EDGE_SE3:QUAT 1987 1988 -0.436785 5.69683 -0.0836018 0.0306477 0.0259759 0.0192651 0.999007 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.29 3.35463 200.747 3997.57 2.39335 4008.56 +EDGE_SE3:QUAT 1988 1989 -0.435948 5.91668 -0.180373 -0.104272 -0.206936 -0.0451478 0.971734 1 9.75002e-19 9.75002e-19 -3.13741e-08 -5.46414e-08 8.63711e-09 1 9.75002e-19 -3.13741e-08 -5.46414e-08 8.63711e-09 1 -3.13741e-08 -5.46414e-08 8.63711e-09 4773.25 93.9555 -1983.43 3827.8 -72.1219 4808.58 +EDGE_SE3:QUAT 1989 1990 -0.585396 5.55171 -0.352709 -0.0470686 -0.150888 0.141025 0.977307 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4300.2 104.928 -1155.48 3944.52 -120.922 4229.51 +EDGE_SE3:QUAT 1990 1991 -0.596032 5.67733 -0.149363 -0.104844 -0.039344 -0.0366066 0.993036 1 4.81482e-20 4.81482e-20 3.84575e-10 1.37851e-08 1.41663e-09 1 4.81482e-20 3.84575e-10 1.37851e-08 1.41663e-09 1 3.84575e-10 1.37851e-08 1.41663e-09 3987.66 18.1232 -357.293 3991.85 2.13261 4026.27 +EDGE_SE3:QUAT 1991 1992 -0.76903 5.29627 0.267368 -0.13595 0.0971673 -0.0167459 0.985797 1 2.0463e-19 2.0463e-19 -5.64529e-10 -2.83394e-08 3.02798e-09 1 2.0463e-19 -5.64529e-10 -2.83394e-08 3.02798e-09 1 -5.64529e-10 -2.83394e-08 3.02798e-09 4061.63 -58.221 749.125 3971.66 -36.0128 4134.43 +EDGE_SE3:QUAT 1992 1993 -0.277116 5.37445 -0.0821976 -0.151555 0.117982 -0.0752877 0.97849 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4056.65 -81.8428 788.493 3976.81 -70.1463 4125.85 +EDGE_SE3:QUAT 1993 1994 -0.555081 5.23659 0.0265068 -0.111615 0.0500389 0.111905 0.986162 1 1.92593e-19 1.92593e-19 -2.02728e-09 2.75596e-09 -2.76222e-08 1 1.92593e-19 -2.02728e-09 2.75596e-09 -2.76222e-08 1 -2.02728e-09 2.75596e-09 -2.76222e-08 4022.09 -22.9441 542.552 3980.2 23.061 4021.83 +EDGE_SE3:QUAT 1994 1995 -0.578141 5.19304 -0.0641115 -0.0264108 -0.0579694 0.0177441 0.997811 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.02 7.7185 -462.656 3987.12 -6.34842 4051.55 +EDGE_SE3:QUAT 1995 1996 -0.549094 5.34499 0.0361013 0.0410193 -0.126197 0.100135 0.986085 1 1.20371e-20 1.20371e-20 -7.08556e-09 -6.6565e-10 9.46012e-10 1 1.20371e-20 -7.08556e-09 -6.6565e-10 9.46012e-10 1 -7.08556e-09 -6.6565e-10 9.46012e-10 4279.61 16.9803 -1107.87 3933.07 -47.8986 4246.23 +EDGE_SE3:QUAT 1996 1997 -0.241224 5.09106 -0.177218 0.192635 -0.23973 0.0531193 0.950052 1 7.70372e-19 7.70372e-19 -5.99969e-08 2.76825e-09 1.52495e-08 1 7.70372e-19 -5.99969e-08 2.76825e-09 1.52495e-08 1 -5.99969e-08 2.76825e-09 1.52495e-08 4982.14 -286.601 -2408.66 3811.2 266.722 5119.29 +EDGE_SE3:QUAT 1997 1998 -0.716318 5.1459 -0.00129482 -0.00766495 -0.0117748 -0.0381168 0.999175 1 6.01853e-21 6.01853e-21 3.59926e-09 3.33493e-09 -1.93567e-11 1 6.01853e-21 3.59926e-09 3.33493e-09 -1.93567e-11 1 3.59926e-09 3.33493e-09 -1.93567e-11 4002.14 0.244577 -97.5393 3999.4 1.85574 3996.57 +EDGE_SE3:QUAT 1998 1999 -0.497844 5.73293 -0.236664 -0.261376 0.00408759 0.0635056 0.963137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3737.99 -36.4941 219.462 3995.43 5.82533 3995.13 +EDGE_SE3:QUAT 1999 2000 -0.645833 5.23841 -0.00331134 0.00482967 0.0418486 -0.0740859 0.996362 1 4.70198e-23 4.70198e-23 -4.33644e-10 3.21811e-11 -1.83241e-11 1 4.70198e-23 -4.33644e-10 3.21811e-11 -1.83241e-11 1 -4.33644e-10 3.21811e-11 -1.83241e-11 4028.33 -2.33814 338.408 3993.07 -12.5813 4006.47 +EDGE_SE3:QUAT 2000 2001 -0.696721 5.42889 -0.00883744 -0.0792533 -0.068702 0.0292411 0.994054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.15 24.3297 -523.253 3984.73 -16.1792 4063.85 +EDGE_SE3:QUAT 2001 2002 -0.177869 5.1593 -0.0347435 0.104611 0.0778046 0.134139 0.982349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.11 31.6383 432.213 3994.19 34.8002 3972.91 +EDGE_SE3:QUAT 2002 2003 -0.334959 5.26476 -0.00677344 0.0999937 0.00353828 -0.0703409 0.992492 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3962.92 6.7395 111.323 3998.81 -4.57746 3983.12 +EDGE_SE3:QUAT 2003 2004 -0.482532 5.38323 0.378103 -0.165978 -0.0168651 -0.00583349 0.985968 1 7.70372e-19 7.70372e-19 5.47671e-08 4.34269e-13 -9.91236e-10 1 7.70372e-19 5.47671e-08 4.34269e-13 -9.91236e-10 1 5.47671e-08 4.34269e-13 -9.91236e-10 3894.77 11.8552 -140.943 3998.86 -0.811838 4004.82 +EDGE_SE3:QUAT 2004 2005 -0.176494 5.35505 0.263594 0.031642 -0.18783 0.0488894 0.980474 1 1.20371e-20 1.20371e-20 -7.33059e-09 -2.98927e-10 1.41939e-09 1 1.20371e-20 -7.33059e-09 -2.98927e-10 1.41939e-09 1 -7.33059e-09 -2.98927e-10 1.41939e-09 4638.11 12.3158 -1726.49 3856.88 -26.1307 4632.56 +EDGE_SE3:QUAT 2005 2006 -0.753822 5.18091 -0.116029 0.089059 -0.017679 0.0534096 0.994436 1 2.0463e-19 2.0463e-19 -2.79777e-08 5.52697e-09 1.41845e-10 1 2.0463e-19 -2.79777e-08 5.52697e-09 1.41845e-10 1 -2.79777e-08 5.52697e-09 1.41845e-10 3977.81 -8.91638 -196.295 3997.21 -4.61939 3998.13 +EDGE_SE3:QUAT 2006 2007 -0.56665 5.38721 0.0385168 0.0553583 0.0604083 0.0431622 0.995702 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4039 16.2282 455.872 3988.24 14.3923 4043.81 +EDGE_SE3:QUAT 2007 2008 -0.770631 4.83752 0.0805775 -0.119127 -0.100905 0.131916 0.97889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4026.68 53.8562 -590.323 3989.35 -55.4423 4013.84 +EDGE_SE3:QUAT 2008 2009 -0.58844 5.1453 0.0735088 -0.211978 0.0291064 0.111295 0.97048 1 8.1852e-19 8.1852e-19 -5.55348e-08 8.48702e-09 -1.21609e-09 1 8.1852e-19 -5.55348e-08 8.48702e-09 -1.21609e-09 1 -5.55348e-08 8.48702e-09 -1.21609e-09 3878.9 -54.7908 493.181 3981.44 17.587 4009.09 +EDGE_SE3:QUAT 2009 2010 -0.647872 5.02912 0.0239336 0.012064 0.122649 0.148789 0.981159 1 1.20371e-20 1.20371e-20 -6.99985e-09 -1.11495e-09 -8.08522e-10 1 1.20371e-20 -6.99985e-09 -1.11495e-09 -8.08522e-10 1 -6.99985e-09 -1.11495e-09 -8.08522e-10 4222.36 59.8234 970.778 3955.12 86.2675 4134.39 +EDGE_SE3:QUAT 2010 2011 -0.599039 4.94016 -0.222044 -0.0370693 -0.0651173 0.0481045 0.996028 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4056.82 14.2126 -503.21 3985.41 -15.9975 4053.06 +EDGE_SE3:QUAT 2011 2012 -0.359858 5.12566 -0.185013 0.0219606 -0.0139155 -0.0386428 0.998915 1 4.81482e-20 4.81482e-20 -1.68866e-10 3.18981e-10 1.38671e-08 1 4.81482e-20 -1.68866e-10 3.18981e-10 1.38671e-08 1 -1.68866e-10 3.18981e-10 1.38671e-08 4000.61 -1.22561 -100.875 3999.41 1.97264 3996.57 +EDGE_SE3:QUAT 2012 2013 -0.0599594 4.78492 -0.198411 0.0481913 -0.0144252 0.120034 0.991495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.83 -3.66388 -181.543 3997.52 -11.7626 3950.49 +EDGE_SE3:QUAT 2013 2014 -0.308885 5.29814 -0.0637988 -0.0549593 -0.0928349 0.0352574 0.993538 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4118.5 28.8505 -734.503 3969.8 -25.0735 4125.61 +EDGE_SE3:QUAT 2014 2015 -0.360001 5.07643 -0.173408 -0.126702 -0.0515809 -0.0599375 0.988784 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.69 29.1407 -497.795 3984.16 5.27923 4046.53 +EDGE_SE3:QUAT 2015 2016 -0.273587 5.18383 -0.0146284 0.0762724 -0.177468 -0.0803121 0.977874 1 9.62965e-19 9.62965e-19 -5.27344e-08 3.39291e-09 -1.93358e-08 1 9.62965e-19 -5.27344e-08 3.39291e-09 -1.93358e-08 1 -5.27344e-08 3.39291e-09 -1.93358e-08 4444.7 -133.796 -1446.83 3911.12 134.437 4442.17 +EDGE_SE3:QUAT 2016 2017 -0.398685 4.86492 -0.0344348 0.0863936 0.0655811 -0.0938742 0.989658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4064.5 16.8685 622.022 3975.59 -20.4428 4059.11 +EDGE_SE3:QUAT 2017 2018 -0.445652 5.4156 0.225995 -0.0259071 -0.110388 -0.00478213 0.993539 1 4.70198e-23 4.70198e-23 -4.91151e-11 -1.13262e-11 4.41665e-10 1 4.70198e-23 -4.91151e-11 -1.13262e-11 4.41665e-10 1 -4.91151e-11 -1.13262e-11 4.41665e-10 4199.94 12.0181 -922.786 3951.3 -5.56204 4202.53 +EDGE_SE3:QUAT 2018 2019 -0.42522 5.30969 -0.158766 -0.0839664 0.052865 -0.0596235 0.993277 1 2.40741e-19 2.40741e-19 2.20013e-10 -1.62875e-08 2.64299e-08 1 2.40741e-19 2.20013e-10 -1.62875e-08 2.64299e-08 1 2.20013e-10 -1.62875e-08 2.64299e-08 4003.54 -17.6082 358.585 3993.51 -14.6845 4017.52 +EDGE_SE3:QUAT 2019 2020 -0.651664 4.9802 -0.433816 0.0726484 -0.109479 -0.021706 0.991093 1 3.97223e-19 3.97223e-19 -2.78327e-08 2.91398e-08 7.82082e-09 1 3.97223e-19 -2.78327e-08 2.91398e-08 7.82082e-09 1 -2.78327e-08 2.91398e-08 7.82082e-09 4165.18 -42.029 -883.192 3957.47 31.7881 4184.41 +EDGE_SE3:QUAT 2020 2021 -0.245534 4.74579 0.206462 -0.150097 -0.184337 0.0796227 0.968065 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4331.62 189.282 -1369.45 3941.22 -180.365 4396.38 +EDGE_SE3:QUAT 2021 2022 -0.436224 5.093 0.140827 0.192224 0.0557493 0.153974 0.967592 1 7.82409e-19 7.82409e-19 -1.61531e-09 1.78162e-08 5.23012e-08 1 7.82409e-19 -1.61531e-09 1.78162e-08 5.23012e-08 1 -1.61531e-09 1.78162e-08 5.23012e-08 3848.94 -5.43148 63.806 4000.34 -3.83382 3901.91 +EDGE_SE3:QUAT 2022 2023 -0.229339 4.90867 -0.119826 0.151624 -0.068509 0.139296 0.976173 1 1.73334e-18 1.73334e-18 5.79719e-08 2.63533e-08 -6.47309e-08 1 1.73334e-18 5.79719e-08 2.63533e-08 -6.47309e-08 1 5.79719e-08 2.63533e-08 -6.47309e-08 4057.36 -41.6034 -789.343 3959.76 -33.3797 4071.71 +EDGE_SE3:QUAT 2023 2024 -0.732119 4.71145 0.00723549 -0.00943188 0.121176 -0.0953713 0.987994 1 1.92593e-19 1.92593e-19 -3.34217e-09 9.44171e-10 -2.82166e-08 1 1.92593e-19 -3.34217e-09 9.44171e-10 -2.82166e-08 1 -3.34217e-09 9.44171e-10 -2.82166e-08 4232.37 -40.1432 992.598 3947.96 -57.6421 4196.35 +EDGE_SE3:QUAT 2024 2025 -0.521622 5.08687 -0.0729147 -0.00398494 0.0135492 0.0378423 0.999184 1 3.76158e-21 3.76158e-21 -1.86493e-09 3.40112e-09 -1.37333e-11 1 3.76158e-21 -1.86493e-09 3.40112e-09 -1.37333e-11 1 -1.86493e-09 3.40112e-09 -1.37333e-11 4002.96 -0.0499314 110.04 3999.24 2.07811 3997.3 +EDGE_SE3:QUAT 2025 2026 -0.556688 5.22947 -0.126865 0.00921087 -0.0959052 0.0582123 0.993644 1 4.83363e-20 4.83363e-20 -2.24021e-09 -7.88677e-11 1.41358e-08 1 4.83363e-20 -2.24021e-09 -7.88677e-11 1.41358e-08 1 -2.24021e-09 -7.88677e-11 1.41358e-08 4152.02 9.51109 -795.401 3963.39 -23.3058 4138.81 +EDGE_SE3:QUAT 2026 2027 -0.588156 5.24077 0.181337 0.0455161 0.00594357 -0.0306601 0.998475 1 4.89006e-20 4.89006e-20 -1.39104e-08 -1.31579e-09 -4.2495e-11 1 4.89006e-20 -1.39104e-08 -1.31579e-09 -4.2495e-11 1 -1.39104e-08 -1.31579e-09 -4.2495e-11 3992.73 1.54218 64.0631 3999.7 -1.0048 3997.26 +EDGE_SE3:QUAT 2027 2028 -0.421063 5.25505 -0.0286267 -0.0700446 0.191829 0.138282 0.96911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4710.76 67.9299 1858.78 3845.09 103.612 4653.89 +EDGE_SE3:QUAT 2028 2029 -0.212893 4.61779 0.036439 0.0258222 0.128318 -0.0552581 0.989856 1 7.82409e-19 7.82409e-19 -9.90184e-09 -5.46014e-08 -2.67952e-10 1 7.82409e-19 -9.90184e-09 -5.46014e-08 -2.67952e-10 1 -9.90184e-09 -5.46014e-08 -2.67952e-10 4281.28 -7.36331 1102.91 3932.81 -24.7174 4271.73 +EDGE_SE3:QUAT 2029 2030 -0.743199 4.93412 -0.171922 -0.213456 -0.0688592 0.0804146 0.9712 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3839.42 28.9818 -308.914 3999.29 -20.1004 3995.81 +EDGE_SE3:QUAT 2030 2031 -0.540833 4.52155 0.132582 0.0558674 -0.105984 0.18665 0.975094 1 1.92593e-19 1.92593e-19 -4.95781e-09 2.7106e-08 -3.8184e-10 1 1.92593e-19 -4.95781e-09 2.7106e-08 -3.8184e-10 1 -4.95781e-09 2.7106e-08 -3.8184e-10 4210.65 31.1937 -970.774 3950.35 -86.744 4083.78 +EDGE_SE3:QUAT 2031 2032 -0.0987516 4.70915 -0.0160759 0.0597461 0.107272 0.121857 0.984923 1 3.85186e-19 3.85186e-19 -3.1611e-08 2.34268e-08 -4.86788e-09 1 3.85186e-19 -3.1611e-08 2.34268e-08 -4.86788e-09 1 -3.1611e-08 2.34268e-08 -4.86788e-09 4127.74 52.9291 768.388 3973.02 63.5543 4082.62 +EDGE_SE3:QUAT 2032 2033 -0.612247 4.94582 -0.295379 -0.0191061 0.0622787 0.0100276 0.997826 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.83 -4.09246 507.124 3984.34 0.826191 4062.89 +EDGE_SE3:QUAT 2033 2034 -0.488837 5.04834 0.141735 0.0200377 0.136439 -0.0460136 0.989376 1 3.00927e-21 3.00927e-21 3.56751e-09 -1.51974e-10 4.96362e-10 1 3.00927e-21 3.56751e-09 -1.51974e-10 4.96362e-10 1 3.56751e-09 -1.51974e-10 4.96362e-10 4318.3 -8.65894 1175.56 3924.76 -22.5962 4311.43 +EDGE_SE3:QUAT 2034 2035 -0.595108 5.10751 -0.18775 0.0334141 -0.147792 0.00682579 0.98843 1 4.70198e-23 4.70198e-23 -6.70853e-11 1.49007e-11 4.48294e-10 1 4.70198e-23 -6.70853e-11 1.49007e-11 4.48294e-10 1 -6.70853e-11 1.49007e-11 4.48294e-10 4369.86 -22.4026 -1279.61 3912.89 14.1621 4374.13 +EDGE_SE3:QUAT 2035 2036 -0.460005 4.50576 0.146356 0.131549 0.159658 -0.0973363 0.973514 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4459.38 56.2634 1547.38 3880.09 7.00291 4490.7 +EDGE_SE3:QUAT 2036 2037 -0.397953 5.09103 0.0916136 0.00242181 0.0587207 0.0367984 0.997593 1 4.81482e-20 4.81482e-20 -5.1817e-10 1.38441e-08 -9.39944e-11 1 4.81482e-20 -5.1817e-10 1.38441e-08 -9.39944e-11 1 -5.1817e-10 1.38441e-08 -9.39944e-11 4055.23 3.67068 473.375 3986.45 9.21499 4049.84 +EDGE_SE3:QUAT 2037 2038 -0.362014 4.60599 -0.221058 -0.0853793 -0.00260835 0.0829299 0.992888 1 3.85938e-19 3.85938e-19 -2.73836e-08 -2.90744e-09 2.73879e-08 1 3.85938e-19 -2.73836e-08 -2.90744e-09 2.73879e-08 1 -2.73836e-08 -2.90744e-09 2.73879e-08 3971.66 -3.87624 63.7505 3999.47 3.76149 3973.31 +EDGE_SE3:QUAT 2038 2039 -0.226644 4.69146 0.224892 -0.0192185 -0.121158 0.0346887 0.991841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4238.54 24.0665 -1008.8 3943.61 -27.292 4235.2 +EDGE_SE3:QUAT 2039 2040 -0.375016 5.0375 -0.449004 -0.0100455 -0.00966735 0.0684735 0.997556 1 1.98612e-19 1.98612e-19 3.45093e-09 4.01215e-09 -2.76812e-08 1 1.98612e-19 3.45093e-09 4.01215e-09 -2.76812e-08 1 3.45093e-09 4.01215e-09 -2.76812e-08 4000.77 0.457915 -68.5715 3999.74 -2.26788 3982.42 +EDGE_SE3:QUAT 2040 2041 -0.301962 4.30213 0.229257 0.0715801 -0.0527914 0.0627305 0.994059 1 2.40741e-19 2.40741e-19 -2.86346e-08 -6.28736e-10 1.55926e-08 1 2.40741e-19 -2.86346e-08 -6.28736e-10 1.55926e-08 1 -2.86346e-08 -6.28736e-10 1.55926e-08 4035.4 -13.123 -476.364 3985.56 -10.1564 4040.16 +EDGE_SE3:QUAT 2041 2042 -0.429543 4.4763 -0.076726 -0.00390451 0.0138089 0.0172113 0.999749 1 1.88079e-22 1.88079e-22 -8.67479e-10 -1.48459e-11 -1.20911e-11 1 1.88079e-22 -8.67479e-10 -1.48459e-11 -1.20911e-11 1 -8.67479e-10 -1.48459e-11 -1.20911e-11 4003.03 -0.138526 111.301 3999.22 0.943843 4001.91 +EDGE_SE3:QUAT 2042 2043 -0.633924 5.08509 -0.0579105 0.141055 0.0464438 0.171117 0.973994 1 7.70372e-19 7.70372e-19 5.4055e-08 9.84686e-09 -2.97134e-10 1 7.70372e-19 5.4055e-08 9.84686e-09 -2.97134e-10 1 5.4055e-08 9.84686e-09 -2.97134e-10 3918.65 -1.95005 63.5099 4000.27 -2.76769 3881.12 +EDGE_SE3:QUAT 2043 2044 -0.264901 4.73041 0.165629 -0.061372 0.132698 0.0949289 0.984689 1 1.01111e-18 1.01111e-18 1.46515e-08 -5.24934e-08 -2.845e-08 1 1.01111e-18 1.46515e-08 -5.24934e-08 -2.845e-08 1 1.46515e-08 -5.24934e-08 -2.845e-08 4314.09 3.26628 1193.78 3922.5 37.9869 4293.11 +EDGE_SE3:QUAT 2044 2045 -0.488445 4.98142 -0.0260727 0.018031 -0.0355011 0.063236 0.997204 1 1.20371e-20 1.20371e-20 -6.93855e-09 -4.31951e-10 2.60759e-10 1 1.20371e-20 -6.93855e-09 -4.31951e-10 2.60759e-10 1 -6.93855e-09 -4.31951e-10 2.60759e-10 4020.67 -0.696579 -297.281 3994.47 -9.06934 4005.98 +EDGE_SE3:QUAT 2045 2046 -0.0332552 4.71791 -0.191801 0.132596 -0.0450238 0.0540805 0.988669 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.21 -27.9416 -439.122 3987.56 -3.97637 4035.84 +EDGE_SE3:QUAT 2046 2047 -0.355465 4.70038 0.0766699 -0.0709493 -0.165917 0.102736 0.978204 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4366.28 123.523 -1303.14 3928.81 -128.707 4344.19 +EDGE_SE3:QUAT 2047 2048 -0.468745 4.67045 -0.0141242 -0.0583407 -0.00448899 -0.0227833 0.998027 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.04 1.63945 -51.6181 3999.8 0.597254 3998.58 +EDGE_SE3:QUAT 2048 2049 -0.448241 4.63612 -0.312095 0.139785 -0.124487 0.0400311 0.981509 1 1.20371e-20 1.20371e-20 9.37983e-10 -9.6178e-10 -7.0503e-09 1 1.20371e-20 9.37983e-10 -9.6178e-10 -7.0503e-09 1 9.37983e-10 -9.6178e-10 -7.0503e-09 4202.65 -73.7231 -1096.4 3936.71 34.3 4274.4 +EDGE_SE3:QUAT 2049 2050 -0.346878 4.63548 -0.177984 -0.0320309 -0.0494992 0.149127 0.987059 1 9.62965e-20 9.62965e-20 1.16275e-08 1.58162e-08 1.04605e-10 1 9.62965e-20 1.16275e-08 1.58162e-08 1.04605e-10 1 1.16275e-08 1.58162e-08 1.04605e-10 4022.31 11.6034 -327.309 3995.12 -24.5679 3937.46 +EDGE_SE3:QUAT 2050 2051 -0.539687 4.67281 0.174035 0.0783081 -0.0916666 0.0512847 0.99138 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4129.01 -22.9796 -798.643 3962.31 -4.77147 4143.02 +EDGE_SE3:QUAT 2051 2052 -0.105522 4.69273 -0.0449966 0.0342909 0.000207968 0.0513224 0.998093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.38 -0.449489 -19.4112 3999.96 -0.676121 3989.55 +EDGE_SE3:QUAT 2052 2053 -0.651872 4.5253 -0.25097 -0.0495961 -0.118981 0.0903524 0.987532 1 2.40741e-19 2.40741e-19 1.11555e-08 2.88568e-08 4.70624e-10 1 2.40741e-19 1.11555e-08 2.88568e-08 4.70624e-10 1 1.11555e-08 2.88568e-08 4.70624e-10 4191.25 54.565 -919.606 3957.66 -62.2937 4168.43 +EDGE_SE3:QUAT 2053 2054 -0.593286 4.11447 0.111667 0.145375 -0.0056088 0.147763 0.978264 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3935.48 -24.467 -293.951 3991.53 -24.9733 3932.68 +EDGE_SE3:QUAT 2054 2055 -0.726299 4.60703 -0.380189 0.0318145 0.166056 -0.0246384 0.985295 1 1.20371e-19 1.20371e-19 2.04939e-08 -5.15401e-10 -3.55529e-09 1 1.20371e-19 2.04939e-08 -5.15401e-10 -3.55529e-09 1 2.04939e-08 -5.15401e-10 -3.55529e-09 4481.91 11.6558 1476.47 3888.59 0.740007 4483.53 +EDGE_SE3:QUAT 2055 2056 -0.0454381 4.12006 0.0618858 0.0151681 0.0292436 0.0983288 0.994609 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.39 3.33281 213.186 3997.49 10.4865 3972.64 +EDGE_SE3:QUAT 2056 2057 -0.261799 4.47616 -0.0383785 0.153842 -0.0564275 -0.238006 0.957341 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3899.17 13.8891 18.9896 3998.28 -21.7913 3767.25 +EDGE_SE3:QUAT 2057 2058 -0.398505 4.46353 0.112294 0.0443169 -0.1765 0.194704 0.963833 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4561.24 130.607 -1612.67 3892.39 -173.362 4417.46 +EDGE_SE3:QUAT 2058 2059 -0.591584 4.47887 0.0735157 -0.0419312 0.0495372 0.167749 0.983691 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4046.81 2.40637 467.45 3986.72 39.0847 3941.28 +EDGE_SE3:QUAT 2059 2060 -0.226248 4.17175 -0.01517 0.0200162 -0.00428768 -0.0667278 0.997561 1 1.20371e-20 1.20371e-20 6.92204e-09 -4.6385e-10 -1.09718e-11 1 1.20371e-20 6.92204e-09 -4.6385e-10 -1.09718e-11 1 6.92204e-09 -4.6385e-10 -1.09718e-11 3998.47 -0.138318 -18.076 3999.99 0.425618 3982.26 +EDGE_SE3:QUAT 2060 2061 -0.349863 4.58082 -0.449287 -0.0411339 0.0276595 0.0479706 0.997618 1 4.81482e-20 4.81482e-20 1.38705e-08 6.34186e-10 4.36363e-10 1 4.81482e-20 1.38705e-08 6.34186e-10 4.36363e-10 1 1.38705e-08 6.34186e-10 4.36363e-10 4008.1 -4.19482 244.414 3996.11 5.2103 4005.66 +EDGE_SE3:QUAT 2061 2062 -0.210403 4.51139 -0.119883 0.0824019 0.0771549 -0.0212306 0.993381 1 3.00927e-21 3.00927e-21 2.79552e-10 2.81254e-10 3.49031e-09 1 3.00927e-21 2.79552e-10 2.81254e-10 3.49031e-09 1 2.79552e-10 2.81254e-10 3.49031e-09 4074.51 25.2849 645.786 3975.32 5.27293 4099.87 +EDGE_SE3:QUAT 2062 2063 -0.177129 4.31979 0.183852 -0.168766 -0.0481879 0.152586 0.972581 1 1.20371e-20 1.20371e-20 -1.10922e-09 6.74053e-09 1.21685e-09 1 1.20371e-20 -1.10922e-09 6.74053e-09 1.21685e-09 1 -1.10922e-09 6.74053e-09 1.21685e-09 3883.73 -3.89457 -56.6916 4000.2 3.34427 3904.53 +EDGE_SE3:QUAT 2063 2064 -0.562568 4.46329 -0.00734404 0.00331418 0.120057 0.139083 0.982971 1 2.40741e-19 2.40741e-19 -1.00311e-08 -2.93182e-08 -6.02797e-10 1 2.40741e-19 -1.00311e-08 -2.93182e-08 -6.02797e-10 1 -1.00311e-08 -2.93182e-08 -6.02797e-10 4223.37 51.001 971.609 3952.96 78.1215 4146.04 +EDGE_SE3:QUAT 2064 2065 -0.339911 4.32828 -0.19689 -0.00826739 -0.0352848 0.00716342 0.999317 1 3.00927e-21 3.00927e-21 -3.47569e-09 -2.70063e-11 1.2228e-10 1 3.00927e-21 -3.47569e-09 -2.70063e-11 1.2228e-10 1 -3.47569e-09 -2.70063e-11 1.2228e-10 4019.61 1.3974 -282.739 3995.06 -1.27248 4019.68 +EDGE_SE3:QUAT 2065 2066 -0.116889 4.56857 -0.0998058 -0.0673928 -0.0988076 0.00407514 0.992814 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4139.04 30.9249 -808.446 3962.94 -18.1125 4157.14 +EDGE_SE3:QUAT 2066 2067 -0.926765 4.39211 -0.118718 0.125805 -0.11431 0.0747912 0.982605 1 4.33334e-19 4.33334e-19 2.7591e-08 -2.44322e-08 1.34785e-08 1 4.33334e-19 2.7591e-08 -2.44322e-08 1.34785e-08 1 2.7591e-08 -2.44322e-08 1.34785e-08 4199.18 -49.4541 -1057.96 3937.27 2.58814 4240.12 +EDGE_SE3:QUAT 2067 2068 -0.688404 4.17061 0.118371 -0.0869662 0.138903 0.00820241 0.986446 1 1.92593e-19 1.92593e-19 -2.84784e-08 4.73162e-10 -3.98951e-09 1 1.92593e-19 -2.84784e-08 4.73162e-10 -3.98951e-09 1 -2.84784e-08 4.73162e-10 -3.98951e-09 4294.75 -58.0102 1185.62 3926.27 -38.3479 4324.74 +EDGE_SE3:QUAT 2068 2069 -0.385736 4.14732 0.0712004 -0.0940848 -0.0363946 0.15843 0.982203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3966.08 2.9475 -101.289 4000.17 -3.65089 3901.09 +EDGE_SE3:QUAT 2069 2070 -0.103708 4.62968 -0.00702797 -0.0441204 -0.077648 -0.0977792 0.991193 1 3.85186e-19 3.85186e-19 -1.68923e-10 -2.67222e-08 -2.8692e-08 1 3.85186e-19 -1.68923e-10 -2.67222e-08 -2.8692e-08 1 -1.68923e-10 -2.67222e-08 -2.8692e-08 4104.29 0.055887 -678.952 3972.37 28.8389 4073.83 +EDGE_SE3:QUAT 2070 2071 -0.456154 4.45098 -0.210239 -0.0148483 -0.0492678 -0.0879881 0.994792 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4040.47 -2.29555 -408.798 3989.86 17.7071 4010.38 +EDGE_SE3:QUAT 2071 2072 -0.0968636 4.22238 0.157437 0.0790085 -0.143953 0.00475945 0.986414 1 7.52316e-22 7.52316e-22 -2.58486e-10 1.46593e-10 1.78476e-09 1 7.52316e-22 -2.58486e-10 1.46593e-10 1.78476e-09 1 -2.58486e-10 1.46593e-10 1.78476e-09 4324.26 -56.8084 -1232.44 3920.83 39.7028 4349.13 +EDGE_SE3:QUAT 2072 2073 -0.580019 4.21498 0.0174657 -0.0556391 -0.120908 0.105729 0.985448 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4185.02 62.0536 -911.138 3960.49 -71.2078 4152.69 +EDGE_SE3:QUAT 2073 2074 -0.785883 4.46647 0.0939115 0.0594047 -0.0287884 0.150348 0.986427 1 4.81482e-20 4.81482e-20 -1.37362e-08 -2.0363e-09 6.25995e-10 1 4.81482e-20 -1.37362e-08 -2.0363e-09 6.25995e-10 1 -1.37362e-08 -2.0363e-09 6.25995e-10 4012.55 -5.50386 -328.901 3992.44 -25.4056 3936.25 +EDGE_SE3:QUAT 2074 2075 -0.274338 4.50722 -0.0717351 0.216172 -0.03765 0.0576278 0.973926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3858.21 -48.4391 -428.38 3988.19 -0.572423 4031.85 +EDGE_SE3:QUAT 2075 2076 -0.628267 4.26676 -0.331736 0.137129 0.115542 0.0442399 0.982796 1 3.08149e-18 3.08149e-18 -1.11508e-07 -8.58103e-09 -1.11437e-08 1 3.08149e-18 -1.11508e-07 -8.58103e-09 -1.11437e-08 1 -1.11508e-07 -8.58103e-09 -1.11437e-08 4098.16 76.0777 851.835 3967.04 59.5769 4165.55 +EDGE_SE3:QUAT 2076 2077 -0.578319 4.02785 0.106668 -0.0268708 -0.103457 0.0858967 0.990554 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4157.38 33.6054 -816.712 3964.19 -45.0948 4130.75 +EDGE_SE3:QUAT 2077 2078 -0.534149 4.20771 -0.167759 -0.0167247 -0.0268312 0.0397939 0.998708 1 6.01853e-20 6.01853e-20 7.2921e-09 5.44642e-10 -1.40548e-08 1 6.01853e-20 7.2921e-09 5.44642e-10 -1.40548e-08 1 7.2921e-09 5.44642e-10 -1.40548e-08 4009.51 2.36376 -206.536 3997.44 -4.35451 4004.3 +EDGE_SE3:QUAT 2078 2079 -0.384234 3.92099 -0.297021 -0.062989 -0.0318176 0.253114 0.964859 1 3.27709e-18 3.27709e-18 2.80339e-08 -4.09196e-09 1.06958e-07 1 3.27709e-18 2.80339e-08 -4.09196e-09 1.06958e-07 1 2.80339e-08 -4.09196e-09 1.06958e-07 3983.37 -0.0859295 -46.1032 4000.2 3.17788 3742.97 +EDGE_SE3:QUAT 2079 2080 -0.356101 4.46646 -0.184093 -0.046133 0.0400912 -0.0584446 0.996418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.93 -8.35286 286.967 3995.45 -9.67237 4006.78 +EDGE_SE3:QUAT 2080 2081 -0.316769 3.86122 0.0294391 -0.0509713 0.0213061 0.000192793 0.998473 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.83 -4.35083 170.171 3998.22 -0.53802 4007.23 +EDGE_SE3:QUAT 2081 2082 -0.301788 3.88378 0.178263 -0.0693705 0.124323 -0.111395 0.983526 1 1.92593e-19 1.92593e-19 2.79761e-08 -3.72862e-09 2.95853e-09 1 1.92593e-19 2.79761e-08 -3.72862e-09 2.95853e-09 1 2.79761e-08 -3.72862e-09 2.95853e-09 4177.66 -71.1261 910.502 3962.83 -78.4691 4147.28 +EDGE_SE3:QUAT 2082 2083 -0.099888 4.30842 0.36087 -0.002905 -0.0195372 -0.0135177 0.999714 1 1.88079e-22 1.88079e-22 -8.67779e-10 1.16439e-11 1.70206e-11 1 1.88079e-22 -8.67779e-10 1.16439e-11 1.70206e-11 1 -8.67779e-10 1.16439e-11 1.70206e-11 4006.11 0.104469 -156.935 3998.46 1.03915 4005.42 +EDGE_SE3:QUAT 2083 2084 -0.334363 3.77365 0.150399 -0.102725 -0.0602253 0.161422 0.979675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.15 15.6569 -260.851 3999.13 -19.1174 3911.13 +EDGE_SE3:QUAT 2084 2085 -0.0365635 4.04959 -0.087661 0.192621 -0.00522139 0.0393262 0.980471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3855.51 -15.0105 -128.067 3998.55 -2.22815 3997.74 +EDGE_SE3:QUAT 2085 2086 -0.902053 4.1912 -0.0343281 0.047261 -0.192016 0.115533 0.973421 1 2.0463e-19 2.0463e-19 -1.3272e-08 -7.01309e-10 3.07918e-08 1 2.0463e-19 -1.3272e-08 -7.01309e-10 3.07918e-08 1 -1.3272e-08 -7.01309e-10 3.07918e-08 4687.22 68.6088 -1808.11 3851.36 -95.8448 4642.76 +EDGE_SE3:QUAT 2086 2087 -0.396209 3.68365 0.0497004 0.0111281 -0.133329 -0.0305134 0.99054 1 4.81482e-20 4.81482e-20 1.9034e-09 -2.85835e-10 -1.4248e-08 1 4.81482e-20 1.9034e-09 -2.85835e-10 -1.4248e-08 1 1.9034e-09 -2.85835e-10 -1.4248e-08 4296.29 -21.544 -1129.26 3930.45 25.5881 4293.06 +EDGE_SE3:QUAT 2087 2088 -0.502048 4.19604 -0.0222424 -0.0205009 -0.0687718 -0.0603877 0.995592 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.41 -1.06679 -571.655 3980.28 15.7964 4065.5 +EDGE_SE3:QUAT 2088 2089 -0.0937345 4.00974 0.293694 -0.0103362 -0.043721 0.129346 0.990581 1 4.81482e-20 4.81482e-20 1.81348e-09 -1.37447e-08 -2.9517e-10 1 4.81482e-20 1.81348e-09 -1.37447e-08 -2.9517e-10 1 1.81348e-09 -1.37447e-08 -2.9517e-10 4026.08 7.06446 -326.886 3994.23 -21.4294 3959.59 +EDGE_SE3:QUAT 2089 2090 -0.319452 4.37153 0.459171 0.0276191 0.0246791 0.0319532 0.998803 1 4.81482e-20 4.81482e-20 -3.17103e-10 -4.05287e-10 -1.38762e-08 1 4.81482e-20 -3.17103e-10 -4.05287e-10 -1.38762e-08 1 -3.17103e-10 -4.05287e-10 -1.38762e-08 4005.64 2.97051 186.663 3997.93 3.31127 4004.6 +EDGE_SE3:QUAT 2090 2091 -0.106242 4.22043 0.179087 0.0796009 0.0139656 -0.0916458 0.992507 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.1 7.89107 196.435 3996.95 -9.39323 3975.85 +EDGE_SE3:QUAT 2091 2092 -0.677371 3.90772 0.285786 0.0181872 -0.0383198 0.0728384 0.996441 1 1.95602e-19 1.95602e-19 -2.33945e-09 -5.96497e-10 -2.76049e-08 1 1.95602e-19 -2.33945e-09 -5.96497e-10 -2.76049e-08 1 -2.33945e-09 -5.96497e-10 -2.76049e-08 4024.38 -0.241284 -321.669 3993.56 -11.376 4004.48 +EDGE_SE3:QUAT 2092 2093 -0.346067 3.99858 -0.184731 -0.0375464 0.0707718 -0.111688 0.990509 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4058.43 -21.1839 510.881 3986.62 -32.5817 4014.17 +EDGE_SE3:QUAT 2093 2094 -0.56905 4.0316 0.0427997 -0.0103227 0.0965514 0.0507097 0.993982 1 7.52316e-22 7.52316e-22 -1.75741e-09 -8.77809e-11 -1.71669e-10 1 7.52316e-22 -1.75741e-09 -8.77809e-11 -1.71669e-10 1 -1.75741e-09 -8.77809e-11 -1.71669e-10 4154.36 7.41662 801.93 3962.67 19.9464 4144.5 +EDGE_SE3:QUAT 2094 2095 0.0633094 4.24473 0.0139966 0.186532 0.0239919 0.0894463 0.978074 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3859.68 -7.99235 -14.8505 3999.57 -3.81276 3966.86 +EDGE_SE3:QUAT 2095 2096 -0.319503 4.11927 -0.320304 -0.00361049 -0.0567122 0.0325812 0.997852 1 4.81482e-20 4.81482e-20 -7.87068e-10 -1.02482e-10 1.39369e-08 1 4.81482e-20 -7.87068e-10 -1.02482e-10 1.39369e-08 1 -7.87068e-10 -1.02482e-10 1.39369e-08 4051.41 3.38758 -456.62 3987.36 -7.9589 4047.22 +EDGE_SE3:QUAT 2096 2097 -0.757715 3.4476 0.100318 -0.0516623 -0.005884 0.163092 0.98524 1 7.70372e-19 7.70372e-19 6.14167e-10 -2.82031e-09 5.4695e-08 1 7.70372e-19 6.14167e-10 -2.82031e-09 5.4695e-08 1 6.14167e-10 -2.82031e-09 5.4695e-08 3989.78 -2.23072 54.1203 3999.51 7.20037 3894.06 +EDGE_SE3:QUAT 2097 2098 -0.430052 3.98667 -0.0406122 0.0262943 0.0368266 0.144656 0.988447 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.56 6.45479 240.709 3997.33 16.9105 3930.62 +EDGE_SE3:QUAT 2098 2099 -0.325357 4.17826 0.112054 0.210382 0.0819518 -0.141722 0.963814 1 7.70372e-19 7.70372e-19 5.51227e-08 -5.59056e-09 7.44567e-09 1 7.70372e-19 5.51227e-08 -5.59056e-09 7.44567e-09 1 5.51227e-08 -5.59056e-09 7.44567e-09 4054.82 82.1741 993.198 3940.09 -18.586 4151.52 +EDGE_SE3:QUAT 2099 2100 -0.161411 4.07766 -0.102812 0.185752 0.0162777 0.0689313 0.980041 1 7.7056e-19 7.7056e-19 -5.43388e-08 -4.74152e-09 7.22515e-10 1 7.7056e-19 -5.43388e-08 -4.74152e-09 7.22515e-10 1 -5.43388e-08 -4.74152e-09 7.22515e-10 3861.49 -7.51614 -27.0234 3999.6 -2.80506 3980.49 +EDGE_SE3:QUAT 2100 2101 -0.238117 3.95365 -0.120235 0.02538 -0.0695313 0.126853 0.989156 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4083.17 8.26953 -591.902 3979.61 -36.8602 4021.38 +EDGE_SE3:QUAT 2101 2102 -0.126467 3.96132 -0.0482152 -0.0694178 0.212391 0.110024 0.968486 1 1.92593e-19 1.92593e-19 -2.97886e-08 -2.7284e-09 -6.81491e-09 1 1.92593e-19 -2.97886e-08 -2.7284e-09 -6.81491e-09 1 -2.97886e-08 -2.7284e-09 -6.81491e-09 4880.21 49.8405 2099.31 3810.34 75.0712 4851.06 +EDGE_SE3:QUAT 2102 2103 -0.386396 3.41937 -0.442195 -0.0616218 0.0153527 0.133809 0.98897 1 8.30557e-19 8.30557e-19 1.29304e-08 -1.9646e-09 -5.49332e-08 1 8.30557e-19 1.29304e-08 -1.9646e-09 -5.49332e-08 1 1.29304e-08 -1.9646e-09 -5.49332e-08 3996.34 -5.74993 217.023 3996.33 15.8171 3939.91 +EDGE_SE3:QUAT 2103 2104 -0.380467 3.61486 -0.308789 -0.0163183 0.0253181 0.134658 0.990434 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.4 0.547481 223.682 3996.91 15.3457 3939.93 +EDGE_SE3:QUAT 2104 2105 -0.375304 4.15087 0.0954699 0.0541448 0.16627 0.108406 0.978607 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4390.71 117.282 1331.95 3923.54 126.361 4355.43 +EDGE_SE3:QUAT 2105 2106 -0.184455 3.39995 0.0275821 -0.12573 -0.0918056 -0.004587 0.987797 1 7.52316e-22 7.52316e-22 -1.58798e-10 -2.24121e-10 1.74254e-09 1 7.52316e-22 -1.58798e-10 -2.24121e-10 1.74254e-09 1 -1.58798e-10 -2.24121e-10 1.74254e-09 4071.04 49.8498 -745.114 3969.87 -24.2495 4134.19 +EDGE_SE3:QUAT 2106 2107 -0.264069 3.81768 0.0205356 -9.82928e-05 0.109565 0.114676 0.987342 1 1.92593e-19 1.92593e-19 3.03055e-09 7.19677e-10 2.806e-08 1 1.92593e-19 3.03055e-09 7.19677e-10 2.806e-08 1 3.03055e-09 7.19677e-10 2.806e-08 4191.08 34.0987 894.97 3957.38 57.4441 4138.48 +EDGE_SE3:QUAT 2107 2108 -0.245812 4.00972 0.353175 0.010338 0.00329527 -0.00737272 0.999914 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.76 0.140521 27.2714 3999.95 -0.0988195 3999.97 +EDGE_SE3:QUAT 2108 2109 -0.377167 3.82787 -0.118463 0.0942151 -0.0831711 0.313674 0.941177 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4174.4 41.419 -940.617 3957.54 -149.614 3816.34 +EDGE_SE3:QUAT 2109 2110 -0.365496 3.52979 -0.212035 0.153129 0.0814794 0.0152439 0.984723 1 1.20371e-20 1.20371e-20 -5.11611e-10 -1.10587e-09 -6.9126e-09 1 1.20371e-20 -5.11611e-10 -1.10587e-09 -6.9126e-09 1 -5.11611e-10 -1.10587e-09 -6.9126e-09 3997.76 50.8791 612.54 3981.4 27.2346 4090.62 +EDGE_SE3:QUAT 2110 2111 -0.561346 3.71793 0.0447958 0.172157 0.150311 0.107611 0.967568 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4086.88 128.253 938.384 3979.64 120.462 4159.11 +EDGE_SE3:QUAT 2111 2112 -0.434897 3.68097 -0.354742 0.0324665 0.0720389 0.0577626 0.995198 1 4.81482e-20 4.81482e-20 -9.47253e-10 -5.73684e-10 -1.39434e-08 1 4.81482e-20 -9.47253e-10 -5.73684e-10 -1.39434e-08 1 -9.47253e-10 -5.73684e-10 -1.39434e-08 4072.39 16.2651 558.937 3982.18 20.586 4063.26 +EDGE_SE3:QUAT 2112 2113 -0.688321 3.89779 -0.0918913 -0.0554102 0.0605574 0.189681 0.978409 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4073.24 5.14629 591.499 3979.22 55.2195 3941.61 +EDGE_SE3:QUAT 2113 2114 -0.108106 3.79841 0.00719278 -0.0401486 0.162644 0.0695552 0.983411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4470.72 14.0681 1461.64 3890.97 35.8646 4457.82 +EDGE_SE3:QUAT 2114 2115 -0.0366925 3.45727 -0.420383 0.0474148 0.0184692 0.0437142 0.997747 1 4.81482e-20 4.81482e-20 1.3853e-08 6.28852e-10 1.96816e-10 1 4.81482e-20 1.3853e-08 6.28852e-10 1.96816e-10 1 1.3853e-08 6.28852e-10 1.96816e-10 3994.71 2.96743 122.107 3999.22 2.77945 3996.06 +EDGE_SE3:QUAT 2115 2116 -0.0964092 3.38317 0.326344 0.129337 -0.0122768 0.0477714 0.990373 1 7.82409e-19 7.82409e-19 5.4727e-08 9.26535e-09 -2.22243e-09 1 7.82409e-19 5.4727e-08 9.26535e-09 -2.22243e-09 1 5.4727e-08 9.26535e-09 -2.22243e-09 3940.09 -12.0742 -168.943 3997.78 -3.46819 3997.87 +EDGE_SE3:QUAT 2116 2117 -0.189319 3.76125 -0.0701014 -0.297399 0.0252927 0.0408634 0.953543 1 4.81482e-20 4.81482e-20 -6.12152e-10 4.10771e-09 -1.32775e-08 1 4.81482e-20 -6.12152e-10 4.10771e-09 -1.32775e-08 1 -6.12152e-10 4.10771e-09 -1.32775e-08 3670.71 -51.8345 314.778 3994.11 -2.53922 4017.81 +EDGE_SE3:QUAT 2117 2118 -0.173453 3.51692 -0.0928348 0.107074 0.0503842 0.145153 0.982307 1 1.92593e-19 1.92593e-19 -2.72954e-08 -4.25019e-09 -4.54954e-10 1 1.92593e-19 -2.72954e-08 -4.25019e-09 -4.54954e-10 1 -2.72954e-08 -4.25019e-09 -4.54954e-10 3962.9 10.4793 200.579 3999.62 12.1706 3924.48 +EDGE_SE3:QUAT 2118 2119 -0.109659 3.4668 0.0135666 -0.193819 -0.002352 0.165277 0.967012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3877.52 -42.2797 353.274 3986.41 34.564 3918.52 +EDGE_SE3:QUAT 2119 2120 -0.313735 3.64826 0.149527 -0.211031 -0.150669 -0.0120923 0.965722 1 7.70372e-19 7.70372e-19 5.60459e-08 3.06644e-09 -8.23206e-09 1 7.70372e-19 5.60459e-08 3.06644e-09 -8.23206e-09 1 5.60459e-08 3.06644e-09 -8.23206e-09 4176.54 154.444 -1243.63 3938.95 -113.287 4354.1 +EDGE_SE3:QUAT 2120 2121 -0.390136 3.6762 0.0880085 0.144453 0.135446 0.0719875 0.977551 1 1.92593e-19 1.92593e-19 -3.04244e-09 -4.78164e-09 -2.78749e-08 1 1.92593e-19 -3.04244e-09 -4.78164e-09 -2.78749e-08 1 -3.04244e-09 -4.78164e-09 -2.78749e-08 4131.43 102.811 954.59 3964.96 91.2029 4194.17 +EDGE_SE3:QUAT 2121 2122 -0.409919 3.62844 -0.0945332 -0.0868434 -0.0652087 0.0494846 0.992853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.61 24.5192 -467.462 3988.54 -19.0502 4043.98 +EDGE_SE3:QUAT 2122 2123 -0.241155 3.18814 0.00806875 0.0149119 -0.111302 0.257669 0.959685 1 1.20371e-20 1.20371e-20 6.82239e-09 1.85595e-09 -7.37581e-10 1 1.20371e-20 6.82239e-09 1.85595e-09 -7.37581e-10 1 6.82239e-09 1.85595e-09 -7.37581e-10 4184.15 70.3514 -881.152 3971.42 -122.255 3919.47 +EDGE_SE3:QUAT 2123 2124 -0.335992 3.3134 -0.165763 -0.184324 0.132618 0.125338 0.965778 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4296.46 -84.5524 1385.06 3899.79 -6.28529 4369.52 +EDGE_SE3:QUAT 2124 2125 -0.286513 3.43859 -0.000368025 -0.0482793 -0.0444173 0.191349 0.979327 1 8.1852e-19 8.1852e-19 -1.23472e-08 7.09799e-10 -5.41339e-08 1 8.1852e-19 -1.23472e-08 7.09799e-10 -5.41339e-08 1 -1.23472e-08 7.09799e-10 -5.41339e-08 4002.93 9.22693 -226.901 3998.72 -18.9689 3865.8 +EDGE_SE3:QUAT 2125 2126 -0.270229 3.28537 0.106975 -0.0515852 0.0164832 0.0166137 0.998394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.37 -3.62856 141.713 3998.7 0.830705 4003.91 +EDGE_SE3:QUAT 2126 2127 -0.574163 3.64052 0.0866071 -0.0469353 -0.0603629 -0.140776 0.987084 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4066.72 -1.32273 -555.027 3981.25 37.1934 3996.26 +EDGE_SE3:QUAT 2127 2128 -0.414905 3.86024 0.193769 0.0652025 -0.0665411 0.0232713 0.995379 1 1.92593e-19 1.92593e-19 -2.78891e-08 -4.0818e-10 1.93214e-09 1 1.92593e-19 -2.78891e-08 -4.0818e-10 1.93214e-09 1 -2.78891e-08 -4.0818e-10 1.93214e-09 4058.82 -16.5156 -555.932 3981.28 0.569688 4073.66 +EDGE_SE3:QUAT 2128 2129 -0.557174 3.37518 0.0397097 0.0691004 -0.0195862 0.267693 0.960824 1 4.81482e-20 4.81482e-20 -1.33884e-08 -3.66382e-09 7.27404e-10 1 4.81482e-20 -1.33884e-08 -3.66382e-09 7.27404e-10 1 -1.33884e-08 -3.66382e-09 7.27404e-10 4011.09 -4.68181 -352.659 3990.68 -54.2898 3743.55 +EDGE_SE3:QUAT 2129 2130 -0.432252 2.91376 -0.0480256 -0.00373974 -0.152581 -0.0974188 0.983471 1 7.70372e-19 7.70372e-19 -5.60504e-09 -5.45737e-08 1.48828e-09 1 7.70372e-19 -5.60504e-09 -5.45737e-08 1.48828e-09 1 -5.60504e-09 -5.45737e-08 1.48828e-09 4390.84 -57.2311 -1310.16 3914.04 77.2163 4352.94 +EDGE_SE3:QUAT 2130 2131 -0.163097 3.53353 0.188726 0.114681 0.00260036 0.0727139 0.990734 1 1.92593e-19 1.92593e-19 -2.75029e-08 -1.98179e-09 3.89155e-10 1 1.92593e-19 -2.75029e-08 -1.98179e-09 3.89155e-10 1 -2.75029e-08 -1.98179e-09 3.89155e-10 3948.67 -6.34794 -78.6306 3999.22 -3.94448 3980.13 +EDGE_SE3:QUAT 2131 2132 -0.804683 3.22745 0.0788459 -0.124637 -0.114052 0.0577914 0.98393 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4101.34 71.0153 -826.405 3969.09 -59.3974 4150.12 +EDGE_SE3:QUAT 2132 2133 -0.429896 3.5637 0.0676296 0.0409586 -0.0791911 -0.0473393 0.994892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4086.73 -20.144 -618.544 3978.25 21.2883 4084.47 +EDGE_SE3:QUAT 2133 2134 -0.222613 3.50177 0.0370278 0.264739 0.0552508 0.105638 0.956923 1 3.09352e-18 3.09352e-18 -1.05372e-07 -1.98541e-08 2.72037e-09 1 3.09352e-18 -1.05372e-07 -1.98541e-08 2.72037e-09 1 -1.05372e-07 -1.98541e-08 2.72037e-09 3716.75 -7.10514 70.4396 4000.64 -1.0552 3952.46 +EDGE_SE3:QUAT 2134 2135 -0.183201 3.31434 0.141067 0.00652401 0.21041 0.147584 0.966387 1 4.81482e-20 4.81482e-20 -1.46254e-08 -2.49322e-09 -2.9996e-09 1 4.81482e-20 -1.46254e-08 -2.49322e-09 -2.9996e-09 1 -1.46254e-08 -2.49322e-09 -2.9996e-09 4737.41 192.577 1869.92 3869.01 210.048 4650.45 +EDGE_SE3:QUAT 2135 2136 -0.670734 3.10036 0.0203506 0.0211084 -0.0313362 0.108039 0.993428 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.96 -0.0596213 -274.489 3995.27 -14.834 3972.05 +EDGE_SE3:QUAT 2136 2137 -0.522108 3.44789 -0.0596672 -0.11325 -0.0696686 0.0580294 0.989421 1 3.85186e-19 3.85186e-19 2.56324e-08 2.94693e-08 1.85562e-09 1 3.85186e-19 2.56324e-08 2.94693e-08 1.85562e-09 1 2.56324e-08 2.94693e-08 1.85562e-09 4002.95 31.2638 -470.32 3989.54 -23.5881 4040.78 +EDGE_SE3:QUAT 2137 2138 -0.49509 3.44041 -0.155052 0.0888856 0.0593775 0.193885 0.975183 1 1.92593e-19 1.92593e-19 2.71121e-08 5.61924e-09 5.57261e-10 1 1.92593e-19 2.71121e-08 5.61924e-09 5.57261e-10 1 2.71121e-08 5.61924e-09 5.57261e-10 3981.16 13.6947 241.648 3999.78 18.9826 3862.4 +EDGE_SE3:QUAT 2138 2139 -0.373862 3.47465 0.287701 -0.000826312 0.0651445 -0.126099 0.989876 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.14 -12.8918 514.675 3985.32 -33.6753 4001.54 +EDGE_SE3:QUAT 2139 2140 -0.253798 3.18045 -0.144788 0.15856 -0.0897442 0.189331 0.964862 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4165.89 -34.2429 -1068.76 3931.42 -65.9233 4123.07 +EDGE_SE3:QUAT 2140 2141 -0.503295 3.58012 -0.124427 0.249045 -0.0490533 0.251577 0.933959 1 9.62965e-19 9.62965e-19 5.94025e-08 -1.47446e-08 -3.41573e-09 1 9.62965e-19 5.94025e-08 -1.47446e-08 -3.41573e-09 1 5.94025e-08 -1.47446e-08 -3.41573e-09 4022.87 -93.725 -1087.78 3916.95 -96.3991 4017.8 +EDGE_SE3:QUAT 2141 2142 -0.283363 3.21819 0.0770441 -0.163481 -0.104534 0.14035 0.970901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3953.61 53.8844 -511.552 3996.99 -51.8811 3981.72 +EDGE_SE3:QUAT 2142 2143 -0.816712 2.85166 0.37833 0.0104768 0.0573197 -0.0171681 0.998153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.1 1.14366 465.845 3986.73 -3.29827 4052.36 +EDGE_SE3:QUAT 2143 2144 -0.229557 3.07731 -0.427185 -0.229915 -0.0442473 0.169415 0.95733 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3786.59 -34.8381 130.79 3994.32 25.7602 3883.23 +EDGE_SE3:QUAT 2144 2145 -0.631264 3.09982 0.0221436 0.0914551 -0.0833581 0.060553 0.990465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4100.1 -25.6413 -743.162 3966.82 -6.83278 4118.89 +EDGE_SE3:QUAT 2145 2146 -0.387599 3.38801 -0.102738 0.0735411 -0.125595 0.0477491 0.988199 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4261.29 -27.3003 -1100.82 3932.75 0.696459 4273.8 +EDGE_SE3:QUAT 2146 2147 -0.20444 3.3359 0.0803408 -0.147144 -0.0300865 0.144894 0.977982 1 7.70372e-19 7.70372e-19 7.90436e-10 -8.30065e-09 5.42761e-08 1 7.70372e-19 7.90436e-10 -8.30065e-09 5.42761e-08 1 7.90436e-10 -8.30065e-09 5.42761e-08 3911.59 -8.36548 23.2886 3999.24 8.2371 3914.22 +EDGE_SE3:QUAT 2147 2148 -0.0472333 3.08313 0.153224 0.0408174 0.0145268 0.022448 0.998809 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.08 2.16521 104.914 3999.37 1.3141 4000.73 +EDGE_SE3:QUAT 2148 2149 -0.213464 2.88307 0.0070767 -0.0727769 -0.0663576 0.151411 0.983552 1 4.81482e-20 4.81482e-20 -2.22395e-09 1.36301e-08 1.24531e-09 1 4.81482e-20 -2.22395e-09 1.36301e-08 1.24531e-09 1 -2.22395e-09 1.36301e-08 1.24531e-09 4013.83 22.2421 -380.255 3995.02 -30.5285 3943.31 +EDGE_SE3:QUAT 2149 2150 -0.251825 2.9491 0.0836012 -0.150627 0.0120188 0.133134 0.979511 1 7.70372e-19 7.70372e-19 5.45524e-08 6.88609e-09 2.80521e-09 1 7.70372e-19 5.45524e-08 6.88609e-09 2.80521e-09 1 5.45524e-08 6.88609e-09 2.80521e-09 3934.53 -26.8755 326.755 3990.41 22.8016 3954.39 +EDGE_SE3:QUAT 2150 2151 -0.225437 3.05397 -0.12552 0.103841 0.12695 0.0107587 0.9864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4210.71 66.7993 1039.27 3944.31 48.0268 4253.38 +EDGE_SE3:QUAT 2151 2152 -0.385477 3.01366 0.232475 0.1416 -0.00457964 -0.037087 0.989218 1 8.1852e-19 8.1852e-19 -5.49965e-08 8.30494e-11 -1.40617e-08 1 8.1852e-19 -5.49965e-08 8.30494e-11 -1.40617e-08 1 -5.49965e-08 8.30494e-11 -1.40617e-08 3919.87 3.40055 26.6526 3999.86 -0.884994 3994.57 +EDGE_SE3:QUAT 2152 2153 -0.606383 3.00582 0.428377 0.106406 0.133787 0.175799 0.969471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4105.07 93.2795 799.328 3985.39 101.669 4026.74 +EDGE_SE3:QUAT 2153 2154 0.0353373 3.47188 -0.200009 0.0288275 -0.154697 0.0842756 0.983939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4420.4 30.9822 -1369.1 3903.65 -53.9367 4395.32 +EDGE_SE3:QUAT 2154 2155 -0.175389 3.07071 -0.354497 0.189437 0.0426535 0.114994 0.974203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3855.18 -2.47164 62.9137 4000.26 -0.849062 3945.83 +EDGE_SE3:QUAT 2155 2156 -0.767607 2.98259 0.0811761 0.0059488 0.0398607 0.116491 0.992374 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.07 5.09432 305.652 3994.75 18.013 3968.93 +EDGE_SE3:QUAT 2156 2157 -0.0760964 3.26709 0.199935 -0.0537124 -0.0209365 -0.0340719 0.997755 1 1.08334e-19 1.08334e-19 1.37424e-08 5.75857e-09 1.38851e-08 1 1.08334e-19 1.37424e-08 5.75857e-09 1.38851e-08 1 1.37424e-08 5.75857e-09 1.38851e-08 3997.34 4.85098 -188.774 3997.64 2.66887 4004.23 +EDGE_SE3:QUAT 2157 2158 0.0511815 2.81513 -0.135615 0.0388232 0.0422872 0.0794229 0.995187 1 1.92593e-19 1.92593e-19 9.86825e-10 1.25716e-09 2.7699e-08 1 1.92593e-19 9.86825e-10 1.25716e-09 2.7699e-08 1 9.86825e-10 1.25716e-09 2.7699e-08 4016.11 8.45625 298.791 3995.19 12.8977 3996.91 +EDGE_SE3:QUAT 2158 2159 -0.46141 3.10979 0.0526655 -0.0289476 -0.0232014 0.180162 0.982937 1 4.81482e-20 4.81482e-20 -1.36466e-08 -2.51751e-09 1.58108e-10 1 4.81482e-20 -1.36466e-08 -2.51751e-09 1.58108e-10 1 -1.36466e-08 -2.51751e-09 1.58108e-10 3999.8 2.49313 -115.229 3999.65 -8.43891 3873.32 +EDGE_SE3:QUAT 2159 2160 -0.241161 3.29573 0.0520342 0.0461524 -0.0861712 0.0913799 0.991007 1 4.81482e-20 4.81482e-20 -1.3988e-08 -1.19164e-09 1.31116e-09 1 4.81482e-20 -1.3988e-08 -1.19164e-09 1.31116e-09 1 -1.3988e-08 -1.19164e-09 1.31116e-09 4128.02 -0.505219 -751.608 3966.51 -28.4662 4103.14 +EDGE_SE3:QUAT 2160 2161 -0.0698642 3.37377 0.0613971 0.106146 -0.0253515 0.149133 0.982776 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.4 -17.146 -382.019 3988.71 -28.6884 3946.5 +EDGE_SE3:QUAT 2161 2162 -0.300623 2.69778 -0.438157 0.0337049 0.111314 0.0837333 0.989678 1 3.85186e-19 3.85186e-19 -3.58091e-10 -2.89495e-08 -2.66323e-08 1 3.85186e-19 -3.58091e-10 -2.89495e-08 -2.66323e-08 1 -3.58091e-10 -2.89495e-08 -2.66323e-08 4179.85 40.7808 878.611 3959.31 50.5633 4156.35 +EDGE_SE3:QUAT 2162 2163 -0.23921 3.12208 -0.371392 -0.18935 0.0326108 -0.0742578 0.978554 1 1.92593e-19 1.92593e-19 6.46119e-11 -5.33591e-09 2.71626e-08 1 1.92593e-19 6.46119e-11 -5.33591e-09 2.71626e-08 1 6.46119e-11 -5.33591e-09 2.71626e-08 3857.24 -2.19486 80.5269 4000.2 -1.71456 3978.59 +EDGE_SE3:QUAT 2163 2164 -0.528544 2.99116 0.0149872 0.268715 0.0408297 0.0344966 0.961735 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3718.99 19.1088 185.426 3999.96 7.20743 4003.06 +EDGE_SE3:QUAT 2164 2165 -0.257166 2.99325 -0.167742 -0.147898 0.116651 0.119881 0.974755 1 7.70372e-19 7.70372e-19 4.66045e-09 -5.43179e-08 -6.69617e-09 1 7.70372e-19 4.66045e-09 -5.43179e-08 -6.69617e-09 1 4.66045e-09 -5.43179e-08 -6.69617e-09 4232.31 -50.5956 1176.07 3922.69 17.1433 4262.32 +EDGE_SE3:QUAT 2165 2166 -0.313068 2.99522 0.25705 0.0359292 0.0396275 -0.0214589 0.998338 1 4.81482e-20 4.81482e-20 1.39008e-08 -2.59268e-10 5.7137e-10 1 4.81482e-20 1.39008e-08 -2.59268e-10 5.7137e-10 1 1.39008e-08 -2.59268e-10 5.7137e-10 4021.45 5.1818 327.363 3993.3 -2.17929 4024.77 +EDGE_SE3:QUAT 2166 2167 -0.28803 2.59181 -0.162887 -0.172026 0.0354632 0.128156 0.976076 1 1.01111e-18 1.01111e-18 5.40669e-08 -3.03859e-09 -2.53052e-08 1 1.01111e-18 5.40669e-08 -3.03859e-09 -2.53052e-08 1 5.40669e-08 -3.03859e-09 -2.53052e-08 3949.59 -43.0161 530.338 3979.05 25.4477 4002.26 +EDGE_SE3:QUAT 2167 2168 -0.371923 3.14869 0.119176 0.0394793 -0.156655 0.0252133 0.986542 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4423.58 -17.5501 -1379.86 3900.59 4.55103 4427.27 +EDGE_SE3:QUAT 2168 2169 -0.670635 2.36194 0.115567 0.0277566 0.10486 0.15939 0.981238 1 2.40741e-19 2.40741e-19 9.20164e-09 2.95744e-08 -3.98393e-10 1 2.40741e-19 9.20164e-09 2.95744e-08 -3.98393e-10 1 9.20164e-09 2.95744e-08 -3.98393e-10 4141.69 49.2208 775.679 3972.64 72.6188 4043.15 +EDGE_SE3:QUAT 2169 2170 -0.494935 3.41485 0.0749443 0.0427459 0.0879333 0.00750945 0.99518 1 3.00927e-21 3.00927e-21 -3.0631e-10 -1.57641e-10 -3.50614e-09 1 3.00927e-21 -3.0631e-10 -1.57641e-10 -3.50614e-09 1 -3.0631e-10 -1.57641e-10 -3.50614e-09 4117.16 17.9431 716.492 3970.05 11.035 4124.24 +EDGE_SE3:QUAT 2170 2171 -0.176369 2.60404 0.0784749 0.0130936 -0.341627 0.120751 0.931954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 6667.38 564.114 -4218.2 3639.05 -543.458 6609.74 +EDGE_SE3:QUAT 2171 2172 -0.135942 2.65884 0.186659 0.146248 -0.0951026 0.144994 0.973932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4158.71 -39.2666 -1019.6 3938.2 -38.0612 4160.17 +EDGE_SE3:QUAT 2172 2173 -0.0962886 2.64882 -0.121651 0.0827449 -0.042993 0.0354152 0.995013 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.97 -14.5755 -377.836 3990.96 -2.75564 4030.34 +EDGE_SE3:QUAT 2173 2174 -0.193454 2.86774 0.211209 0.237419 -0.115946 0.000609535 0.964463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.95 -116.205 -884.988 3970.99 72.8222 4186.42 +EDGE_SE3:QUAT 2174 2175 -0.313223 2.67071 0.194469 0.0558045 -0.149761 0.0697741 0.984677 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4396.46 -2.8704 -1342.74 3904.9 -23.5497 4389.45 +EDGE_SE3:QUAT 2175 2176 -0.0639791 2.55696 -0.201048 -0.170474 0.0323282 0.209882 0.962207 1 9.62965e-19 9.62965e-19 -5.93816e-08 1.62536e-08 -1.45991e-09 1 9.62965e-19 -5.93816e-08 1.62536e-08 -1.45991e-09 1 -5.93816e-08 1.62536e-08 -1.45991e-09 3986.19 -43.6223 657.29 3966.26 64.6578 3926.24 +EDGE_SE3:QUAT 2176 2177 -0.43862 2.6519 -0.154647 0.000569676 0.121167 0.133813 0.983571 1 7.82409e-19 7.82409e-19 -1.36803e-08 -2.89472e-09 -5.70171e-08 1 7.82409e-19 -1.36803e-08 -2.89472e-09 -5.70171e-08 1 -1.36803e-08 -2.89472e-09 -5.70171e-08 4231.3 49.1204 989.471 3950.58 76.0215 4159.68 +EDGE_SE3:QUAT 2177 2178 -0.854541 2.69873 0.0913981 0.168866 0.0670633 0.099753 0.978282 1 1.92593e-19 1.92593e-19 -7.94221e-10 -5.00457e-09 -2.72302e-08 1 1.92593e-19 -7.94221e-10 -5.00457e-09 -2.72302e-08 1 -7.94221e-10 -5.00457e-09 -2.72302e-08 3907.84 25.0175 308.409 3998.52 20.1601 3982.1 +EDGE_SE3:QUAT 2178 2179 -0.191954 2.84012 0.273749 0.159574 0.0532351 -0.0822754 0.98231 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.72 42.1483 570.972 3978.76 -8.85237 4052.5 +EDGE_SE3:QUAT 2179 2180 -0.535647 2.77158 -0.225386 -0.0713207 -0.133385 0.0307938 0.988015 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4258.39 59.2333 -1092.21 3938.15 -51.1401 4274.94 +EDGE_SE3:QUAT 2180 2181 -0.157748 2.46767 -0.212002 0.0703619 0.0195598 0.157007 0.984894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.76 -0.816646 19.5695 3999.99 -2.05812 3900.96 +EDGE_SE3:QUAT 2181 2182 -0.588899 2.60973 -0.489634 -0.0302817 0.00434234 0.0972777 0.994787 1 1.20371e-20 1.20371e-20 -6.90374e-09 -6.72088e-10 -7.01864e-11 1 1.20371e-20 -6.90374e-09 -6.72088e-10 -7.01864e-11 1 -6.90374e-09 -6.72088e-10 -7.01864e-11 3997.5 -1.08686 69.325 3999.6 3.89459 3963.32 +EDGE_SE3:QUAT 2182 2183 -0.337335 3.00125 0.0787124 0.078999 -0.143346 0.0656507 0.984328 1 4.81482e-20 4.81482e-20 -2.19519e-09 9.0745e-10 1.43025e-08 1 4.81482e-20 -2.19519e-09 9.0745e-10 1.43025e-08 1 -2.19519e-09 9.0745e-10 1.43025e-08 4356.6 -24.9572 -1293.05 3910.69 -6.36024 4364.32 +EDGE_SE3:QUAT 2183 2184 -0.379877 2.54622 -0.0607461 0.00416218 0.134804 -0.0194988 0.990672 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4307.56 -6.44836 1151.16 3927.36 -11.4166 4306.11 +EDGE_SE3:QUAT 2184 2185 -0.552633 2.66875 -0.0712351 0.0399743 -0.0393854 -0.0474072 0.997298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4014.77 -7.32627 -291.832 3995.12 8.1503 4012.17 +EDGE_SE3:QUAT 2185 2186 -0.35722 2.73987 -0.135254 -0.00961278 -0.019542 0.107927 0.99392 1 3.00927e-21 3.00927e-21 3.45053e-09 3.76182e-10 -5.9081e-11 1 3.00927e-21 3.45053e-09 3.76182e-10 -5.9081e-11 1 3.45053e-09 3.76182e-10 -5.9081e-11 4004.61 1.5096 -141.379 3998.91 -7.45874 3958.39 +EDGE_SE3:QUAT 2186 2187 -0.436362 3.00231 0.0235869 0.0101352 0.182805 0.242916 0.952613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4452.84 202.266 1424.56 3947.7 233.206 4217.22 +EDGE_SE3:QUAT 2187 2188 -0.64568 2.20863 0.0716068 0.162517 -0.00633599 0.118316 0.979566 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3911.78 -26.2471 -273.433 3992.79 -17.6508 3961.43 +EDGE_SE3:QUAT 2188 2189 -0.181762 2.48462 0.140324 -0.13578 0.0997416 0.124513 0.97781 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4167.8 -38.461 1013.07 3939.77 27.7251 4179.53 +EDGE_SE3:QUAT 2189 2190 -0.0864468 2.54365 0.151309 0.169111 0.0586868 -0.0925323 0.979487 1 7.70372e-19 7.70372e-19 5.50742e-08 -3.8458e-09 4.79751e-09 1 7.70372e-19 5.50742e-08 -3.8458e-09 4.79751e-09 1 5.50742e-08 -3.8458e-09 4.79751e-09 3985.94 49.0764 642.837 3973.34 -10.4531 4066.08 +EDGE_SE3:QUAT 2190 2191 -0.160456 2.50473 -0.118847 0.0919255 0.016201 -0.129223 0.987213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.39 11.7108 266.126 3994.23 -18.3509 3950.39 +EDGE_SE3:QUAT 2191 2192 -0.305028 2.26279 -0.0850892 0.0466766 -0.0984449 0.223679 0.968554 1 7.70372e-19 7.70372e-19 -6.18792e-09 -3.77361e-11 5.50748e-08 1 7.70372e-19 -6.18792e-09 -3.77361e-11 5.50748e-08 1 -6.18792e-09 -3.77361e-11 5.50748e-08 4178.48 40.0667 -885.345 3961.49 -99.9204 3987.07 +EDGE_SE3:QUAT 2192 2193 -0.448591 2.68266 -0.366825 -0.20684 -0.108626 -0.147007 0.961149 1 3.27408e-18 3.27408e-18 -1.07063e-07 1.59282e-08 -9.87041e-09 1 3.27408e-18 -1.07063e-07 1.59282e-08 -9.87041e-09 1 -1.07063e-07 1.59282e-08 -9.87041e-09 4180.72 88.3239 -1239.17 3914.53 11.1942 4265.41 +EDGE_SE3:QUAT 2193 2194 -0.516832 2.43954 -0.236686 -0.00899631 0.177712 0.159127 0.97109 1 1.55278e-18 1.55278e-18 8.06246e-09 5.79998e-08 5.59472e-08 1 1.55278e-18 8.06246e-09 5.79998e-08 5.59472e-08 1 8.06246e-09 5.79998e-08 5.59472e-08 4524.81 127.443 1541.87 3899.75 155.891 4423.84 +EDGE_SE3:QUAT 2194 2195 0.0700819 2.23489 0.355385 -0.0254439 0.322932 0.133671 0.936589 1 3.85186e-18 3.85186e-18 -5.59949e-09 -1.08716e-07 -5.76511e-08 1 3.85186e-18 -5.59949e-09 -1.08716e-07 -5.76511e-08 1 -5.59949e-09 -1.08716e-07 -5.76511e-08 6306.02 477.408 3816.53 3665.98 460.652 6237.14 +EDGE_SE3:QUAT 2195 2196 -0.402829 2.53009 -0.126484 -0.0523566 -0.0272423 -0.0107924 0.998198 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.58 5.77153 -224.4 3996.85 0.254298 4012.08 +EDGE_SE3:QUAT 2196 2197 -0.2394 2.45679 -0.105709 -0.0254208 -0.178788 -0.0343754 0.982958 1 8.30557e-19 8.30557e-19 6.12867e-09 5.41658e-08 1.40372e-08 1 8.30557e-19 6.12867e-09 5.41658e-08 1.40372e-08 1 6.12867e-09 5.41658e-08 1.40372e-08 4568.89 -3.54146 -1616.32 3870.9 14.3774 4566.75 +EDGE_SE3:QUAT 2197 2198 -0.164628 2.20385 0.0209477 0.0913499 0.0346339 0.0924519 0.990913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.47 7.46949 169.875 3999.09 7.52829 3972.66 +EDGE_SE3:QUAT 2198 2199 -0.339773 2.20193 -0.124436 0.0315617 -0.0721897 0.056874 0.995268 1 1.20371e-20 1.20371e-20 -6.98378e-09 -3.70422e-10 5.27698e-10 1 1.20371e-20 -6.98378e-09 -3.70422e-10 5.27698e-10 1 -6.98378e-09 -3.70422e-10 5.27698e-10 4086.2 -2.54699 -607.379 3977.66 -14.1693 4077.25 +EDGE_SE3:QUAT 0 50 5.9082 -0.178671 -1.45472 -0.0280926 0.00155925 -0.0508952 0.998308 1 4.81482e-20 4.81482e-20 -1.81246e-11 -3.90042e-10 1.38543e-08 1 4.81482e-20 -1.81246e-11 -3.90042e-10 1.38543e-08 1 -1.81246e-11 -3.90042e-10 1.38543e-08 3996.84 0.146812 -4.70787 3999.99 0.26591 3989.64 +EDGE_SE3:QUAT 1 51 5.84926 -0.0580794 -1.48569 0.115756 -0.148554 0.0489733 0.980884 1 1.92593e-19 1.92593e-19 -2.85982e-08 -4.25538e-10 4.53536e-09 1 1.92593e-19 -2.85982e-08 -4.25538e-10 4.53536e-09 1 -2.85982e-08 -4.25538e-10 4.53536e-09 4354.2 -66.8336 -1340.72 3907.6 31.9581 4398.21 +EDGE_SE3:QUAT 0 51 5.82374 3.36015 -1.61871 -0.139161 0.0455357 0.194393 0.969934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.47 -28.8054 664.288 3968.6 58.3002 3954.78 +EDGE_SE3:QUAT 1 50 6.20676 -2.87686 -1.73334 0.0901879 -0.0211538 -0.0825232 0.992274 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.7 -2.37017 -76.9804 3999.91 2.22068 3973.99 +EDGE_SE3:QUAT 2 52 5.86186 0.142283 -1.2868 -0.042957 -0.0923546 -0.13099 0.986137 1 1.20371e-20 1.20371e-20 6.97984e-09 -8.84359e-10 -7.0908e-10 1 1.20371e-20 6.97984e-09 -8.84359e-10 -7.0908e-10 1 6.97984e-09 -8.84359e-10 -7.0908e-10 4151.66 -11.6978 -813.354 3962.27 49.3405 4090.41 +EDGE_SE3:QUAT 1 52 5.76486 3.01175 -1.33183 0.0455362 0.0252593 0.173743 0.983413 1 7.70372e-19 7.70372e-19 4.46631e-10 2.85759e-09 5.46055e-08 1 7.70372e-19 4.46631e-10 2.85759e-09 5.46055e-08 1 4.46631e-10 2.85759e-09 5.46055e-08 3993.85 2.44824 99.4093 3999.89 5.87988 3881.4 +EDGE_SE3:QUAT 2 51 5.80248 -2.96965 -1.13758 0.0318214 0.287516 0.109028 0.951018 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5543.35 396.628 2930.57 3767.83 394.923 5499.85 +EDGE_SE3:QUAT 3 53 6.20111 -0.266146 -1.26464 0.0214056 0.0534826 -0.0310828 0.997855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.89 2.65179 439.525 3988.1 -5.54722 4043.86 +EDGE_SE3:QUAT 2 53 6.18042 3.18066 -1.28011 -0.11011 0.162909 0.0863818 0.976665 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4478.5 -42.3548 1544.68 3880.14 -1.48176 4497.15 +EDGE_SE3:QUAT 3 52 6.14955 -3.28899 -1.22857 0.293972 -0.0620882 0.0687332 0.951316 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3765.82 -103.519 -677.545 3976.22 19.9311 4092.6 +EDGE_SE3:QUAT 4 54 6.15598 0.0592618 -1.15199 0.0542462 0.0479242 -0.142753 0.987108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.07 2.92224 467.668 3986.06 -32.1827 3972.33 +EDGE_SE3:QUAT 3 54 5.96522 3.19213 -1.22554 -0.0676897 -0.0022727 0.07573 0.994826 1 1.92593e-19 1.92593e-19 2.21315e-10 -1.86678e-09 2.76132e-08 1 1.92593e-19 2.21315e-10 -1.86678e-09 2.76132e-08 1 2.21315e-10 -1.86678e-09 2.76132e-08 3982.04 -2.13533 43.193 3999.75 2.39431 3977.42 +EDGE_SE3:QUAT 4 53 5.81911 -2.80318 -1.29486 0.213628 0.0750983 -0.0833271 0.970453 1 9.62965e-19 9.62965e-19 5.61797e-08 2.44463e-08 1.88958e-10 1 9.62965e-19 5.61797e-08 2.44463e-08 1.88958e-10 1 5.61797e-08 2.44463e-08 1.88958e-10 3967.22 79.6662 789.212 3963.71 7.48014 4122 +EDGE_SE3:QUAT 5 55 6.24699 -0.307229 -1.36078 0.0398909 -0.0489584 -0.219537 0.973558 1 4.81482e-20 4.81482e-20 1.35399e-08 -3.10858e-09 -3.74144e-10 1 4.81482e-20 1.35399e-08 -3.10858e-09 -3.74144e-10 1 1.35399e-08 -3.10858e-09 -3.74144e-10 4010.01 -11.4744 -261.477 3998.41 25.5102 3823.59 +EDGE_SE3:QUAT 4 55 6.01168 3.1031 -1.37019 0.0575187 -0.115649 0.143216 0.981227 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4245.17 20.3674 -1049.07 3940.06 -66.1751 4176.36 +EDGE_SE3:QUAT 5 54 5.78823 -3.13856 -1.45089 -0.00738846 0.0325384 -0.289341 0.956644 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010 -5.97639 204.409 3999.03 -27.0668 3675.35 +EDGE_SE3:QUAT 6 56 6.11371 0.0468313 -1.69972 -0.0501144 -0.0569825 0.156174 0.98481 1 4.81482e-20 4.81482e-20 -1.37186e-08 -2.25556e-09 5.3416e-10 1 4.81482e-20 -1.37186e-08 -2.25556e-09 5.3416e-10 1 -1.37186e-08 -2.25556e-09 5.3416e-10 4019.35 16.1271 -346.776 3995.28 -27.4507 3931.84 +EDGE_SE3:QUAT 5 56 5.82788 3.07155 -1.23931 0.129686 0.0112481 0.0602686 0.989658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3932.48 -2.42749 -5.28509 3999.92 -1.12305 3985.22 +EDGE_SE3:QUAT 6 55 5.8351 -3.19008 -1.1434 -0.0458792 -0.145763 0.164195 0.974519 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4263.92 104.286 -1080.84 3954.78 -123.872 4164.5 +EDGE_SE3:QUAT 7 57 6.15288 -0.105929 -1.50731 -0.00529007 -0.160024 -0.186416 0.969337 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4401.91 -118.362 -1331.02 3927.54 152.675 4263.02 +EDGE_SE3:QUAT 6 57 5.98829 2.93016 -1.63413 0.119061 0.0333817 0.134541 0.983163 1 1.92593e-19 1.92593e-19 2.72879e-08 3.84964e-09 -9.59434e-12 1 1.92593e-19 2.72879e-08 3.84964e-09 -9.59434e-12 1 2.72879e-08 3.84964e-09 -9.59434e-12 3943.21 0.444796 65.8434 4000.16 0.357588 3927.5 +EDGE_SE3:QUAT 7 56 6.108 -3.24328 -1.04652 -0.0267406 -0.0932076 -0.0404709 0.994464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4144.06 2.44219 -780.561 3964.15 11.3869 4140.37 +EDGE_SE3:QUAT 8 58 6.06015 -0.00488526 -1.10105 0.0199551 0.137405 -0.048038 0.989148 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4323.17 -9.94802 1185.13 3923.74 -24.2738 4315.54 +EDGE_SE3:QUAT 7 58 5.81745 3.37316 -1.63412 0.0434292 0.00565366 -0.0534993 0.997607 1 4.81482e-20 4.81482e-20 -1.38468e-08 7.33039e-10 -1.4208e-10 1 4.81482e-20 -1.38468e-08 7.33039e-10 -1.4208e-10 1 -1.38468e-08 7.33039e-10 -1.4208e-10 3993.76 1.69057 72.7251 3999.59 -2.12 3989.85 +EDGE_SE3:QUAT 8 57 5.90852 -3.20362 -1.29525 0.101442 -0.148592 -0.0989119 0.978696 1 1.92593e-19 1.92593e-19 2.81085e-08 -3.78533e-09 -3.48713e-09 1 1.92593e-19 2.81085e-08 -3.78533e-09 -3.48713e-09 1 2.81085e-08 -3.78533e-09 -3.48713e-09 4234.47 -110.047 -1087.83 3952.56 109.638 4236.49 +EDGE_SE3:QUAT 9 59 6.16582 -0.054583 -1.81395 -0.0121018 -0.043353 0.13571 0.989726 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.71 7.34541 -319.38 3994.61 -21.8832 3951.63 +EDGE_SE3:QUAT 8 59 6.3206 3.21671 -1.4316 -0.000455873 -0.125603 -0.134371 0.982938 1 1.20371e-20 1.20371e-20 7.03451e-09 -9.92159e-10 -8.66282e-10 1 1.20371e-20 7.03451e-09 -9.92159e-10 -8.66282e-10 1 7.03451e-09 -9.92159e-10 -8.66282e-10 4250.14 -52.799 -1031.24 3946.75 80.0329 4177.91 +EDGE_SE3:QUAT 9 58 5.97331 -2.99838 -1.59445 0.0857276 0.0776907 0.0558497 0.991714 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4048.21 31.5163 563.139 3983.58 26.701 4065.13 +EDGE_SE3:QUAT 10 60 6.1516 0.164451 -1.48173 0.0262892 -0.147594 0.0406481 0.987863 1 1.20371e-20 1.20371e-20 7.17274e-09 2.50044e-10 -1.0828e-09 1 1.20371e-20 7.17274e-09 2.50044e-10 -1.0828e-09 1 7.17274e-09 2.50044e-10 -1.0828e-09 4376.29 3.05381 -1288.38 3911.53 -16.89 4372.45 +EDGE_SE3:QUAT 9 60 5.88053 3.10462 -1.43224 -0.139415 -0.0347772 -0.089503 0.985567 1 1.92593e-19 1.92593e-19 2.13172e-09 2.73847e-08 3.65326e-09 1 1.92593e-19 2.13172e-09 2.73847e-08 3.65326e-09 1 2.13172e-09 2.73847e-08 3.65326e-09 3965.17 27.9369 -418.475 3987.53 13.2797 4010.87 +EDGE_SE3:QUAT 10 59 5.50713 -3.02982 -1.59368 0.020247 0.0174041 0.055588 0.998097 1 1.20371e-20 1.20371e-20 -6.92908e-09 -3.90697e-10 -1.04367e-10 1 1.20371e-20 -6.92908e-09 -3.90697e-10 -1.04367e-10 1 -6.92908e-09 -3.90697e-10 -1.04367e-10 4002.26 1.56561 125.124 3999.11 3.48061 3991.54 +EDGE_SE3:QUAT 11 61 6.12958 0.105844 -1.36472 0.101897 -0.00740018 0.0311039 0.994281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.74 -5.43462 -95.9985 3999.29 -1.39046 3998.4 +EDGE_SE3:QUAT 10 61 6.08934 3.09731 -1.54237 -0.068661 0.131313 0.0727007 0.986285 1 1.92593e-19 1.92593e-19 -2.84535e-08 -1.62262e-09 -4.00953e-09 1 1.92593e-19 -2.84535e-08 -1.62262e-09 -4.00953e-09 1 -2.84535e-08 -1.62262e-09 -4.00953e-09 4299.84 -13.2398 1173.24 3924.37 18.073 4297.56 +EDGE_SE3:QUAT 11 60 5.78208 -3.33649 -1.83312 0.0826398 -0.143433 -0.0366253 0.985523 1 1.54074e-18 1.54074e-18 -5.34202e-08 5.82133e-08 2.40869e-09 1 1.54074e-18 -5.34202e-08 5.82133e-08 2.40869e-09 1 -5.34202e-08 5.82133e-08 2.40869e-09 4289.9 -76.432 -1170.49 3932.03 67.5601 4311.85 +EDGE_SE3:QUAT 12 62 6.42912 0.192638 -1.49518 -0.0143429 -0.152816 0.181158 0.971403 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4336.46 111.754 -1210.72 3941.3 -140.932 4206.01 +EDGE_SE3:QUAT 11 62 5.93578 3.35674 -1.5333 0.0513706 0.0889078 0.0421561 0.993821 1 4.81482e-20 4.81482e-20 1.17873e-09 8.38685e-10 1.39952e-08 1 4.81482e-20 1.17873e-09 8.38685e-10 1.39952e-08 1 1.17873e-09 8.38685e-10 1.39952e-08 4107.57 26.8343 697.574 3972.76 25.1062 4111.02 +EDGE_SE3:QUAT 12 61 5.39104 -3.29169 -1.73243 0.0580444 0.00660445 -0.0412551 0.997439 1 4.81482e-20 4.81482e-20 -1.38451e-08 5.58239e-10 -1.57062e-10 1 4.81482e-20 -1.38451e-08 5.58239e-10 -1.57062e-10 1 -1.38451e-08 5.58239e-10 -1.57062e-10 3988.15 2.54316 81.1067 3999.49 -1.74719 3994.81 +EDGE_SE3:QUAT 13 63 6.26975 0.0928859 -1.28784 -0.199341 0.0145016 -0.0718205 0.977187 1 9.62965e-19 9.62965e-19 5.38346e-08 -9.51584e-09 2.63017e-08 1 9.62965e-19 5.38346e-08 -9.51584e-09 2.63017e-08 1 5.38346e-08 -9.51584e-09 2.63017e-08 3841.09 11.7893 -58.3826 3999.13 4.2445 3979.4 +EDGE_SE3:QUAT 12 63 6.29747 3.50544 -1.26656 -0.0772761 -0.014336 0.190145 0.978605 1 7.70372e-19 7.70372e-19 -8.6799e-10 4.27567e-09 -5.43246e-08 1 7.70372e-19 -8.6799e-10 4.27567e-09 -5.43246e-08 1 -8.6799e-10 4.27567e-09 -5.43246e-08 3976.28 -4.81615 63.8659 3999.02 11.8857 3855.54 +EDGE_SE3:QUAT 13 62 5.74423 -3.25867 -1.39897 -0.130095 0.00164629 -0.0384792 0.990753 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3932.75 4.32163 -46.5309 3999.73 1.23009 3994.52 +EDGE_SE3:QUAT 14 64 6.01634 0.103873 -2.13039 -0.0589392 0.0920648 -0.00725477 0.993981 1 5.11575e-20 5.11575e-20 -1.37076e-08 4.20046e-11 2.22916e-09 1 5.11575e-20 -1.37076e-08 4.20046e-11 2.22916e-09 1 -1.37076e-08 4.20046e-11 2.22916e-09 4121.71 -25.4487 748.881 3967.79 -15.215 4135.39 +EDGE_SE3:QUAT 13 64 5.89291 3.59089 -1.2203 -0.113638 0.0043952 0.201268 0.972912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.93 -17.7637 298.691 3991.17 36.8329 3858.55 +EDGE_SE3:QUAT 14 63 5.76839 -3.22186 -1.57382 -0.0464181 -0.0931635 -0.195576 0.975149 1 1.20371e-20 1.20371e-20 -6.91339e-09 1.34649e-09 7.35211e-10 1 1.20371e-20 -6.91339e-09 1.34649e-09 7.35211e-10 1 -6.91339e-09 1.34649e-09 7.35211e-10 4160.16 -27.6519 -838.835 3962.91 81.0268 4015.78 +EDGE_SE3:QUAT 15 65 6.26312 -0.177095 -1.93263 0.0178082 0.0534852 0.075722 0.995534 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4040.61 8.61176 411.478 3990.25 16.9244 4018.94 +EDGE_SE3:QUAT 14 65 5.86004 3.56985 -1.40405 -0.0230432 0.0108759 0.0535488 0.99824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.44 -1.03129 101.4 3999.3 2.76376 3991.09 +EDGE_SE3:QUAT 15 64 6.2164 -3.35222 -1.74961 -0.210633 0.0643742 -0.0759798 0.97248 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3841.79 -26.5368 290.592 3999.22 -17.6583 3996.16 +EDGE_SE3:QUAT 16 66 6.03713 -0.0388504 -1.35793 -0.0142854 0.136005 -0.134188 0.981474 1 4.81482e-20 4.81482e-20 1.41004e-08 -2.05681e-09 1.82288e-09 1 4.81482e-20 1.41004e-08 -2.05681e-09 1.82288e-09 1 1.41004e-08 -2.05681e-09 1.82288e-09 4280.13 -69.7035 1097.08 3942.63 -92.8653 4208.92 +EDGE_SE3:QUAT 15 66 6.05592 3.12521 -1.56518 -0.154026 0.0822756 0.0845499 0.980999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.2 -52.221 811.411 3960.53 4.16504 4129.5 +EDGE_SE3:QUAT 16 65 5.95738 -3.46314 -1.67804 0.0131349 0.0679251 -0.223191 0.972317 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.43 -21.7222 545.961 3986.03 -62.2703 3873.86 +EDGE_SE3:QUAT 17 67 5.88055 0.12659 -1.50721 -0.0990026 -0.117409 0.0154964 0.988015 1 2.0463e-19 2.0463e-19 2.8949e-08 1.86872e-09 -1.02244e-08 1 2.0463e-19 2.8949e-08 1.86872e-09 -1.02244e-08 1 2.8949e-08 1.86872e-09 -1.02244e-08 4174.05 58.2587 -948.04 3952.84 -41.5054 4212.3 +EDGE_SE3:QUAT 16 67 5.76368 3.49551 -1.47777 -0.193254 0.0769497 -0.00257341 0.978123 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3934.48 -59.0209 585.758 3983.94 -26.6467 4083.84 +EDGE_SE3:QUAT 17 66 6.01067 -3.56558 -1.43222 -0.136342 0.0540337 -0.0683468 0.986823 1 4.81482e-20 4.81482e-20 1.11936e-09 1.3682e-08 1.98329e-09 1 4.81482e-20 1.11936e-09 1.3682e-08 1.98329e-09 1 1.11936e-09 1.3682e-08 1.98329e-09 3948.69 -21.4603 307.945 3996.5 -15.1099 4004.36 +EDGE_SE3:QUAT 18 68 6.04639 0.0548041 -1.39735 0.209808 0.0861584 0.0151929 0.973821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3916.77 68.7677 617.94 3984.49 37.0895 4091.93 +EDGE_SE3:QUAT 17 68 5.95387 3.2634 -1.38406 -0.0680208 -0.0585609 -0.00320009 0.995959 1 1.88079e-22 1.88079e-22 -5.10499e-11 -5.94892e-11 8.69834e-10 1 1.88079e-22 -5.10499e-11 -5.94892e-11 8.69834e-10 1 -5.10499e-11 -5.94892e-11 8.69834e-10 4036.78 16.4126 -473.501 3986.59 -4.90879 4055.25 +EDGE_SE3:QUAT 18 67 5.77746 -3.45035 -1.50786 -0.166122 -0.0290273 -0.0251196 0.985358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3908.11 23.3568 -272.817 3995.39 -0.762358 4015.98 +EDGE_SE3:QUAT 19 69 6.02638 -0.0212721 -1.89401 -0.0558569 -0.277151 0.0731753 0.956406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5409.46 328.833 -2777.14 3768.67 -328.889 5400.52 +EDGE_SE3:QUAT 18 69 6.32167 3.55617 -1.69916 -0.0778503 0.0132614 -0.0418032 0.996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.8 -2.13694 66.0028 3999.84 -1.26399 3994.05 +EDGE_SE3:QUAT 19 68 5.53908 -3.25194 -1.38661 -0.0181164 -0.0858869 -0.185971 0.978627 1 7.52316e-22 7.52316e-22 -1.72431e-09 3.27114e-10 1.52489e-10 1 7.52316e-22 -1.72431e-09 3.27114e-10 1.52489e-10 1 -1.72431e-09 3.27114e-10 1.52489e-10 4120.9 -28.1417 -709.87 3974.41 68.1089 3983.87 +EDGE_SE3:QUAT 20 70 6.36012 -0.0330515 -1.51587 -0.0983218 -0.0259725 0.0881599 0.990902 1 1.92593e-19 1.92593e-19 -2.18226e-10 -2.81579e-09 2.75105e-08 1 1.92593e-19 -2.18226e-10 -2.81579e-09 2.75105e-08 1 -2.18226e-10 -2.81579e-09 2.75105e-08 3963.46 3.61385 -99.481 3999.84 -3.35021 3971.04 +EDGE_SE3:QUAT 19 70 5.65037 3.30467 -1.26691 -0.0485654 -0.134116 -0.155435 0.977494 1 1.20371e-20 1.20371e-20 7.06815e-09 -1.06716e-09 -1.02933e-09 1 1.20371e-20 7.06815e-09 -1.06716e-09 -1.02933e-09 1 7.06815e-09 -1.06716e-09 -1.02933e-09 4325.77 -44.6701 -1205.48 3926.03 89.4017 4238.56 +EDGE_SE3:QUAT 20 69 5.69719 -3.49446 -1.22827 -0.0138496 0.0376084 -0.120885 0.991857 1 2.0463e-19 2.0463e-19 7.82131e-09 -1.47664e-09 2.78259e-08 1 2.0463e-19 7.82131e-09 -1.47664e-09 2.78259e-08 1 7.82131e-09 -1.47664e-09 2.78259e-08 4018.07 -5.47504 275.359 3995.92 -16.7407 3960.38 +EDGE_SE3:QUAT 21 71 6.30528 0.041472 -1.75558 -0.0459772 -0.0421172 0.00399138 0.998046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.52 8.0035 -335.691 3993.15 -2.62638 4027.91 +EDGE_SE3:QUAT 20 71 6.00137 3.29278 -1.18031 0.0961473 -0.0344996 -0.0931341 0.9904 1 2.0463e-19 2.0463e-19 -2.683e-08 9.59544e-09 -2.70889e-10 1 2.0463e-19 -2.683e-08 9.59544e-09 -2.70889e-10 1 -2.683e-08 9.59544e-09 -2.70889e-10 3969.21 -7.25187 -162.398 3999.25 7.10313 3971.5 +EDGE_SE3:QUAT 21 70 5.67318 -3.40873 -1.3905 0.0294533 -0.102738 -0.331242 0.937473 1 3.27408e-18 3.27408e-18 -2.66238e-09 -3.58519e-08 -1.02814e-07 1 3.27408e-18 -2.66238e-09 -3.58519e-08 -1.02814e-07 1 -2.66238e-09 -3.58519e-08 -1.02814e-07 4077.14 -61.3817 -586.04 4000.75 95.3184 3641.73 +EDGE_SE3:QUAT 22 72 5.85813 0.104987 -1.79557 -0.00957153 -0.0232778 -0.0482199 0.99852 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.78 0.274089 -191.468 3997.7 4.55246 3999.84 +EDGE_SE3:QUAT 21 72 5.96803 3.50693 -1.76956 0.0562979 -0.191417 0.128296 0.971458 1 4.81482e-20 4.81482e-20 -1.46408e-08 -1.73805e-09 3.00005e-09 1 4.81482e-20 -1.46408e-08 -1.73805e-09 3.00005e-09 1 -1.46408e-08 -1.73805e-09 3.00005e-09 4692.22 72.0477 -1821.12 3850.38 -103.312 4639.06 +EDGE_SE3:QUAT 22 71 5.9208 -3.64381 -1.40192 -0.0584181 -0.090832 -0.0444412 0.993158 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4131.76 15.2799 -776.426 3964.31 6.23979 4137.51 +EDGE_SE3:QUAT 23 73 6.33118 0.229992 -1.7806 -0.0955674 -0.0699209 -0.0616116 0.991051 1 1.92593e-19 1.92593e-19 2.7845e-08 -1.34155e-09 -2.24625e-09 1 1.92593e-19 2.7845e-08 -1.34155e-09 -2.24625e-09 1 2.7845e-08 -1.34155e-09 -2.24625e-09 4061.13 24.1988 -632.837 3975.31 7.63519 4082.48 +EDGE_SE3:QUAT 22 73 6.18077 3.28551 -1.4147 -0.289442 -0.188422 0.0431755 0.937473 1 3.08149e-18 3.08149e-18 1.08955e-07 1.71961e-08 -1.48497e-08 1 3.08149e-18 1.08955e-07 1.71961e-08 -1.48497e-08 1 1.08955e-07 1.71961e-08 -1.48497e-08 4009.63 247.588 -1238.22 3996.41 -226.832 4337.28 +EDGE_SE3:QUAT 23 72 5.66633 -3.16554 -1.6011 -0.0185091 -0.0675422 -0.23512 0.96944 1 7.52316e-22 7.52316e-22 -1.69848e-09 4.11409e-10 1.20042e-10 1 7.52316e-22 -1.69848e-09 4.11409e-10 1.20042e-10 1 -1.69848e-09 4.11409e-10 1.20042e-10 4074.33 -22.1614 -555.62 3985.62 66.7619 3854.57 +EDGE_SE3:QUAT 24 74 6.09294 -0.0349642 -1.69755 0.0233016 -0.215852 -0.0849559 0.972444 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4807.19 -149.118 -1973.12 3840.62 156.678 4780.49 +EDGE_SE3:QUAT 23 74 6.30893 3.59436 -1.28052 0.159918 -0.131313 0.234294 0.949889 1 7.70372e-19 7.70372e-19 -1.07051e-08 5.32442e-08 -4.9244e-09 1 7.70372e-19 -1.07051e-08 5.32442e-08 -4.9244e-09 1 -1.07051e-08 5.32442e-08 -4.9244e-09 4417.78 12.8834 -1534.74 3881.41 -121.135 4300.49 +EDGE_SE3:QUAT 24 73 5.71067 -3.51547 -1.82993 -0.083433 -0.0486084 0.177194 0.979428 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3980.27 9.11912 -193.366 3999.75 -13.1779 3882.52 +EDGE_SE3:QUAT 25 75 6.09872 0.128983 -1.52269 -0.0506094 0.172161 0.162653 0.970229 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4546.72 89.8269 1593.14 3884.83 130.252 4451.14 +EDGE_SE3:QUAT 24 75 5.6922 3.50172 -1.36068 -0.0864576 0.026375 0.123451 0.988225 1 1.92593e-19 1.92593e-19 -1.29025e-09 2.15958e-09 -2.75236e-08 1 1.92593e-19 -1.29025e-09 2.15958e-09 -2.75236e-08 1 -1.29025e-09 2.15958e-09 -2.75236e-08 3997.2 -11.9467 332.337 3991.83 20.226 3966.14 +EDGE_SE3:QUAT 25 74 5.83769 -3.47234 -1.45288 0.0635688 -0.0618224 0.00472328 0.99605 1 1.9264e-19 1.9264e-19 2.78873e-08 -1.16355e-10 -2.1673e-09 1 1.9264e-19 2.78873e-08 -1.16355e-10 -2.1673e-09 1 2.78873e-08 -1.16355e-10 -2.1673e-09 4045.85 -16.1621 -501.898 3984.91 4.73032 4061.92 +EDGE_SE3:QUAT 26 76 5.88485 0.233553 -1.68948 0.0381312 0.112756 -0.0415925 0.992019 1 2.40741e-19 2.40741e-19 -1.50787e-08 -2.70603e-08 -8.2555e-10 1 2.40741e-19 -1.50787e-08 -2.70603e-08 -8.2555e-10 1 -1.50787e-08 -2.70603e-08 -8.2555e-10 4213.17 7.04287 961.206 3947.24 -10.1027 4212.07 +EDGE_SE3:QUAT 25 76 5.90321 3.19128 -1.70463 -0.0542466 -0.0464572 0.0504696 0.996169 1 4.81482e-20 4.81482e-20 1.38737e-08 7.71818e-10 -5.63436e-10 1 4.81482e-20 1.38737e-08 7.71818e-10 -5.63436e-10 1 1.38737e-08 7.71818e-10 -5.63436e-10 4016.51 11.2827 -337.748 3993.66 -10.8238 4018.09 +EDGE_SE3:QUAT 26 75 5.66484 -3.13824 -1.5761 0.059367 0.175924 -0.14217 0.972273 1 7.70372e-19 7.70372e-19 7.18809e-09 5.40702e-08 -4.95546e-10 1 7.70372e-19 7.18809e-09 5.40702e-08 -4.95546e-10 1 7.18809e-09 5.40702e-08 -4.95546e-10 4581.4 -67.027 1654.28 3872.39 -105.123 4514.65 +EDGE_SE3:QUAT 27 77 5.97789 -0.334459 -1.70516 -0.139473 -0.0471204 -0.0478266 0.987947 1 4.81482e-20 4.81482e-20 -8.14734e-10 -1.8863e-09 1.37972e-08 1 4.81482e-20 -8.14734e-10 -1.8863e-09 1.37972e-08 1 -8.14734e-10 -1.8863e-09 1.37972e-08 3971.89 30.4156 -449.006 3987.26 1.70891 4040.55 +EDGE_SE3:QUAT 26 77 6.458 3.2759 -1.69365 0.0817446 0.0133888 -0.0395664 0.995778 1 4.81482e-20 4.81482e-20 2.72366e-10 1.11747e-09 1.38282e-08 1 4.81482e-20 2.72366e-10 1.11747e-09 1.38282e-08 1 2.72366e-10 1.11747e-09 1.38282e-08 3978.45 6.15987 144.576 3998.5 -2.54435 3998.92 +EDGE_SE3:QUAT 27 76 5.87035 -3.32793 -1.46186 0.0798342 0.0225389 -0.0605106 0.994715 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.31 9.08789 236.001 3996.08 -6.24886 3999.16 +EDGE_SE3:QUAT 28 78 5.65678 -0.05245 -1.5818 -0.0380245 0.121987 0.0945404 0.987287 1 1.01111e-18 1.01111e-18 1.53937e-08 -5.31502e-08 -2.73219e-08 1 1.01111e-18 1.53937e-08 -5.31502e-08 -2.73219e-08 1 1.53937e-08 -5.31502e-08 -2.73219e-08 4259.29 14.6278 1063.29 3937.68 43.6163 4229.32 +EDGE_SE3:QUAT 27 78 5.96457 3.71438 -2.17053 -0.00391744 -0.0482788 -0.161203 0.985732 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4036.02 -8.19856 -381.7 3992.15 31.0992 3932.14 +EDGE_SE3:QUAT 28 77 5.66496 -3.57243 -1.5916 0.125366 -0.033119 -0.120677 0.984187 1 1.92593e-19 1.92593e-19 -3.50608e-11 3.60099e-09 2.73179e-08 1 1.92593e-19 -3.50608e-11 3.60099e-09 2.73179e-08 1 -3.50608e-11 3.60099e-09 2.73179e-08 3937.48 -1.25709 -74.8454 4000.15 1.25597 3942.1 +EDGE_SE3:QUAT 29 79 6.10762 0.17423 -1.83126 0.0152135 0.0237783 -0.0883395 0.99569 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.5 0.253366 204.47 3997.36 -9.06191 3979.21 +EDGE_SE3:QUAT 28 79 5.57453 3.6695 -1.29748 0.0163902 -0.0686435 0.11222 0.991174 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.7 8.56368 -570.482 3981.06 -31.9061 4029.4 +EDGE_SE3:QUAT 29 78 5.83175 -3.48375 -1.59894 -0.278387 0.191091 0.0327515 0.940698 1 3.08149e-18 3.08149e-18 -1.12474e-07 9.37723e-09 -2.1272e-08 1 3.08149e-18 -1.12474e-07 9.37723e-09 -2.1272e-08 1 -1.12474e-07 9.37723e-09 -2.1272e-08 4276.6 -286.651 1642.73 3933.14 -244.16 4582.3 +EDGE_SE3:QUAT 30 80 6.15532 -0.00934468 -1.53621 -0.094242 0.0731927 -0.100351 0.987771 1 1.92593e-19 1.92593e-19 1.43687e-09 -3.0134e-09 2.75967e-08 1 1.92593e-19 1.43687e-09 -3.0134e-09 2.75967e-08 1 1.43687e-09 -3.0134e-09 2.75967e-08 4016.23 -29.6433 460.504 3991.02 -30.4261 4011.47 +EDGE_SE3:QUAT 29 80 6.0944 3.28609 -1.81999 0.000893736 0.0334748 -0.00501447 0.999427 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.99 -0.014043 268.896 3995.52 -0.657991 4017.89 +EDGE_SE3:QUAT 30 79 5.9811 -3.39687 -1.92919 0.0827107 0.0729649 -0.0441279 0.992919 1 2.40741e-19 2.40741e-19 2.67867e-08 -1.9758e-09 -1.17279e-08 1 2.40741e-19 2.67867e-08 -1.9758e-09 -1.17279e-08 1 2.67867e-08 -1.9758e-09 -1.17279e-08 4070.55 21.8902 633.501 3975.65 -3.08791 4090.12 +EDGE_SE3:QUAT 31 81 6.15804 0.157903 -2.07048 0.0515969 -0.0481527 0.092587 0.9932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.26 -5.74576 -440.616 3987.59 -18.2108 4013.62 +EDGE_SE3:QUAT 30 81 6.085 3.49106 -1.51185 -0.166169 -0.194093 0.17656 0.950548 1 7.70372e-19 7.70372e-19 5.46888e-08 1.40128e-08 -6.19629e-09 1 7.70372e-19 5.46888e-08 1.40128e-08 -6.19629e-09 1 5.46888e-08 1.40128e-08 -6.19629e-09 4162.55 204.958 -1102.86 4002.53 -205.489 4148.3 +EDGE_SE3:QUAT 31 80 5.97958 -3.37558 -1.48924 -0.0276366 0.120053 0.00630658 0.992363 1 7.52316e-22 7.52316e-22 -2.14748e-10 4.80683e-11 -1.77272e-09 1 7.52316e-22 -2.14748e-10 4.80683e-11 -1.77272e-09 1 -2.14748e-10 4.80683e-11 -1.77272e-09 4238.44 -13.7922 1012.08 3942.37 -6.60056 4241.34 +EDGE_SE3:QUAT 32 82 6.47995 -0.0341606 -1.78806 0.0369926 0.174818 -0.109895 0.977749 1 2.0463e-19 2.0463e-19 1.2542e-08 -8.13092e-10 3.03145e-08 1 2.0463e-19 1.2542e-08 -8.13092e-10 3.03145e-08 1 1.2542e-08 -8.13092e-10 3.03145e-08 4552.36 -57.8185 1594.53 3878.27 -85.1523 4509.53 +EDGE_SE3:QUAT 31 82 6.10181 3.74441 -1.99183 -0.131463 0.194763 -0.0465972 0.970883 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4494.42 -187.954 1604.99 3903.16 -176.462 4554.86 +EDGE_SE3:QUAT 32 81 5.30182 -3.63572 -1.69575 0.0884809 0.0914296 0.0270747 0.991503 1 1.92593e-19 1.92593e-19 -1.20387e-09 2.75037e-08 -2.62978e-09 1 1.92593e-19 -1.20387e-09 2.75037e-08 -2.62978e-09 1 -1.20387e-09 2.75037e-08 -2.62978e-09 4091.33 38.7471 711.268 3972.55 27.2842 4119.72 +EDGE_SE3:QUAT 33 83 6.1976 0.430746 -1.45041 -0.0778649 -0.209829 -0.0342695 0.97403 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4804.23 70.004 -2000.08 3823.26 -54.1583 4823.79 +EDGE_SE3:QUAT 32 83 5.83481 3.56722 -1.81244 0.185414 0.138812 0.0690297 0.970355 1 7.70372e-19 7.70372e-19 -5.52721e-08 -6.7419e-09 -5.76945e-09 1 7.70372e-19 -5.52721e-08 -6.7419e-09 -5.76945e-09 1 -5.52721e-08 -6.7419e-09 -5.76945e-09 4064.32 118.142 926.135 3973.86 101.392 4182.77 +EDGE_SE3:QUAT 33 82 5.78779 -3.82729 -1.97382 0.137518 0.0325002 -0.104013 0.984487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.75 27.4037 421.512 3986.98 -17.411 4000.12 +EDGE_SE3:QUAT 34 84 6.06439 0.262144 -1.49652 0.0205043 -0.0841136 -0.0571624 0.994604 1 6.01853e-20 6.01853e-20 5.85468e-09 -4.82058e-12 1.34207e-08 1 6.01853e-20 5.85468e-09 -4.82058e-12 1.34207e-08 1 5.85468e-09 -4.82058e-12 1.34207e-08 4107.7 -16.9501 -670.495 3974.23 23.8439 4096.32 +EDGE_SE3:QUAT 33 84 5.84748 3.45492 -1.3078 -0.0814893 0.0264678 0.165567 0.98247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.52 -10.2273 362.318 3990.23 31.266 3922.43 +EDGE_SE3:QUAT 34 83 5.4987 -3.78186 -1.7498 -0.233777 -0.00890741 -0.00540646 0.972234 1 7.73381e-19 7.73381e-19 5.39786e-08 -3.41573e-09 -1.38783e-09 1 7.73381e-19 5.39786e-08 -3.41573e-09 -1.38783e-09 1 5.39786e-08 -3.41573e-09 -1.38783e-09 3783 9.71734 -80.1405 3999.65 -0.326327 4001.49 +EDGE_SE3:QUAT 35 85 6.14227 -0.120395 -1.78272 -0.0371108 -0.134024 0.172522 0.975139 1 4.81482e-20 4.81482e-20 -1.39313e-08 -2.68837e-09 1.60307e-09 1 4.81482e-20 -1.39313e-08 -2.68837e-09 1.60307e-09 1 -1.39313e-08 -2.68837e-09 1.60307e-09 4225.09 87.4623 -989.656 3961 -110.664 4111.54 +EDGE_SE3:QUAT 34 85 6.01282 3.44309 -1.86311 0.0604073 -0.131055 0.0175978 0.989376 1 8.1852e-19 8.1852e-19 1.43311e-08 -5.49031e-08 1.30849e-09 1 8.1852e-19 1.43311e-08 -5.49031e-08 1.30849e-09 1 1.43311e-08 -5.49031e-08 1.30849e-09 4279.14 -32.2788 -1123.04 3931.06 15.7301 4292.49 +EDGE_SE3:QUAT 35 84 5.7603 -3.37648 -1.44264 0.126174 0.00265699 -0.188692 0.973893 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3956.48 20.8041 297.083 3990.99 -34.4306 3877.74 +EDGE_SE3:QUAT 36 86 5.77433 -0.109101 -1.46816 0.118725 0.147778 -0.0449361 0.98084 1 1.20371e-20 1.20371e-20 1.12152e-09 8.02611e-10 7.14303e-09 1 1.20371e-20 1.12152e-09 8.02611e-10 7.14303e-09 1 1.12152e-09 8.02611e-10 7.14303e-09 4343.69 70.9978 1326.78 3909.82 36.4518 4391.99 +EDGE_SE3:QUAT 35 86 5.87752 4.13746 -1.57497 0.0952278 -0.09793 0.0405315 0.989797 1 3.85186e-19 3.85186e-19 -2.86695e-08 2.68715e-08 4.7228e-10 1 3.85186e-19 -2.86695e-08 2.68715e-08 4.7228e-10 1 -2.86695e-08 2.68715e-08 4.7228e-10 4136.41 -34.7836 -848.878 3958.38 5.49375 4166.11 +EDGE_SE3:QUAT 36 85 5.41996 -3.51254 -1.61805 0.125743 -0.0486773 0.053217 0.989438 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.74 -27.507 -463.789 3986.27 -3.85245 4041.65 +EDGE_SE3:QUAT 37 87 5.67637 -0.102551 -1.82675 0.215089 0.06441 0.0450929 0.973424 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3847.45 37.8947 367.052 3996.35 20.5395 4024.37 +EDGE_SE3:QUAT 36 87 5.30026 3.86049 -1.39082 -0.105873 0.102379 -0.000541621 0.989095 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4121.94 -48.8806 833.685 3962.17 -27.6343 4166.78 +EDGE_SE3:QUAT 37 86 5.75796 -3.48158 -1.59317 0.02289 0.0148705 0.053557 0.998192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.59 1.36189 103.734 3999.4 2.74521 3991.21 +EDGE_SE3:QUAT 38 88 6.01686 0.114515 -1.72335 -0.0203051 0.0413196 -0.0392659 0.998168 1 1.20371e-20 1.20371e-20 -6.94845e-09 2.85729e-10 -2.7537e-10 1 1.20371e-20 -6.94845e-09 2.85729e-10 -2.7537e-10 1 -6.94845e-09 2.85729e-10 -2.7537e-10 4024.07 -4.8313 321.785 3993.8 -7.15609 4019.55 +EDGE_SE3:QUAT 37 88 6.28099 3.6149 -1.64876 -0.0401474 0.00478713 -0.0620845 0.997252 1 4.81482e-20 4.81482e-20 -3.28605e-12 -5.611e-10 1.38396e-08 1 4.81482e-20 -3.28605e-12 -5.611e-10 1.38396e-08 1 -3.28605e-12 -5.611e-10 1.38396e-08 3993.54 0.0331227 8.18123 4000 0.0556195 3984.57 +EDGE_SE3:QUAT 38 87 5.77465 -3.66929 -1.82176 0.0325853 -0.0370504 -0.024419 0.998483 1 6.01853e-20 6.01853e-20 -1.36465e-08 1.3395e-10 -6.45458e-09 1 6.01853e-20 -1.36465e-08 1.3395e-10 -6.45458e-09 1 -1.36465e-08 1.3395e-10 -6.45458e-09 4016.29 -5.45811 -287.376 3995.05 4.53897 4018.15 +EDGE_SE3:QUAT 39 89 5.95942 0.0408236 -1.34856 -0.0628243 -0.113033 0.0302357 0.991142 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4182.21 41.45 -911.793 3954.86 -34.8932 4194.34 +EDGE_SE3:QUAT 38 89 5.72733 3.54903 -1.51003 -0.0919451 0.0683668 0.0366681 0.992737 1 1.20371e-20 1.20371e-20 -5.17616e-10 6.14214e-10 -6.96225e-09 1 1.20371e-20 -5.17616e-10 6.14214e-10 -6.96225e-09 1 -5.17616e-10 6.14214e-10 -6.96225e-09 4051.5 -24.4523 590.434 3978.88 -0.0344781 4079.94 +EDGE_SE3:QUAT 39 88 5.74449 -3.82304 -1.52217 0.234134 0.0760817 -0.0941118 0.964643 1 9.62965e-19 9.62965e-19 5.16246e-08 -9.07425e-09 -2.11449e-08 1 9.62965e-19 5.16246e-08 -9.07425e-09 -2.11449e-08 1 5.16246e-08 -9.07425e-09 -2.11449e-08 3949.5 93.2327 839.978 3959.28 9.22843 4133.35 +EDGE_SE3:QUAT 40 90 6.11246 0.043113 -1.64931 -0.0609968 0.0360802 -0.0502466 0.996219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.64 -8.57593 250.036 3996.64 -7.55752 4005.42 +EDGE_SE3:QUAT 39 90 6.38181 4.00666 -1.90191 0.0609092 0.0325676 -0.123754 0.989906 1 1.92593e-19 1.92593e-19 2.7578e-08 -3.32139e-09 1.28999e-09 1 1.92593e-19 2.7578e-08 -3.32139e-09 1.28999e-09 1 2.7578e-08 -3.32139e-09 1.28999e-09 4014.55 6.54372 344.994 3991.84 -20.9541 3968.13 +EDGE_SE3:QUAT 40 89 5.83939 -3.75292 -1.87805 -0.000965932 0.25281 0.114719 0.96069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5195 235.377 2491.81 3786.06 241.976 5142.36 +EDGE_SE3:QUAT 41 91 5.60831 0.0681095 -1.54185 -0.0342021 -0.115335 -0.00310849 0.992733 1 1.92781e-19 1.92781e-19 3.21799e-11 -2.75843e-08 -7.03444e-11 1 1.92781e-19 3.21799e-11 -2.75843e-08 -7.03444e-11 1 3.21799e-11 -2.75843e-08 -7.03444e-11 4216.79 17.8142 -966.922 3947.11 -9.94084 4221.43 +EDGE_SE3:QUAT 40 91 6.1234 3.82538 -1.95412 0.10716 0.0179237 0.18432 0.976843 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3954.85 -9.4734 -96.1425 3998.01 -16.3951 3864.89 +EDGE_SE3:QUAT 41 90 5.69973 -3.48959 -1.58262 -0.0383892 -0.0211637 -0.0390972 0.998273 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.81 3.22555 -186.902 3997.71 3.303 4002.59 +EDGE_SE3:QUAT 42 92 5.91581 -0.00110584 -1.27231 -0.0685196 0.1685 -0.0202811 0.983108 1 7.70372e-19 7.70372e-19 -2.51501e-09 -5.45271e-08 -4.41873e-09 1 7.70372e-19 -2.51501e-09 -5.45271e-08 -4.41873e-09 1 -2.51501e-09 -5.45271e-08 -4.41873e-09 4454.55 -79.9152 1455.19 3897.06 -71.0671 4471.68 +EDGE_SE3:QUAT 41 92 5.89725 3.57254 -1.8393 -0.0482591 -0.234738 -0.0248518 0.970542 1 8.1852e-19 8.1852e-19 -1.53283e-08 -5.3845e-08 1.38205e-09 1 8.1852e-19 -1.53283e-08 -5.3845e-08 1.38205e-09 1 -1.53283e-08 -5.3845e-08 1.38205e-09 5053.32 46.3778 -2319.42 3779 -39.0809 5060.16 +EDGE_SE3:QUAT 42 91 5.89764 -3.8084 -1.6068 -0.0386007 0.0990201 -0.123379 0.986652 1 1.92593e-19 1.92593e-19 3.68787e-09 2.73509e-08 1.73819e-09 1 1.92593e-19 3.68787e-09 2.73509e-08 1.73819e-09 1 3.68787e-09 2.73509e-08 1.73819e-09 4124.36 -41.0207 734.427 3973.6 -56.1028 4069.43 +EDGE_SE3:QUAT 43 93 5.96033 0.225195 -1.58161 -0.0363554 -0.046525 -0.0245101 0.997954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.42 5.87924 -384.935 3990.79 2.8786 4034.3 +EDGE_SE3:QUAT 42 93 5.94247 3.51503 -1.70645 -0.22679 0.21295 0.210968 0.926667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5144.21 -69.7286 2688.18 3734.94 -2.07125 5171.92 +EDGE_SE3:QUAT 43 92 5.92395 -3.54578 -1.45706 -0.120698 0.0159044 -0.105553 0.986933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3941.26 4.87182 -27.9219 3999.6 4.26335 3954.96 +EDGE_SE3:QUAT 44 94 5.93868 -0.140265 -1.8357 -0.25435 0.045805 0.059768 0.964176 1 4.81482e-20 4.81482e-20 -9.66667e-10 3.4804e-09 -1.34954e-08 1 4.81482e-20 -9.66667e-10 3.4804e-09 -1.34954e-08 1 -9.66667e-10 3.4804e-09 -1.34954e-08 3805.56 -68.231 512.23 3984.46 -5.39596 4050.05 +EDGE_SE3:QUAT 43 94 5.78336 4.18052 -2.01723 0.160754 -0.178453 0.096777 0.965892 1 2.31112e-18 2.31112e-18 -4.83487e-08 4.34516e-08 -5.36215e-08 1 2.31112e-18 -4.83487e-08 4.34516e-08 -5.36215e-08 1 -4.83487e-08 4.34516e-08 -5.36215e-08 4573.07 -99.4869 -1778.69 3854.18 49.261 4638.97 +EDGE_SE3:QUAT 44 93 5.30923 -3.53895 -1.60436 -0.0187497 0.109047 -0.0233955 0.993584 1 2.0463e-19 2.0463e-19 6.27985e-09 -2.77738e-08 9.04892e-11 1 2.0463e-19 6.27985e-09 -2.77738e-08 9.04892e-11 1 6.27985e-09 -2.77738e-08 9.04892e-11 4192.76 -16.4923 902.431 3953.68 -17.4574 4191.98 +EDGE_SE3:QUAT 45 95 6.12362 -0.0662114 -1.56843 -0.00833275 -0.0153508 -0.176145 0.984209 1 7.52316e-22 7.52316e-22 1.70833e-09 -3.05419e-10 -3.00056e-11 1 7.52316e-22 1.70833e-09 -3.05419e-10 -3.00056e-11 1 1.70833e-09 -3.05419e-10 -3.00056e-11 4004.24 -0.589557 -134.515 3998.94 12.1706 3880.41 +EDGE_SE3:QUAT 44 95 5.97681 3.85582 -1.70055 0.080118 -0.101395 0.0289156 0.991193 1 1.92593e-19 1.92593e-19 -2.81216e-08 -3.60535e-10 2.96857e-09 1 1.92593e-19 -2.81216e-08 -3.60535e-10 2.96857e-09 1 -2.81216e-08 -3.60535e-10 2.96857e-09 4152.59 -30.9069 -863.063 3957.22 7.71547 4174.93 +EDGE_SE3:QUAT 45 94 5.78027 -3.91186 -1.13986 -0.0877164 0.0978131 0.0227164 0.991071 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4132.97 -34.5547 825.715 3960.97 -11.4345 4161.68 +EDGE_SE3:QUAT 46 96 6.07609 -0.308555 -1.53642 0.0197864 0.0078013 0.0699392 0.997324 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.94 0.456092 45.3715 3999.91 1.40591 3980.94 +EDGE_SE3:QUAT 45 96 5.67429 4.00618 -1.60163 -0.103981 0.0129266 0.115155 0.987806 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3970.87 -13.1357 241.996 3995.03 14.9447 3961.08 +EDGE_SE3:QUAT 46 95 5.97201 -3.81726 -1.72332 -0.00802395 -0.105706 -0.210229 0.971888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4168.49 -53.0447 -839.318 3968.97 95.2102 3991.96 +EDGE_SE3:QUAT 47 97 5.8293 -0.0093391 -1.8353 0.0467693 -0.0505419 0.129561 0.989177 1 7.70372e-19 7.70372e-19 -3.39294e-09 1.8127e-09 5.52908e-08 1 7.70372e-19 -3.39294e-09 1.8127e-09 5.52908e-08 1 -3.39294e-09 1.8127e-09 5.52908e-08 4045.85 -1.67934 -470.795 3986.09 -29.1459 3987.46 +EDGE_SE3:QUAT 46 97 6.32001 3.77041 -1.59152 0.0284255 -0.087054 0.0227068 0.995539 1 1.20371e-20 1.20371e-20 7.01641e-09 1.2699e-10 -6.21162e-10 1 1.20371e-20 7.01641e-09 1.2699e-10 -6.21162e-10 1 7.01641e-09 1.2699e-10 -6.21162e-10 4123.22 -6.77698 -722.361 3969.04 -3.44151 4124.39 +EDGE_SE3:QUAT 47 96 5.77964 -3.7472 -1.75289 0.0982419 0.0623696 0.023406 0.99293 1 1.20371e-20 1.20371e-20 -3.94506e-10 -7.11174e-10 -6.93689e-09 1 1.20371e-20 -3.94506e-10 -7.11174e-10 -6.93689e-09 1 -3.94506e-10 -7.11174e-10 -6.93689e-09 4015.62 25.3346 469.102 3987.92 13.9317 4052.04 +EDGE_SE3:QUAT 48 98 5.85492 -0.157606 -1.70658 -0.0620725 -0.0465225 -0.0551228 0.995462 1 4.81482e-20 4.81482e-20 1.3888e-08 -6.86088e-10 -7.35753e-10 1 4.81482e-20 1.3888e-08 -6.86088e-10 -7.35753e-10 1 1.3888e-08 -6.86088e-10 -7.35753e-10 4026.81 10.1628 -413.254 3989.09 8.22058 4030.06 +EDGE_SE3:QUAT 47 98 5.99882 3.6996 -2.01345 -0.185355 0.18444 0.124248 0.957177 1 7.70372e-19 7.70372e-19 -5.83422e-08 -3.31904e-09 -1.30484e-08 1 7.70372e-19 -5.83422e-08 -3.31904e-09 -1.30484e-08 1 -5.83422e-08 -3.31904e-09 -1.30484e-08 4651.43 -111.793 1943.91 3833.1 -51.9422 4727.11 +EDGE_SE3:QUAT 48 97 5.73476 -3.76681 -1.6667 0.0387948 0.0967031 0.00844598 0.994521 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4145.51 18.8218 793.146 3963.65 12.6801 4151.24 +EDGE_SE3:QUAT 49 99 6.02746 0.318965 -1.87242 -0.0773694 0.0666275 -0.0259334 0.994436 1 1.20371e-20 1.20371e-20 -4.31495e-10 5.69384e-10 -6.95573e-09 1 1.20371e-20 -4.31495e-10 5.69384e-10 -6.95573e-09 1 -4.31495e-10 5.69384e-10 -6.95573e-09 4040.14 -22.826 510.462 3985.32 -14.5065 4061.39 +EDGE_SE3:QUAT 48 99 5.61961 3.49117 -1.55858 0.0617119 -0.0294376 0.0772105 0.994668 1 4.81482e-20 4.81482e-20 -1.38401e-08 -1.01792e-09 5.33858e-10 1 4.81482e-20 -1.38401e-08 -1.01792e-09 5.33858e-10 1 -1.38401e-08 -1.01792e-09 5.33858e-10 4005.66 -7.37077 -290.35 3994.27 -10.2374 3997.05 +EDGE_SE3:QUAT 49 98 5.57007 -3.64396 -1.53621 -0.188457 0.079932 -0.227945 0.951912 1 7.70372e-19 7.70372e-19 5.27794e-08 -1.34055e-08 -9.39908e-10 1 7.70372e-19 5.27794e-08 -1.34055e-08 -9.39908e-10 1 5.27794e-08 -1.34055e-08 -9.39908e-10 3849.4 9.81508 67.8443 4000.62 12.9417 3783.63 +EDGE_SE3:QUAT 50 100 6.44048 0.0481054 -1.72836 0.0960498 -0.105655 0.136525 0.980292 1 1.92593e-19 1.92593e-19 2.8052e-08 3.34962e-09 -3.61402e-09 1 1.92593e-19 2.8052e-08 3.34962e-09 -3.61402e-09 1 2.8052e-08 3.34962e-09 -3.61402e-09 4208.79 -8.78608 -1021.81 3940.05 -47.909 4171.13 +EDGE_SE3:QUAT 49 100 5.94044 4.21023 -1.63116 -0.0461824 -0.156294 -0.0169523 0.986485 1 4.81482e-20 4.81482e-20 1.44013e-08 -4.05168e-11 -2.29437e-09 1 4.81482e-20 1.44013e-08 -4.05168e-11 -2.29437e-09 1 1.44013e-08 -4.05168e-11 -2.29437e-09 4416.85 28.7782 -1372.03 3901.96 -16.1222 4424.23 +EDGE_SE3:QUAT 50 99 5.86989 -4.20762 -2.00758 0.183037 -0.035721 -0.0621657 0.980488 1 7.70372e-19 7.70372e-19 -5.4456e-08 3.94021e-09 5.92352e-10 1 7.70372e-19 -5.4456e-08 3.94021e-09 5.92352e-10 1 -5.4456e-08 3.94021e-09 5.92352e-10 3869.95 -8.57884 -136.547 3999.9 4.66542 3988.5 +EDGE_SE3:QUAT 51 101 6.15768 0.0131536 -1.77308 0.124171 -0.0555189 -0.0105981 0.99065 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.34 -27.1952 -422.062 3990.31 10.8042 4043.56 +EDGE_SE3:QUAT 50 101 5.97739 4.18945 -1.9437 0.0987001 0.0962713 0.0169213 0.990305 1 9.62965e-19 9.62965e-19 5.49343e-08 2.95095e-08 2.25603e-09 1 9.62965e-19 5.49343e-08 2.95095e-08 2.25603e-09 1 5.49343e-08 2.95095e-08 2.25603e-09 4100.71 44.2515 760.555 3968.73 28.5115 4138.53 +EDGE_SE3:QUAT 51 100 5.71187 -3.84824 -1.80154 0.128514 0.131342 0.0117503 0.982901 1 1.20371e-20 1.20371e-20 -8.86707e-10 -9.76109e-10 -7.04651e-09 1 1.20371e-20 -8.86707e-10 -9.76109e-10 -7.04651e-09 1 -8.86707e-10 -9.76109e-10 -7.04651e-09 4198.85 84.5067 1063.22 3944.68 61.5608 4264.36 +EDGE_SE3:QUAT 52 102 6.2082 0.43876 -1.87039 0.00795227 -0.0767901 0.204768 0.975761 1 3.00927e-21 3.00927e-21 3.42485e-09 7.23162e-10 -2.57975e-10 1 3.00927e-21 3.42485e-09 7.23162e-10 -2.57975e-10 1 3.42485e-09 7.23162e-10 -2.57975e-10 4089.66 26.4222 -606.713 3982.53 -64.2126 3922.19 +EDGE_SE3:QUAT 51 102 5.72864 3.82307 -1.92853 -0.0217737 0.0344258 0.103436 0.993802 1 4.81482e-20 4.81482e-20 -1.4172e-09 1.37937e-08 1.9801e-10 1 4.81482e-20 -1.4172e-09 1.37937e-08 1.9801e-10 1 -1.4172e-09 1.37937e-08 1.9801e-10 4020.35 -0.0181699 299.168 3994.4 15.3648 3979.45 +EDGE_SE3:QUAT 52 101 5.85501 -4.09069 -1.43692 -0.0787811 -3.73752e-05 0.0526477 0.995501 1 7.52316e-22 7.52316e-22 9.02087e-11 -1.72698e-09 -1.35917e-10 1 7.52316e-22 9.02087e-11 -1.72698e-09 -1.35917e-10 1 9.02087e-11 -1.72698e-09 -1.35917e-10 3975.71 -2.56284 49.1854 3999.73 1.68917 3989.45 +EDGE_SE3:QUAT 53 103 6.15166 0.188446 -1.48548 0.0409408 0.0823457 -0.140901 0.985743 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4121.26 -10.4847 726.845 3969.62 -48.6204 4048.55 +EDGE_SE3:QUAT 52 103 5.78526 4.31103 -1.85257 -0.0777278 -0.0564957 0.0327218 0.994835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.51 18.6333 -420.472 3990.16 -12.2383 4039.39 +EDGE_SE3:QUAT 53 102 5.7828 -3.74817 -1.80447 -0.10472 0.108675 -0.0323939 0.988015 1 3.85186e-19 3.85186e-19 -2.64697e-08 2.89661e-08 3.54712e-10 1 3.85186e-19 -2.64697e-08 2.89661e-08 3.54712e-10 1 -2.64697e-08 2.89661e-08 3.54712e-10 4125.97 -57.0257 841.917 3963.73 -43.2475 4165.64 +EDGE_SE3:QUAT 54 104 5.74519 0.0702005 -1.59591 0.206861 0.0494952 0.0610441 0.975209 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3840.04 18.598 221.565 3999.42 10.3448 3996.3 +EDGE_SE3:QUAT 53 104 5.95982 3.82791 -1.53172 -0.140107 0.180926 0.0897028 0.969324 1 7.70372e-19 7.70372e-19 -2.21874e-09 5.39926e-08 6.37316e-09 1 7.70372e-19 -2.21874e-09 5.39926e-08 6.37316e-09 1 -2.21874e-09 5.39926e-08 6.37316e-09 4595.71 -80.2753 1775.34 3852.99 -36.6409 4642.04 +EDGE_SE3:QUAT 54 103 5.53096 -3.8242 -1.93268 -0.0776498 0.000115075 -0.135413 0.987742 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.28 5.96127 -123.347 3998.33 10.9398 3930.05 +EDGE_SE3:QUAT 55 105 6.27984 -0.203416 -1.73821 -0.0291978 0.0204608 -0.121502 0.991951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.99 -2.24882 117.785 3999.42 -6.41702 3944.35 +EDGE_SE3:QUAT 54 105 5.76131 3.97714 -1.87475 -0.0782203 0.0263987 0.230021 0.969678 1 1.92593e-19 1.92593e-19 -2.70557e-08 -6.24254e-09 -1.62604e-09 1 1.92593e-19 -2.70557e-08 -6.24254e-09 -1.62604e-09 1 -2.70557e-08 -6.24254e-09 -1.62604e-09 4015.36 -7.0696 404.527 3988.02 50.968 3828.19 +EDGE_SE3:QUAT 55 104 5.39164 -3.84602 -1.62197 0.0139121 -0.0430414 -0.129855 0.990501 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.95 -7.25433 -315.695 3994.72 20.7451 3957.27 +EDGE_SE3:QUAT 56 106 5.99179 0.00578715 -1.73418 -0.0810752 -0.0260138 0.00749562 0.99634 1 3.00927e-21 3.00927e-21 8.49511e-11 2.83329e-10 -3.46105e-09 1 3.00927e-21 8.49511e-11 2.83329e-10 -3.46105e-09 1 8.49511e-11 2.83329e-10 -3.46105e-09 3983.6 8.11724 -199.199 3997.68 -1.97408 4009.67 +EDGE_SE3:QUAT 55 106 5.98142 3.63697 -2.01004 0.0412091 0.0943709 0.0444911 0.993688 1 9.62965e-20 9.62965e-20 -1.27545e-08 -3.84722e-11 1.27545e-08 1 9.62965e-20 -1.27545e-08 -3.84722e-11 1.27545e-08 1 -1.27545e-08 -3.84722e-11 1.27545e-08 4129.14 26.0635 749.884 3968.43 26.6986 4128.02 +EDGE_SE3:QUAT 56 105 5.45643 -4.13577 -1.88546 0.0725126 -0.0117712 -0.130682 0.988699 1 1.92593e-19 1.92593e-19 2.7441e-08 -3.63592e-09 2.08058e-10 1 1.92593e-19 2.7441e-08 -3.63592e-09 2.08058e-10 1 2.7441e-08 -3.63592e-09 2.08058e-10 3978.71 2.18153 20.9968 3999.78 -3.92247 3931.43 +EDGE_SE3:QUAT 57 107 6.05369 -0.0802747 -1.65349 0.0914909 0.0492298 -0.150189 0.983183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4039.64 13.2814 547.304 3979.94 -37.2618 3982.9 +EDGE_SE3:QUAT 56 107 6.00362 4.08773 -1.57998 -0.00803074 0.000511277 0.121017 0.992618 1 1.95602e-19 1.95602e-19 3.51118e-09 2.06821e-10 2.75593e-08 1 1.95602e-19 3.51118e-09 2.06821e-10 2.75593e-08 1 3.51118e-09 2.06821e-10 2.75593e-08 3999.8 -0.0702392 15.5484 3999.98 1.17368 3941.48 +EDGE_SE3:QUAT 57 106 5.64425 -4.12187 -1.34274 -0.157622 0.0584762 -0.108395 0.979789 1 7.70372e-19 7.70372e-19 -5.44805e-08 6.76452e-09 -1.13512e-09 1 7.70372e-19 -5.44805e-08 6.76452e-09 -1.13512e-09 1 -5.44805e-08 6.76452e-09 -1.13512e-09 3913.53 -16.7877 241.63 3999.45 -14.2177 3965.91 +EDGE_SE3:QUAT 58 108 5.91328 0.0640745 -1.93498 -0.0678044 -0.0460149 -0.0744929 0.993849 1 1.92593e-19 1.92593e-19 2.77413e-08 -1.89601e-09 -1.54039e-09 1 1.92593e-19 2.77413e-08 -1.89601e-09 -1.54039e-09 1 2.77413e-08 -1.89601e-09 -1.54039e-09 4026.68 10.6947 -427.3 3988.15 12.6544 4022.87 +EDGE_SE3:QUAT 57 108 5.6853 3.98768 -1.78569 -0.15043 0.0678569 0.195763 0.966666 1 7.70372e-19 7.70372e-19 5.49295e-08 9.62759e-09 6.67458e-09 1 7.70372e-19 5.49295e-08 9.62759e-09 6.67458e-09 1 5.49295e-08 9.62759e-09 6.67458e-09 4090.41 -31.6895 873.285 3950.6 66.6152 4027.64 +EDGE_SE3:QUAT 58 107 5.46048 -4.08645 -1.66398 -0.0594676 0.0167646 0.00297397 0.998085 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.45 -4.03927 135.659 3998.86 -0.205958 4004.56 +EDGE_SE3:QUAT 59 109 6.06285 0.0735781 -2.01152 0.0723531 0.0497339 0.199103 0.976038 1 4.81482e-20 4.81482e-20 -2.83829e-09 1.35297e-08 -1.19554e-09 1 4.81482e-20 -2.83829e-09 1.35297e-08 -1.19554e-09 1 -2.83829e-09 1.35297e-08 -1.19554e-09 3988.12 9.60057 203.235 3999.77 15.4985 3850.5 +EDGE_SE3:QUAT 58 109 5.88467 3.97509 -2.11681 -0.0296006 0.00339901 0.241342 0.969983 1 7.70372e-19 7.70372e-19 -9.36097e-10 1.364e-09 -5.38644e-08 1 7.70372e-19 -9.36097e-10 1.364e-09 -5.38644e-08 1 -9.36097e-10 1.364e-09 -5.38644e-08 3999.23 -1.24985 107.244 3998.97 16.203 3769.75 +EDGE_SE3:QUAT 59 108 5.57565 -3.72092 -1.82918 0.12422 0.0878336 -0.123646 0.980595 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4127.39 30.9736 890.997 3951.91 -30.5203 4127.96 +EDGE_SE3:QUAT 60 110 6.02706 0.0972524 -1.94602 -0.0720933 -0.193124 0.0740949 0.975713 1 9.62965e-19 9.62965e-19 -2.30134e-08 -5.72083e-08 -6.57137e-10 1 9.62965e-19 -2.30134e-08 -5.72083e-08 -6.57137e-10 1 -2.30134e-08 -5.72083e-08 -6.57137e-10 4559.67 151.959 -1631.23 3889.77 -152.249 4558.5 +EDGE_SE3:QUAT 59 110 5.77318 4.37629 -1.73068 -0.0673918 -0.053048 -0.115338 0.989617 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4046.5 8.2848 -513.234 3983.05 26.1043 4011.46 +EDGE_SE3:QUAT 60 109 5.87494 -3.79101 -1.68994 0.135172 0.0445038 -0.159854 0.976829 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.38 29.4324 598.097 3974.55 -40.8736 3984.25 +EDGE_SE3:QUAT 61 111 5.70853 -0.0806927 -1.97166 0.00781435 -0.0918855 0.0897525 0.991686 1 4.23178e-22 4.23178e-22 1.31254e-09 1.18915e-10 -1.21495e-10 1 4.23178e-22 1.31254e-09 1.18915e-10 -1.21495e-10 1 1.31254e-09 1.18915e-10 -1.21495e-10 4138.16 15.79 -756.832 3967.43 -35.3616 4106.18 +EDGE_SE3:QUAT 60 111 5.68916 3.8996 -1.87913 0.165298 -0.00658173 0.178866 0.969866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3926.29 -35.5255 -392.501 3985.03 -39.5321 3907.61 +EDGE_SE3:QUAT 61 110 5.53487 -4.20691 -1.60664 -0.113035 0.192149 -0.161316 0.961394 1 7.70372e-19 7.70372e-19 5.6029e-08 -1.24216e-08 7.99089e-09 1 7.70372e-19 5.6029e-08 -1.24216e-08 7.99089e-09 1 5.6029e-08 -1.24216e-08 7.99089e-09 4335.95 -208.167 1311.61 3964.11 -212.808 4282.97 +EDGE_SE3:QUAT 62 112 5.91833 -0.451955 -2.17809 0.11301 0.0924007 0.159964 0.97627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.06 42.2356 487.153 3994.72 46.9957 3953.79 +EDGE_SE3:QUAT 61 112 5.68766 4.03711 -1.55877 -0.0117598 -0.108285 0.198861 0.973956 1 4.81482e-20 4.81482e-20 1.37932e-08 2.91752e-09 -1.34212e-09 1 4.81482e-20 1.37932e-08 2.91752e-09 -1.34212e-09 1 1.37932e-08 2.91752e-09 -1.34212e-09 4158.05 56.877 -813.34 3972.22 -90.6469 4000.42 +EDGE_SE3:QUAT 62 111 5.66238 -4.18381 -2.03914 -0.0607449 0.108618 0.0673955 0.989934 1 2.40741e-19 2.40741e-19 1.56374e-08 -2.67108e-08 3.40015e-10 1 2.40741e-19 1.56374e-08 -2.67108e-08 3.40015e-10 1 1.56374e-08 -2.67108e-08 3.40015e-10 4199.9 -11.274 951.23 3947.94 17.0589 4196.49 +EDGE_SE3:QUAT 63 113 6.19482 0.0499579 -1.79926 0.0318304 -0.147081 0.050939 0.987299 1 7.82409e-19 7.82409e-19 9.58462e-09 -5.451e-08 -1.05091e-10 1 7.82409e-19 9.58462e-09 -5.451e-08 -1.05091e-10 1 9.58462e-09 -5.451e-08 -1.05091e-10 4375.44 4.67675 -1289.19 3911.49 -21.8837 4369.12 +EDGE_SE3:QUAT 62 113 5.70426 3.92733 -2.09427 0.178805 0.132978 -0.0829445 0.971322 1 4.81482e-20 4.81482e-20 2.22081e-09 2.34435e-09 1.41194e-08 1 4.81482e-20 2.22081e-09 2.34435e-09 1.41194e-08 1 2.22081e-09 2.34435e-09 1.41194e-08 4247.22 96.5562 1281.24 3915.92 35.0661 4347.59 +EDGE_SE3:QUAT 63 112 5.60793 -3.86649 -1.75452 -0.0869409 0.0329793 -0.246009 0.964797 1 1.95602e-19 1.95602e-19 -2.59111e-08 1.02271e-08 6.76424e-10 1 1.95602e-19 -2.59111e-08 1.02271e-08 6.76424e-10 1 -2.59111e-08 1.02271e-08 6.76424e-10 3967.7 4.32173 -7.91345 3999.46 12.5981 3755.85 +EDGE_SE3:QUAT 64 114 6.08481 0.214146 -1.84204 -0.0416851 0.134162 -0.0472608 0.988954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4278.89 -48.4437 1106.91 3935.58 -49.5668 4276.9 +EDGE_SE3:QUAT 63 114 5.63738 4.16498 -1.96945 -0.0339749 0.0107652 0.028115 0.998969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.75 -1.62498 97.3728 3999.37 1.30854 3999.2 +EDGE_SE3:QUAT 64 113 5.54386 -3.92161 -1.55179 -0.0582369 0.0892301 -0.147201 0.98335 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.3 -38.8104 594.638 3985.15 -52.1007 3999.2 +EDGE_SE3:QUAT 65 115 5.51118 -0.0249466 -1.92335 0.213981 0.0120371 0.0542542 0.975256 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3816.83 -10.0866 -45.4489 3999.44 -2.55984 3988.2 +EDGE_SE3:QUAT 64 115 5.74664 4.19152 -1.73562 -0.0658361 0.132673 -0.0295118 0.98853 1 9.62965e-19 9.62965e-19 -2.57074e-08 5.62175e-08 5.69686e-10 1 9.62965e-19 -2.57074e-08 5.62175e-08 5.69686e-10 1 -2.57074e-08 5.62175e-08 5.69686e-10 4260.78 -55.0439 1090.89 3937.7 -47.7374 4274.63 +EDGE_SE3:QUAT 65 114 5.43235 -4.30164 -2.22078 -0.0477213 -0.104429 -0.121144 0.985972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4194.03 -11.8797 -924.085 3951.84 49.4095 4144.44 +EDGE_SE3:QUAT 66 116 6.22342 0.106962 -2.00162 -0.115436 0.141221 0.0625357 0.981234 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4326.19 -56.261 1289.24 3912.41 -17.1271 4363.85 +EDGE_SE3:QUAT 65 116 5.88266 3.91184 -2.06299 -0.0647181 0.0376794 0.139432 0.987396 1 4.81482e-20 4.81482e-20 1.37723e-08 1.86794e-09 7.50428e-10 1 4.81482e-20 1.37723e-08 1.86794e-09 7.50428e-10 1 1.37723e-08 1.86794e-09 7.50428e-10 4022.94 -6.73922 401.399 3989.12 27.3395 3961.93 +EDGE_SE3:QUAT 66 115 5.85985 -4.25801 -1.68844 0.0289934 0.0126364 -0.104875 0.993982 1 1.50463e-20 1.50463e-20 7.26202e-09 2.72674e-09 3.83651e-11 1 1.50463e-20 7.26202e-09 2.72674e-09 3.83651e-11 1 7.26202e-09 2.72674e-09 3.83651e-11 4001.2 1.49141 135.658 3998.69 -7.55822 3960.57 +EDGE_SE3:QUAT 67 117 5.89476 0.175566 -1.86406 0.0625522 0.00935738 -0.0694539 0.995578 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.24 4.13384 125.839 3998.75 -4.66174 3984.59 +EDGE_SE3:QUAT 66 117 5.91322 4.09 -1.53106 -0.0182305 -0.0433229 0.00601826 0.998877 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.61 3.49533 -347.327 3992.59 -1.88734 4029.79 +EDGE_SE3:QUAT 67 116 5.36871 -4.22462 -1.80966 -0.207389 -0.07718 -0.227312 0.948347 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4132.65 60.8901 -1151.02 3917.41 83.7189 4098.01 +EDGE_SE3:QUAT 68 118 5.93151 -0.398632 -1.87541 1.50964e-05 0.0431162 -0.00830113 0.999036 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.9 -0.370999 347.151 3992.57 -1.46832 4029.63 +EDGE_SE3:QUAT 67 118 5.86557 4.10388 -1.5609 0.0520752 0.0266055 -0.0776168 0.995267 1 2.52778e-19 2.52778e-19 -1.34073e-08 -4.55198e-09 2.75357e-08 1 2.52778e-19 -1.34073e-08 -4.55198e-09 2.75357e-08 1 -1.34073e-08 -4.55198e-09 2.75357e-08 4005.85 5.40375 259.339 3995.43 -9.53767 3992.6 +EDGE_SE3:QUAT 68 117 5.4008 -4.60981 -1.87817 0.0978216 0.0276086 0.110255 0.988692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3963.04 2.54005 86.024 4000 2.73106 3952.69 +EDGE_SE3:QUAT 69 119 5.91142 -0.190225 -1.65065 -0.039509 -0.0532455 -0.0535215 0.996363 1 4.81482e-20 4.81482e-20 -7.96372e-10 -4.72094e-10 1.39152e-08 1 4.81482e-20 -7.96372e-10 -4.72094e-10 1.39152e-08 1 -7.96372e-10 -4.72094e-10 1.39152e-08 4044.54 5.37853 -453.625 3987.17 9.76281 4039.33 +EDGE_SE3:QUAT 68 119 6.10471 4.04176 -1.61189 0.144031 0.0652748 -0.00417028 0.987409 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.65 38.5296 520.591 3985.21 13.652 4066.56 +EDGE_SE3:QUAT 69 118 5.46399 -4.10622 -1.98061 -0.0752428 0.117333 0.0331132 0.989684 1 3.85186e-19 3.85186e-19 -2.87248e-08 2.70323e-08 -1.52889e-09 1 3.85186e-19 -2.87248e-08 2.70323e-08 -1.52889e-09 1 -2.87248e-08 2.70323e-08 -1.52889e-09 4218.08 -31.8356 1010.38 3942.74 -8.3314 4236.34 +EDGE_SE3:QUAT 70 120 6.18176 -0.0761332 -1.71794 0.0389718 0.175855 0.185854 0.965927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4402.88 164.245 1345.68 3940.52 185.155 4270.79 +EDGE_SE3:QUAT 69 120 5.85812 4.56854 -1.84225 0.0295173 -0.0992138 0.12602 0.986613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4169.64 19.1232 -849.981 3959.8 -52.2213 4109.6 +EDGE_SE3:QUAT 70 119 5.93405 -4.29232 -1.92088 -0.112017 0.0495115 -0.116747 0.985582 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3961.66 -12.6913 226.241 3998.86 -12.9733 3957.33 +EDGE_SE3:QUAT 71 121 6.09141 0.118595 -1.8074 0.0924975 0.095773 0.0719712 0.98848 1 1.92593e-19 1.92593e-19 2.78302e-08 2.52784e-09 2.24058e-09 1 1.92593e-19 2.78302e-08 2.52784e-09 2.24058e-09 1 2.78302e-08 2.52784e-09 2.24058e-09 4079.76 46.3623 685.852 3977.23 42.8955 4093.26 +EDGE_SE3:QUAT 70 121 5.91757 4.04804 -1.55912 -0.0131408 0.167604 0.072824 0.983073 1 2.93874e-22 2.93874e-22 1.12973e-09 8.33953e-11 1.9273e-10 1 2.93874e-22 1.12973e-09 8.33953e-11 1.9273e-10 1 1.12973e-09 8.33953e-11 1.9273e-10 4490.45 44.0036 1485.19 3890.16 60.3492 4469.93 +EDGE_SE3:QUAT 71 120 5.79543 -4.09028 -1.53713 0.0157152 0.00463087 -0.0306284 0.999397 1 1.50463e-20 1.50463e-20 -3.42882e-09 2.12603e-10 6.91573e-09 1 1.50463e-20 -3.42882e-09 2.12603e-10 6.91573e-09 1 -3.42882e-09 2.12603e-10 6.91573e-09 3999.47 0.331239 42.7572 3999.88 -0.673971 3996.7 +EDGE_SE3:QUAT 72 122 5.90347 -0.245995 -2.35358 -0.0938437 -0.0387938 -0.00741791 0.994803 1 1.92593e-19 1.92593e-19 2.76977e-08 -1.22832e-12 -1.09965e-09 1 1.92593e-19 2.76977e-08 -1.22832e-12 -1.09965e-09 1 2.76977e-08 -1.22832e-12 -1.09965e-09 3989.63 14.8704 -316.276 3993.98 -2.30575 4024.63 +EDGE_SE3:QUAT 71 122 5.64802 4.40598 -2.09708 0.0325728 -0.00319115 0.14319 0.989154 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.28 -1.35258 -79.9048 3999.42 -6.98278 3919.51 +EDGE_SE3:QUAT 72 121 5.92624 -4.28963 -1.88326 0.0147603 -0.0353619 -0.213311 0.976233 1 7.70372e-19 7.70372e-19 -1.44301e-09 1.56851e-09 5.42823e-08 1 7.70372e-19 -1.44301e-09 1.56851e-09 5.42823e-08 1 -1.44301e-09 1.56851e-09 5.42823e-08 4011.89 -6.25022 -227.57 3998.05 22.7995 3830.75 +EDGE_SE3:QUAT 73 123 5.97515 -0.00701364 -1.90303 -0.0361836 0.150575 -0.00337203 0.98793 1 7.73381e-19 7.73381e-19 -2.7678e-10 -5.49768e-08 1.4275e-09 1 7.73381e-19 -2.7678e-10 -5.49768e-08 1.4275e-09 1 -2.7678e-10 -5.49768e-08 1.4275e-09 4381.01 -31.2813 1301.6 3910.81 -24.6492 4386.2 +EDGE_SE3:QUAT 72 123 5.60049 4.22568 -2.11082 -0.150516 -0.0898796 0.142696 0.974117 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3950.32 38.5854 -421.902 3997.84 -37.9654 3959.49 +EDGE_SE3:QUAT 73 122 5.52461 -4.04594 -1.91006 0.135486 0.00336677 -0.136554 0.981318 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3940.12 19.528 242.851 3994.03 -19.7128 3938.96 +EDGE_SE3:QUAT 74 124 5.94207 0.11972 -1.42486 0.122101 -0.134929 -0.128681 0.974847 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4117.83 -97.1669 -866.906 3976.52 98.0758 4111.23 +EDGE_SE3:QUAT 73 124 5.91381 4.40227 -2.27619 -0.00369672 0.0592838 -0.0639726 0.996182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4055.38 -6.29974 474.158 3986.64 -15.9727 4039.07 +EDGE_SE3:QUAT 74 123 5.69376 -4.10013 -1.99887 0.021297 0.0992542 -0.048328 0.99366 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4164.54 -2.39898 832.532 3959.71 -16.9336 4157.01 +EDGE_SE3:QUAT 75 125 5.9056 0.0167239 -1.68108 0.0672209 -0.00297621 0.0718464 0.995144 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.48 -3.24635 -81.0791 3999.38 -3.48647 3980.91 +EDGE_SE3:QUAT 74 125 5.66695 3.92166 -1.57552 -0.0113868 0.0354523 -0.0468314 0.998209 1 5.11575e-20 5.11575e-20 -2.80898e-09 1.40184e-08 8.48221e-11 1 5.11575e-20 -2.80898e-09 1.40184e-08 8.48221e-11 1 -2.80898e-09 1.40184e-08 8.48221e-11 4018.62 -2.95087 277.374 3995.37 -6.85256 4010.37 +EDGE_SE3:QUAT 75 124 5.40716 -4.28991 -1.8274 0.0363769 -0.0545761 -0.110928 0.991662 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.8 -13.3032 -382.319 3992.53 22.8491 3986.88 +EDGE_SE3:QUAT 76 126 6.11999 -0.0677824 -1.72666 0.143694 0.132291 -0.0233156 0.980463 1 3.08149e-18 3.08149e-18 1.12943e-07 1.7831e-09 1.53684e-08 1 3.08149e-18 1.12943e-07 1.7831e-09 1.53684e-08 1 1.12943e-07 1.7831e-09 1.53684e-08 4217.2 86.5591 1135.4 3935.06 51.5324 4297.62 +EDGE_SE3:QUAT 75 126 5.53084 4.02573 -1.86485 0.0275032 -0.0259532 0.0811043 0.995988 1 1.20371e-20 1.20371e-20 6.92278e-09 5.53803e-10 -2.08693e-10 1 1.20371e-20 6.92278e-09 5.53803e-10 -2.08693e-10 1 6.92278e-09 5.53803e-10 -2.08693e-10 4010.46 -1.76498 -232.721 3996.48 -9.31181 3987.17 +EDGE_SE3:QUAT 76 125 5.18392 -4.3581 -2.09944 0.09354 -0.100344 -0.133925 0.981451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.28 -52.0078 -632.124 3985.26 57.6727 4024.54 +EDGE_SE3:QUAT 77 127 5.87631 0.178756 -1.85972 0.0076677 0.16982 -0.121343 0.977946 1 7.70372e-19 7.70372e-19 9.79868e-09 -2.0533e-09 5.75598e-08 1 7.70372e-19 9.79868e-09 -2.0533e-09 5.75598e-08 1 9.79868e-09 -2.0533e-09 5.75598e-08 4488.84 -87.9819 1481.83 3897.86 -111.516 4430.18 +EDGE_SE3:QUAT 76 127 5.85782 3.95312 -1.85715 -0.160692 0.0229953 0.205727 0.965052 1 7.70372e-19 7.70372e-19 4.70056e-09 -7.75295e-09 5.40906e-08 1 7.70372e-19 4.70056e-09 -7.75295e-09 5.40906e-08 1 4.70056e-09 -7.75295e-09 5.40906e-08 3969.65 -38.2495 555.075 3974.39 57.8077 3903.65 +EDGE_SE3:QUAT 77 126 5.6088 -4.08616 -2.08984 -0.108945 -0.00970641 -0.0714686 0.991428 1 1.20371e-20 1.20371e-20 4.69877e-10 6.88124e-09 7.39142e-10 1 1.20371e-20 4.69877e-10 6.88124e-09 7.39142e-10 1 4.69877e-10 6.88124e-09 7.39142e-10 3959.39 10.2661 -168.367 3997.61 6.22057 3986.44 +EDGE_SE3:QUAT 78 128 5.95774 0.21211 -2.08527 -0.0818284 -0.120713 0.083981 0.985738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4164.51 66.6628 -896.468 3962.2 -67.0488 4163.08 +EDGE_SE3:QUAT 77 128 5.50251 4.29591 -2.27997 0.0608405 -0.191546 0.117296 0.972548 1 4.81482e-20 4.81482e-20 -1.46628e-08 -1.53017e-09 3.01405e-09 1 4.81482e-20 -1.46628e-08 -1.53017e-09 3.01405e-09 1 -1.46628e-08 -1.53017e-09 3.01405e-09 4695.36 53.9371 -1828.94 3847.03 -84.2854 4655.13 +EDGE_SE3:QUAT 78 127 5.7367 -4.14442 -1.99837 0.0584985 0.17495 -0.00620848 0.982818 1 7.52316e-22 7.52316e-22 -3.2233e-10 -1.10943e-10 -1.816e-09 1 7.52316e-22 -3.2233e-10 -1.10943e-10 -1.816e-09 1 -3.2233e-10 -1.10943e-10 -1.816e-09 4522.58 55.4061 1559.7 3880.36 43.5704 4536.11 +EDGE_SE3:QUAT 79 129 6.19907 0.0730268 -1.82659 -0.0800884 0.0144395 0.0351764 0.996062 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.79 -6.11667 148.028 3998.46 2.2045 4000.49 +EDGE_SE3:QUAT 78 129 5.8324 4.70371 -2.04743 -0.0755801 -0.0205976 -0.0349765 0.996313 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.62 7.32464 -195.092 3997.44 2.5973 4004.58 +EDGE_SE3:QUAT 79 128 5.58366 -3.94748 -1.55657 0.114221 -0.0621428 -0.165663 0.977572 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.77 -15.0383 -245.301 3999.78 17.4917 3903.18 +EDGE_SE3:QUAT 80 130 6.02739 -0.0322733 -1.80351 0.0805883 -0.0356369 -0.0461735 0.995039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.01 -10.0979 -237.597 3997.11 7.04027 4005.46 +EDGE_SE3:QUAT 79 130 5.99305 4.30144 -1.95401 -0.086387 0.316219 0.149788 0.932795 1 4.81482e-20 4.81482e-20 1.64999e-08 2.15934e-09 5.77246e-09 1 4.81482e-20 1.64999e-08 2.15934e-09 5.77246e-09 1 1.64999e-08 2.15934e-09 5.77246e-09 6406.51 296.314 3959.96 3607.25 275.891 6346.62 +EDGE_SE3:QUAT 80 129 5.47314 -4.26615 -1.61677 0.0545378 -0.0764659 0.0481591 0.994414 1 4.81482e-20 4.81482e-20 1.39793e-08 5.63205e-10 -1.1382e-09 1 4.81482e-20 1.39793e-08 5.63205e-10 -1.1382e-09 1 1.39793e-08 5.63205e-10 -1.1382e-09 4092.09 -11.7496 -653.306 3974.15 -8.51129 4094.71 +EDGE_SE3:QUAT 81 131 5.66654 0.325636 -2.15667 -0.0334865 0.0190725 -0.0515077 0.997929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.8 -2.44038 131.175 3999.06 -3.43631 3993.67 +EDGE_SE3:QUAT 80 131 6.212 4.71947 -2.30886 0.120061 -0.0149529 0.0401686 0.991841 1 1.92593e-19 1.92593e-19 2.75554e-08 9.8544e-10 -6.68098e-10 1 1.92593e-19 2.75554e-08 9.8544e-10 -6.68098e-10 1 2.75554e-08 9.8544e-10 -6.68098e-10 3949.86 -11.2076 -174.351 3997.78 -2.69036 4001.06 +EDGE_SE3:QUAT 81 130 5.23117 -4.27825 -1.65607 0.118388 0.0849065 -0.129049 0.980878 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4122.42 26.4979 864.562 3954.39 -34.5608 4111.87 +EDGE_SE3:QUAT 82 132 6.09157 0.04161 -1.35082 -0.0111695 -0.017347 0.151117 0.9883 1 7.70372e-19 7.70372e-19 -7.33652e-10 -8.80185e-10 5.48844e-08 1 7.70372e-19 -7.33652e-10 -8.80185e-10 5.48844e-08 1 -7.33652e-10 -8.80185e-10 5.48844e-08 4002.73 1.41118 -114.143 3999.39 -8.07469 3911.89 +EDGE_SE3:QUAT 81 132 5.97135 4.25998 -2.28172 0.0323124 -7.55692e-06 0.0474518 0.998351 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.9 -0.393086 -18.4195 3999.96 -0.58009 3991.07 +EDGE_SE3:QUAT 82 131 5.54625 -4.31543 -1.84577 -4.42552e-05 -0.0739964 -0.18236 0.980444 1 3.00927e-21 3.00927e-21 3.43671e-09 -6.46274e-10 -2.41991e-10 1 3.00927e-21 3.43671e-09 -6.46274e-10 -2.41991e-10 1 3.43671e-09 -6.46274e-10 -2.41991e-10 4080.21 -23.0719 -572.414 3983.93 54.2222 3947.19 +EDGE_SE3:QUAT 83 133 5.72073 0.0476171 -2.59938 0.0137115 0.061098 0.279766 0.958024 1 1.20371e-20 1.20371e-20 -6.6812e-09 -1.97531e-09 -3.06936e-10 1 1.20371e-20 -6.6812e-09 -1.97531e-09 -3.06936e-10 1 -6.6812e-09 -1.97531e-09 -3.06936e-10 4036.52 21.057 391.193 3996.24 52.4363 3724.2 +EDGE_SE3:QUAT 82 133 5.8755 4.06446 -1.88582 -0.101876 -0.0853537 0.0277953 0.990739 1 1.92593e-19 1.92593e-19 2.78556e-08 1.26755e-09 -2.18432e-09 1 1.92593e-19 2.78556e-08 1.26755e-09 -2.18432e-09 1 2.78556e-08 1.26755e-09 -2.18432e-09 4061.77 39.3185 -651.296 3977.39 -26.1047 4100.19 +EDGE_SE3:QUAT 83 132 5.81965 -4.41209 -2.05652 0.0231062 -0.0666689 -0.200443 0.977161 1 4.81482e-20 4.81482e-20 1.36488e-08 -2.86244e-09 -7.2669e-10 1 4.81482e-20 1.36488e-08 -2.86244e-09 -7.2669e-10 1 1.36488e-08 -2.86244e-09 -7.2669e-10 4047.73 -21.9543 -451.075 3991.82 45.9722 3889.15 +EDGE_SE3:QUAT 84 134 6.03456 -0.361114 -2.51549 -0.198951 -0.146915 -0.00313864 0.96893 1 1.20371e-20 1.20371e-20 -9.83519e-10 -1.49665e-09 7.00454e-09 1 1.20371e-20 -9.83519e-10 -1.49665e-09 7.00454e-09 1 -9.83519e-10 -1.49665e-09 7.00454e-09 4168.99 141.615 -1191.02 3942.55 -104.402 4327.27 +EDGE_SE3:QUAT 83 134 5.60368 4.32086 -1.96536 0.0481558 -0.150211 0.0357532 0.986833 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4388.38 -17.6317 -1322.41 3907.44 0.313439 4392.54 +EDGE_SE3:QUAT 84 133 5.49014 -4.53592 -2.02175 0.137276 -0.0648601 -0.057455 0.986736 1 9.62965e-19 9.62965e-19 5.63538e-08 -8.13621e-09 -3.01113e-08 1 9.62965e-19 5.63538e-08 -8.13621e-09 -3.01113e-08 1 5.63538e-08 -8.13621e-09 -3.01113e-08 3966 -30.7388 -411.122 3992.82 20.9875 4028.17 +EDGE_SE3:QUAT 85 135 5.79513 0.0986802 -2.22955 0.0938388 0.0104485 0.117473 0.988577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3964.91 -4.42863 -49.5241 3999.44 -5.54794 3944.93 +EDGE_SE3:QUAT 84 135 5.79679 4.38179 -1.88974 -0.0826765 -0.0643003 -0.00204923 0.994498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.78 22.119 -518.541 3984.21 -7.76229 4066.11 +EDGE_SE3:QUAT 85 134 5.71195 -4.44982 -2.04982 0.0560089 0.242754 0.165674 0.954194 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4836.9 344.601 2033.36 3900.91 349.986 4739.66 +EDGE_SE3:QUAT 86 136 5.95384 0.134246 -2.06313 -0.0449113 -0.0757391 0.224851 0.970406 1 4.81482e-20 4.81482e-20 1.35517e-08 3.25174e-09 -6.67248e-10 1 4.81482e-20 1.35517e-08 3.25174e-09 -6.67248e-10 1 1.35517e-08 3.25174e-09 -6.67248e-10 4039.56 29.0663 -444.419 3994.79 -49.7495 3845.39 +EDGE_SE3:QUAT 85 136 5.87835 4.6678 -2.05787 0.160719 0.115498 -0.0355293 0.979575 1 7.82409e-19 7.82409e-19 5.68814e-08 1.27718e-09 1.39064e-08 1 7.82409e-19 5.68814e-08 1.27718e-09 1.39064e-08 1 5.68814e-08 1.27718e-09 1.39064e-08 4135.34 80.9377 1005.8 3947.51 38.2182 4233.62 +EDGE_SE3:QUAT 86 135 5.60579 -4.3696 -1.89782 0.147377 0.0158323 -0.0278409 0.988562 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3920.39 13.4951 171.225 3997.98 -1.14673 4004.17 +EDGE_SE3:QUAT 87 137 5.90194 -0.0231154 -2.02796 0.00575609 -0.0497218 -0.182809 0.981873 1 3.00927e-21 3.00927e-21 -3.4213e-09 6.42014e-10 1.54352e-10 1 3.00927e-21 -3.4213e-09 6.42014e-10 1.54352e-10 1 -3.4213e-09 6.42014e-10 1.54352e-10 4033.4 -10.8325 -368.161 3993.43 33.7741 3899.85 +EDGE_SE3:QUAT 86 137 5.50842 4.7657 -1.88254 0.0441778 0.098172 0.0651993 0.992048 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4133.65 32.7225 765.587 3968.21 36.7242 4124.45 +EDGE_SE3:QUAT 87 136 5.65055 -4.78779 -1.88278 0.108941 -0.0227805 -0.238131 0.964835 1 1.93345e-19 1.93345e-19 2.71979e-08 -4.91182e-09 6.58872e-10 1 1.93345e-19 2.71979e-08 -4.91182e-09 6.58872e-10 1 2.71979e-08 -4.91182e-09 6.58872e-10 3954.39 12.9737 133.326 3996.31 -28.8555 3775.04 +EDGE_SE3:QUAT 88 138 5.95033 -0.0723457 -2.13706 0.0823072 -0.229797 -0.0265628 0.969388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4907.31 -180.216 -2147.46 3820.94 174.659 4931.58 +EDGE_SE3:QUAT 87 138 5.78472 4.36299 -2.70199 0.0784875 0.0684495 -0.0715544 0.991985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4068.76 16.6607 618.545 3976.25 -13.383 4072.92 +EDGE_SE3:QUAT 88 137 5.41626 -4.52667 -1.84475 0.111224 0.0495457 -0.170798 0.977754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4040.02 18.7082 607.569 3974.8 -46.7636 3972.81 +EDGE_SE3:QUAT 89 139 6.05061 -0.0499731 -1.79146 -0.163442 0.0762577 -0.0954952 0.978955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3930.23 -34.6697 395.376 3996.23 -28.3045 4000.6 +EDGE_SE3:QUAT 88 139 5.68276 4.40607 -2.29125 -0.139727 -0.0771596 0.02817 0.986777 1 4.81482e-20 4.81482e-20 9.26049e-10 2.03806e-09 -1.3828e-08 1 4.81482e-20 9.26049e-10 2.03806e-09 -1.3828e-08 1 9.26049e-10 2.03806e-09 -1.3828e-08 3998.72 43.3024 -560.317 3984.56 -25.3854 4073.64 +EDGE_SE3:QUAT 89 138 5.50432 -4.59872 -2.0978 -0.219951 0.00912976 -0.0902432 0.971285 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3811.69 26.4245 -162.471 3996.39 10.0084 3972.63 +EDGE_SE3:QUAT 90 140 6.146 -0.0612203 -1.98155 -0.125398 -0.0271032 -0.0294879 0.991298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3953.43 16.3586 -256.348 3995.73 1.10366 4012.85 +EDGE_SE3:QUAT 89 140 5.70676 4.05343 -2.04309 0.11528 -0.0939823 0.136847 0.979362 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4160.14 -22.2547 -948.836 3946.44 -40.9185 4138.38 +EDGE_SE3:QUAT 90 139 5.58159 -4.26204 -2.13346 -0.00503463 -0.0761245 -0.0304296 0.996621 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4094.57 -2.70232 -622.607 3976.8 9.33654 4090.97 +EDGE_SE3:QUAT 91 141 6.05222 -0.118516 -1.77238 -0.0573134 -0.0982929 -0.0821885 0.9901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4165.74 5.91727 -864.673 3956.27 24.7193 4151.86 +EDGE_SE3:QUAT 90 141 5.54733 4.50247 -2.26705 -0.0647587 -0.0935053 0.0405733 0.992682 1 1.92593e-19 1.92593e-19 -2.79952e-08 -1.49915e-09 2.45469e-09 1 1.92593e-19 -2.79952e-08 -1.49915e-09 2.45469e-09 1 -2.79952e-08 -1.49915e-09 2.45469e-09 4111.95 33.4465 -729.197 3970.83 -28.8881 4122.14 +EDGE_SE3:QUAT 91 140 5.71233 -4.48282 -1.87264 0.0708596 0.0336825 -0.226147 0.970928 1 4.81482e-20 4.81482e-20 -1.35575e-08 3.07176e-09 -8.53826e-10 1 4.81482e-20 -1.35575e-08 3.07176e-09 -8.53826e-10 1 -1.35575e-08 3.07176e-09 -8.53826e-10 4026.78 3.91482 437.615 3986.96 -52.6431 3842.29 +EDGE_SE3:QUAT 92 142 6.02038 -0.140131 -2.15771 0.0441853 -0.0578117 -0.0725888 0.994704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4036.34 -14.4033 -422.87 3990.22 18.4015 4023.07 +EDGE_SE3:QUAT 91 142 5.52647 4.73795 -2.08966 0.151293 0.0866597 -0.040043 0.983868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4049.27 55.6263 763.675 3967.17 14.9601 4134.41 +EDGE_SE3:QUAT 92 141 5.64763 -4.46423 -2.18575 0.224165 0.0974455 -0.0189632 0.969482 1 1.88079e-22 1.88079e-22 -8.48159e-11 -1.9894e-10 -8.57638e-10 1 1.88079e-22 -8.48159e-11 -1.9894e-10 -8.57638e-10 1 -8.48159e-11 -1.9894e-10 -8.57638e-10 3951.73 93.7725 796.727 3971.55 45.6616 4151.29 +EDGE_SE3:QUAT 93 143 6.12743 -0.237457 -2.25377 0.0150013 -0.0519225 -0.140326 0.988629 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4034.97 -10.8514 -380.842 3992.5 27.3855 3957.1 +EDGE_SE3:QUAT 92 143 5.75792 4.40261 -1.74924 -0.0733214 0.0869919 0.0914807 0.989286 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4128.08 -12.1499 788.071 3962.74 24.1621 4116.11 +EDGE_SE3:QUAT 93 142 5.78023 -4.48745 -2.01564 -0.0232125 0.0545284 0.0729509 0.995573 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4049.59 0.0655626 457.924 3987.13 15.6663 4030.46 +EDGE_SE3:QUAT 94 144 6.06392 -0.114394 -2.30408 -0.0382792 -0.0030575 -0.0956876 0.99467 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.24 1.45361 -67.734 3999.58 3.88818 3964.47 +EDGE_SE3:QUAT 93 144 6.09722 4.76092 -1.89434 0.0550428 0.0795747 0.136302 0.985931 1 1.92593e-19 1.92593e-19 -4.04082e-09 2.73282e-08 -2.0857e-09 1 1.92593e-19 -4.04082e-09 2.73282e-08 -2.0857e-09 1 -4.04082e-09 2.73282e-08 -2.0857e-09 4057.41 30.4807 533.728 3987.35 42.306 3995.22 +EDGE_SE3:QUAT 94 143 5.29285 -4.65881 -1.93759 -0.0861935 -0.13555 -0.0305703 0.986541 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4293.1 46.1964 -1181.3 3925.1 -21.2693 4319.08 +EDGE_SE3:QUAT 95 145 5.76202 0.0132334 -2.31157 -0.0299473 0.0276979 0.0304689 0.998703 1 1.20371e-20 1.20371e-20 2.04511e-10 -1.9636e-10 6.94158e-09 1 1.20371e-20 2.04511e-10 -1.9636e-10 6.94158e-09 1 2.04511e-10 -1.9636e-10 6.94158e-09 4009.89 -2.95911 232.621 3996.56 3.03156 4009.77 +EDGE_SE3:QUAT 94 145 5.71322 4.64167 -1.94376 -0.0128426 -0.0915335 -0.0359277 0.995071 1 4.81482e-20 4.81482e-20 1.30167e-09 8.99556e-11 -1.40477e-08 1 4.81482e-20 1.30167e-09 8.99556e-11 -1.40477e-08 1 1.30167e-09 8.99556e-11 -1.40477e-08 4138.4 -2.28331 -758.681 3966.16 12.1544 4133.9 +EDGE_SE3:QUAT 95 144 5.21024 -4.72035 -2.33247 0.0324467 0.116439 -0.0976149 0.987857 1 2.40741e-19 2.40741e-19 -1.66853e-08 -2.61099e-08 -1.45319e-09 1 2.40741e-19 -1.66853e-08 -2.61099e-08 -1.45319e-09 1 -1.66853e-08 -2.61099e-08 -1.45319e-09 4234.32 -16.7352 1005.49 3943.98 -44.9978 4200.41 +EDGE_SE3:QUAT 96 146 5.8574 0.111144 -2.12462 0.0966326 -0.119506 0.0790755 0.98495 1 1.92593e-19 1.92593e-19 -2.82839e-08 -1.62449e-09 3.77376e-09 1 1.92593e-19 -2.82839e-08 -1.62449e-09 3.77376e-09 1 -2.82839e-08 -1.62449e-09 3.77376e-09 4240.53 -29.5803 -1090.44 3933.25 -10.8344 4252.87 +EDGE_SE3:QUAT 95 146 6.04354 4.40911 -2.48915 0.251542 -0.0582159 0.0874442 0.962128 1 1.92593e-19 1.92593e-19 -2.61408e-09 6.76776e-09 2.71123e-08 1 1.92593e-19 -2.61408e-09 6.76776e-09 2.71123e-08 1 -2.61408e-09 6.76776e-09 2.71123e-08 3861.73 -87.1608 -688.982 3971.41 4.57845 4084.24 +EDGE_SE3:QUAT 96 145 5.70777 -4.58063 -2.13144 -0.0292582 -0.0396155 -0.0219774 0.998545 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.95 4.01886 -325.9 3993.37 2.51742 4024.45 +EDGE_SE3:QUAT 97 147 6.12061 -0.163282 -2.16112 -0.171394 0.0195686 0.0836171 0.981453 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3907.05 -29.6722 317.986 3991.99 10.5159 3996.58 +EDGE_SE3:QUAT 96 147 5.62466 4.2977 -2.23614 -0.0723813 0.00694761 -0.00656863 0.997331 1 1.92593e-19 1.92593e-19 -2.76836e-08 2.08281e-10 -1.64484e-10 1 1.92593e-19 -2.76836e-08 2.08281e-10 -1.64484e-10 1 -2.76836e-08 2.08281e-10 -1.64484e-10 3979.65 -1.72306 49.4617 3999.86 -0.226056 4000.44 +EDGE_SE3:QUAT 97 146 5.29549 -4.53981 -1.81628 -0.0334573 -0.0448659 0.00122201 0.998432 1 1.88079e-22 1.88079e-22 -3.8912e-11 -2.93496e-11 8.69485e-10 1 1.88079e-22 -3.8912e-11 -2.93496e-11 8.69485e-10 1 -3.8912e-11 -2.93496e-11 8.69485e-10 4027.73 6.20875 -360.349 3992.05 -1.84988 4032.2 +EDGE_SE3:QUAT 98 148 5.89346 -0.4658 -2.13553 -0.0516021 -0.0224545 -0.0263318 0.998068 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.87 4.84035 -195.432 3997.52 1.9422 4006.75 +EDGE_SE3:QUAT 97 148 5.96937 4.81904 -2.15077 0.0795002 0.224369 0.0699218 0.968736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4792.48 217.034 1985.65 3855.53 216.076 4798.2 +EDGE_SE3:QUAT 98 147 5.47149 -4.31887 -1.84096 -0.128123 0.16109 0.0227734 0.978323 1 7.71547e-19 7.71547e-19 5.69775e-08 -8.44106e-10 7.22791e-09 1 7.71547e-19 5.69775e-08 -8.44106e-10 7.22791e-09 1 5.69775e-08 -8.44106e-10 7.22791e-09 4386.87 -100.611 1419.52 3903.28 -71.3275 4450.46 +EDGE_SE3:QUAT 99 149 6.16778 0.112732 -1.94956 -0.0793893 -0.00376685 -0.0686119 0.994473 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.91 4.44965 -94.5766 3999.17 3.7971 3983.29 +EDGE_SE3:QUAT 98 149 5.97363 4.60036 -2.14352 -0.0242218 0.0808822 -0.16793 0.982177 1 2.40741e-19 2.40741e-19 -8.95686e-09 2.96702e-08 4.3686e-10 1 2.40741e-19 -8.95686e-09 2.96702e-08 4.3686e-10 1 -8.95686e-09 2.96702e-08 4.3686e-10 4079.93 -29.777 580.599 3984.56 -52.8474 3969.48 +EDGE_SE3:QUAT 99 148 5.40001 -4.55747 -1.92673 -0.0956504 -0.157325 -0.0549483 0.981367 1 1.92593e-19 1.92593e-19 -2.87781e-08 7.54345e-10 4.82216e-09 1 1.92593e-19 -2.87781e-08 7.54345e-10 4.82216e-09 1 -2.87781e-08 7.54345e-10 4.82216e-09 4423.54 48.9495 -1432.61 3894.96 -17.8872 4448.06 +EDGE_SE3:QUAT 100 150 5.68103 -0.0342001 -2.11039 0.194622 -0.0153864 0.0475436 0.979605 1 1.20371e-20 1.20371e-20 -2.64511e-10 6.80023e-09 -1.336e-09 1 1.20371e-20 -2.64511e-10 6.80023e-09 -1.336e-09 1 -2.64511e-10 6.80023e-09 -1.336e-09 3860.84 -24.5887 -224.564 3996.19 -3.14775 4003.31 +EDGE_SE3:QUAT 99 150 5.77754 4.25843 -2.41296 -0.197879 -0.201697 0.0524534 0.957816 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4355.01 250.395 -1524.46 3942.85 -235.488 4500.63 +EDGE_SE3:QUAT 100 149 6.15811 -4.56509 -2.37138 0.00375219 -0.08186 0.120938 0.989272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4106.31 18.4835 -660.924 3975.83 -42.0002 4047.86 +EDGE_SE3:QUAT 101 151 5.93511 0.133961 -2.21135 -0.226921 -0.0327176 0.0158987 0.973234 1 7.70372e-19 7.70372e-19 -5.40952e-08 -1.59896e-09 1.23847e-09 1 7.70372e-19 -5.40952e-08 -1.59896e-09 1.23847e-09 1 -5.40952e-08 -1.59896e-09 1.23847e-09 3803.85 20.7539 -200.179 3998.69 -5.41123 4008.81 +EDGE_SE3:QUAT 100 151 5.98544 4.44489 -2.03434 -0.024801 0.00708336 0.0556312 0.998118 1 1.50463e-20 1.50463e-20 7.11857e-09 -3.07978e-09 -1.48842e-11 1 1.50463e-20 7.11857e-09 -3.07978e-09 -1.48842e-11 1 7.11857e-09 -3.07978e-09 -1.48842e-11 3998.86 -0.871403 72.8915 3999.62 2.13487 3988.94 +EDGE_SE3:QUAT 101 150 5.83939 -4.57891 -2.16852 0.0113842 0.0301983 0.0530778 0.998069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.12 2.43469 233.959 3996.72 6.42995 4002.37 +EDGE_SE3:QUAT 102 152 6.08276 -0.093896 -2.51903 0.178049 0.179095 -0.0445137 0.966562 1 1.54375e-18 1.54375e-18 -5.57368e-08 -5.43267e-08 2.32804e-09 1 1.54375e-18 -5.57368e-08 -5.43267e-08 2.32804e-09 1 -5.57368e-08 -5.43267e-08 2.32804e-09 4464.27 159.08 1647.39 3884.09 119.471 4583.15 +EDGE_SE3:QUAT 101 152 5.72867 4.31574 -1.723 -0.00290804 0.151129 0.0110102 0.988448 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4392.18 4.38583 1312.51 3908.65 7.21054 4391.73 +EDGE_SE3:QUAT 102 151 5.6786 -4.65251 -2.13881 -0.0857204 -0.12337 -0.0536819 0.987193 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4248.98 32.6288 -1091.37 3933.79 -1.681 4266.85 +EDGE_SE3:QUAT 103 153 5.65447 -0.210372 -2.22945 0.132763 0.00501152 -0.160417 0.978067 1 7.70372e-19 7.70372e-19 2.57375e-09 6.92224e-09 5.44285e-08 1 7.70372e-19 2.57375e-09 6.92224e-09 5.44285e-08 1 2.57375e-09 6.92224e-09 5.44285e-08 3948.55 21.4696 287.136 3991.86 -27.196 3916.12 +EDGE_SE3:QUAT 102 153 5.78676 4.71682 -2.17633 -0.0457525 -0.0754561 0.0773447 0.993092 1 4.81482e-20 4.81482e-20 -1.39161e-08 -1.18827e-09 9.39952e-10 1 4.81482e-20 -1.39161e-08 -1.18827e-09 9.39952e-10 1 -1.39161e-08 -1.18827e-09 9.39952e-10 4069.21 22.7104 -562.795 3982.9 -27.9391 4053.66 +EDGE_SE3:QUAT 103 152 5.50321 -4.53439 -2.13971 -0.140555 -0.114572 -0.0221737 0.983171 1 3.00927e-21 3.00927e-21 -4.14446e-10 -4.96446e-10 3.50701e-09 1 3.00927e-21 -4.14446e-10 -4.96446e-10 3.50701e-09 1 -4.14446e-10 -4.96446e-10 3.50701e-09 4144.63 70.7465 -971.93 3950.4 -36.2465 4221.68 +EDGE_SE3:QUAT 104 154 6.19576 -0.0324169 -2.22069 0.174011 0.150272 -0.0780459 0.970076 1 4.81482e-20 4.81482e-20 2.45455e-09 2.30369e-09 1.42448e-08 1 4.81482e-20 2.45455e-09 2.30369e-09 1.42448e-08 1 2.45455e-09 2.30369e-09 1.42448e-08 4341.77 106.955 1437.38 3899.03 51.4446 4438.53 +EDGE_SE3:QUAT 103 154 6.06937 4.85158 -2.44088 -0.0721587 -0.000782 0.0383966 0.996654 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.32 -1.36609 26.9073 3999.91 0.719731 3994.25 +EDGE_SE3:QUAT 104 153 5.26878 -4.56792 -2.49804 0.0180782 -0.0217952 -0.0445709 0.998605 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.43 -1.92547 -164.331 3998.4 3.79114 3998.79 +EDGE_SE3:QUAT 105 155 5.96825 -0.51389 -2.3323 0.0903531 -0.0270985 0.0398092 0.994745 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.82 -11.4234 -257.534 3995.58 -3.34097 4010.14 +EDGE_SE3:QUAT 104 155 5.44153 4.85124 -2.37167 -0.100869 -0.131802 -0.207367 0.964081 1 1.92593e-19 1.92593e-19 -2.8141e-08 5.40001e-09 4.67063e-09 1 1.92593e-19 -2.8141e-08 5.40001e-09 4.67063e-09 1 -2.8141e-08 5.40001e-09 4.67063e-09 4363.27 -39.981 -1334.18 3910.57 115.58 4231.97 +EDGE_SE3:QUAT 105 154 5.37789 -4.76272 -2.16652 -0.167024 0.100563 -0.151038 0.969112 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3933.79 -45.6296 449.255 3999.42 -44.5161 3954.13 +EDGE_SE3:QUAT 106 156 5.48335 0.164469 -2.37914 -0.033402 0.240162 -0.00578544 0.970141 1 4.81482e-20 4.81482e-20 -1.52085e-08 3.78072e-10 -3.7481e-09 1 4.81482e-20 -1.52085e-08 3.78072e-10 -3.7481e-09 1 -1.52085e-08 3.78072e-10 -3.7481e-09 5097.98 -75.6757 2371.74 3773.96 -73.2251 5102.31 +EDGE_SE3:QUAT 105 156 5.39645 4.74384 -2.26455 0.00491827 0.169224 0.0862917 0.98178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4483.66 71.5569 1472.82 3895.31 86.5205 4453.97 +EDGE_SE3:QUAT 106 155 5.20224 -4.63366 -1.80122 -0.0232487 0.216733 -0.0165279 0.975814 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4861.61 -59.565 2049.68 3816.09 -58.6994 4862.67 +EDGE_SE3:QUAT 107 157 5.87013 0.069606 -2.22277 0.0948351 -0.0388782 0.0103425 0.99468 1 7.52316e-22 7.52316e-22 -6.98355e-11 1.64122e-10 1.73103e-09 1 7.52316e-22 -6.98355e-11 1.64122e-10 1.73103e-09 1 -6.98355e-11 1.64122e-10 1.73103e-09 3989.51 -15.1637 -320.306 3993.78 1.91776 4025.06 +EDGE_SE3:QUAT 106 157 5.6878 4.47088 -2.28782 -0.099609 -0.113639 0.155579 0.976196 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4074.42 66.6513 -691.559 3985.47 -74.0488 4017.29 +EDGE_SE3:QUAT 107 156 5.67796 -4.55915 -2.42411 -0.0093523 -0.0160112 0.0265325 0.999476 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.56 0.738826 -125.066 3999.04 -1.70512 4001.09 +EDGE_SE3:QUAT 108 158 5.8139 0.0165993 -2.16605 0.0813573 -0.0461041 0.0676018 0.99332 1 4.81482e-20 4.81482e-20 8.26693e-10 -1.37922e-08 1.03829e-09 1 4.81482e-20 8.26693e-10 -1.37922e-08 1.03829e-09 1 8.26693e-10 -1.37922e-08 1.03829e-09 4019.77 -14.4481 -432.94 3987.8 -10.3456 4027.97 +EDGE_SE3:QUAT 107 158 5.86085 4.30797 -2.13958 -0.0428263 0.139334 -0.0187099 0.989142 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4313.7 -39.7044 1177.82 3926.09 -34.7667 4319.64 +EDGE_SE3:QUAT 108 157 5.83727 -4.8913 -2.16558 -0.0286649 0.103727 -0.0892542 0.990178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4156.21 -35.1554 814.722 3964.65 -46.8748 4127.63 +EDGE_SE3:QUAT 109 159 6.28175 0.192764 -2.09186 -0.110878 0.149714 0.0168208 0.982349 1 9.63998e-19 9.63998e-19 2.79385e-08 -5.5261e-08 2.88144e-10 1 9.63998e-19 2.79385e-08 -5.5261e-08 2.88144e-10 1 2.79385e-08 -5.5261e-08 2.88144e-10 4335.37 -79.368 1298.51 3915.27 -53.5864 4383.42 +EDGE_SE3:QUAT 108 159 5.56366 5.11638 -2.37317 0.00842961 0.0579049 0.0357954 0.997645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4052.83 4.90153 463.969 3987.02 9.24613 4047.99 +EDGE_SE3:QUAT 109 158 5.69338 -4.65254 -2.14413 0.136482 0.0250788 -0.132577 0.981411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3965.38 26.3383 406.044 3986.99 -25.2046 3969.58 +EDGE_SE3:QUAT 110 160 6.14775 0.239705 -2.08036 -0.00906701 -0.0242712 -0.098949 0.994755 1 1.92593e-19 1.92593e-19 -7.1089e-10 -1.14402e-10 2.76456e-08 1 1.92593e-19 -7.1089e-10 -1.14402e-10 2.76456e-08 1 -7.1089e-10 -1.14402e-10 2.76456e-08 4009.89 -0.564472 -202.464 3997.48 10.075 3971.06 +EDGE_SE3:QUAT 109 160 5.70115 5.00433 -2.0722 0.00318279 0.228043 0.0574701 0.971948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4966.97 98.1763 2191.63 3801.23 104.091 4953.8 +EDGE_SE3:QUAT 110 159 5.53199 -4.90977 -2.16362 -0.143631 -0.0163397 -0.0302997 0.989032 1 7.70372e-19 7.70372e-19 -5.49576e-08 1.35716e-09 1.3476e-09 1 7.70372e-19 -5.49576e-08 1.35716e-09 1.3476e-09 1 -5.49576e-08 1.35716e-09 1.3476e-09 3925.37 13.6869 -178.348 3997.79 1.42343 4004.22 +EDGE_SE3:QUAT 111 161 5.82257 -0.488347 -2.20629 0.0748555 0.0127568 -0.082406 0.993702 1 1.92593e-19 1.92593e-19 -2.76066e-08 2.21206e-09 -6.86423e-10 1 1.92593e-19 -2.76066e-08 2.21206e-09 -6.86423e-10 1 -2.76066e-08 2.21206e-09 -6.86423e-10 3985 6.65742 173.913 3997.62 -7.47795 3980.25 +EDGE_SE3:QUAT 110 161 5.70577 4.50768 -2.17314 -0.0627111 0.139226 0.0843612 0.984666 1 4.81482e-20 4.81482e-20 -1.42721e-08 -1.00436e-09 -2.13202e-09 1 4.81482e-20 -1.42721e-08 -1.00436e-09 -2.13202e-09 1 -1.42721e-08 -1.00436e-09 -2.13202e-09 4344.2 -1.73068 1252.75 3915.52 30.4293 4331.46 +EDGE_SE3:QUAT 111 160 5.36739 -4.54449 -2.21982 0.00788916 -0.0348666 -0.0399669 0.998561 1 5.11575e-20 5.11575e-20 -3.94725e-09 2.89687e-10 1.40092e-08 1 5.11575e-20 -3.94725e-09 2.89687e-10 1.40092e-08 1 -3.94725e-09 2.89687e-10 1.40092e-08 4018.65 -2.23939 -275.579 3995.38 5.77225 4012.51 +EDGE_SE3:QUAT 112 162 5.69587 -0.112562 -2.56935 0.0974313 -0.0818923 -0.130514 0.983243 1 1.92593e-19 1.92593e-19 2.74877e-08 -4.06394e-09 -1.45458e-09 1 1.92593e-19 2.74877e-08 -4.06394e-09 -1.45458e-09 1 2.74877e-08 -4.06394e-09 -1.45458e-09 4018.33 -35.2529 -482.638 3991.8 39.2376 3988.17 +EDGE_SE3:QUAT 111 162 5.69451 4.85407 -1.98233 -0.0213171 -0.0576173 0.0124678 0.998033 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.98 6.08566 -462.576 3987.04 -4.68115 4052.17 +EDGE_SE3:QUAT 112 161 5.30234 -4.57593 -2.30976 0.0414861 0.199638 -0.0540051 0.9775 1 4.81482e-20 4.81482e-20 -3.06198e-09 -3.31532e-10 -1.47743e-08 1 4.81482e-20 -3.06198e-09 -3.31532e-10 -1.47743e-08 1 -3.06198e-09 -3.31532e-10 -1.47743e-08 4734.95 -8.49822 1875.54 3837.22 -23.4848 4730.17 +EDGE_SE3:QUAT 113 163 5.99735 0.0622654 -1.95881 -0.0963118 0.144451 0.0615767 0.982887 1 2.40741e-19 2.40741e-19 3.08222e-08 -1.81358e-10 1.87488e-08 1 2.40741e-19 3.08222e-08 -1.81358e-10 1.87488e-08 1 3.08222e-08 -1.81358e-10 1.87488e-08 4353.85 -41.8134 1310.25 3909.19 -7.61191 4375.78 +EDGE_SE3:QUAT 112 163 5.78041 4.85364 -2.01438 0.153289 0.0835801 0.0593931 0.982847 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.07 47.6598 540.577 3988.22 34.5051 4056.95 +EDGE_SE3:QUAT 113 162 5.5137 -4.64294 -2.35126 -0.0565865 -0.119254 -0.0898493 0.987169 1 1.92593e-19 1.92593e-19 -3.63935e-09 -1.01958e-09 2.82933e-08 1 1.92593e-19 -3.63935e-09 -1.01958e-09 2.82933e-08 1 -3.63935e-09 -1.01958e-09 2.82933e-08 4249.83 -0.615761 -1058.14 3937.28 33.3564 4230.35 +EDGE_SE3:QUAT 114 164 5.907 -0.00350745 -2.34458 -0.0422332 -0.0816848 0.0791445 0.992613 1 4.81482e-20 4.81482e-20 -1.39359e-08 -1.21894e-09 1.03312e-09 1 4.81482e-20 -1.39359e-08 -1.21894e-09 1.03312e-09 1 -1.39359e-08 -1.21894e-09 1.03312e-09 4085.85 25.171 -617.206 3979.42 -31.5816 4067.93 +EDGE_SE3:QUAT 113 164 5.37353 4.45766 -2.25897 0.0822386 -0.0338236 0.171598 0.981146 1 1.92593e-19 1.92593e-19 2.73885e-08 4.58794e-09 -1.65205e-09 1 1.92593e-19 2.73885e-08 4.58794e-09 -1.65205e-09 1 2.73885e-08 4.58794e-09 -1.65205e-09 4017.4 -10.0186 -426.23 3987.09 -37.0026 3926.66 +EDGE_SE3:QUAT 114 163 5.52703 -4.7554 -2.07657 -0.074737 0.0181503 0.0369382 0.996354 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.45 -6.63646 177.003 3997.85 2.66669 4002.34 +EDGE_SE3:QUAT 115 165 5.97242 0.222059 -2.44573 -0.0744257 0.0374999 -0.0626129 0.994552 1 1.92593e-19 1.92593e-19 2.76543e-08 -1.8807e-09 7.64196e-10 1 1.92593e-19 2.76543e-08 -1.8807e-09 7.64196e-10 1 2.76543e-08 -1.8807e-09 7.64196e-10 3992.17 -9.83425 240.74 3997.16 -8.80127 3998.64 +EDGE_SE3:QUAT 114 165 5.78725 4.8512 -2.40048 -0.145749 0.0646267 0.0867926 0.983386 1 9.62965e-19 9.62965e-19 5.71409e-08 -2.36703e-08 1.12301e-09 1 9.62965e-19 5.71409e-08 -2.36703e-08 1.12301e-09 1 5.71409e-08 -2.36703e-08 1.12301e-09 4021.09 -41.2404 660.833 3972.36 10.5171 4075.92 +EDGE_SE3:QUAT 115 164 5.72919 -4.70369 -2.14633 -0.136588 0.0908014 0.200263 0.965916 1 1.92593e-19 1.92593e-19 2.76963e-08 4.94803e-09 3.85322e-09 1 1.92593e-19 2.76963e-08 4.94803e-09 3.85322e-09 1 2.76963e-08 4.94803e-09 3.85322e-09 4180.4 -15.3866 1043.7 3935.66 78.7962 4094.61 +EDGE_SE3:QUAT 116 166 6.00206 -0.0399233 -2.24463 -0.0545581 -0.120845 0.0685171 0.9888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4202.8 52.6481 -951.58 3953.4 -55.3583 4195.93 +EDGE_SE3:QUAT 115 166 5.59775 4.90762 -2.30729 -0.0267909 -0.00206288 0.10257 0.994363 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.17 -0.366785 16.5029 3999.95 1.41411 3957.96 +EDGE_SE3:QUAT 116 165 5.46043 -4.47872 -2.13665 0.00944792 0.0505477 -0.130213 0.990152 1 1.88079e-22 1.88079e-22 8.63405e-10 -1.13293e-10 4.47079e-11 1 1.88079e-22 8.63405e-10 -1.13293e-10 4.47079e-11 1 8.63405e-10 -1.13293e-10 4.47079e-11 4041.74 -6.28467 412.518 3990.2 -27.096 3974.28 +EDGE_SE3:QUAT 117 167 6.17368 -0.249457 -2.07193 -0.216387 0.127363 0.0670752 0.965638 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4143.82 -125.555 1197.54 3931.26 -60.3176 4313.11 +EDGE_SE3:QUAT 116 167 5.43975 4.93332 -2.31049 -0.0915235 -0.0292284 0.181472 0.978692 1 1.95602e-19 1.95602e-19 -2.65229e-08 -8.49481e-09 -4.92324e-10 1 1.95602e-19 -2.65229e-08 -8.49481e-09 -4.92324e-10 1 -2.65229e-08 -8.49481e-09 -4.92324e-10 3965.41 -1.79223 -25.4681 3999.97 4.0104 3867.19 +EDGE_SE3:QUAT 117 166 5.5215 -4.56089 -2.08469 0.0179384 0.0515981 -0.0963629 0.993846 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4044.82 -2.59475 431.912 3988.72 -20.4294 4008.96 +EDGE_SE3:QUAT 118 168 5.70346 0.114378 -2.3118 0.0740823 0.0966832 -0.10611 0.986866 1 1.92593e-19 1.92593e-19 -3.10661e-09 -1.51241e-09 -2.80327e-08 1 1.92593e-19 -3.10661e-09 -1.51241e-09 -2.80327e-08 1 -3.10661e-09 -1.51241e-09 -2.80327e-08 4164.84 8.0473 884.568 3954.07 -33.076 4141.76 +EDGE_SE3:QUAT 117 168 5.19824 4.97491 -2.07317 -0.136894 -0.00963978 -0.276058 0.951294 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.98 27.0276 -498.993 3977.29 81.6285 3753.11 +EDGE_SE3:QUAT 118 167 5.65079 -4.73513 -2.5933 -0.000561405 -0.146582 0.0488565 0.987991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4364.16 28.3058 -1260.66 3916.05 -38.1549 4354.61 +EDGE_SE3:QUAT 119 169 5.89955 0.278023 -2.58552 -0.15002 -0.0200892 -0.147068 0.977477 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3950.53 30.6218 -411.644 3985.84 29.7366 3954.04 +EDGE_SE3:QUAT 118 169 5.6874 4.86794 -1.92334 -0.111171 -0.0372485 -0.113252 0.986624 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.13 20.5255 -440.73 3986.22 21.1754 3996.26 +EDGE_SE3:QUAT 119 168 5.31853 -4.68032 -2.4232 -0.163457 -0.0556607 0.0449714 0.983952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3921.59 27.8876 -341.093 3995.44 -15.2858 4020.37 +EDGE_SE3:QUAT 120 170 5.76497 -0.112431 -2.43456 0.133515 0.180039 -0.0645437 0.972417 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4559.49 93.8835 1709.13 3863.66 57.1195 4614.13 +EDGE_SE3:QUAT 119 170 5.88809 4.67811 -2.09043 -0.0815608 0.0198303 0.190933 0.978008 1 7.70372e-19 7.70372e-19 2.70917e-09 -3.80492e-09 5.44798e-08 1 7.70372e-19 2.70917e-09 -3.80492e-09 5.44798e-08 1 2.70917e-09 -3.80492e-09 5.44798e-08 4000.19 -9.80701 332.393 3991.29 35.0214 3880.98 +EDGE_SE3:QUAT 120 169 5.66763 -4.84311 -2.08911 0.0836774 -0.0334458 0.142862 0.985632 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.54 -11.5059 -401.574 3988.52 -28.0346 3957.91 +EDGE_SE3:QUAT 121 171 5.96551 -0.122696 -2.50557 -0.014533 0.113099 0.0211515 0.993252 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4213.38 -0.900587 950.142 3948.49 6.65285 4212.43 +EDGE_SE3:QUAT 120 171 5.51606 4.77474 -2.12168 -0.043486 0.0646277 0.167878 0.982725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.07 7.03327 591.632 3979.53 48.615 3972.9 +EDGE_SE3:QUAT 121 170 5.28858 -5.07133 -2.08428 -0.0402974 -0.0418958 -0.0392487 0.997537 1 4.81482e-20 4.81482e-20 1.38978e-08 -4.99935e-10 -6.24189e-10 1 4.81482e-20 1.38978e-08 -4.99935e-10 -6.24189e-10 1 1.38978e-08 -4.99935e-10 -6.24189e-10 4024.76 5.60176 -355.022 3992.05 5.36056 4025.1 +EDGE_SE3:QUAT 122 172 5.55422 0.148304 -2.34678 -0.00776983 -0.0104745 -0.0755213 0.997059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.79 0.13521 -90.129 3999.48 3.46412 3979.22 +EDGE_SE3:QUAT 121 172 5.47364 4.96378 -2.307 0.276596 -0.174132 0.0529793 0.943592 1 7.71124e-19 7.71124e-19 -2.41047e-09 -5.29036e-08 1.35628e-08 1 7.71124e-19 -2.41047e-09 -5.29036e-08 1.35628e-08 1 -2.41047e-09 -5.29036e-08 1.35628e-08 4237.06 -249.127 -1571.7 3923.37 192.669 4531.86 +EDGE_SE3:QUAT 122 171 5.43698 -5.01811 -1.78277 -0.062094 -0.0585538 -0.0125755 0.996272 1 4.81482e-20 4.81482e-20 -1.39246e-08 7.36652e-11 8.3375e-10 1 4.81482e-20 -1.39246e-08 7.36652e-11 8.3375e-10 1 -1.39246e-08 7.36652e-11 8.3375e-10 4041.59 14.4733 -480.959 3985.98 -2.17294 4056.38 +EDGE_SE3:QUAT 123 173 5.8929 0.21067 -2.28319 -0.110039 0.0559489 0.100094 0.98729 1 1.92593e-19 1.92593e-19 2.11523e-09 -2.73408e-09 2.76831e-08 1 1.92593e-19 2.11523e-09 -2.73408e-09 2.76831e-08 1 2.11523e-09 -2.73408e-09 2.76831e-08 4032.14 -23.9313 574.387 3978.39 19.6335 4040.5 +EDGE_SE3:QUAT 122 173 5.87044 4.85714 -2.51818 -0.0364625 -0.0525102 0.0274495 0.997577 1 4.81482e-20 4.81482e-20 -1.39162e-08 -4.3756e-10 7.01366e-10 1 4.81482e-20 -1.39162e-08 -4.3756e-10 7.01366e-10 1 -1.39162e-08 -4.3756e-10 7.01366e-10 4036.35 9.36163 -410.384 3990 -8.05561 4038.65 +EDGE_SE3:QUAT 123 172 5.25891 -4.84878 -1.95557 -0.11287 0.0647411 -0.0838584 0.987946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.65 -26.0517 392.569 3993.71 -22.7387 4009.48 +EDGE_SE3:QUAT 124 174 5.97279 0.208251 -2.02125 0.196845 -0.0854467 -0.0921144 0.972351 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3887.24 -43.2147 -425.119 3997.22 33.9208 4008.3 +EDGE_SE3:QUAT 123 174 5.34111 4.99667 -2.43079 0.0314588 -0.0128262 0.11959 0.992242 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.26 -1.68187 -145.145 3998.48 -9.33631 3948.01 +EDGE_SE3:QUAT 124 173 5.14176 -4.98473 -2.62517 -0.0466675 0.119841 0.0565314 0.990083 1 1.92593e-19 1.92593e-19 -1.29349e-09 2.74947e-08 9.42819e-10 1 1.92593e-19 -1.29349e-09 2.74947e-08 9.42819e-10 1 -1.29349e-09 2.74947e-08 9.42819e-10 4244.65 -6.36182 1038.12 3939.29 16.1524 4240.58 +EDGE_SE3:QUAT 125 175 6.22362 0.272739 -2.71356 -0.0602668 0.0343075 -0.102414 0.992322 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.81 -6.889 195.495 3998.42 -9.76121 3967.38 +EDGE_SE3:QUAT 124 175 5.39525 4.87722 -2.10146 0.0823308 0.0371549 0.125287 0.988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.17 6.79919 165.235 3999.37 8.80445 3943.49 +EDGE_SE3:QUAT 125 174 5.35901 -4.96771 -2.24247 0.141533 -0.0478475 -0.181441 0.971987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3917.49 3.13892 -54.6033 4000.18 -4.52717 3865.93 +EDGE_SE3:QUAT 126 176 5.86799 -0.14686 -2.20328 -0.0884716 0.0150815 0.0169955 0.99582 1 1.50463e-20 1.50463e-20 3.57887e-11 -6.60487e-09 -4.06732e-09 1 1.50463e-20 3.57887e-11 -6.60487e-09 -4.06732e-09 1 3.57887e-11 -6.60487e-09 -4.06732e-09 3973.39 -6.22022 137.286 3998.76 0.622501 4003.54 +EDGE_SE3:QUAT 125 176 5.56908 4.99421 -2.80511 0.244913 -0.149318 -0.0450083 0.95692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.49 -154.571 -994.681 3979.4 127.893 4222.31 +EDGE_SE3:QUAT 126 175 5.32303 -4.56035 -2.2881 -0.0110544 0.108911 -0.0387126 0.993236 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4192.79 -17.111 900.277 3954.06 -22.8467 4187.29 +EDGE_SE3:QUAT 127 177 5.91717 -0.0245539 -2.27714 0.0201436 -0.0624911 0.165718 0.983985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4066.54 11.4342 -526.574 3984.61 -44.0216 3958.31 +EDGE_SE3:QUAT 126 177 5.70013 5.21512 -2.09403 0.0791176 0.0935656 0.165183 0.978622 1 7.70372e-19 7.70372e-19 5.48612e-08 1.01082e-08 3.41887e-09 1 7.70372e-19 5.48612e-08 1.01082e-08 3.41887e-09 1 5.48612e-08 1.01082e-08 3.41887e-09 4051.41 44.2754 563.458 3989.61 55.3535 3967.3 +EDGE_SE3:QUAT 127 176 5.76226 -5.10333 -2.02638 -0.0879082 -0.046366 0.00635315 0.995029 1 1.92593e-19 1.92593e-19 2.77307e-08 4.02087e-10 -1.24085e-09 1 1.92593e-19 2.77307e-08 4.02087e-10 -1.24085e-09 1 2.77307e-08 4.02087e-10 -1.24085e-09 4001.66 16.4374 -362.458 3992.34 -5.55356 4032.41 +EDGE_SE3:QUAT 128 178 5.84615 -0.0527712 -2.3096 0.102295 0.0989206 0.0557658 0.988251 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4085.23 50.5622 725.063 3974.11 42.4041 4114.65 +EDGE_SE3:QUAT 127 178 5.88089 5.35008 -2.50151 -0.120261 -0.104568 0.20997 0.964632 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.83 47.0589 -470.478 4000.21 -53.317 3873.33 +EDGE_SE3:QUAT 128 177 5.87215 -4.93492 -1.84427 0.0648771 0.00755182 0.0274522 0.997487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.52 1.03815 38.6644 3999.94 0.477027 3997.35 +EDGE_SE3:QUAT 129 179 5.59952 0.214617 -2.58177 0.215776 -0.0213576 -0.220139 0.951064 1 7.70372e-19 7.70372e-19 -5.30159e-08 1.16032e-08 -4.06841e-09 1 7.70372e-19 -5.30159e-08 1.16032e-08 -4.06841e-09 1 -5.30159e-08 1.16032e-08 -4.06841e-09 3844.21 57.5637 389.563 3979.59 -58.9685 3836.6 +EDGE_SE3:QUAT 128 179 5.59614 4.73591 -2.00136 0.130511 -0.0552514 0.0973015 0.985113 1 7.70372e-19 7.70372e-19 5.52692e-08 4.50995e-09 -4.35312e-09 1 7.70372e-19 5.52692e-08 4.50995e-09 -4.35312e-09 1 5.52692e-08 4.50995e-09 -4.35312e-09 4015.73 -31.6845 -586.448 3977.35 -16.8987 4045.99 +EDGE_SE3:QUAT 129 178 5.40435 -4.87834 -2.49152 0.165083 0.0367477 -0.219336 0.960879 1 9.62965e-19 9.62965e-19 -5.96446e-08 -1.57077e-08 -1.95665e-09 1 9.62965e-19 -5.96446e-08 -1.57077e-08 -1.95665e-09 1 -5.96446e-08 -1.57077e-08 -1.95665e-09 4005.75 40.1754 695.433 3963.39 -71.2617 3922.33 +EDGE_SE3:QUAT 130 180 5.73614 -0.394684 -2.31595 0.178338 0.205814 -0.0616913 0.960224 1 1.58889e-18 1.58889e-18 -5.47165e-08 -5.16983e-08 1.09166e-08 1 1.58889e-18 -5.47165e-08 -5.16983e-08 1.09166e-08 1 -5.47165e-08 -5.16983e-08 1.09166e-08 4706.51 185.719 2007.51 3840.06 150.76 4818.51 +EDGE_SE3:QUAT 129 180 5.53828 5.13995 -2.44252 -0.0186057 0.0385085 0.0876941 0.995229 1 3.00927e-21 3.00927e-21 3.46434e-09 3.01014e-10 1.43242e-10 1 3.00927e-21 3.46434e-09 3.01014e-10 1.43242e-10 1 3.46434e-09 3.01014e-10 1.43242e-10 4024.97 0.285328 325.782 3993.42 14.0306 3995.59 +EDGE_SE3:QUAT 130 179 5.2083 -5.25966 -2.4132 -0.0657843 0.181662 -0.0499509 0.979886 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4517.05 -111.812 1556.84 3890.02 -109.201 4524.38 +EDGE_SE3:QUAT 131 181 5.79406 -0.123834 -2.21826 -0.0967369 -0.0605459 0.0547963 0.991954 1 4.81482e-20 4.81482e-20 -6.75469e-10 -1.44308e-09 1.38401e-08 1 4.81482e-20 -6.75469e-10 -1.44308e-09 1.38401e-08 1 -6.75469e-10 -1.44308e-09 1.38401e-08 4005.1 23.4115 -415.522 3991.37 -17.8606 4030.52 +EDGE_SE3:QUAT 130 181 5.90307 4.95299 -2.68126 -0.0202398 -0.189278 0.20007 0.961112 1 7.70372e-19 7.70372e-19 9.69985e-09 5.80957e-09 -5.6803e-08 1 7.70372e-19 9.69985e-09 5.80957e-09 -5.6803e-08 1 9.69985e-09 5.80957e-09 -5.6803e-08 4507.22 196.064 -1517.2 3927.37 -220.069 4348.74 +EDGE_SE3:QUAT 131 180 5.33178 -4.77937 -2.30748 -0.0199113 -0.211525 -0.00252576 0.977167 1 4.70198e-23 4.70198e-23 -1.00713e-10 -9.86968e-12 4.65422e-10 1 4.70198e-23 -1.00713e-10 -9.86968e-12 4.65422e-10 1 -1.00713e-10 -9.86968e-12 4.65422e-10 4822.84 26.1931 -1994.33 3821.55 -23.0983 4824.4 +EDGE_SE3:QUAT 132 182 5.60687 -0.122765 -2.42271 0.0459016 -0.0208883 0.0668063 0.996491 1 1.92593e-19 1.92593e-19 7.42968e-10 -1.18817e-09 -2.76937e-08 1 1.92593e-19 7.42968e-10 -1.18817e-09 -2.76937e-08 1 7.42968e-10 -1.18817e-09 -2.76937e-08 4001.78 -3.99397 -202.604 3997.2 -6.54445 3992.35 +EDGE_SE3:QUAT 131 182 5.60339 5.20283 -2.06299 0.0172481 0.0668086 0.075246 0.994775 1 2.0463e-19 2.0463e-19 4.79105e-09 2.81513e-08 -3.1384e-10 1 2.0463e-19 4.79105e-09 2.81513e-08 -3.1384e-10 1 4.79105e-09 2.81513e-08 -3.1384e-10 4065.66 12.409 521.474 3984.41 22.0313 4044.2 +EDGE_SE3:QUAT 132 181 5.42393 -4.91206 -2.55235 -0.166884 -0.0179568 -0.150011 0.974332 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3932.2 36.7292 -428.293 3984.26 31.3824 3953.59 +EDGE_SE3:QUAT 133 183 5.84813 0.21541 -2.36346 -0.0598996 0.0354926 -0.0158443 0.997447 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.05 -8.56734 271.996 3995.64 -3.84421 4017.4 +EDGE_SE3:QUAT 132 183 5.25092 5.08892 -2.4484 -0.201409 -0.0957857 -0.00256203 0.974809 1 1.20371e-20 1.20371e-20 6.2763e-10 1.44517e-09 -6.88195e-09 1 1.20371e-20 6.2763e-10 1.44517e-09 -6.88195e-09 1 6.2763e-10 1.44517e-09 -6.88195e-09 3972.5 80.4658 -747.043 3974.73 -42.3567 4134.74 +EDGE_SE3:QUAT 133 182 5.30217 -5.2572 -2.40463 0.00480171 -0.0395639 -0.0648118 0.997101 1 7.52316e-22 7.52316e-22 -1.73495e-09 1.1378e-10 6.71728e-11 1 7.52316e-22 -1.73495e-09 1.1378e-10 6.71728e-11 1 -1.73495e-09 1.1378e-10 6.71728e-11 4024.16 -3.14667 -312.412 3994.15 10.4027 4007.45 +EDGE_SE3:QUAT 134 184 5.92794 0.255991 -2.60956 0.0342711 0.172944 -0.0169052 0.98419 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4524.17 20.9696 1547.63 3879.84 11.4179 4527.72 +EDGE_SE3:QUAT 133 184 5.67384 5.1733 -2.45621 0.00302853 0.0955032 0.0219984 0.995181 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4149.43 6.32811 787.527 3963.78 10.1836 4147.53 +EDGE_SE3:QUAT 134 183 5.42816 -5.12901 -2.62488 0.0576205 0.0964441 -0.0816685 0.990307 1 2.40741e-19 2.40741e-19 1.69898e-08 1.7905e-10 2.95534e-08 1 2.40741e-19 1.69898e-08 1.7905e-10 2.95534e-08 1 1.69898e-08 1.7905e-10 2.95534e-08 4159.17 6.40136 848.339 3957.76 -24.0805 4145.77 +EDGE_SE3:QUAT 135 185 5.36391 -0.0397055 -2.31117 0.0622611 0.0157506 0.144451 0.987426 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.2 -0.619492 15.1815 3999.99 -1.58268 3916.25 +EDGE_SE3:QUAT 134 185 5.8027 5.21114 -2.78348 0.167547 0.0308839 -0.0452737 0.98434 1 7.70372e-19 7.70372e-19 5.4828e-08 -1.81709e-09 2.45096e-09 1 7.70372e-19 5.4828e-08 -1.81709e-09 2.45096e-09 1 5.4828e-08 -1.81709e-09 2.45096e-09 3914.22 28.4049 327.386 3992.9 -2.01736 4018.31 +EDGE_SE3:QUAT 135 184 5.0093 -5.05313 -2.26938 -0.0963778 0.0858117 0.0394661 0.990853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4096.24 -31.4541 742.59 3967.52 -3.13888 4127.16 +EDGE_SE3:QUAT 136 186 5.54717 0.0722619 -2.37288 0.00665845 0.0089089 0.055289 0.998408 1 4.89006e-20 4.89006e-20 -1.84488e-09 -2.01656e-10 -1.38717e-08 1 4.89006e-20 -1.84488e-09 -2.01656e-10 -1.38717e-08 1 -1.84488e-09 -2.01656e-10 -1.38717e-08 4000.93 0.311318 66.5465 3999.74 1.80872 3988.88 +EDGE_SE3:QUAT 135 186 5.30487 5.03863 -2.56942 0.0156249 -0.0174052 0.0820015 0.996358 1 2.40741e-20 2.40741e-20 -7.48407e-09 6.34817e-09 4.96358e-11 1 2.40741e-20 -7.48407e-09 6.34817e-09 4.96358e-11 1 -7.48407e-09 6.34817e-09 4.96358e-11 4004.89 -0.542467 -153.302 3998.48 -6.36576 3978.97 +EDGE_SE3:QUAT 136 185 5.59955 -5.35601 -2.46519 -0.031908 0.0130027 0.0618311 0.997492 1 6.01853e-20 6.01853e-20 -6.69151e-09 -8.40341e-10 1.37332e-08 1 6.01853e-20 -6.69151e-09 -8.40341e-10 1.37332e-08 1 -6.69151e-09 -8.40341e-10 1.37332e-08 3999.94 -1.80741 126.991 3998.89 3.99305 3988.72 +EDGE_SE3:QUAT 137 187 5.89674 0.371665 -2.52691 0.0390605 -0.0819926 0.135849 0.986558 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4119.37 10.0004 -719.531 3970.15 -46.4006 4051.66 +EDGE_SE3:QUAT 136 187 5.78447 4.80478 -2.50649 0.0269612 0.175561 0.163508 0.970421 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4445.35 147.686 1413.49 3923.69 168.908 4341.32 +EDGE_SE3:QUAT 137 186 5.14944 -4.85513 -2.52298 -0.0152016 -0.0928864 0.0924699 0.991257 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4130.36 24.9255 -736.564 3970.21 -39.7567 4097.08 +EDGE_SE3:QUAT 138 188 5.7008 0.117893 -2.54192 0.0409006 -0.00622435 0.00709529 0.999119 1 7.52316e-22 7.52316e-22 1.17674e-11 -7.08029e-11 -1.73335e-09 1 7.52316e-22 1.17674e-11 -7.08029e-11 -1.73335e-09 1 1.17674e-11 -7.08029e-11 -1.73335e-09 3994.01 -1.10302 -53.1532 3999.82 -0.150459 4000.5 +EDGE_SE3:QUAT 137 188 5.33291 5.40376 -2.20474 -0.0518456 0.00106367 0.100131 0.993622 1 2.40741e-19 2.40741e-19 -1.34761e-08 -2.78531e-09 2.74249e-08 1 2.40741e-19 -1.34761e-08 -2.78531e-09 2.74249e-08 1 -1.34761e-08 -2.78531e-09 2.74249e-08 3990.38 -2.23657 70.1363 3999.49 4.48776 3961.02 +EDGE_SE3:QUAT 138 187 5.87181 -5.10374 -2.30505 -0.121488 -0.011609 -0.0104121 0.99247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.76 6.66739 -105.908 3999.28 0.0879056 4002.37 +EDGE_SE3:QUAT 139 189 5.59642 0.182224 -2.13997 -0.101064 -0.0767993 0.169518 0.977318 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.73 27.7474 -378.603 3997.24 -33.574 3918.64 +EDGE_SE3:QUAT 138 189 5.37343 5.08936 -2.22796 0.0787781 0.104082 0.107448 0.985604 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4102.52 52.6619 726.722 3976.26 57.3863 4081.17 +EDGE_SE3:QUAT 139 188 5.25336 -5.29514 -2.48408 0.100964 -0.168144 0.138777 0.970708 1 7.70372e-19 7.70372e-19 -1.11697e-08 3.28699e-09 5.78443e-08 1 7.70372e-19 -1.11697e-08 3.28699e-09 5.78443e-08 1 -1.11697e-08 3.28699e-09 5.78443e-08 4553.79 14.0267 -1652.98 3867.13 -63.7937 4517.53 +EDGE_SE3:QUAT 140 190 5.90577 0.0107626 -2.47934 0.0256794 -0.110206 -0.118404 0.986497 1 2.40741e-19 2.40741e-19 1.75086e-08 2.55533e-08 -2.86775e-09 1 2.40741e-19 1.75086e-08 2.55533e-08 -2.86775e-09 1 1.75086e-08 2.55533e-08 -2.86775e-09 4172.77 -45.1957 -856.199 3963.05 62.909 4119.33 +EDGE_SE3:QUAT 139 190 5.57877 5.42826 -2.6594 -0.201552 -0.0494227 -0.0414593 0.977351 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3892.95 48.603 -474.411 3986.82 -5.39568 4048.57 +EDGE_SE3:QUAT 140 189 5.40848 -5.01256 -2.34823 0.00913321 0.0136856 -0.0626181 0.997902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.01 0.231492 115.761 3999.15 -3.65189 3987.66 +EDGE_SE3:QUAT 141 191 5.51391 -0.149762 -2.84646 -0.198008 -0.0731512 0.00911038 0.977425 1 7.82409e-19 7.82409e-19 -5.43094e-08 -6.68084e-10 -3.27268e-09 1 7.82409e-19 -5.43094e-08 -6.68084e-10 -3.27268e-09 1 -5.43094e-08 -6.68084e-10 -3.27268e-09 3913.95 55.1756 -537.589 3987.08 -25.2156 4070.44 +EDGE_SE3:QUAT 140 191 5.82075 5.24033 -2.42012 0.00912719 0.0870844 0.0964057 0.991483 1 2.0463e-19 2.0463e-19 -4.22074e-09 -2.82111e-08 1.32439e-10 1 2.0463e-19 -4.22074e-09 -2.82111e-08 1.32439e-10 1 -4.22074e-09 -2.82111e-08 1.32439e-10 4116.41 20.8172 693.32 3973.3 37.357 4079.56 +EDGE_SE3:QUAT 141 190 5.5634 -5.00081 -2.31772 -0.00978881 -0.079627 -0.0624864 0.994816 1 7.52316e-22 7.52316e-22 1.74824e-09 -1.0845e-10 -1.40979e-10 1 7.52316e-22 1.74824e-09 -1.0845e-10 -1.40979e-10 1 1.74824e-09 -1.0845e-10 -1.40979e-10 4104.22 -6.48605 -655.261 3974.65 20.3425 4088.99 +EDGE_SE3:QUAT 142 192 6.10018 0.605342 -2.46377 -0.259147 -0.0446448 -0.112345 0.958242 1 3.08149e-18 3.08149e-18 1.07905e-07 -8.51183e-09 -1.05589e-08 1 3.08149e-18 1.07905e-07 -8.51183e-09 -1.05589e-08 1 1.07905e-07 -8.51183e-09 -1.05589e-08 3837.7 88.2296 -664.963 3970.14 9.22254 4055.84 +EDGE_SE3:QUAT 141 192 5.45543 5.15652 -2.65765 0.00159941 -0.0435095 0.0828118 0.995614 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.1 3.4925 -348.361 3992.75 -14.6111 4002.68 +EDGE_SE3:QUAT 142 191 5.47387 -5.1139 -2.42789 -0.00352216 -0.056434 -0.111733 0.992128 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.54 -7.79262 -452.676 3988.2 25.7991 4000.65 +EDGE_SE3:QUAT 143 193 5.54485 0.0788294 -2.09211 0.169049 0.0138221 -0.0799695 0.982261 1 7.82409e-19 7.82409e-19 -5.51374e-08 -2.87839e-09 -1.0494e-09 1 7.82409e-19 -5.51374e-08 -2.87839e-09 -1.0494e-09 1 -5.51374e-08 -2.87839e-09 -1.0494e-09 3902.56 25.2964 264.47 3994.15 -9.3172 3991.29 +EDGE_SE3:QUAT 142 193 5.27828 5.27366 -2.28474 -0.0317717 -0.0503149 0.0671419 0.995967 1 4.81482e-20 4.81482e-20 9.78606e-10 -1.38186e-08 -5.32791e-10 1 4.81482e-20 9.78606e-10 -1.38186e-08 -5.32791e-10 1 9.78606e-10 -1.38186e-08 -5.32791e-10 4031.04 9.65703 -376.367 3991.97 -14.3644 4017.04 +EDGE_SE3:QUAT 143 192 5.60551 -5.42086 -2.19678 -0.129622 -0.0746588 -0.116844 0.981821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4077.43 33.8532 -775.414 3962.27 25.5634 4090.03 +EDGE_SE3:QUAT 144 194 5.53038 0.154123 -2.45609 -0.0549602 0.182421 -0.13609 0.972204 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4455.46 -159.618 1446.99 3921.29 -171.342 4393.46 +EDGE_SE3:QUAT 143 194 5.47404 4.90539 -2.52181 0.0131145 -0.149165 -0.131231 0.979978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4344.65 -82.8307 -1225.36 3929.96 105.132 4276.45 +EDGE_SE3:QUAT 144 193 5.11713 -5.30055 -2.5111 0.032759 0.143677 -0.161341 0.975835 1 3.00927e-21 3.00927e-21 -3.54032e-09 5.75411e-10 -5.31682e-10 1 3.00927e-21 -3.54032e-09 5.75411e-10 -5.31682e-10 1 -3.54032e-09 5.75411e-10 -5.31682e-10 4359.73 -66.8189 1260.43 3923.41 -107.022 4259.9 +EDGE_SE3:QUAT 145 195 6.00528 0.338408 -2.33438 -0.0354545 -0.100603 -0.132056 0.985486 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4177.03 -19.0055 -872.588 3957.7 55.2108 4112.31 +EDGE_SE3:QUAT 144 195 5.91341 5.14322 -2.47995 0.265734 -0.106334 0.190811 0.938973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4183.57 -133.647 -1446.23 3887.55 -11.6962 4320.39 +EDGE_SE3:QUAT 145 194 5.17869 -5.16481 -2.07276 -0.0168883 0.155183 -0.13174 0.978917 1 7.70372e-19 7.70372e-19 7.95871e-09 5.425e-08 3.27711e-09 1 7.70372e-19 7.95871e-09 5.425e-08 3.27711e-09 1 7.95871e-09 5.425e-08 3.27711e-09 4370.38 -92.6583 1274.86 3925.94 -113.749 4302.1 +EDGE_SE3:QUAT 146 196 5.77691 -0.0673114 -2.63535 0.136232 -0.094047 -0.0733733 0.98347 1 9.62965e-19 9.62965e-19 -5.25385e-08 3.27091e-08 -2.81545e-10 1 9.62965e-19 -5.25385e-08 3.27091e-08 -2.81545e-10 1 -5.25385e-08 3.27091e-08 -2.81545e-10 4017.87 -53.451 -616.704 3984.45 44.1619 4070.57 +EDGE_SE3:QUAT 145 196 5.51284 5.37853 -2.47287 0.124505 -0.134805 0.0429194 0.982081 1 1.92593e-19 1.92593e-19 -2.83812e-08 -2.58974e-10 4.07647e-09 1 1.92593e-19 -2.83812e-08 -2.58974e-10 4.07647e-09 1 -2.83812e-08 -2.58974e-10 4.07647e-09 4268.95 -68.7383 -1197.24 3924.8 32.3631 4323.59 +EDGE_SE3:QUAT 146 195 5.30299 -5.43059 -2.23262 -0.146677 0.0128741 0.0256533 0.988768 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3919.1 -11.4501 144.264 3998.53 1.01854 4002.53 +EDGE_SE3:QUAT 147 197 5.87344 -0.366444 -2.67575 -0.0406181 -0.122712 0.0554616 0.990059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4227.08 43.4658 -994.765 3947.29 -46.4523 4221.38 +EDGE_SE3:QUAT 146 197 5.24946 5.23037 -2.40452 0.0311415 -0.0785424 -0.0710682 0.993887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4086.3 -19.8666 -607.463 3979.36 26.9111 4069.97 +EDGE_SE3:QUAT 147 196 5.25471 -5.25822 -2.3024 -0.0159115 0.00394332 -0.0464268 0.998787 1 1.88079e-22 1.88079e-22 4.0358e-11 8.66306e-10 1.4059e-11 1 1.88079e-22 4.0358e-11 8.66306e-10 1.4059e-11 1 4.0358e-11 8.66306e-10 1.4059e-11 3999.11 -0.166377 22.5826 3999.98 -0.458401 3991.5 +EDGE_SE3:QUAT 148 198 5.87682 -0.35702 -2.58831 0.183259 -0.0340951 0.184153 0.96506 1 7.70372e-19 7.70372e-19 -5.42839e-08 -9.02688e-09 5.34355e-09 1 7.70372e-19 -5.42839e-08 -9.02688e-09 5.34355e-09 1 -5.42839e-08 -9.02688e-09 5.34355e-09 3966.05 -50.9131 -649.828 3967.33 -51.3823 3964.74 +EDGE_SE3:QUAT 147 198 5.6383 4.95511 -2.63821 0.122366 0.0112668 0.142729 0.982104 1 1.93345e-19 1.93345e-19 -2.75122e-08 -2.21463e-09 4.52618e-10 1 1.93345e-19 -2.75122e-08 -2.21463e-09 4.52618e-10 1 -2.75122e-08 -2.21463e-09 4.52618e-10 3942.51 -11.4063 -119.304 3997.75 -13.3867 3920.91 +EDGE_SE3:QUAT 148 197 5.22896 -5.13185 -2.13961 -0.103869 0.0274803 -0.0883653 0.990277 1 1.92593e-19 1.92593e-19 -2.28957e-10 2.97528e-09 -2.7494e-08 1 1.92593e-19 -2.28957e-10 2.97528e-09 -2.7494e-08 1 -2.28957e-10 2.97528e-09 -2.7494e-08 3959.2 -4.01249 104.866 3999.83 -3.59588 3971.12 +EDGE_SE3:QUAT 149 199 5.73374 0.183222 -2.36103 0.00504641 0.184753 -0.140071 0.972739 1 1.55278e-18 1.55278e-18 -9.61021e-09 5.79373e-08 -5.64449e-08 1 1.55278e-18 -9.61021e-09 5.79373e-08 -5.64449e-08 1 -9.61021e-09 5.79373e-08 -5.64449e-08 4574.71 -126.233 1621.88 3887.47 -149.908 4496.33 +EDGE_SE3:QUAT 148 199 5.35935 5.19843 -2.8463 0.00782254 0.126328 0.134365 0.982815 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4245.44 57.0872 1021.6 3948.61 82.1477 4173.47 +EDGE_SE3:QUAT 149 198 5.24375 -5.67019 -2.61422 0.0180264 0.00619558 -0.0533568 0.998394 1 7.52316e-22 7.52316e-22 -9.21216e-11 -1.73196e-09 2.99508e-11 1 7.52316e-22 -9.21216e-11 -1.73196e-09 2.99508e-11 1 -9.21216e-11 -1.73196e-09 2.99508e-11 3999.62 0.514593 60.8603 3999.74 -1.702 3989.53 +EDGE_SE3:QUAT 150 200 5.58006 -0.309189 -2.48945 0.0871199 0.115427 -0.0706188 0.986965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4221.99 26.0441 1036 3939.16 -9.73615 4232.4 +EDGE_SE3:QUAT 149 200 5.5383 5.40229 -2.6186 -0.0328694 0.206025 -0.0340175 0.977403 1 7.70372e-19 7.70372e-19 2.85838e-09 5.42143e-08 2.81668e-09 1 7.70372e-19 2.85838e-09 5.42143e-08 2.81668e-09 1 2.85838e-09 5.42143e-08 2.81668e-09 4749.9 -87.3501 1893.63 3840.18 -87.5137 4749.59 +EDGE_SE3:QUAT 150 199 5.52179 -5.9097 -2.77447 0.166485 -0.0424791 0.0569899 0.983479 1 4.81482e-20 4.81482e-20 8.18477e-10 -2.25304e-09 -1.37324e-08 1 4.81482e-20 8.18477e-10 -2.25304e-09 -1.37324e-08 1 8.18477e-10 -2.25304e-09 -1.37324e-08 3937 -36.621 -440.954 3987.41 -2.76234 4034.88 +EDGE_SE3:QUAT 151 201 6.12642 -0.176569 -2.39727 0.0186522 0.255148 -0.0899358 0.96253 1 7.52316e-22 7.52316e-22 -1.92052e-09 1.85339e-10 -5.07144e-10 1 7.52316e-22 -1.92052e-09 1.85339e-10 -5.07144e-10 1 -1.92052e-09 1.85339e-10 -5.07144e-10 5279.09 -155.684 2600.32 3754.05 -161.96 5248.12 +EDGE_SE3:QUAT 150 201 5.19108 5.38404 -2.62887 0.0664684 0.0330439 -0.105335 0.991663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.54 8.24967 343.877 3991.89 -17.1036 3984.83 +EDGE_SE3:QUAT 151 200 5.30619 -5.48531 -2.08596 -0.0257061 -0.0158784 -0.0488921 0.998347 1 2.40741e-20 2.40741e-20 7.26512e-09 6.59417e-09 3.98481e-11 1 2.40741e-20 7.26512e-09 6.59417e-09 3.98481e-11 1 7.26512e-09 6.59417e-09 3.98481e-11 4002.36 1.53681 -141.664 3998.67 3.40691 3995.44 +EDGE_SE3:QUAT 152 202 5.6972 0.414014 -2.55337 0.128413 -0.0834846 0.189234 0.969913 1 7.70372e-19 7.70372e-19 -7.01252e-09 5.1447e-09 5.53174e-08 1 7.70372e-19 -7.01252e-09 5.1447e-09 5.53174e-08 1 -7.01252e-09 5.1447e-09 5.53174e-08 4146.08 -16.8415 -946.955 3945.63 -69.3846 4068.8 +EDGE_SE3:QUAT 151 202 5.62136 5.29816 -2.70623 0.131281 0.0662691 0.0392211 0.98835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.74 32.9451 458.62 3989.88 20.0278 4045.53 +EDGE_SE3:QUAT 152 201 5.36675 -5.2782 -2.04677 -0.0890593 0.019905 -0.0750333 0.992997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3969.54 -2.4266 76.5121 3999.89 -2.13124 3978.74 +EDGE_SE3:QUAT 153 203 5.79645 0.108173 -2.19167 0.0271696 -0.0316832 0.0414631 0.998268 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4014.8 -2.6416 -267.1 3995.47 -4.97581 4010.88 +EDGE_SE3:QUAT 152 203 5.75139 5.2928 -2.70165 -0.0337385 -0.199884 0.106505 0.973429 1 9.62965e-19 9.62965e-19 2.19808e-08 5.77634e-08 -1.11702e-09 1 9.62965e-19 2.19808e-08 5.77634e-08 -1.11702e-09 1 2.19808e-08 5.77634e-08 -1.11702e-09 4641.49 155.835 -1732.99 3877.4 -165.958 4600.67 +EDGE_SE3:QUAT 153 202 5.47218 -5.18507 -2.43399 -0.152657 -0.0548774 -0.102579 0.981408 1 1.15556e-18 1.15556e-18 5.50926e-08 1.87708e-08 2.68221e-08 1 1.15556e-18 5.50926e-08 1.87708e-08 2.68221e-08 1 5.50926e-08 1.87708e-08 2.68221e-08 3998.65 40.5844 -614.829 3974.93 16.7664 4049.78 +EDGE_SE3:QUAT 154 204 5.47347 0.291375 -2.45807 0.145354 0.0676767 0.0554036 0.985506 1 4.81482e-20 4.81482e-20 1.01245e-09 -1.36608e-08 2.12202e-09 1 4.81482e-20 1.01245e-09 -1.36608e-08 2.12202e-09 1 1.01245e-09 -1.36608e-08 2.12202e-09 3960.67 33.9242 429.819 3992.29 22.6717 4032.9 +EDGE_SE3:QUAT 153 204 5.6118 5.42005 -2.84535 -0.167687 0.130593 0.110237 0.970914 1 9.62965e-19 9.62965e-19 -5.19726e-08 -7.84201e-09 1.90965e-08 1 9.62965e-19 -5.19726e-08 -7.84201e-09 1.90965e-08 1 -5.19726e-08 -7.84201e-09 1.90965e-08 4279.5 -74.9575 1312.59 3908.64 -6.51187 4343.37 +EDGE_SE3:QUAT 154 203 4.9494 -5.34602 -2.37214 -0.108342 0.00769077 0.0562743 0.99249 1 1.95602e-19 1.95602e-19 -2.7747e-08 1.96349e-09 -1.7272e-10 1 1.95602e-19 -2.7747e-08 1.96349e-09 -1.7272e-10 1 -2.7747e-08 1.96349e-09 -1.7272e-10 3957.32 -8.2098 132.742 3998.51 3.85691 3991.6 +EDGE_SE3:QUAT 155 205 5.62677 -0.153171 -2.57639 0.0112928 0.063591 0.122801 0.990327 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4057.78 13.9981 486.567 3987.16 31.5343 3997.97 +EDGE_SE3:QUAT 154 205 5.70134 5.26986 -2.67475 0.0929629 -0.0889099 -0.00770999 0.991662 1 3.97223e-19 3.97223e-19 2.80181e-08 2.75055e-08 1.90785e-09 1 3.97223e-19 2.80181e-08 2.75055e-08 1.90785e-09 1 2.80181e-08 2.75055e-08 1.90785e-09 4088.29 -36.9816 -711.776 3971.75 20.6117 4122.62 +EDGE_SE3:QUAT 155 204 5.58714 -5.59757 -2.22411 -0.0290151 -0.00455959 0.0140445 0.99947 1 1.20371e-20 1.20371e-20 -6.93543e-09 -9.91308e-11 2.5921e-11 1 1.20371e-20 -6.93543e-09 -9.91308e-11 2.5921e-11 1 -6.93543e-09 -9.91308e-11 2.5921e-11 3996.88 0.439263 -31.5347 3999.94 -0.221494 3999.46 +EDGE_SE3:QUAT 156 206 5.63195 -0.238806 -2.66519 -0.0164281 0.168051 0.164168 0.971873 1 1.54375e-18 1.54375e-18 -3.88055e-09 -5.69058e-08 -5.55155e-08 1 1.54375e-18 -3.88055e-09 -5.69058e-08 -5.55155e-08 1 -3.88055e-09 -5.69058e-08 -5.55155e-08 4474.3 110.753 1458.84 3907.32 143.455 4367.57 +EDGE_SE3:QUAT 155 206 5.55504 5.35342 -2.7088 -0.0227176 -0.0439954 0.100872 0.993667 1 1.20371e-20 1.20371e-20 -6.91713e-09 -7.17929e-10 2.67808e-10 1 1.20371e-20 -6.91713e-09 -7.17929e-10 2.67808e-10 1 -6.91713e-09 -7.17929e-10 2.67808e-10 4023.44 7.6624 -320.653 3994.4 -16.8293 3984.8 +EDGE_SE3:QUAT 156 205 5.3268 -5.80555 -2.07548 -0.0837187 -0.0376882 -0.0542022 0.9943 1 4.81482e-20 4.81482e-20 6.40892e-10 1.10644e-09 -1.38525e-08 1 4.81482e-20 6.40892e-10 1.10644e-09 -1.38525e-08 1 6.40892e-10 1.10644e-09 -1.38525e-08 4002.95 13.3886 -353.735 3991.77 6.52771 4019.23 +EDGE_SE3:QUAT 157 207 5.20732 -0.130134 -2.73509 -0.0578294 0.132029 -0.0525936 0.988159 1 1.92593e-19 1.92593e-19 -2.83332e-08 1.99862e-09 -3.55611e-09 1 1.92593e-19 -2.83332e-08 1.99862e-09 -3.55611e-09 1 -2.83332e-08 1.99862e-09 -3.55611e-09 4253.27 -58.1379 1066.83 3941.46 -57.1061 4255.59 +EDGE_SE3:QUAT 156 207 5.50793 5.32175 -2.714 0.0590264 -0.138778 0.270307 0.950889 1 1.20371e-20 1.20371e-20 6.91876e-09 1.92274e-09 -1.08385e-09 1 1.20371e-20 6.91876e-09 1.92274e-09 -1.08385e-09 1 6.91876e-09 1.92274e-09 -1.08385e-09 4354.67 111.061 -1269.18 3938.01 -181.139 4076.34 +EDGE_SE3:QUAT 157 206 5.34907 -5.2499 -2.23056 -0.124738 0.0408235 -0.168344 0.976951 1 7.70372e-19 7.70372e-19 -2.18293e-10 -7.28771e-09 5.42235e-08 1 7.70372e-19 -2.18293e-10 -7.28771e-09 5.42235e-08 1 -2.18293e-10 -7.28771e-09 5.42235e-08 3936.6 1.09922 60.1477 4000.21 1.99433 3885.48 +EDGE_SE3:QUAT 158 208 5.97909 0.161842 -2.65823 -0.164792 0.023459 0.021238 0.985821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3903.62 -18.9781 221.844 3996.92 -0.38243 4010.45 +EDGE_SE3:QUAT 157 208 5.45611 5.38829 -2.52415 -0.0758682 0.0694175 0.195644 0.975269 1 3.85186e-19 3.85186e-19 3.26538e-08 -2.18983e-08 1.38715e-09 1 3.85186e-19 3.26538e-08 -2.18983e-08 1.38715e-09 1 3.26538e-08 -2.18983e-08 1.38715e-09 4100.18 3.46484 713.499 3969.59 66.0592 3970.1 +EDGE_SE3:QUAT 158 207 5.19783 -5.1566 -2.92324 0.288721 0.0682956 -0.102008 0.949511 1 1.92593e-19 1.92593e-19 3.18819e-09 7.7555e-09 2.69555e-08 1 1.92593e-19 3.18819e-09 7.7555e-09 2.69555e-08 1 3.18819e-09 7.7555e-09 2.69555e-08 3834.87 121.571 839.291 3960.55 15.9532 4126.69 +EDGE_SE3:QUAT 159 209 5.81265 0.224317 -2.5836 -0.250041 -0.102514 0.0518506 0.961396 1 1.92593e-19 1.92593e-19 -1.77455e-09 -7.40334e-09 2.69879e-08 1 1.92593e-19 -1.77455e-09 -7.40334e-09 2.69879e-08 1 -1.77455e-09 -7.40334e-09 2.69879e-08 3835.05 79.3278 -598.32 3993.58 -55.3378 4074.38 +EDGE_SE3:QUAT 158 209 5.62377 5.35305 -2.46868 0.0947265 -0.0558919 0.0372674 0.993234 1 2.40741e-19 2.40741e-19 2.81364e-08 -1.30546e-08 -4.65856e-10 1 2.40741e-19 2.81364e-08 -1.30546e-08 -4.65856e-10 1 2.81364e-08 -1.30546e-08 -4.65856e-10 4022.96 -21.3385 -488.858 3985.22 -1.4752 4053.3 +EDGE_SE3:QUAT 159 208 5.29126 -5.564 -2.21951 0.0481605 0.110671 -0.0859795 0.988959 1 2.40741e-19 2.40741e-19 -1.07672e-08 1.93586e-09 2.65389e-08 1 2.40741e-19 -1.07672e-08 1.93586e-09 2.65389e-08 1 -1.07672e-08 1.93586e-09 2.65389e-08 4212.74 -2.08609 968.218 3946.67 -31.7102 4192.45 +EDGE_SE3:QUAT 160 210 5.7524 -0.13081 -2.59576 -0.0735249 -0.0280914 -0.166867 0.982833 1 7.70372e-19 7.70372e-19 -2.80983e-09 -3.36407e-09 5.47823e-08 1 7.70372e-19 -2.80983e-09 -3.36407e-09 5.47823e-08 1 -2.80983e-09 -3.36407e-09 5.47823e-08 4010.25 8.20134 -360.594 3990.58 31.2853 3920.49 +EDGE_SE3:QUAT 159 210 5.42796 5.51222 -2.5968 0.0827276 0.0645854 -0.0351069 0.993857 1 1.92593e-19 1.92593e-19 -2.78459e-08 6.78519e-10 -1.94393e-09 1 1.92593e-19 -2.78459e-08 6.78519e-10 -1.94393e-09 1 -2.78459e-08 6.78519e-10 -1.94393e-09 4048.05 20.4907 554.494 3981.23 -1.1079 4070.5 +EDGE_SE3:QUAT 160 209 4.86272 -5.44902 -2.72507 -0.0518573 -0.0538877 -0.103912 0.991771 1 1.92593e-19 1.92593e-19 -1.7678e-09 -1.11541e-09 2.77352e-08 1 1.92593e-19 -1.7678e-09 -1.11541e-09 2.77352e-08 1 -1.7678e-09 -1.11541e-09 2.77352e-08 4049.15 4.74938 -493.435 3984.63 23.0447 4016.72 +EDGE_SE3:QUAT 161 211 5.63668 0.355203 -2.58275 -0.0690527 -0.0344147 -0.0302831 0.996559 1 1.92593e-19 1.92593e-19 2.77375e-08 -7.04779e-10 -1.06339e-09 1 1.92593e-19 2.77375e-08 -7.04779e-10 -1.06339e-09 1 2.77375e-08 -7.04779e-10 -1.06339e-09 4003.22 9.76159 -299.512 3994.27 2.46861 4018.62 +EDGE_SE3:QUAT 160 211 5.84281 5.42981 -2.71854 0.0266904 0.107257 0.110628 0.987697 1 1.92593e-19 1.92593e-19 2.78775e-09 1.43408e-09 2.79883e-08 1 1.92593e-19 2.78775e-09 1.43408e-09 2.79883e-08 1 2.78775e-09 1.43408e-09 2.79883e-08 4164.04 41.5093 834.25 3964.31 57.5623 4117.93 +EDGE_SE3:QUAT 161 210 5.28593 -5.53847 -2.43091 0.102513 0.0226468 -0.0916442 0.990242 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3978.46 14.3658 288.92 3993.72 -12.297 3986.9 +EDGE_SE3:QUAT 162 212 5.85486 0.380353 -2.76484 -0.0512712 0.243111 0.0390472 0.967855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5155.44 -28.3479 2454.23 3760.54 -20.6901 5159.85 +EDGE_SE3:QUAT 161 212 5.23401 5.53649 -2.70483 0.0725731 -0.128911 -0.150483 0.977481 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4165.91 -83.3855 -888.023 3970.33 95.6545 4096.39 +EDGE_SE3:QUAT 162 211 5.36629 -5.67382 -2.5004 -0.0873175 0.0248974 -0.0317463 0.995363 1 1.92593e-19 1.92593e-19 -2.765e-08 9.8974e-10 -5.26111e-10 1 1.92593e-19 -2.765e-08 9.8974e-10 -5.26111e-10 1 -2.765e-08 9.8974e-10 -5.26111e-10 3976.15 -7.01482 163.719 3998.64 -3.39005 4002.62 +EDGE_SE3:QUAT 163 213 5.63703 0.164873 -2.76765 0.0411418 -0.0328034 -0.134938 0.989456 1 1.20371e-20 1.20371e-20 -9.53061e-10 -6.86343e-09 3.36351e-10 1 1.20371e-20 -9.53061e-10 -6.86343e-09 3.36351e-10 1 -9.53061e-10 -6.86343e-09 3.36351e-10 4001.97 -5.55883 -189.086 3998.57 11.8363 3935.91 +EDGE_SE3:QUAT 162 213 5.2401 5.24597 -2.60135 0.146149 -0.157158 -0.00276267 0.976696 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4307.52 -121.726 -1314.22 3922.03 95.1554 4392.92 +EDGE_SE3:QUAT 163 212 5.18301 -5.47773 -2.48091 -0.0518972 0.0498371 -0.0702129 0.994934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.01 -12.4207 352.706 3993.34 -14.6685 4011.07 +EDGE_SE3:QUAT 164 214 5.75433 -0.165045 -2.87003 -0.101542 0.0517477 0.146958 0.982555 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.15 -17.046 581.684 3977.32 37.1349 3996.01 +EDGE_SE3:QUAT 163 214 5.79363 5.32925 -2.73341 0.0404346 0.11336 0.076685 0.989765 1 5.77779e-19 5.77779e-19 2.86822e-08 3.16043e-08 2.94883e-08 1 5.77779e-19 2.86822e-08 3.16043e-08 2.94883e-08 1 2.86822e-08 3.16043e-08 2.94883e-08 4184.01 43.1919 893.838 3958.01 50.2731 4167.03 +EDGE_SE3:QUAT 164 213 5.18737 -5.51737 -2.6353 0.0656177 0.019296 -0.0147771 0.997549 1 3.00927e-21 3.00927e-21 7.31221e-11 2.25954e-10 3.4639e-09 1 3.00927e-21 7.31221e-11 2.25954e-10 3.4639e-09 1 7.31221e-11 2.25954e-10 3.4639e-09 3989.58 5.41115 165.18 3998.25 -0.598476 4005.93 +EDGE_SE3:QUAT 165 215 5.96721 -0.260701 -2.21177 -0.193485 -0.0286069 0.0290748 0.980255 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3855.66 12.2995 -150.103 3999.37 -3.86513 4002.03 +EDGE_SE3:QUAT 164 215 5.71768 5.42538 -2.62781 -0.0973683 -0.0675115 0.145002 0.982312 1 7.70372e-19 7.70372e-19 -1.9665e-09 -6.31416e-09 5.47345e-08 1 7.70372e-19 -1.9665e-09 -6.31416e-09 5.47345e-08 1 -1.9665e-09 -6.31416e-09 5.47345e-08 3991.25 22.8614 -350.037 3996.67 -27.1191 3945.07 +EDGE_SE3:QUAT 165 214 5.22932 -5.57135 -2.84426 0.049978 -0.0199422 -0.122132 0.991054 1 4.81482e-20 4.81482e-20 1.37563e-08 -1.71515e-09 -9.90671e-11 1 4.81482e-20 1.37563e-08 -1.71515e-09 -9.90671e-11 1 1.37563e-08 -1.71515e-09 -9.90671e-11 3991.56 -1.88924 -82.965 3999.85 3.68688 3941.88 +EDGE_SE3:QUAT 166 216 5.90974 0.0736436 -2.72897 -0.0578885 -0.107217 -0.0817171 0.989179 1 2.40741e-19 2.40741e-19 -1.60505e-08 -2.64735e-08 5.0166e-10 1 2.40741e-19 -1.60505e-08 -2.64735e-08 5.0166e-10 1 -1.60505e-08 -2.64735e-08 5.0166e-10 4198.49 5.25865 -944.777 3948.65 25.7787 4185.18 +EDGE_SE3:QUAT 165 216 5.54926 5.09991 -3.01754 0.0133923 0.0877916 0.0398886 0.99525 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4122.43 12.658 712.573 3970.44 17.8258 4116.78 +EDGE_SE3:QUAT 166 215 5.15073 -5.60376 -2.56218 -0.0226475 0.332953 -0.00185353 0.94267 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 6592.71 -117.658 4136.65 3561.8 -120.215 6594.75 +EDGE_SE3:QUAT 167 217 5.74797 -0.125602 -2.88424 -0.14994 0.0502254 -0.118523 0.980279 1 7.70372e-19 7.70372e-19 -6.38717e-10 8.77212e-09 -5.44566e-08 1 7.70372e-19 -6.38717e-10 8.77212e-09 -5.44566e-08 1 -6.38717e-10 8.77212e-09 -5.44566e-08 3915.75 -9.26915 171.183 4000.13 -8.36807 3949.49 +EDGE_SE3:QUAT 166 217 5.42032 5.41352 -2.95565 0.0644341 0.167939 0.0134571 0.983597 1 1.92593e-19 1.92593e-19 -2.88884e-08 -1.07763e-09 -4.8325e-09 1 1.92593e-19 -2.88884e-08 -1.07763e-09 -4.8325e-09 1 -2.88884e-08 -1.07763e-09 -4.8325e-09 4459.82 71.2179 1460.42 3895.07 61.7486 4475.71 +EDGE_SE3:QUAT 167 216 5.08024 -5.67831 -2.46817 -0.0118102 0.197389 -0.1202 0.972857 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4649.61 -143.834 1739.12 3874.16 -159.639 4592.38 +EDGE_SE3:QUAT 168 218 5.5804 -0.0920245 -2.59576 -0.00582539 0.124127 0.0819835 0.988856 1 7.52316e-22 7.52316e-22 1.76982e-09 1.48763e-10 2.20833e-10 1 7.52316e-22 1.76982e-09 1.48763e-10 2.20833e-10 1 1.76982e-09 1.48763e-10 2.20833e-10 4255.92 29.0502 1043.95 3940.96 47.4619 4229.17 +EDGE_SE3:QUAT 167 218 5.19449 5.83538 -2.70181 -0.0255525 0.12513 0.191754 0.973098 1 4.70198e-23 4.70198e-23 -4.36264e-10 -8.5863e-11 -5.6251e-11 1 4.70198e-23 -4.36264e-10 -8.5863e-11 -5.6251e-11 1 -4.36264e-10 -8.5863e-11 -5.6251e-11 4261.82 63.8901 1062.06 3947.24 109.073 4117.35 +EDGE_SE3:QUAT 168 217 5.3116 -5.69869 -2.45873 -0.135787 -0.0432469 0.048472 0.988606 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3942.54 17.1348 -257.906 3997.27 -9.56648 4006.9 +EDGE_SE3:QUAT 169 219 5.91983 0.0407929 -2.54113 -0.0221168 0.0520978 0.0119007 0.998326 1 3.00927e-21 3.00927e-21 1.83369e-10 -7.32166e-11 3.48281e-09 1 3.00927e-21 1.83369e-10 -7.32166e-11 3.48281e-09 1 1.83369e-10 -7.32166e-11 3.48281e-09 4042.42 -4.03596 423.639 3988.97 1.12328 4043.81 +EDGE_SE3:QUAT 168 219 5.26093 5.48522 -2.76437 -0.0690457 0.142079 0.0968617 0.982682 1 4.81482e-20 4.81482e-20 1.42835e-08 1.16346e-09 2.20779e-09 1 4.81482e-20 1.42835e-08 1.16346e-09 2.20779e-09 1 1.42835e-08 1.16346e-09 2.20779e-09 4364.23 1.22579 1296.26 3910.52 37.6581 4345.77 +EDGE_SE3:QUAT 169 218 4.7257 -5.85657 -3.03623 0.0737472 -0.207101 -0.103673 0.970012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4616.38 -202.715 -1721.85 3892.72 206.254 4595.15 +EDGE_SE3:QUAT 170 220 5.58537 0.186187 -2.67767 -0.0248355 -0.110327 -0.0412224 0.99273 1 2.52778e-19 2.52778e-19 6.48864e-09 2.70687e-08 1.37801e-08 1 2.52778e-19 6.48864e-09 2.70687e-08 1.37801e-08 1 6.48864e-09 2.70687e-08 1.37801e-08 4204.22 0.109684 -932.447 3950.21 13.9565 4199.89 +EDGE_SE3:QUAT 169 220 5.71887 5.44085 -2.61296 0.0121787 -0.0521483 0.056171 0.996984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4044.6 1.11619 -427.551 3988.83 -11.5911 4032.57 +EDGE_SE3:QUAT 170 219 5.44509 -5.62913 -2.32379 0.08159 0.0862501 -0.059003 0.991172 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4113.09 22.1032 760.64 3965.4 -7.90324 4125.8 +EDGE_SE3:QUAT 171 221 5.74932 -0.0995631 -2.62682 0.05292 0.0285006 0.0563905 0.996598 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.82 5.58279 190.596 3998.1 5.8423 3996.3 +EDGE_SE3:QUAT 170 221 5.45242 5.60056 -2.59702 -0.0226572 0.0145952 0.217584 0.975669 1 1.20371e-20 1.20371e-20 -6.77614e-09 -1.50598e-09 -1.58522e-10 1 1.20371e-20 -6.77614e-09 -1.50598e-09 -1.58522e-10 1 -6.77614e-09 -1.50598e-09 -1.58522e-10 4004.79 -0.0638695 166.049 3998.19 19.7507 3817.47 +EDGE_SE3:QUAT 171 220 5.44157 -5.57406 -2.18125 -0.23611 -0.0052278 -0.0968228 0.966876 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3798.19 44.2584 -301.933 3991.22 13.6155 3983.68 +EDGE_SE3:QUAT 172 222 5.84075 0.175023 -2.44528 -0.0316647 0.0141011 0.0868412 0.995619 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.17 -1.84203 144.362 3998.54 6.51803 3975.01 +EDGE_SE3:QUAT 171 222 5.36549 5.92649 -2.78182 0.0857956 -0.0632637 0.165818 0.980378 1 1.92593e-19 1.92593e-19 2.75847e-08 4.34016e-09 -2.45068e-09 1 1.92593e-19 2.75847e-08 4.34016e-09 -2.45068e-09 1 2.75847e-08 4.34016e-09 -2.45068e-09 4077.61 -7.4229 -664.163 3972.17 -49.4998 3997.07 +EDGE_SE3:QUAT 172 221 5.07082 -5.46609 -2.61239 0.0074189 0.0301275 -0.165204 0.985771 1 1.88079e-22 1.88079e-22 8.56681e-10 -1.43443e-10 2.68533e-11 1 1.88079e-22 8.56681e-10 -1.43443e-10 2.68533e-11 1 8.56681e-10 -1.43443e-10 2.68533e-11 4014.91 -2.84725 246.48 3996.6 -20.5228 3905.96 +EDGE_SE3:QUAT 173 223 5.89327 -0.406692 -2.20829 0.0207031 -0.0781168 0.0819521 0.993354 1 3.00927e-21 3.00927e-21 3.49121e-09 2.79979e-10 -2.82645e-10 1 3.00927e-21 3.49121e-09 2.79979e-10 -2.82645e-10 1 3.49121e-09 2.79979e-10 -2.82645e-10 4102.29 5.59326 -653.336 3974.78 -25.4967 4077.14 +EDGE_SE3:QUAT 172 223 5.28793 5.31517 -2.57787 0.194243 0.0918637 -0.0742964 0.973812 1 4.81482e-20 4.81482e-20 -1.60231e-09 -2.59339e-09 -1.38473e-08 1 4.81482e-20 -1.60231e-09 -2.59339e-09 -1.38473e-08 1 -1.60231e-09 -2.59339e-09 -1.38473e-08 4040.58 80.1934 896.273 3955.23 15.8197 4169.42 +EDGE_SE3:QUAT 173 222 5.06415 -5.41929 -2.8203 -0.0940593 0.178226 0.103699 0.973979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4601.18 -8.38334 1718.08 3857.76 29.5628 4593.55 +EDGE_SE3:QUAT 174 224 5.74308 -0.186843 -2.46012 -0.0116395 -0.0901546 0.0102344 0.995807 1 6.01853e-21 6.01853e-21 3.82865e-09 9.24721e-11 -3.82865e-09 1 6.01853e-21 3.82865e-09 9.24721e-11 -3.82865e-09 1 3.82865e-09 9.24721e-11 -3.82865e-09 4132.09 6.74434 -740.357 3967.74 -6.4641 4132.21 +EDGE_SE3:QUAT 173 224 5.36784 5.53716 -2.65043 -0.0602395 -0.0225979 0.289729 0.954944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.56 -3.61184 39.7082 3999.16 17.0706 3663.3 +EDGE_SE3:QUAT 174 223 5.18101 -5.32923 -2.75293 0.115554 -0.0717155 -0.158589 0.977933 1 4.81482e-20 4.81482e-20 -2.37984e-09 -1.35413e-08 1.84159e-09 1 4.81482e-20 -2.37984e-09 -1.35413e-08 1.84159e-09 1 -2.37984e-09 -1.35413e-08 1.84159e-09 3970.93 -23.2388 -325.956 3998.5 26.265 3923.74 +EDGE_SE3:QUAT 175 225 5.9663 0.0721305 -2.18248 0.0265667 -0.0832971 0.0153153 0.996053 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4111.95 -7.1559 -687.215 3971.88 -1.03884 4113.83 +EDGE_SE3:QUAT 174 225 5.5816 5.68543 -2.29426 -0.00635381 0.0437049 0.0214805 0.998793 1 4.81482e-20 4.81482e-20 -2.91499e-10 1.38612e-08 6.23093e-11 1 4.81482e-20 -2.91499e-10 1.38612e-08 6.23093e-11 1 -2.91499e-10 1.38612e-08 6.23093e-11 4030.82 -0.146545 353.4 3992.29 3.5813 4029.14 +EDGE_SE3:QUAT 175 224 4.98168 -5.68113 -2.44622 -0.0119473 -0.0151805 0.0173631 0.999663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.96 0.80023 -118.965 3999.13 -1.0918 4002.33 +EDGE_SE3:QUAT 176 226 5.85859 -0.0246843 -2.8682 -0.142144 -0.0264601 0.035745 0.988846 1 7.70372e-19 7.70372e-19 -5.49277e-08 -2.32111e-09 8.47364e-10 1 7.70372e-19 -5.49277e-08 -2.32111e-09 8.47364e-10 1 -5.49277e-08 -2.32111e-09 8.47364e-10 3924.28 9.08109 -144.861 3999.23 -3.56587 3999.98 +EDGE_SE3:QUAT 175 226 5.62057 5.61503 -2.94603 0.270304 0.0967046 -0.110535 0.951507 1 3.27408e-18 3.27408e-18 1.05539e-07 -1.24503e-08 -1.1417e-08 1 3.27408e-18 1.05539e-07 -1.24503e-08 -1.1417e-08 1 1.05539e-07 -1.24503e-08 -1.1417e-08 3984.44 137.7 1088.8 3938.64 33.3822 4227.82 +EDGE_SE3:QUAT 176 225 5.19807 -5.90772 -2.52314 0.0504201 0.0192344 -0.152504 0.986828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.96 3.99182 239.528 3995.8 -19.6547 3921.1 +EDGE_SE3:QUAT 177 227 5.55387 -0.196159 -2.85041 0.024633 -0.0328201 -0.0238248 0.998874 1 1.20371e-20 1.20371e-20 -2.19484e-10 1.82327e-10 6.94521e-09 1 1.20371e-20 -2.19484e-10 1.82327e-10 6.94521e-09 1 -2.19484e-10 1.82327e-10 6.94521e-09 4013.88 -3.74815 -255.949 3996.04 3.66468 4014.04 +EDGE_SE3:QUAT 176 227 5.49234 5.53827 -2.88975 -0.00793918 -0.0214116 0.149677 0.988471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.47 1.95876 -151.676 3998.84 -10.9707 3916.11 +EDGE_SE3:QUAT 177 226 5.26057 -5.4205 -2.38274 0.0223878 0.0640848 -0.00450479 0.997683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4064.74 5.63376 520.99 3983.53 1.0324 4066.66 +EDGE_SE3:QUAT 178 228 5.41886 -0.401754 -2.59307 0.00557716 0.167392 0.0944021 0.981345 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4468.85 76.1908 1447.79 3899.46 92.5651 4433.33 +EDGE_SE3:QUAT 177 228 5.28732 5.82559 -2.73513 -0.110319 -0.180323 0.0654961 0.975204 1 1.54074e-18 1.54074e-18 -6.33289e-08 4.74849e-08 1.71131e-08 1 1.54074e-18 -6.33289e-08 4.74849e-08 1.71131e-08 1 -6.33289e-08 4.74849e-08 1.71131e-08 4417.96 154.574 -1445.01 3916.64 -147.832 4449.48 +EDGE_SE3:QUAT 178 227 4.86326 -5.63915 -2.41699 0.173749 0.00446468 0.169658 0.970055 1 1.54074e-18 1.54074e-18 5.10343e-08 1.81501e-08 5.10343e-08 1 1.54074e-18 5.10343e-08 1.81501e-08 5.10343e-08 1 5.10343e-08 1.81501e-08 5.10343e-08 3900.14 -33.7837 -308.842 3989.17 -32.8213 3905.76 +EDGE_SE3:QUAT 179 229 5.72693 -0.108177 -2.37753 -0.0882839 0.106321 -0.0275094 0.990023 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4137.79 -48.0147 839.488 3962.48 -36.1532 4165.94 +EDGE_SE3:QUAT 178 229 5.00507 5.89529 -2.68781 -0.027967 -0.107873 0.0904744 0.989644 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4170.36 37.8405 -851.114 3961.67 -50.0387 4140.74 +EDGE_SE3:QUAT 179 228 4.98234 -5.54623 -2.63488 -0.0408083 0.0493363 0.00272114 0.997944 1 4.816e-20 4.816e-20 1.39065e-08 -9.42986e-12 4.71383e-10 1 4.816e-20 1.39065e-08 -9.42986e-12 4.71383e-10 1 1.39065e-08 -9.42986e-12 4.71383e-10 4032.64 -8.17966 398.432 3990.31 -1.86142 4039.27 +EDGE_SE3:QUAT 180 230 6.18696 -0.0690324 -2.60016 0.0484023 0.022455 0.116238 0.991787 1 6.01853e-20 6.01853e-20 1.29505e-08 8.51784e-09 -2.16193e-10 1 6.01853e-20 1.29505e-08 8.51784e-09 -2.16193e-10 1 1.29505e-08 8.51784e-09 -2.16193e-10 3993.42 2.73176 108.579 3999.63 5.21929 3948.75 +EDGE_SE3:QUAT 179 230 5.41908 5.73112 -2.54273 0.0148963 0.104232 0.379867 0.919029 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4084.32 69.7121 604.565 4005.68 110.858 3508.02 +EDGE_SE3:QUAT 180 229 5.07298 -5.74163 -2.82123 -0.0451729 -0.0385498 -0.0347749 0.997629 1 1.92593e-19 1.92593e-19 -2.77822e-08 8.70398e-10 1.15423e-09 1 1.92593e-19 -2.77822e-08 8.70398e-10 1.15423e-09 1 -2.77822e-08 8.70398e-10 1.15423e-09 4018.5 6.29178 -327.686 3993.2 4.12158 4021.82 +EDGE_SE3:QUAT 181 231 5.58486 -0.162071 -2.71099 -0.0714751 0.0253308 0.00218078 0.997118 1 2.93874e-24 2.93874e-24 2.75558e-12 -7.75737e-12 1.08248e-10 1 2.93874e-24 2.75558e-12 -7.75737e-12 1.08248e-10 1 2.75558e-12 -7.75737e-12 1.08248e-10 3989.88 -7.28891 203.418 3997.48 -0.886196 4010.3 +EDGE_SE3:QUAT 180 231 5.48175 5.58826 -2.884 -0.0243015 -0.0328565 0.138449 0.989526 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.15 5.12755 -215.681 3997.81 -14.4231 3934.84 +EDGE_SE3:QUAT 181 230 5.09797 -5.79394 -2.59163 -0.107609 -0.102536 0.0498729 0.987633 1 9.62965e-19 9.62965e-19 -5.3791e-08 -3.14384e-08 1.69406e-09 1 9.62965e-19 -5.3791e-08 -3.14384e-08 1.69406e-09 1 -5.3791e-08 -3.14384e-08 1.69406e-09 4092.79 54.7231 -759.578 3971.61 -44.4058 4129.16 +EDGE_SE3:QUAT 182 232 5.56033 -0.00387626 -2.69492 -0.00969935 -0.126788 -0.0362952 0.991218 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4271.03 -9.10004 -1076.7 3935.66 18.8456 4266.14 +EDGE_SE3:QUAT 181 232 5.74315 6.17973 -2.84986 -0.26046 -0.0724848 0.0474452 0.96159 1 1.92593e-19 1.92593e-19 1.06304e-09 7.47861e-09 -2.68114e-08 1 1.92593e-19 1.06304e-09 7.47861e-09 -2.68114e-08 1 1.06304e-09 7.47861e-09 -2.68114e-08 3762.59 45.2608 -379.307 3998.35 -25.6965 4024.94 +EDGE_SE3:QUAT 182 231 5.40556 -5.7875 -2.30635 0.0163216 -0.154479 0.0652216 0.985706 1 7.52316e-22 7.52316e-22 -1.79672e-09 -1.15302e-10 2.83024e-10 1 7.52316e-22 -1.79672e-09 -1.15302e-10 2.83024e-10 1 -1.79672e-09 -1.15302e-10 2.83024e-10 4413.51 28.5487 -1352.84 3905.21 -44.9598 4397.56 +EDGE_SE3:QUAT 183 233 5.79929 0.101654 -2.5781 -0.0724596 0.0289695 -0.0646866 0.99485 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.34 -6.41989 172.758 3998.64 -5.9224 3990.6 +EDGE_SE3:QUAT 182 233 5.1023 5.34495 -2.56879 0.0926462 0.0553373 0.0329552 0.993614 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.81 20.6497 403.075 3991.22 12.5147 4035.8 +EDGE_SE3:QUAT 183 232 5.04836 -5.95122 -2.5976 0.0167448 -0.194621 -0.0878609 0.976792 1 1.92593e-19 1.92593e-19 5.62733e-09 -1.61458e-09 -2.92344e-08 1 1.92593e-19 5.62733e-09 -1.61458e-09 -2.92344e-08 1 5.62733e-09 -1.61458e-09 -2.92344e-08 4643.39 -113.022 -1730.3 3867.77 123.934 4613.64 +EDGE_SE3:QUAT 184 234 5.79777 -0.109456 -2.59426 0.0156755 0.041481 -0.0178192 0.998857 1 1.20371e-20 1.20371e-20 6.95536e-09 -1.15374e-10 2.92425e-10 1 1.20371e-20 6.95536e-09 -1.15374e-10 2.92425e-10 1 6.95536e-09 -1.15374e-10 2.92425e-10 4027.21 1.94463 336.999 3992.96 -2.40413 4026.92 +EDGE_SE3:QUAT 183 234 5.37434 5.97837 -2.93693 -0.0613885 0.00091588 -0.0381346 0.997385 1 4.81482e-20 4.81482e-20 1.38416e-08 -5.26796e-10 -5.22295e-11 1 4.81482e-20 1.38416e-08 -5.26796e-10 -5.22295e-11 1 1.38416e-08 -5.26796e-10 -5.22295e-11 3985.01 0.921284 -20.7252 3999.94 0.569456 3994.27 +EDGE_SE3:QUAT 184 233 5.19818 -5.81473 -2.41786 -0.00830686 0.0753568 -0.232431 0.969654 1 1.20371e-20 1.20371e-20 6.79141e-09 -1.65451e-09 4.43378e-10 1 1.20371e-20 6.79141e-09 -1.65451e-09 4.43378e-10 1 6.79141e-09 -1.65451e-09 4.43378e-10 4070.91 -29.6907 539.779 3988.75 -64.2898 3855.09 +EDGE_SE3:QUAT 185 235 5.79252 -0.219116 -2.95243 0.144739 -0.103022 0.0507361 0.982783 1 1.01111e-18 1.01111e-18 -5.48931e-08 2.42365e-08 -1.13573e-08 1 1.01111e-18 -5.48931e-08 2.42365e-08 -1.13573e-08 1 -5.48931e-08 2.42365e-08 -1.13573e-08 4119.16 -61.2032 -923.651 3952.61 17.2994 4192.66 +EDGE_SE3:QUAT 184 235 5.59532 5.24517 -2.84128 -0.301672 0.143706 0.0121655 0.942441 1 3.12964e-18 3.12964e-18 1.10381e-07 -1.31224e-08 2.78334e-08 1 3.12964e-18 1.10381e-07 -1.31224e-08 2.78334e-08 1 1.10381e-07 -1.31224e-08 2.78334e-08 3915.58 -189.647 1097.81 3973.37 -137.87 4279.01 +EDGE_SE3:QUAT 185 234 5.27255 -5.88842 -2.68695 -0.0716583 0.0860147 -0.157973 0.981077 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4047.26 -37.2448 529.215 3989.89 -48.5326 3967.98 +EDGE_SE3:QUAT 186 236 5.37954 -0.165462 -2.71069 -0.215835 -0.105508 0.00669284 0.97069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3964.55 93.9259 -792.704 3974.65 -56.3406 4150.71 +EDGE_SE3:QUAT 185 236 5.37502 6.02925 -2.68757 -0.0790433 -0.193354 -0.0703951 0.975403 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4694.14 23.2827 -1842.22 3841.61 1.89288 4699.31 +EDGE_SE3:QUAT 186 235 5.14133 -5.92672 -2.54156 0.00345344 -0.0354529 -0.13796 0.989797 1 7.70372e-19 7.70372e-19 -1.8446e-09 7.25361e-10 5.50725e-08 1 7.70372e-19 -1.8446e-09 7.25361e-10 5.50725e-08 1 -1.8446e-09 7.25361e-10 5.50725e-08 4018.21 -4.37794 -270.958 3995.98 18.7061 3942.13 +EDGE_SE3:QUAT 187 237 5.73292 -0.0673582 -2.72907 0.0349988 -0.180477 0.02408 0.982661 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4578.19 -16.4271 -1634.73 3868.57 5.83207 4580.77 +EDGE_SE3:QUAT 186 237 4.96916 5.56517 -2.74869 0.09538 0.1026 0.147474 0.979095 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4057.59 54.1894 625.652 3986.99 61.1245 4006.99 +EDGE_SE3:QUAT 187 236 4.9308 -5.55079 -3.17102 0.202699 0.0616099 -0.0554201 0.975728 1 1.92593e-19 1.92593e-19 7.43006e-10 2.71154e-08 -5.46244e-09 1 1.92593e-19 7.43006e-10 2.71154e-08 -5.46244e-09 1 7.43006e-10 2.71154e-08 -5.46244e-09 3924.93 60.847 604.599 3978.68 7.41308 4077 +EDGE_SE3:QUAT 188 238 5.45989 -0.0486248 -2.83012 -0.025718 0.0174273 0.264984 0.963752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.62 0.785601 203.332 3997.46 29.6473 3729.39 +EDGE_SE3:QUAT 187 238 4.93861 5.53914 -2.42918 -0.0448838 0.0488776 0.177008 0.98197 1 8.1852e-19 8.1852e-19 1.02653e-09 1.22274e-08 5.52441e-08 1 8.1852e-19 1.02653e-09 1.22274e-08 5.52441e-08 1 1.02653e-09 1.22274e-08 5.52441e-08 4046.61 2.34931 471.117 3986.48 41.7687 3929.34 +EDGE_SE3:QUAT 188 237 5.16513 -5.37033 -2.85704 -0.0634436 0.0431084 -0.115308 0.990364 1 1.92593e-19 1.92593e-19 -2.75413e-08 3.34178e-09 -7.52186e-10 1 1.92593e-19 -2.75413e-08 3.34178e-09 -7.52186e-10 1 -2.75413e-08 3.34178e-09 -7.52186e-10 3999.12 -10.1932 249.613 3997.47 -14.4815 3962.04 +EDGE_SE3:QUAT 189 239 5.51199 -0.33106 -2.97455 0.204496 -0.0823615 -0.110673 0.969097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3858.39 -32.3023 -342.418 4000.21 26.8699 3976.67 +EDGE_SE3:QUAT 188 239 5.14117 6.25117 -2.65085 -0.0950294 0.174585 -0.0075526 0.980017 1 2.0463e-19 2.0463e-19 -3.01572e-08 2.02024e-09 -1.22308e-08 1 2.0463e-19 -3.01572e-08 2.02024e-09 -1.22308e-08 1 -3.01572e-08 2.02024e-09 -1.22308e-08 4475.75 -101.492 1519.81 3891.68 -85.9983 4511.65 +EDGE_SE3:QUAT 189 238 4.98814 -5.86939 -2.81184 -0.0217504 -0.0330641 -0.0705299 0.996724 1 6.01853e-20 6.01853e-20 -7.89359e-09 -1.33523e-08 1.39406e-11 1 6.01853e-20 -7.89359e-09 -1.33523e-08 1.39406e-11 1 -7.89359e-09 -1.33523e-08 1.39406e-11 4017.88 1.11458 -281.968 3994.98 9.62637 3999.88 +EDGE_SE3:QUAT 190 240 5.8279 -0.200442 -2.67831 -0.0382316 -0.0911194 -0.0407726 0.99427 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4136.45 7.33052 -767.766 3965.15 8.94731 4135.65 +EDGE_SE3:QUAT 189 240 5.43781 5.73904 -2.97676 -0.0233955 -0.0551614 0.118572 0.991136 1 1.20371e-20 1.20371e-20 -6.91213e-09 -8.48754e-10 3.34697e-10 1 1.20371e-20 -6.91213e-09 -8.48754e-10 3.34697e-10 1 -6.91213e-09 -8.48754e-10 3.34697e-10 4037.71 12.2145 -401.86 3991.49 -25.1495 3983.66 +EDGE_SE3:QUAT 190 239 5.01973 -6.07334 -2.50336 0.0557957 0.0775753 -0.0844549 0.991835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4101.51 6.66084 684.85 3971.56 -22.2174 4085.44 +EDGE_SE3:QUAT 191 241 5.61834 -0.0929872 -2.70918 -0.0943282 0.0536645 0.0540669 0.992622 1 4.81482e-20 4.81482e-20 8.75286e-10 -1.23835e-09 1.38776e-08 1 4.81482e-20 8.75286e-10 -1.23835e-09 1.38776e-08 1 8.75286e-10 -1.23835e-09 1.38776e-08 4023.31 -20.1326 489.193 3984.84 6.14819 4047.21 +EDGE_SE3:QUAT 190 241 5.42987 5.79566 -2.70268 0.116704 -0.101658 0.152134 0.976167 1 3.85186e-19 3.85186e-19 3.15284e-08 -2.35232e-08 -1.40616e-09 1 3.85186e-19 3.15284e-08 -2.35232e-08 -1.40616e-09 1 3.15284e-08 -2.35232e-08 -1.40616e-09 4198.4 -16.884 -1037.93 3937.45 -51.8965 4160.3 +EDGE_SE3:QUAT 191 240 5.10902 -5.87151 -3.123 0.235249 -0.224175 -0.162463 0.93167 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4059.13 -263.582 -1141.36 4045.78 265.012 4174.92 +EDGE_SE3:QUAT 192 242 5.71102 0.106306 -2.96441 0.157514 -0.0312753 0.0299181 0.986568 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3922.77 -24.0509 -297.798 3994.42 0.185668 4018.44 +EDGE_SE3:QUAT 191 242 5.32329 5.87229 -3.00839 0.0967117 0.0653136 -0.0764998 0.990217 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.91 22.3553 611.645 3976.49 -12.9205 4067.91 +EDGE_SE3:QUAT 192 241 4.95343 -6.12339 -2.26661 -0.188898 -0.0888276 -0.0927421 0.973564 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4054.63 74.598 -910.938 3951.96 -4.07379 4162.95 +EDGE_SE3:QUAT 193 243 5.70909 -0.193193 -2.77689 0.0126458 -0.112228 0.0102584 0.993549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4209.37 -3.43824 -940.285 3949.47 -1.39539 4209.59 +EDGE_SE3:QUAT 192 243 5.40129 5.6721 -2.64726 -0.146631 0.0900189 0.0648847 0.982948 1 9.62965e-19 9.62965e-19 5.47027e-08 2.94091e-08 9.71535e-09 1 9.62965e-19 5.47027e-08 2.94091e-08 9.71535e-09 1 5.47027e-08 2.94091e-08 9.71535e-09 4082 -53.6589 837.047 3959.38 -5.43316 4151.16 +EDGE_SE3:QUAT 193 242 5.31386 -5.73997 -2.78645 -0.0808495 -0.0341829 -0.172347 0.981117 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.45 9.57613 -426.87 3987.11 37.2355 3925.78 +EDGE_SE3:QUAT 194 244 5.95751 0.2244 -3.072 -0.160312 0.0422318 0.0441675 0.985173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3939.03 -33.0708 411.554 3989.33 0.335376 4034.02 +EDGE_SE3:QUAT 193 244 5.48128 6.06631 -2.81151 -0.119482 0.0675033 -0.104643 0.984996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.49 -26.2932 373.312 3995.37 -24.8051 3989.79 +EDGE_SE3:QUAT 194 243 5.44654 -6.44404 -3.17288 0.0976483 -0.00527297 -0.164056 0.981592 1 7.70372e-19 7.70372e-19 -1.47516e-09 -5.22552e-09 -5.45213e-08 1 7.70372e-19 -1.47516e-09 -5.22552e-09 -5.45213e-08 1 -1.47516e-09 -5.22552e-09 -5.45213e-08 3966.39 9.70675 147.825 3997.24 -17.0476 3896.87 +EDGE_SE3:QUAT 195 245 5.51774 -0.0575161 -2.65026 0.0767259 0.0260963 -0.0939305 0.992275 1 1.92593e-19 1.92593e-19 2.76142e-08 -2.47697e-09 1.10383e-09 1 1.92593e-19 2.76142e-08 -2.47697e-09 1.10383e-09 1 2.76142e-08 -2.47697e-09 1.10383e-09 3997.41 9.70905 291.369 3993.93 -12.9613 3985.66 +EDGE_SE3:QUAT 194 245 5.0418 6.15719 -2.87874 -0.0105435 -0.102499 0.124088 0.986907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4157.97 35.6009 -811.849 3965.7 -57.6987 4096.82 +EDGE_SE3:QUAT 195 244 4.724 -6.19248 -2.99442 0.045936 -0.144459 -0.0702045 0.985948 1 4.81482e-20 4.81482e-20 -1.42274e-08 1.24854e-09 1.95626e-09 1 4.81482e-20 -1.42274e-08 1.24854e-09 1.95626e-09 1 -1.42274e-08 1.24854e-09 1.95626e-09 4313.43 -68.621 -1179.68 3930.75 73.2908 4302.16 +EDGE_SE3:QUAT 196 246 5.3482 0.067681 -3.14886 -0.0530356 -0.080817 0.105401 0.98972 1 2.40741e-19 2.40741e-19 -1.19894e-08 3.42656e-10 -2.68079e-08 1 2.40741e-19 -1.19894e-08 3.42656e-10 -2.68079e-08 1 -1.19894e-08 3.42656e-10 -2.68079e-08 4069.62 29.3589 -575.356 3983.57 -37.7124 4036.43 +EDGE_SE3:QUAT 195 246 5.6806 6.00884 -2.91438 0.0190839 -0.175273 -0.0929028 0.979941 1 7.70372e-19 7.70372e-19 5.86674e-09 5.43257e-08 -2.99077e-09 1 7.70372e-19 5.86674e-09 5.43257e-08 -2.99077e-09 1 5.86674e-09 5.43257e-08 -2.99077e-09 4503.76 -94.9715 -1508.85 3894.63 107.804 4470.7 +EDGE_SE3:QUAT 196 245 5.03436 -6.07786 -2.91766 -0.0329429 -0.0916686 -0.103942 0.989802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4144.84 -9.04847 -786.776 3964.27 37.8247 4105.97 +EDGE_SE3:QUAT 197 247 5.64437 -0.164072 -2.75615 -0.023983 -0.132964 -0.0894547 0.986784 1 3.00927e-21 3.00927e-21 -3.55331e-09 3.10234e-10 4.86373e-10 1 3.00927e-21 -3.55331e-09 3.10234e-10 4.86373e-10 1 -3.55331e-09 3.10234e-10 4.86373e-10 4304.04 -25.9814 -1148.56 3929.26 50.1023 4274.33 +EDGE_SE3:QUAT 196 247 5.54697 6.18158 -2.96999 0.0993339 -0.157658 0.14475 0.971763 1 1.54074e-18 1.54074e-18 1.7076e-08 -5.73201e-08 -5.44719e-08 1 1.54074e-18 1.7076e-08 -5.73201e-08 -5.44719e-08 1 1.7076e-08 -5.73201e-08 -5.44719e-08 4486.03 15.0561 -1542.33 3881.3 -68.4518 4441.69 +EDGE_SE3:QUAT 197 246 5.39434 -6.27644 -2.94286 -0.219047 -0.00532067 -0.0177694 0.975538 1 7.73381e-19 7.73381e-19 5.42136e-08 2.61903e-09 7.03754e-11 1 7.73381e-19 5.42136e-08 2.61903e-09 7.03754e-11 1 5.42136e-08 2.61903e-09 7.03754e-11 3809.83 10.8387 -84.7638 3999.45 0.40268 4000.5 +EDGE_SE3:QUAT 198 248 5.51866 0.245103 -2.87143 -0.0519814 0.141573 0.0188472 0.988382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4334.8 -28.6788 1225.51 3919.31 -13.8794 4344.19 +EDGE_SE3:QUAT 197 248 5.33688 5.83978 -3.01045 -0.0646265 0.114279 0.217907 0.967099 1 1.92593e-19 1.92593e-19 2.7777e-08 5.97199e-09 3.75022e-09 1 1.92593e-19 2.7777e-08 5.97199e-09 3.75022e-09 1 2.7777e-08 5.97199e-09 3.75022e-09 4252.87 47.5406 1072.88 3943.04 113.552 4079.64 +EDGE_SE3:QUAT 198 247 4.8274 -5.93428 -3.11188 0.0336054 0.0864238 -0.152213 0.983988 1 7.70372e-19 7.70372e-19 -5.22124e-09 -3.53435e-10 -5.55638e-08 1 7.70372e-19 -5.22124e-09 -3.53435e-10 -5.55638e-08 1 -5.22124e-09 -3.53435e-10 -5.55638e-08 4131.29 -17.2687 749.451 3968.74 -56.0062 4043.13 +EDGE_SE3:QUAT 199 249 5.5916 0.250764 -2.47558 -0.0724224 -0.0619651 -0.0322409 0.994925 1 3.97223e-19 3.97223e-19 -2.80326e-08 -2.64917e-08 -7.02979e-09 1 3.97223e-19 -2.80326e-08 -2.64917e-08 -7.02979e-09 1 -2.80326e-08 -2.64917e-08 -7.02979e-09 4047.28 16.9188 -527 3982.98 1.64344 4064.1 +EDGE_SE3:QUAT 198 249 5.63788 6.25086 -3.28155 0.0744941 0.0776775 0.0791703 0.991034 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.2 29.9942 547.678 3984.98 30.7198 4048.32 +EDGE_SE3:QUAT 199 248 4.92075 -6.10454 -2.90008 0.0429162 -1.13897e-05 -0.0300567 0.998626 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.69 0.438749 15.3601 3999.97 -0.306137 3996.44 +EDGE_SE3:QUAT 200 250 5.87019 0.296383 -2.82807 0.0863715 0.00472824 0.132318 0.987426 1 7.52316e-22 7.52316e-22 2.27531e-10 -1.71318e-09 1.46741e-10 1 7.52316e-22 2.27531e-10 -1.71318e-09 1.46741e-10 1 2.27531e-10 -1.71318e-09 1.46741e-10 3972.09 -6.02376 -98.4844 3998.71 -9.42599 3931.9 +EDGE_SE3:QUAT 199 250 5.28925 5.86577 -2.90151 0.0364964 -0.124741 0.122595 0.98391 1 4.81482e-20 4.81482e-20 -1.41286e-08 -1.68132e-09 1.86341e-09 1 4.81482e-20 -1.41286e-08 -1.68132e-09 1.86341e-09 1 -1.41286e-08 -1.68132e-09 1.86341e-09 4272.9 28.8872 -1091.02 3936.36 -63.5742 4218.11 +EDGE_SE3:QUAT 200 249 5.03269 -5.76747 -2.80934 0.0104411 -0.000586313 0.0198905 0.999747 1 1.20371e-20 1.20371e-20 -6.94568e-12 7.22309e-11 6.93715e-09 1 1.20371e-20 -6.94568e-12 7.22309e-11 6.93715e-09 1 -6.94568e-12 7.22309e-11 6.93715e-09 3999.58 -0.0414787 -7.1783 4000 -0.0794688 3998.43 +EDGE_SE3:QUAT 201 251 5.51937 -0.148639 -2.64908 0.17465 -0.0209604 -0.121294 0.976906 1 1.92593e-19 1.92593e-19 -6.20145e-10 -4.84274e-09 -2.71155e-08 1 1.92593e-19 -6.20145e-10 -4.84274e-09 -2.71155e-08 1 -6.20145e-10 -4.84274e-09 -2.71155e-08 3878.24 15.5926 90.1422 3998 -10.8169 3941.4 +EDGE_SE3:QUAT 200 251 5.33202 6.06795 -2.86517 -0.0873465 -0.071192 0.133672 0.984598 1 1.01111e-18 1.01111e-18 -2.79295e-08 -2.34855e-08 5.47396e-08 1 1.01111e-18 -2.79295e-08 -2.34855e-08 5.47396e-08 1 -2.79295e-08 -2.34855e-08 5.47396e-08 4010.61 26.4465 -412.086 3993.96 -31.5804 3969.66 +EDGE_SE3:QUAT 201 250 5.00246 -5.81458 -2.82159 -0.307478 0.0844389 -0.0552745 0.946188 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3655.45 -50.6603 387.355 4002.18 -32.6463 4021.4 +EDGE_SE3:QUAT 202 252 5.68227 0.44631 -2.97122 0.0740827 -0.080888 0.0278957 0.993575 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4091.33 -22.5868 -682.637 3972.31 2.32896 4110.17 +EDGE_SE3:QUAT 201 252 5.49702 6.20194 -2.73094 0.120877 0.0167294 0.150775 0.981007 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3942.13 -9.75739 -86.8721 3998.36 -12.1941 3909.64 +EDGE_SE3:QUAT 202 251 5.21917 -5.71154 -2.88012 0.0298139 0.200205 -0.132035 0.970359 1 1.88079e-22 1.88079e-22 9.169e-10 -1.23711e-10 1.89822e-10 1 1.88079e-22 9.169e-10 -1.23711e-10 1.89822e-10 1 9.169e-10 -1.23711e-10 1.89822e-10 4730.12 -118.17 1863.64 3851.76 -142.616 4663.95 +EDGE_SE3:QUAT 203 253 5.44082 0.0297183 -2.71966 0.119004 0.117484 -0.0439771 0.984937 1 1.92593e-19 1.92593e-19 2.81987e-08 -4.47823e-10 3.56033e-09 1 1.92593e-19 2.81987e-08 -4.47823e-10 3.56033e-09 1 2.81987e-08 -4.47823e-10 3.56033e-09 4195.55 55.2213 1035.59 3941.2 19.0916 4244.46 +EDGE_SE3:QUAT 202 253 4.92798 5.59787 -2.83774 0.121737 0.0783671 -0.0982142 0.984577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4084.08 33.1238 771.419 3963.3 -17.9936 4104.78 +EDGE_SE3:QUAT 203 252 5.07026 -5.95231 -2.97606 0.0765358 0.175025 0.0392475 0.9808 1 1.92593e-19 1.92593e-19 -2.88688e-08 -2.03778e-09 -4.88016e-09 1 1.92593e-19 -2.88688e-08 -2.03778e-09 -4.88016e-09 1 -2.88688e-08 -2.03778e-09 -4.88016e-09 4470.08 106.002 1489.39 3897.54 99.5916 4487.35 +EDGE_SE3:QUAT 204 254 5.66739 -0.10207 -2.54497 0.00592395 -0.0694969 0.0425305 0.996658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.71 3.30648 -567.097 3980.68 -11.9809 4071.61 +EDGE_SE3:QUAT 203 254 5.28673 5.93303 -3.01676 0.0195566 -0.0956475 0.0337601 0.99465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4151.54 -0.718696 -797.327 3962.76 -10.2584 4148.52 +EDGE_SE3:QUAT 204 253 5.03426 -6.18801 -2.69847 0.109438 0.0305351 -0.0448282 0.992513 1 1.92593e-19 1.92593e-19 2.76251e-08 -1.03545e-09 1.09797e-09 1 1.92593e-19 2.76251e-08 -1.03545e-09 1.09797e-09 1 2.76251e-08 -1.03545e-09 1.09797e-09 3974.28 16.1646 299.121 3994.03 -3.79408 4014.14 +EDGE_SE3:QUAT 205 255 5.56834 -0.0867893 -2.82368 0.116644 -0.0723518 0.103132 0.985151 1 1.92593e-19 1.92593e-19 2.62039e-09 -2.83941e-09 -2.778e-08 1 1.92593e-19 2.62039e-09 -2.83941e-09 -2.778e-08 1 2.62039e-09 -2.83941e-09 -2.778e-08 4071.53 -29.0649 -721.691 3967.32 -21.14 4083.41 +EDGE_SE3:QUAT 204 255 5.30224 5.64262 -2.71908 -0.0128721 -0.0148812 0.0787475 0.9967 1 3.00927e-21 3.00927e-21 -3.45921e-09 -2.74654e-10 4.39726e-11 1 3.00927e-21 -3.45921e-09 -2.74654e-10 4.39726e-11 1 -3.45921e-09 -2.74654e-10 4.39726e-11 4002.13 1.00464 -105.86 3999.38 -4.05923 3977.99 +EDGE_SE3:QUAT 205 254 4.96663 -6.28897 -2.84074 -0.0883541 0.00957389 -0.0293398 0.995611 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3969.24 -1.53097 44.6687 3999.93 -0.587242 3997.03 +EDGE_SE3:QUAT 206 256 5.76087 0.244736 -2.82818 -0.0153857 -0.0981217 0.0162952 0.994922 1 2.0463e-19 2.0463e-19 -6.49209e-09 -2.77521e-08 1.64586e-10 1 2.0463e-19 -6.49209e-09 -2.77521e-08 1.64586e-10 1 -6.49209e-09 -2.77521e-08 1.64586e-10 4156.13 10.7558 -808.084 3962.09 -10.9413 4156.02 +EDGE_SE3:QUAT 205 256 5.4828 6.34106 -3.28067 -0.00877524 -0.166499 0.0452896 0.984962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4475.53 42.5053 -1459.38 3892.84 -49.4268 4467.63 +EDGE_SE3:QUAT 206 255 4.88904 -5.90782 -3.04019 -0.0704258 -0.0567116 -0.111305 0.989664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4052.79 9.43612 -544.379 3981.06 25.8247 4023.08 +EDGE_SE3:QUAT 207 257 5.3297 0.0018288 -3.09456 -0.0505265 0.0625715 -0.0130081 0.996676 1 4.81482e-20 4.81482e-20 -2.69118e-10 -1.38302e-08 -7.29048e-10 1 4.81482e-20 -2.69118e-10 -1.38302e-08 -7.29048e-10 1 -2.69118e-10 -1.38302e-08 -7.29048e-10 4050.63 -14.1898 497.084 3985.36 -8.03549 4060.17 +EDGE_SE3:QUAT 206 257 5.28298 6.10696 -3.06588 -0.0621622 -0.0366459 0.0602753 0.99557 1 2.40741e-19 2.40741e-19 -2.67898e-08 -1.56063e-08 -1.23928e-10 1 2.40741e-19 -2.67898e-08 -1.56063e-08 -1.23928e-10 1 -2.67898e-08 -1.56063e-08 -1.23928e-10 3999.52 8.71669 -245.786 3996.88 -8.54395 4000.44 +EDGE_SE3:QUAT 207 256 5.07596 -6.23169 -2.67448 0.12084 0.134766 -0.0137198 0.983386 1 1.88079e-22 1.88079e-22 -1.2071e-10 -1.09505e-10 -8.85346e-10 1 1.88079e-22 -1.2071e-10 -1.09505e-10 -8.85346e-10 1 -1.2071e-10 -1.09505e-10 -8.85346e-10 4246.58 76.2096 1145.88 3932.82 48.3497 4304.23 +EDGE_SE3:QUAT 208 258 5.36299 0.179036 -2.95937 -0.249195 0.0512444 -0.123816 0.959138 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3747.07 15.7484 11.1079 3999.4 7.30469 3934.14 +EDGE_SE3:QUAT 207 258 5.10397 6.26065 -3.17072 -0.0458431 0.118784 0.159543 0.978946 1 2.0463e-19 2.0463e-19 -1.12633e-08 2.6105e-08 -7.2708e-10 1 2.0463e-19 -1.12633e-08 2.6105e-08 -7.2708e-10 1 -1.12633e-08 2.6105e-08 -7.2708e-10 4254.05 35.4416 1057.7 3941.43 81.1719 4160.64 +EDGE_SE3:QUAT 208 257 5.12257 -6.01765 -2.83488 0.0582415 0.108752 -0.0624642 0.990393 1 9.62965e-20 9.62965e-20 -1.24755e-08 1.37003e-09 1.24755e-08 1 9.62965e-20 -1.24755e-08 1.37003e-09 1.24755e-08 1 -1.24755e-08 1.37003e-09 1.24755e-08 4199.47 11.4461 947.437 3948.36 -15.0977 4197.43 +EDGE_SE3:QUAT 209 259 5.64186 -0.0826943 -2.87664 -0.0039131 -0.139005 -0.0669558 0.988018 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4325.25 -31.2205 -1186.2 3925.17 45.8843 4307.37 +EDGE_SE3:QUAT 208 259 5.25247 6.03379 -2.65644 -0.0480506 -0.166021 0.167216 0.970653 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4350.82 139.872 -1255.47 3943.62 -157.978 4248.21 +EDGE_SE3:QUAT 209 258 4.86513 -6.41084 -2.74829 0.0456871 -0.085661 -0.0334934 0.994713 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4103.92 -22.3316 -679.528 3973.64 20.0382 4107.78 +EDGE_SE3:QUAT 210 260 5.65708 0.100912 -2.78758 0.026235 -0.00735044 0.108966 0.993672 1 2.0463e-19 2.0463e-19 -6.5401e-09 -1.41969e-09 -2.7498e-08 1 2.0463e-19 -6.5401e-09 -1.41969e-09 -2.7498e-08 1 -6.5401e-09 -1.41969e-09 -2.7498e-08 3999.32 -1.05713 -91.7661 3999.36 -5.53695 3954.58 +EDGE_SE3:QUAT 209 260 5.05848 6.38338 -2.81593 0.0234843 -0.082804 0.203366 0.975312 1 1.93345e-19 1.93345e-19 3.89823e-09 -2.74326e-08 -1.68308e-10 1 1.93345e-19 3.89823e-09 -2.74326e-08 -1.68308e-10 1 3.89823e-09 -2.74326e-08 -1.68308e-10 4115.11 27.8356 -695.068 3975.85 -72.4679 3951.89 +EDGE_SE3:QUAT 210 259 5.36335 -6.02076 -2.60052 0.0365195 -0.191984 -0.104921 0.97509 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4581.51 -143.2 -1641.17 3887.32 153.364 4542.81 +EDGE_SE3:QUAT 211 261 5.64296 -0.159488 -2.96184 -0.0286099 0.0209071 0.120272 0.992108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.16 -1.37253 204.834 3997.2 12.7248 3952.57 +EDGE_SE3:QUAT 210 261 5.42841 6.09466 -3.15088 -0.109298 0.0508981 0.0905205 0.988569 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.62 -23.0775 520.573 3982.09 15.9383 4033.63 +EDGE_SE3:QUAT 211 260 5.11074 -6.10553 -3.1053 -0.104698 0.16448 0.174477 0.965164 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4551.2 41.895 1653.79 3869.95 101.813 4473.28 +EDGE_SE3:QUAT 212 262 5.55149 0.00351138 -3.06903 0.174826 -0.142609 0.0387998 0.973444 1 7.73381e-19 7.73381e-19 5.70592e-08 -1.35452e-09 -1.20771e-08 1 7.73381e-19 5.70592e-08 -1.35452e-09 -1.20771e-08 1 5.70592e-08 -1.35452e-09 -1.20771e-08 4242.88 -114.581 -1262.51 3924.16 69.8649 4359.11 +EDGE_SE3:QUAT 211 262 5.29529 6.15779 -2.90518 -0.0286322 -0.14768 0.0803882 0.985347 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4341.77 65.5304 -1224.61 3925.21 -75.5552 4319.2 +EDGE_SE3:QUAT 212 261 4.92152 -6.15755 -2.82938 -0.0783666 0.0813174 -1.94531e-05 0.993603 1 3.85938e-19 3.85938e-19 2.77274e-08 -2.80768e-08 1.8006e-09 1 3.85938e-19 2.77274e-08 -2.80768e-08 1.8006e-09 1 2.77274e-08 -2.80768e-08 1.8006e-09 4081.33 -27.5594 659.394 3974.9 -12.7001 4105.89 +EDGE_SE3:QUAT 213 263 5.70876 -0.0444967 -2.95425 0.00898383 0.0617118 -0.0688607 0.995675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4062.3 -4.14383 504.402 3984.74 -17.2694 4043.66 +EDGE_SE3:QUAT 212 263 5.24265 5.83825 -2.90662 0.208258 0.0426933 0.287711 0.933825 1 7.70372e-19 7.70372e-19 -5.20164e-08 -1.55326e-08 4.45582e-09 1 7.70372e-19 -5.20164e-08 -1.55326e-08 4.45582e-09 1 -5.20164e-08 -1.55326e-08 4.45582e-09 3850.64 -61.5775 -381.546 3975.02 -88.6524 3693.02 +EDGE_SE3:QUAT 213 262 5.32296 -6.30537 -2.66636 0.0194224 -0.040633 0.0628097 0.997009 1 6.01853e-20 6.01853e-20 -6.34791e-09 -6.25729e-10 -1.35884e-08 1 6.01853e-20 -6.34791e-09 -6.25729e-10 -1.35884e-08 1 -6.34791e-09 -6.25729e-10 -1.35884e-08 4027.14 -0.731228 -339.737 3992.81 -10.1703 4012.87 +EDGE_SE3:QUAT 214 264 5.67881 -0.100077 -2.67169 0.114238 -0.161349 0.142033 0.969919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4513.61 -0.677709 -1607.58 3872.05 -55.2204 4485.12 +EDGE_SE3:QUAT 213 264 5.36487 6.14701 -3.04287 -0.133714 -0.00170644 0.168927 0.976515 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3942.45 -20.5182 250.842 3993.04 27.0384 3899.82 +EDGE_SE3:QUAT 214 263 5.1583 -6.30907 -2.68673 -0.254147 0.121083 -0.208771 0.93657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3734.26 -3.9823 210.36 4007.86 -7.51237 3818.28 +EDGE_SE3:QUAT 215 265 5.54385 0.106236 -2.71486 0.177139 0.00192735 0.207088 0.96215 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3911.82 -41.6414 -408.603 3982.15 -51.167 3865.79 +EDGE_SE3:QUAT 214 265 5.06977 6.34241 -2.97194 0.0726596 -0.115912 0.245578 0.959675 1 4.81482e-20 4.81482e-20 -1.38242e-08 -3.37253e-09 1.9603e-09 1 4.81482e-20 -1.38242e-08 -3.37253e-09 1.9603e-09 1 -1.38242e-08 -3.37253e-09 1.9603e-09 4269.49 58.9304 -1116.68 3941.28 -134.674 4049.37 +EDGE_SE3:QUAT 215 264 4.94498 -6.05817 -2.98925 -0.101927 -0.0826615 -0.0976204 0.986533 1 1.92593e-19 1.92593e-19 2.78961e-08 -2.26775e-09 -2.81059e-09 1 1.92593e-19 2.78961e-08 -2.26775e-09 -2.81059e-09 1 2.78961e-08 -2.26775e-09 -2.81059e-09 4107.44 24.2294 -786.727 3962.26 21.3847 4110.88 +EDGE_SE3:QUAT 216 266 5.20119 -0.0740365 -3.23141 0.0221883 -0.00495919 -0.0594965 0.99797 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.16 -0.219231 -23.6348 3999.98 0.54986 3985.97 +EDGE_SE3:QUAT 215 266 5.43451 6.4069 -3.09844 -0.0331291 0.117698 0.0865201 0.988718 1 1.92593e-19 1.92593e-19 -2.24696e-09 2.74555e-08 3.57146e-10 1 1.92593e-19 -2.24696e-09 2.74555e-08 3.57146e-10 1 -2.24696e-09 2.74555e-08 3.57146e-10 4238.91 12.6792 1016.08 3942.48 38.6786 4213.36 +EDGE_SE3:QUAT 216 265 5.07544 -6.11887 -2.92179 0.00168987 -0.10135 -0.0182504 0.994682 1 1.92781e-19 1.92781e-19 3.53999e-10 -2.76244e-08 6.24956e-11 1 1.92781e-19 3.53999e-10 -2.76244e-08 6.24956e-11 1 3.53999e-10 -2.76244e-08 6.24956e-11 4169.2 -5.51094 -839.933 3959.09 8.93341 4167.88 +EDGE_SE3:QUAT 217 267 5.61838 0.0830514 -3.13268 -0.0856942 -0.0341963 -0.0184572 0.995563 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.64 12.2756 -290.697 3994.72 0.114544 4019.65 +EDGE_SE3:QUAT 216 267 5.12368 6.01888 -2.7366 0.0289469 -0.0560502 0.123278 0.990365 1 6.01853e-20 6.01853e-20 -8.59783e-09 1.2905e-08 2.28064e-10 1 6.01853e-20 -8.59783e-09 1.2905e-08 2.28064e-10 1 -8.59783e-09 1.2905e-08 2.28064e-10 4054.96 3.16524 -486.511 3985.76 -29.2513 3997.52 +EDGE_SE3:QUAT 217 266 4.75892 -6.22925 -3.1581 -0.0545794 0.0762564 0.0248279 0.995284 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4086.98 -14.8973 636.704 3975.66 0.334166 4096.43 +EDGE_SE3:QUAT 218 268 5.62357 -0.153428 -3.16032 -0.157502 0.0402012 -0.0583781 0.984972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3910.25 -13.7734 199.857 3998.9 -7.74944 3995.85 +EDGE_SE3:QUAT 217 268 5.1231 6.60725 -2.62931 0.093127 -0.0102217 -0.0254418 0.995277 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3965.97 -2.01457 -52.3795 3999.9 0.662574 3998.07 +EDGE_SE3:QUAT 218 267 4.85124 -5.73304 -2.46586 -0.0622091 -0.29661 -0.010875 0.952908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5862.78 171.661 -3322.8 3661.52 -174.038 5877.79 +EDGE_SE3:QUAT 219 269 5.6822 -0.352842 -2.83399 -0.0772638 0.264042 -0.0119954 0.961337 1 1.92593e-19 1.92593e-19 -8.2882e-09 3.1081e-09 -3.08747e-08 1 1.92593e-19 -8.2882e-09 3.1081e-09 -3.08747e-08 1 -8.2882e-09 3.1081e-09 -3.08747e-08 5320.26 -211.892 2680.25 3752.23 -209.462 5343.56 +EDGE_SE3:QUAT 218 269 5.41534 6.15981 -2.86649 0.0898148 0.0754044 -0.026409 0.992749 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4066.89 26.8178 637.557 3975.86 4.32295 4096.37 +EDGE_SE3:QUAT 219 268 5.20002 -6.52878 -3.10007 0.0543368 0.0491132 -0.175461 0.981758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4047.75 -0.0532369 492.258 3984.88 -42.8639 3936.41 +EDGE_SE3:QUAT 220 270 5.48656 -0.129762 -2.74084 0.0770862 -0.0963816 -0.188947 0.974201 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.75 -46.6623 -558.082 3991.61 60.1496 3931.72 +EDGE_SE3:QUAT 219 270 5.09748 6.45335 -3.15236 -0.118942 -0.02165 0.187084 0.974876 1 9.63012e-19 9.63012e-19 -2.58149e-08 -1.13411e-08 5.3508e-08 1 9.63012e-19 -2.58149e-08 -1.13411e-08 5.3508e-08 1 -2.58149e-08 -1.13411e-08 5.3508e-08 3943.84 -11.3187 97.7272 3997.72 17.8452 3860.43 +EDGE_SE3:QUAT 220 269 4.68064 -6.60529 -2.97246 0.128948 -0.147434 -0.0722218 0.977967 1 1.54074e-18 1.54074e-18 4.99987e-08 -6.04914e-08 1.59e-09 1 1.54074e-18 4.99987e-08 -6.04914e-08 1.59e-09 1 4.99987e-08 -6.04914e-08 1.59e-09 4207.52 -114.344 -1084.38 3952.92 105.073 4253.16 +EDGE_SE3:QUAT 221 271 5.41902 -0.222778 -3.27935 0.214912 0.0915799 0.0821877 0.96885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3867.46 52.6137 471.649 3996.71 39.8933 4025.19 +EDGE_SE3:QUAT 220 271 5.30814 6.43069 -3.03179 -0.00951997 0.0111409 0.109324 0.993898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.13 -0.101236 99.9704 3999.36 5.63668 3954.69 +EDGE_SE3:QUAT 221 270 5.36664 -6.23846 -3.098 -0.245145 -0.0254679 0.0764938 0.966128 1 7.70372e-19 7.70372e-19 5.36217e-08 4.40617e-09 7.86034e-10 1 7.70372e-19 5.36217e-08 4.40617e-09 7.86034e-10 1 5.36217e-08 4.40617e-09 7.86034e-10 3758.34 -13.8955 31.3065 3999.23 4.36545 3975.31 +EDGE_SE3:QUAT 222 272 5.37021 0.278722 -3.01012 -0.169782 0.0147957 0.141896 0.9751 1 7.70372e-19 7.70372e-19 -3.36863e-09 8.87065e-09 -5.43884e-08 1 7.70372e-19 -3.36863e-09 8.87065e-09 -5.43884e-08 1 -3.36863e-09 8.87065e-09 -5.43884e-08 3921.34 -35.7749 393.312 3986.36 27.7382 3956.1 +EDGE_SE3:QUAT 221 272 5.25762 6.39294 -3.05405 0.0372269 -0.0943204 -0.1153 0.988142 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4114.39 -36.0147 -703.531 3975.09 49.8898 4066.76 +EDGE_SE3:QUAT 222 271 5.13216 -6.495 -2.9278 0.037345 -0.0259541 -0.144904 0.9884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.93 -3.38889 -136.766 3999.36 8.54178 3920.52 +EDGE_SE3:QUAT 223 273 5.67402 -0.00299511 -2.75921 0.00918327 -0.0468861 -0.0615757 0.996958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.38 -4.88496 -368.793 3991.9 11.9908 4018.55 +EDGE_SE3:QUAT 222 273 5.08899 6.12446 -3.10762 -0.0651646 0.0602097 0.162297 0.982745 1 4.81482e-20 4.81482e-20 -1.37901e-08 -2.16837e-09 -1.08805e-09 1 4.81482e-20 -1.37901e-08 -2.16837e-09 -1.08805e-09 1 -1.37901e-08 -2.16837e-09 -1.08805e-09 4069.95 -1.51646 596.68 3977.94 45.6467 3981.58 +EDGE_SE3:QUAT 223 272 4.86424 -6.27026 -3.17109 0.0833588 -0.102029 -0.0357946 0.990636 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4124.31 -44.527 -794.95 3966.36 35.4359 4146.98 +EDGE_SE3:QUAT 224 274 5.61448 0.238493 -3.29781 0.118344 0.03118 0.0629115 0.990487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3949.66 8.02947 154.484 3999.24 5.25361 3989.85 +EDGE_SE3:QUAT 223 274 4.93612 6.50254 -2.65259 0.114036 -0.045747 0.0427129 0.991503 1 2.88889e-19 2.88889e-19 -2.73524e-08 1.13508e-08 -1.38564e-08 1 2.88889e-19 -2.73524e-08 1.13508e-08 -1.38564e-08 1 -2.73524e-08 1.13508e-08 -1.38564e-08 3991.58 -22.8563 -420.073 3988.82 -2.40996 4036.29 +EDGE_SE3:QUAT 224 273 4.91146 -6.71434 -2.84283 -0.0115444 0.104087 -0.111407 0.988241 1 1.92593e-19 1.92593e-19 3.2245e-09 2.7414e-08 9.68805e-10 1 1.92593e-19 3.2245e-09 2.7414e-08 9.68805e-10 1 3.2245e-09 2.7414e-08 9.68805e-10 4164.78 -34.1371 829.976 3963.54 -53.7943 4115.67 +EDGE_SE3:QUAT 225 275 5.58309 -0.0652983 -3.11476 0.0623303 -0.0711687 -0.137403 0.985987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4034.44 -25.326 -452.308 3991.43 34.9586 3974.46 +EDGE_SE3:QUAT 224 275 5.39639 6.46691 -2.71579 -0.00411604 -0.111612 0.148219 0.982628 1 7.70372e-19 7.70372e-19 -5.98723e-09 -2.12426e-09 5.58528e-08 1 7.70372e-19 -5.98723e-09 -2.12426e-09 5.58528e-08 1 -5.98723e-09 -2.12426e-09 5.58528e-08 4189.3 46.49 -890.986 3960.63 -74.8744 4101.49 +EDGE_SE3:QUAT 225 274 4.99812 -6.6565 -2.9389 -0.0344056 0.0234381 -0.0594825 0.997361 1 1.20371e-20 1.20371e-20 4.23312e-10 6.91994e-09 2.56578e-10 1 1.20371e-20 4.23312e-10 6.91994e-09 2.56578e-10 1 4.23312e-10 6.91994e-09 2.56578e-10 4001.79 -3.27773 161.893 3998.57 -4.94465 3992.37 +EDGE_SE3:QUAT 226 276 5.63498 0.148678 -2.75859 -0.0841175 -0.283175 -0.0676204 0.952976 1 4.81482e-20 4.81482e-20 -4.82336e-09 -9.33807e-10 1.58833e-08 1 4.81482e-20 -4.82336e-09 -9.33807e-10 1.58833e-08 1 -4.82336e-09 -9.33807e-10 1.58833e-08 5725.44 51.0862 -3176.57 3670.19 -51.0994 5735.45 +EDGE_SE3:QUAT 225 276 5.30633 6.37243 -2.98632 -0.187934 -0.191504 0.0524262 0.961904 1 9.62965e-19 9.62965e-19 5.20204e-08 9.38647e-10 1.91887e-08 1 9.62965e-19 5.20204e-08 9.38647e-10 1.91887e-08 1 5.20204e-08 9.38647e-10 1.91887e-08 4324.5 220.421 -1446.49 3941.25 -204.373 4454.79 +EDGE_SE3:QUAT 226 275 5.17501 -6.54749 -2.90939 0.0640561 -0.0278434 -0.150257 0.986177 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.65 -2.80736 -100.334 3999.93 4.83333 3911.76 +EDGE_SE3:QUAT 227 277 5.69682 0.127663 -3.03357 -0.071668 0.0203891 -0.0716629 0.994642 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.8 -3.15079 99.3955 3999.66 -3.15061 3981.81 +EDGE_SE3:QUAT 226 277 5.2634 6.33303 -3.15333 -0.0281802 0.0878846 0.0747322 0.992924 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4130.41 3.61909 743.094 3967.53 24.6759 4111.24 +EDGE_SE3:QUAT 227 276 4.69194 -6.75115 -2.98784 0.0122792 -0.0543163 -0.0630093 0.996458 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4044.39 -7.01351 -426.658 3989.27 14.5672 4029.12 +EDGE_SE3:QUAT 228 278 5.53447 -0.186561 -2.98994 -0.149966 -0.0269551 -0.0289454 0.9879 1 2.40741e-20 2.40741e-20 3.75125e-10 7.88863e-09 -5.83957e-09 1 2.40741e-20 3.75125e-10 7.88863e-09 -5.83957e-09 1 3.75125e-10 7.88863e-09 -5.83957e-09 3926.9 20.1475 -260.497 3995.64 0.452687 4013.51 +EDGE_SE3:QUAT 227 278 5.22178 6.48771 -2.9609 -0.0898615 -0.06871 0.175442 0.977969 1 1.92593e-19 1.92593e-19 2.72361e-08 5.18085e-09 -8.94467e-10 1 1.92593e-19 2.72361e-08 5.18085e-09 -8.94467e-10 1 2.72361e-08 5.18085e-09 -8.94467e-10 3993.72 21.8107 -333.556 3997.87 -28.591 3902.9 +EDGE_SE3:QUAT 228 277 5.24804 -6.48643 -2.83219 -0.0625473 0.0425056 0.127055 0.989009 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.64 -6.61429 428.74 3987.86 25.7874 3980.72 +EDGE_SE3:QUAT 229 279 5.36632 0.0102049 -3.04147 0.0657144 0.0219405 0.021641 0.997362 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.9 5.20746 157.444 3998.61 2.28886 4004.3 +EDGE_SE3:QUAT 228 279 5.42111 6.5403 -2.86106 -0.0623905 -0.0438046 0.200956 0.976629 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.68 7.52576 -181.112 3999.76 -13.6657 3845.72 +EDGE_SE3:QUAT 229 278 5.06037 -6.79272 -3.17255 0.0178762 -0.125548 0.0472956 0.990798 1 1.20371e-20 1.20371e-20 -7.10243e-09 -3.16997e-10 9.07827e-10 1 1.20371e-20 -7.10243e-09 -3.16997e-10 9.07827e-10 1 -7.10243e-09 -3.16997e-10 9.07827e-10 4267.06 8.36799 -1070.22 3936.36 -22.2552 4259.39 +EDGE_SE3:QUAT 230 280 5.53929 0.0120774 -2.97096 0.104769 0.108815 0.17776 0.972412 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.05 59.2755 602.705 3992.13 67.4192 3959.56 +EDGE_SE3:QUAT 229 280 4.92809 6.66908 -3.11181 0.0220315 0.0444778 0.10304 0.993438 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.18 7.78757 324.558 3994.27 17.3767 3983.65 +EDGE_SE3:QUAT 230 279 4.82254 -6.48911 -2.77516 -0.0279566 -0.034806 -0.0126023 0.998923 1 6.31946e-20 6.31946e-20 6.97346e-09 1.36946e-08 3.60442e-09 1 6.31946e-20 6.97346e-09 1.36946e-08 3.60442e-09 1 6.97346e-09 1.36946e-08 3.60442e-09 4016.87 3.65575 -283.529 3994.99 0.981996 4019.36 +EDGE_SE3:QUAT 231 281 5.64213 -0.360999 -2.87115 0.148534 0.160798 -0.251418 0.942799 1 1.92593e-19 1.92593e-19 2.85597e-08 -6.32334e-09 6.32934e-09 1 1.92593e-19 2.85597e-08 -6.32334e-09 6.32934e-09 1 2.85597e-08 -6.32334e-09 6.32934e-09 4621.11 -76.9444 1828.39 3853.57 -171.109 4456.51 +EDGE_SE3:QUAT 230 281 5.09691 6.44223 -2.95379 0.0699872 0.016225 0.177493 0.981496 1 1.92781e-19 1.92781e-19 2.70858e-08 5.7915e-09 -3.213e-10 1 1.92781e-19 2.70858e-08 5.7915e-09 -3.213e-10 1 2.70858e-08 5.7915e-09 -3.213e-10 3979.89 -2.62988 -22.6975 3999.66 -6.6432 3873.47 +EDGE_SE3:QUAT 231 280 4.90222 -6.4852 -2.99484 0.0540772 0.00241961 -0.160249 0.985591 1 4.81482e-20 4.81482e-20 -1.36838e-08 2.20839e-09 -2.68847e-10 1 4.81482e-20 -1.36838e-08 2.20839e-09 -2.68847e-10 1 -1.36838e-08 2.20839e-09 -2.68847e-10 3991.68 3.61134 120.646 3998.55 -12.2337 3900.66 +EDGE_SE3:QUAT 232 282 5.57401 0.0453829 -3.07388 0.0429765 -0.0262676 -0.0130434 0.998646 1 4.81482e-20 4.81482e-20 1.38769e-08 -2.12195e-10 -3.47942e-10 1 4.81482e-20 1.38769e-08 -2.12195e-10 -3.47942e-10 1 1.38769e-08 -2.12195e-10 -3.47942e-10 4002.91 -4.54995 -203.231 3997.51 1.99483 4009.62 +EDGE_SE3:QUAT 231 282 4.97024 6.23956 -3.09228 0.235072 -0.0789814 0.120267 0.96127 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.83 -98.606 -939.671 3947.77 -0.141917 4151 +EDGE_SE3:QUAT 232 281 4.78641 -6.67133 -3.46695 0.0897093 -0.118696 0.158867 0.976025 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4274 9.79894 -1148.61 3927.95 -70.1218 4205.24 +EDGE_SE3:QUAT 233 283 5.41677 0.0201462 -3.17657 -0.0352956 -0.0812803 0.0642538 0.993992 1 4.81482e-20 4.81482e-20 -1.39616e-08 -9.93121e-10 1.06465e-09 1 4.81482e-20 -1.39616e-08 -9.93121e-10 1.06465e-09 1 -1.39616e-08 -9.93121e-10 1.06465e-09 4091.98 21.3824 -630.429 3977.76 -26.5785 4080.45 +EDGE_SE3:QUAT 232 283 5.22336 6.36979 -3.30318 -0.0883207 0.0859169 0.00149115 0.992379 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4087.24 -32.8791 698.447 3972.21 -15.4796 4118.43 +EDGE_SE3:QUAT 233 282 5.05739 -6.45544 -2.75847 -0.00148733 -0.0386347 -0.130252 0.990727 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.12 -4.37881 -305.072 3994.72 20.0044 3955.27 +EDGE_SE3:QUAT 234 284 5.41976 0.265462 -3.0898 -0.119063 -0.0878454 -0.0947781 0.984441 1 3.85186e-19 3.85186e-19 2.48944e-08 -4.96457e-09 2.48944e-08 1 3.85186e-19 2.48944e-08 -4.96457e-09 2.48944e-08 1 2.48944e-08 -4.96457e-09 2.48944e-08 4114.45 34.0561 -845.464 3956.98 16.2765 4135.22 +EDGE_SE3:QUAT 233 284 5.45156 6.14415 -3.2532 0.148975 0.191033 -0.0254183 0.96988 1 1.54074e-18 1.54074e-18 5.6289e-08 5.58281e-08 3.02444e-09 1 1.54074e-18 5.6289e-08 5.58281e-08 3.02444e-09 1 5.6289e-08 5.58281e-08 3.02444e-09 4560.84 154.969 1738.06 3871.77 126.997 4647.03 +EDGE_SE3:QUAT 234 283 5.11377 -6.43124 -2.67227 -0.0773116 -0.0348587 -0.0236146 0.996118 1 2.40741e-19 2.40741e-19 2.79752e-08 1.33243e-08 -7.36724e-12 1 2.40741e-19 2.79752e-08 1.33243e-08 -7.36724e-12 1 2.79752e-08 1.33243e-08 -7.36724e-12 3998.38 11.2136 -299.482 3994.34 1.13419 4020.06 +EDGE_SE3:QUAT 235 285 5.13921 -0.338954 -3.19672 -0.11713 0.0468536 -0.0692233 0.989593 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3962.75 -16.1295 268.899 3997.15 -11.9946 3998.46 +EDGE_SE3:QUAT 234 285 4.93989 6.47109 -2.88931 -0.129552 -0.153762 0.100287 0.974431 1 9.62965e-19 9.62965e-19 -5.25583e-08 -3.4349e-09 -2.11974e-08 1 9.62965e-19 -5.25583e-08 -3.4349e-09 -2.11974e-08 1 -5.25583e-08 -3.4349e-09 -2.11974e-08 4202.2 127.163 -1076.27 3959.95 -122.883 4229.1 +EDGE_SE3:QUAT 235 284 4.98523 -6.72649 -2.99101 0.132174 0.00207089 0.0231416 0.990954 1 7.70372e-19 7.70372e-19 -5.50095e-08 -1.26985e-09 2.25699e-10 1 7.70372e-19 -5.50095e-08 -1.26985e-09 2.25699e-10 1 -5.50095e-08 -1.26985e-09 2.25699e-10 3930.19 -2.14847 -20.1426 3999.93 -0.369911 3997.92 +EDGE_SE3:QUAT 236 286 5.70304 -0.148115 -3.51542 -0.0962364 -0.216374 -0.233685 0.943033 1 1.92593e-19 1.92593e-19 -2.95114e-08 6.63861e-09 7.36528e-09 1 1.92593e-19 -2.95114e-08 6.63861e-09 7.36528e-09 1 -2.95114e-08 6.63861e-09 7.36528e-09 4985.63 -221.692 -2266.42 3823.25 264.469 4804.24 +EDGE_SE3:QUAT 235 286 5.18185 6.26421 -3.08529 -0.0371005 -0.076885 -0.0796776 0.993158 1 1.20371e-20 1.20371e-20 6.9825e-09 -5.25254e-10 -5.74137e-10 1 1.20371e-20 6.9825e-09 -5.25254e-10 -5.74137e-10 1 6.9825e-09 -5.25254e-10 -5.74137e-10 4100.16 0.63776 -658.688 3973.94 22.5117 4080.27 +EDGE_SE3:QUAT 236 285 4.90638 -6.75353 -3.27975 -0.0296072 0.144875 -0.0571557 0.987354 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4335.93 -52.4494 1213.73 3924.06 -57.9223 4326.37 +EDGE_SE3:QUAT 237 287 5.90416 0.133164 -3.03 -0.0270741 -0.031133 -0.0736096 0.996433 1 1.20371e-20 1.20371e-20 -6.9301e-09 5.00547e-10 2.41564e-10 1 1.20371e-20 -6.9301e-09 5.00547e-10 2.41564e-10 1 -6.9301e-09 5.00547e-10 2.41564e-10 4015.43 1.8504 -271.742 3995.27 9.65656 3996.69 +EDGE_SE3:QUAT 236 287 5.12533 6.64874 -3.07883 -0.0629672 0.283846 0.0681038 0.954373 1 4.81482e-20 4.81482e-20 1.58896e-08 6.65897e-10 4.80597e-09 1 4.81482e-20 1.58896e-08 6.65897e-10 4.80597e-09 1 1.58896e-08 6.65897e-10 4.80597e-09 5729.95 15.9222 3167.19 3670 15.7504 5727.25 +EDGE_SE3:QUAT 237 286 4.94778 -6.12976 -3.14075 -0.0860273 -0.0525972 0.202477 0.974082 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.44 9.07899 -187.533 4000.28 -12.9543 3843.05 +EDGE_SE3:QUAT 238 288 5.31402 0.0789638 -3.20372 0.0687256 -0.117602 0.0512897 0.989351 1 1.92593e-19 1.92593e-19 9.95278e-10 -2.74789e-08 1.61327e-09 1 1.92593e-19 9.95278e-10 -2.74789e-08 1.61327e-09 1 9.95278e-10 -2.74789e-08 1.61327e-09 4229.29 -21.727 -1026.83 3940.44 -4.70939 4237.66 +EDGE_SE3:QUAT 237 288 5.25797 6.51337 -3.42749 0.0432006 0.245458 0.0529344 0.966996 1 8.1852e-19 8.1852e-19 -1.05649e-08 -5.48666e-08 5.55972e-10 1 8.1852e-19 -1.05649e-08 -5.48666e-08 5.55972e-10 1 -1.05649e-08 -5.48666e-08 5.55972e-10 5096.62 184.764 2374.02 3789.91 185.476 5092.87 +EDGE_SE3:QUAT 238 287 4.88059 -6.34443 -2.89845 0.0379595 -0.0369076 -0.024503 0.998297 1 4.81482e-20 4.81482e-20 -1.3889e-08 3.79847e-10 4.85442e-10 1 4.81482e-20 -1.3889e-08 3.79847e-10 4.85442e-10 1 -1.3889e-08 3.79847e-10 4.85442e-10 4014.35 -6.15168 -284.414 3995.18 4.65435 4017.72 +EDGE_SE3:QUAT 239 289 5.59438 0.222467 -2.94227 0.0112403 -0.0877692 0.0125157 0.995999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4126.18 -1.98747 -723.049 3969.04 -2.73214 4126.06 +EDGE_SE3:QUAT 238 289 5.42571 6.4228 -3.49775 0.0715642 -0.00109925 0.144703 0.986883 1 1.95602e-19 1.95602e-19 -2.79016e-08 -5.48204e-10 3.59679e-10 1 1.95602e-19 -2.79016e-08 -5.48204e-10 3.59679e-10 1 -2.79016e-08 -5.48204e-10 3.59679e-10 3983.4 -5.57489 -130.691 3998.21 -12.1647 3920.13 +EDGE_SE3:QUAT 239 288 5.00149 -6.27248 -2.95893 -0.0277657 -0.083074 -0.0334967 0.995593 1 2.0463e-19 2.0463e-19 7.82024e-09 2.7431e-08 2.80997e-11 1 2.0463e-19 7.82024e-09 2.7431e-08 2.80997e-11 1 7.82024e-09 2.7431e-08 2.80997e-11 4112.97 4.47597 -691.148 3971.49 7.61778 4111.56 +EDGE_SE3:QUAT 240 290 5.51623 0.200088 -2.91885 -0.0822407 -0.0194911 -0.00124748 0.996421 1 2.93874e-24 2.93874e-24 2.10841e-12 8.92488e-12 -1.08115e-10 1 2.93874e-24 2.10841e-12 8.92488e-12 -1.08115e-10 1 2.10841e-12 8.92488e-12 -1.08115e-10 3979 6.41517 -155.781 3998.53 -0.653629 4006.05 +EDGE_SE3:QUAT 239 290 5.30656 6.50199 -3.38798 0.102732 0.000436914 -0.0359218 0.99406 1 4.81482e-20 4.81482e-20 -1.07745e-10 -1.42167e-09 -1.37962e-08 1 4.81482e-20 -1.07745e-10 -1.42167e-09 -1.37962e-08 1 -1.07745e-10 -1.42167e-09 -1.37962e-08 3958.29 3.1719 47.3736 3999.76 -1.0616 3995.35 +EDGE_SE3:QUAT 240 289 4.95556 -6.45085 -3.27696 0.0784013 0.0604788 -0.200522 0.974673 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.09 0.235597 650.11 3973.93 -62.8515 3941.84 +EDGE_SE3:QUAT 241 291 5.21364 0.172487 -2.79141 0.0799506 -0.0878887 -0.00386984 0.992909 1 3.00927e-21 3.00927e-21 3.0335e-10 -2.88444e-10 -3.4976e-09 1 3.00927e-21 3.0335e-10 -2.88444e-10 -3.4976e-09 1 3.0335e-10 -2.88444e-10 -3.4976e-09 4097.07 -31.3121 -711.066 3971.22 16.5501 4122.58 +EDGE_SE3:QUAT 240 291 5.03492 6.52555 -3.27174 0.125661 0.116925 0.249554 0.953027 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.85 52.139 464.428 4005.59 57.2846 3795.9 +EDGE_SE3:QUAT 241 290 5.20504 -6.59729 -2.9935 0.0329474 0.0795428 -0.0264032 0.995937 1 1.20371e-20 1.20371e-20 -5.69625e-10 -2.0452e-10 -7.00194e-09 1 1.20371e-20 -5.69625e-10 -2.0452e-10 -7.00194e-09 1 -5.69625e-10 -2.0452e-10 -7.00194e-09 4101.81 7.43299 660.21 3973.87 -4.06723 4103.36 +EDGE_SE3:QUAT 242 292 5.4664 -0.0973805 -3.08419 -0.0796212 0.146211 0.0259958 0.985701 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4349.1 -47.8622 1279.87 3913.94 -25.9223 4371.76 +EDGE_SE3:QUAT 241 292 5.51386 6.79677 -3.17938 -0.0248202 -0.0628754 -0.0248745 0.997403 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.24 4.25587 -516.872 3983.69 4.2759 4063.23 +EDGE_SE3:QUAT 242 291 5.17232 -6.18943 -3.39753 -0.0620421 0.0182733 -0.0780882 0.994846 1 3.00927e-21 3.00927e-21 2.76762e-10 3.4511e-09 2.22556e-10 1 3.00927e-21 2.76762e-10 3.4511e-09 2.22556e-10 1 2.76762e-10 3.4511e-09 2.22556e-10 3986.36 -2.34709 86.2537 3999.76 -2.81949 3977.36 +EDGE_SE3:QUAT 243 293 5.23211 -0.186903 -2.86577 0.11093 0.118198 -0.142361 0.976451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4266.77 12.8372 1168.36 3923.94 -50.0244 4234.92 +EDGE_SE3:QUAT 242 293 5.31563 6.30215 -3.65791 -7.51754e-05 0.0339869 0.16578 0.985577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.06 4.38319 261.866 3996.37 21.6512 3907.13 +EDGE_SE3:QUAT 243 292 5.17586 -6.8707 -3.25899 0.0418786 0.0212511 -0.0654159 0.996752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.11 3.53562 201.708 3997.25 -6.38156 3993 +EDGE_SE3:QUAT 244 294 4.98422 -0.214713 -2.92269 0.043163 0.0739252 0.14743 0.985361 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.94 25.8025 500.852 3988.74 40.7332 3974.45 +EDGE_SE3:QUAT 243 294 5.14129 6.61244 -3.30882 0.159157 0.0504196 0.141701 0.975729 1 1.55278e-18 1.55278e-18 -5.32126e-08 -2.44024e-08 -5.30977e-08 1 1.55278e-18 -5.32126e-08 -2.44024e-08 -5.30977e-08 1 -5.32126e-08 -2.44024e-08 -5.30977e-08 3899.33 2.72462 112.751 4000.57 2.80367 3920.34 +EDGE_SE3:QUAT 244 293 4.92442 -6.60269 -2.94185 -0.0278794 0.0479213 -0.107438 0.992665 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4025.95 -9.68643 342.585 3993.8 -19.3229 3982.89 +EDGE_SE3:QUAT 245 295 5.29088 0.114294 -2.95261 0.149496 0.0735787 0.158102 0.973263 1 8.1852e-19 8.1852e-19 -5.17292e-08 -2.31326e-08 1.18602e-09 1 8.1852e-19 -5.17292e-08 -2.31326e-08 1.18602e-09 1 -5.17292e-08 -2.31326e-08 1.18602e-09 3925.57 19.5408 270.604 4000.55 19.8867 3914.98 +EDGE_SE3:QUAT 244 295 4.96102 6.66967 -2.99657 -0.00941107 -0.0375586 0.0422567 0.998356 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.47 2.80523 -296.245 3994.68 -6.62228 4014.68 +EDGE_SE3:QUAT 245 294 4.60291 -6.69663 -3.31578 -0.136895 0.0538529 0.0376609 0.988403 1 1.20371e-20 1.20371e-20 -4.3307e-10 9.32094e-10 -6.909e-09 1 1.20371e-20 -4.3307e-10 9.32094e-10 -6.909e-09 1 -4.3307e-10 9.32094e-10 -6.909e-09 3983.09 -32.3415 485.497 3985.64 -1.80845 4052.38 +EDGE_SE3:QUAT 246 296 5.3891 0.306028 -3.2644 0.096114 -0.126402 -0.169441 0.972664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4106.69 -82.9762 -778.652 3983.15 92.6137 4028.8 +EDGE_SE3:QUAT 245 296 4.81219 6.62376 -3.18973 0.181894 -0.0807703 0.0179448 0.979831 1 7.71124e-19 7.71124e-19 -5.52945e-08 1.00571e-09 6.32921e-09 1 7.71124e-19 -5.52945e-08 1.00571e-09 6.32921e-09 1 -5.52945e-08 1.00571e-09 6.32921e-09 3976.34 -62.3788 -668.301 3976.9 23.9597 4107.4 +EDGE_SE3:QUAT 246 295 5.05524 -6.24545 -3.29021 0.0453298 0.0212773 -0.137506 0.989234 1 4.81482e-20 4.81482e-20 1.37532e-08 -1.87955e-09 4.55132e-10 1 4.81482e-20 1.37532e-08 -1.87955e-09 4.55132e-10 1 1.37532e-08 -1.87955e-09 4.55132e-10 4005.97 3.37872 239.518 3995.95 -17.3191 3938.56 +EDGE_SE3:QUAT 247 297 5.55883 -0.175471 -3.30467 0.0478899 -0.0577594 0.00790464 0.99715 1 7.52316e-22 7.52316e-22 -1.01733e-10 8.25962e-11 1.74157e-09 1 7.52316e-22 -1.01733e-10 8.25962e-11 1.74157e-09 1 -1.01733e-10 8.25962e-11 1.74157e-09 4045.44 -11.0405 -470.567 3986.55 2.01126 4054.36 +EDGE_SE3:QUAT 246 297 4.84332 6.90552 -3.02723 0.15608 0.0242817 0.0321362 0.986923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3906.49 8.49451 127.76 3999.46 2.89611 3999.8 +EDGE_SE3:QUAT 247 296 4.60086 -6.66868 -3.2835 -0.00724437 -0.0296189 -0.153431 0.987689 1 1.22251e-20 1.22251e-20 -1.92184e-09 -6.72045e-09 4.08509e-11 1 1.22251e-20 -1.92184e-09 -6.72045e-09 4.08509e-11 1 -1.92184e-09 -6.72045e-09 4.08509e-11 4014.44 -2.49552 -242.543 3996.65 18.7505 3920.49 +EDGE_SE3:QUAT 248 298 5.76163 -0.0869995 -3.12983 0.0402645 -0.0289408 0.124534 0.990976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.87 -2.65964 -286.525 3994.54 -18.029 3958.32 +EDGE_SE3:QUAT 247 298 4.86268 6.7162 -3.02427 0.0404313 0.0506359 0.17713 0.982052 1 4.81482e-20 4.81482e-20 -1.36679e-08 -2.52424e-09 -4.60851e-10 1 4.81482e-20 -1.36679e-08 -2.52424e-09 -4.60851e-10 1 -1.36679e-08 -2.52424e-09 -4.60851e-10 4015.74 12.6205 302.033 3996.67 25.7572 3896.77 +EDGE_SE3:QUAT 248 297 4.74299 -6.76913 -3.17279 0.12502 -0.0363561 -0.22683 0.965192 1 7.52316e-22 7.52316e-22 3.96443e-10 1.67364e-09 -2.22194e-10 1 7.52316e-22 3.96443e-10 1.67364e-09 -2.22194e-10 1 3.96443e-10 1.67364e-09 -2.22194e-10 3935.05 11.8117 63.2619 3997.87 -21.2705 3791.76 +EDGE_SE3:QUAT 249 299 5.27598 0.302995 -3.40816 0.0474175 0.117041 0.0604586 0.99015 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4197.66 44.5439 932.559 3953.94 47.1237 4192.04 +EDGE_SE3:QUAT 248 299 4.87831 6.61313 -3.18687 -0.0028178 -0.0397908 0.018131 0.99904 1 1.88079e-22 1.88079e-22 -8.69269e-10 -1.60212e-11 3.45095e-11 1 1.88079e-22 -8.69269e-10 -1.60212e-11 3.45095e-11 1 -8.69269e-10 -1.60212e-11 3.45095e-11 4025.3 1.14872 -319.308 3993.72 -3.04793 4024.01 +EDGE_SE3:QUAT 249 298 4.84688 -6.74001 -2.76875 -0.21813 0.0666655 -0.0670917 0.971326 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3833.91 -31.6935 322.561 3998.59 -20.0417 4006.23 +EDGE_SE3:QUAT 250 300 5.24766 0.162617 -3.48534 -0.0704845 0.0895482 0.124756 0.985621 1 4.81482e-20 4.81482e-20 -1.39631e-08 -1.60183e-09 -1.46762e-09 1 4.81482e-20 -1.39631e-08 -1.60183e-09 -1.46762e-09 1 -1.39631e-08 -1.60183e-09 -1.46762e-09 4145.36 -2.83576 829.866 3959.31 41.535 4102.97 +EDGE_SE3:QUAT 249 300 5.17142 6.81691 -3.10854 0.209723 0.0214421 0.0797879 0.974264 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3823.2 -11.2076 -35.3687 3999.3 -4.29516 3973.67 +EDGE_SE3:QUAT 250 299 5.28154 -6.62533 -3.13904 -0.00818222 0.00407781 -0.0173947 0.999807 1 1.20371e-20 1.20371e-20 -2.63005e-11 5.7729e-11 -6.93776e-09 1 1.20371e-20 -2.63005e-11 5.7729e-11 -6.93776e-09 1 -2.63005e-11 5.7729e-11 -6.93776e-09 3999.97 -0.13046 30.8984 3999.94 -0.266778 3999.03 +EDGE_SE3:QUAT 251 301 5.55082 0.0167136 -3.41913 0.00959607 0.0199658 0.0165487 0.999618 1 3.00927e-21 3.00927e-21 -3.47082e-09 -5.88255e-11 -6.81698e-11 1 3.00927e-21 -3.47082e-09 -5.88255e-11 -6.81698e-11 1 -3.47082e-09 -5.88255e-11 -6.81698e-11 4005.86 0.913356 157.946 3998.46 1.39702 4005.13 +EDGE_SE3:QUAT 250 301 5.09117 6.6903 -2.98757 0.142847 0.0701767 0.0659469 0.985049 1 4.81482e-20 4.81482e-20 -1.16022e-09 1.36517e-08 -2.10676e-09 1 4.81482e-20 -1.16022e-09 1.36517e-08 -2.10676e-09 1 -1.16022e-09 1.36517e-08 -2.10676e-09 3963.94 34.2008 432.332 3992.6 24.8553 4028.17 +EDGE_SE3:QUAT 251 300 4.51898 -6.7035 -3.12226 -0.0629244 -0.0715333 -0.0943795 0.990967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4086.17 8.17892 -647.086 3974.24 23.9934 4066.38 +EDGE_SE3:QUAT 252 302 5.33852 -0.107621 -2.48306 0.0590845 -0.0119257 -0.0272976 0.997808 1 1.20371e-20 1.20371e-20 -5.97181e-11 4.14054e-10 6.92492e-09 1 1.20371e-20 -5.97181e-11 4.14054e-10 6.92492e-09 1 -5.97181e-11 4.14054e-10 6.92492e-09 3987.45 -2.10239 -75.5172 3999.71 1.08281 3998.43 +EDGE_SE3:QUAT 251 302 5.65346 6.57134 -3.23259 -0.0344028 -0.00566189 -0.0545875 0.9979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.39 1.20923 -67.5052 3999.65 1.99541 3989.21 +EDGE_SE3:QUAT 252 301 4.67037 -6.71369 -3.12495 0.137611 -0.12576 -0.073471 0.979719 1 7.70372e-19 7.70372e-19 5.56538e-08 -6.11948e-09 -5.60771e-09 1 7.70372e-19 5.56538e-08 -6.11948e-09 -5.60771e-09 1 5.56538e-08 -6.11948e-09 -5.60771e-09 4107.53 -88.3012 -878.241 3969.16 77.8977 4161.68 +EDGE_SE3:QUAT 253 303 5.3644 -0.0421619 -3.29984 0.00751509 -0.150608 -0.0109657 0.988504 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4388.02 -12.7631 -1305.27 3909.68 13.4632 4387.77 +EDGE_SE3:QUAT 252 303 5.08102 6.58116 -3.09255 -0.0233874 -0.0828762 0.0978333 0.99147 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4097.25 23.095 -638.669 3977.86 -36.4156 4061.15 +EDGE_SE3:QUAT 253 302 5.09965 -6.64157 -3.58989 -0.0372574 -0.0398801 -0.106261 0.992839 1 2.40741e-19 2.40741e-19 -1.25318e-08 2.2237e-09 -2.70187e-08 1 2.40741e-19 -1.25318e-08 2.2237e-09 -2.70187e-08 1 -1.25318e-08 2.2237e-09 -2.70187e-08 4027.07 2.1591 -362.897 3991.6 18.6446 3987.46 +EDGE_SE3:QUAT 254 304 5.0381 0.411605 -3.15954 0.126432 0.104315 0.0545627 0.984965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4070.83 61.9122 747.825 3974.3 49.6311 4122.86 +EDGE_SE3:QUAT 253 304 4.73528 6.90829 -3.31245 -0.0299308 -0.0406664 0.168474 0.984412 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.08 8.06832 -252.41 3997.41 -20.2557 3902.13 +EDGE_SE3:QUAT 254 303 4.92972 -6.89088 -3.42207 0.0494848 -0.0860699 0.0418417 0.994179 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4119.08 -11.5786 -729.474 3968.28 -7.05543 4121.87 +EDGE_SE3:QUAT 255 305 5.27387 -0.0691896 -3.20499 -0.053663 0.05195 -0.0321079 0.99669 1 9.62965e-20 9.62965e-20 -1.33762e-08 1.43546e-08 1.22841e-10 1 9.62965e-20 -1.33762e-08 1.43546e-08 1.22841e-10 1 -1.33762e-08 1.43546e-08 1.22841e-10 4027.23 -12.6229 395.706 3990.95 -9.62311 4034.63 +EDGE_SE3:QUAT 254 305 5.26152 6.87815 -3.24232 -0.00552083 -0.265285 0.197798 0.943647 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5175.04 437.645 -2468.61 3865.94 -440.025 5018.67 +EDGE_SE3:QUAT 255 304 4.88283 -7.06815 -3.24414 0.11363 0.00180239 -0.0725328 0.99087 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3951.23 8.00254 111.816 3998.72 -4.90311 3981.83 +EDGE_SE3:QUAT 256 306 5.42153 0.364604 -3.25672 0.0504501 -0.0221409 -0.123919 0.990762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.04 -2.43666 -98.2422 3999.75 4.70823 3940.8 +EDGE_SE3:QUAT 255 306 5.26083 6.73029 -3.18834 0.0697582 -0.0505687 0.0294794 0.995845 1 2.40741e-19 2.40741e-19 -2.81079e-08 1.32006e-08 5.80237e-10 1 2.40741e-19 -2.81079e-08 1.32006e-08 5.80237e-10 1 -2.81079e-08 1.32006e-08 5.80237e-10 4026.25 -13.6878 -430.089 3988.5 -1.9115 4042.24 +EDGE_SE3:QUAT 256 305 4.38804 -6.86778 -3.30589 0.103603 -0.154539 -0.0700021 0.980043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4286.02 -112.452 -1194.54 3938.41 106.729 4309.35 +EDGE_SE3:QUAT 257 307 5.4255 -0.00617806 -3.26932 -0.179856 -0.182851 -0.0036619 0.966542 1 8.1852e-19 8.1852e-19 5.4719e-08 9.8489e-10 4.15033e-09 1 8.1852e-19 5.4719e-08 9.8489e-10 4.15033e-09 1 5.4719e-08 9.8489e-10 4.15033e-09 4406.7 185.352 -1560.19 3906.16 -156.486 4536.04 +EDGE_SE3:QUAT 256 307 5.43734 6.67896 -3.28866 -0.0283187 -0.0206764 0.0930079 0.995048 1 1.92593e-19 1.92593e-19 4.17597e-10 8.7976e-10 -2.76331e-08 1 1.92593e-19 4.17597e-10 8.7976e-10 -2.76331e-08 1 4.17597e-10 8.7976e-10 -2.76331e-08 4001.09 2.39024 -131.754 3999.15 -5.82836 3969.7 +EDGE_SE3:QUAT 257 306 4.65432 -6.75323 -3.31338 0.0865034 0.0410717 0.0235172 0.995127 1 2.40741e-19 2.40741e-19 2.7278e-08 1.46519e-08 -2.18015e-10 1 2.40741e-19 2.7278e-08 1.46519e-08 -2.18015e-10 1 2.7278e-08 1.46519e-08 -2.18015e-10 3992.67 13.6872 301.705 3994.93 6.57474 4020.39 +EDGE_SE3:QUAT 258 308 5.22273 0.0274235 -3.25157 0.147474 -0.0553212 -0.0612541 0.985616 1 4.81482e-20 4.81482e-20 1.0406e-09 1.3665e-08 -2.1328e-09 1 4.81482e-20 1.0406e-09 1.3665e-08 -2.1328e-09 1 1.0406e-09 1.3665e-08 -2.1328e-09 3937.94 -23.849 -320.11 3996.22 15.4859 4009.92 +EDGE_SE3:QUAT 257 308 4.7009 6.9669 -3.73432 -0.047557 -0.0117129 -0.0356927 0.998162 1 4.81482e-20 4.81482e-20 1.38579e-08 -4.78005e-10 -2.08532e-10 1 4.81482e-20 1.38579e-08 -4.78005e-10 -2.08532e-10 1 1.38579e-08 -4.78005e-10 -2.08532e-10 3994.17 2.70434 -113.617 3999.11 1.93669 3998.12 +EDGE_SE3:QUAT 258 307 4.9015 -7.11389 -3.39869 -0.145368 -0.0387936 -0.111202 0.982343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.48 32.5334 -492.081 3982.67 20.2218 4009.54 +EDGE_SE3:QUAT 259 309 5.2396 0.110963 -3.26551 -0.122871 0.108435 0.0199018 0.98628 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4139.11 -57.5549 915.311 3954.56 -27.4001 4197.91 +EDGE_SE3:QUAT 258 309 5.06066 6.90086 -3.25241 -0.0779608 0.0927626 -0.151035 0.981074 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4056.51 -43.5767 578.355 3987.79 -53.5245 3989.58 +EDGE_SE3:QUAT 259 308 4.86795 -6.9243 -3.41903 0.0697121 0.0136835 -0.0569625 0.995845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.56 5.53129 155.774 3998.21 -4.33527 3993.02 +EDGE_SE3:QUAT 260 310 5.64908 -0.0887168 -3.32954 -0.0248385 0.0449741 0.0775146 0.995667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.75 -0.792731 382.359 3990.9 14.0821 4012.18 +EDGE_SE3:QUAT 259 310 5.25759 6.97242 -3.43394 -0.121258 -0.114804 0.199426 0.965581 1 9.62965e-19 9.62965e-19 3.20396e-09 -3.55695e-08 4.97305e-08 1 9.62965e-19 3.20396e-09 -3.55695e-08 4.97305e-08 1 3.20396e-09 -3.55695e-08 4.97305e-08 4014.46 61.4614 -564.405 3997.91 -68.0978 3914.2 +EDGE_SE3:QUAT 260 309 4.74691 -6.5636 -3.0864 0.0107146 0.251331 0.100747 0.962584 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5167.08 225.571 2456.5 3788.33 230.978 5126.94 +EDGE_SE3:QUAT 261 311 5.49591 -0.130131 -3.1244 7.81399e-05 -0.0169977 0.146512 0.989063 1 1.88079e-22 1.88079e-22 -8.58351e-10 -1.2722e-10 1.41373e-11 1 1.88079e-22 -8.58351e-10 -1.2722e-10 1.41373e-11 1 -8.58351e-10 -1.2722e-10 1.41373e-11 4004.34 0.973952 -131.886 3999.04 -9.58453 3918.48 +EDGE_SE3:QUAT 260 311 5.31396 6.87798 -3.30356 -0.0625666 0.147817 0.120878 0.979604 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4401.57 24.1 1357.61 3904.84 63.7249 4358.78 +EDGE_SE3:QUAT 261 310 4.66886 -6.90925 -3.32252 0.0448471 0.132505 -0.00446007 0.990157 1 8.1852e-19 8.1852e-19 -1.382e-08 -5.50729e-08 6.08964e-10 1 8.1852e-19 -1.382e-08 -5.50729e-08 6.08964e-10 1 -1.382e-08 -5.50729e-08 6.08964e-10 4287.93 27.975 1127.61 3930.55 17.6185 4295.9 +EDGE_SE3:QUAT 262 312 5.31605 -0.0564517 -2.66756 -0.0823029 0.0042315 -0.0921034 0.992333 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.49 3.55878 -56.9661 3999.52 3.99247 3966.66 +EDGE_SE3:QUAT 261 312 4.94434 6.99586 -3.31617 0.0716366 -0.268274 0.06563 0.958431 1 9.62965e-20 9.62965e-20 -1.11732e-08 -1.25026e-09 -1.11732e-08 1 9.62965e-20 -1.11732e-08 -1.25026e-09 -1.11732e-08 1 -1.11732e-08 -1.25026e-09 -1.11732e-08 5499.02 -18.2237 -2896.07 3703.78 13.597 5502.32 +EDGE_SE3:QUAT 262 311 4.74073 -6.89466 -3.12392 0.035791 -0.0944738 0.0529182 0.993475 1 4.81482e-20 4.81482e-20 1.37981e-09 -3.69618e-10 -1.40515e-08 1 4.81482e-20 1.37981e-09 -3.69618e-10 -1.40515e-08 1 1.37981e-09 -3.69618e-10 -1.40515e-08 4149.1 -3.49001 -800.454 3962.35 -15.0614 4143.03 +EDGE_SE3:QUAT 263 313 5.01137 -0.317167 -3.64362 -0.00108894 0.0254132 -0.0248403 0.999368 1 1.20371e-20 1.20371e-20 -1.75971e-10 1.63439e-11 -6.94344e-09 1 1.20371e-20 -1.75971e-10 1.63439e-11 -6.94344e-09 1 -1.75971e-10 1.63439e-11 -6.94344e-09 4010.3 -0.496144 203.249 3997.44 -2.55621 4007.83 +EDGE_SE3:QUAT 262 313 5.25945 6.58963 -3.13376 0.11699 0.0211749 0.177784 0.976861 1 1.92593e-19 1.92593e-19 -2.71183e-08 -4.90729e-09 5.90739e-10 1 1.92593e-19 -2.71183e-08 -4.90729e-09 5.90739e-10 1 -2.71183e-08 -4.90729e-09 5.90739e-10 3945.29 -10.0098 -84.0677 3998.17 -15.2145 3873.61 +EDGE_SE3:QUAT 263 312 4.98469 -7.10484 -3.18566 0.0177272 0.166271 -0.0183137 0.985751 1 3.00927e-21 3.00927e-21 3.62119e-09 -4.85782e-11 6.12523e-10 1 3.00927e-21 3.62119e-09 -4.85782e-11 6.12523e-10 1 3.62119e-09 -4.85782e-11 6.12523e-10 4482.93 2.96472 1473.5 3888.93 -3.97491 4482.85 +EDGE_SE3:QUAT 264 314 5.18126 0.016285 -3.41341 -0.053326 0.0162301 -0.0210869 0.998223 1 5.11575e-20 5.11575e-20 1.37802e-08 -3.7784e-09 5.35495e-12 1 5.11575e-20 1.37802e-08 -3.7784e-09 5.35495e-12 1 1.37802e-08 -3.7784e-09 5.35495e-12 3991.97 -3.08172 115.812 3999.24 -1.45756 4001.57 +EDGE_SE3:QUAT 263 314 4.96977 6.96243 -3.12404 0.22248 -0.0894117 0.138819 0.960853 1 9.62965e-19 9.62965e-19 5.27109e-08 3.1931e-08 -1.33537e-08 1 9.62965e-19 5.27109e-08 3.1931e-08 -1.33537e-08 1 5.27109e-08 3.1931e-08 -1.33537e-08 4067.38 -94.913 -1066.19 3933.51 -8.86099 4188.28 +EDGE_SE3:QUAT 264 313 4.69349 -7.01667 -3.00364 0.102533 0.00368404 -0.182652 0.97781 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3971.97 13.7604 246.624 3993.92 -27.8559 3880.58 +EDGE_SE3:QUAT 265 315 5.2506 -0.191861 -3.11662 -0.0428504 0.0319288 -0.0600338 0.996765 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.03 -5.78513 223.11 3997.29 -7.28262 3997.96 +EDGE_SE3:QUAT 264 315 4.75187 6.93849 -3.16037 -0.11146 0.0470072 0.0139013 0.992559 1 1.92593e-19 1.92593e-19 -2.76806e-08 -8.83899e-11 -1.36408e-09 1 1.92593e-19 -2.76806e-08 -8.83899e-11 -1.36408e-09 1 -2.76806e-08 -8.83899e-11 -1.36408e-09 3988.11 -21.7329 390.703 3990.89 -3.49575 4037.03 +EDGE_SE3:QUAT 265 314 5.04324 -7.21136 -3.07745 -0.024814 -0.00108005 -0.127839 0.991484 1 1.20371e-20 1.20371e-20 -6.88023e-09 8.85666e-10 5.08922e-11 1 1.20371e-20 -6.88023e-09 8.85666e-10 5.08922e-11 1 -6.88023e-09 8.85666e-10 5.08922e-11 3998.03 0.659745 -46.0637 3999.79 3.73778 3935.12 +EDGE_SE3:QUAT 266 316 5.33415 -0.0576024 -3.67391 -0.167669 0.0648659 -0.0782032 0.980594 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3914.99 -28.3478 339.23 3996.94 -20.3911 4002.98 +EDGE_SE3:QUAT 265 316 4.93003 6.80523 -3.35138 0.0560621 -0.234457 0.102908 0.965037 1 4.81482e-20 4.81482e-20 1.51439e-08 1.35995e-09 -3.7739e-09 1 4.81482e-20 1.51439e-08 1.35995e-09 -3.7739e-09 1 1.51439e-08 1.35995e-09 -3.7739e-09 5089.09 80.5979 -2370.73 3776.27 -96.6424 5059.31 +EDGE_SE3:QUAT 266 315 4.83002 -6.82615 -3.36753 -0.132546 0.000595633 -0.00953887 0.991131 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3929.75 1.02396 -10.354 3999.99 0.071368 3999.66 +EDGE_SE3:QUAT 267 317 5.18229 -0.1285 -3.3133 0.0521363 -0.0963253 0.201848 0.973273 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4174.51 29.9322 -880.875 3959.39 -87.2272 4022.41 +EDGE_SE3:QUAT 266 317 5.16184 6.80531 -3.3021 0.0750879 0.116157 0.123618 0.982643 1 3.85186e-19 3.85186e-19 -2.38652e-08 -3.12487e-08 2.56828e-10 1 3.85186e-19 -2.38652e-08 -3.12487e-08 2.56828e-10 1 -2.38652e-08 -3.12487e-08 2.56828e-10 4135.62 65.4583 813.137 3971.87 73.477 4097.05 +EDGE_SE3:QUAT 267 316 4.40529 -6.84846 -3.17413 0.116324 0.200577 0.0233652 0.972467 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4604.38 169.521 1751.93 3875.26 156.592 4656.32 +EDGE_SE3:QUAT 268 318 5.65667 0.244099 -3.50549 0.0455709 -0.0241384 -0.041391 0.997811 1 4.81482e-20 4.81482e-20 2.80372e-10 -6.59226e-10 -1.38599e-08 1 4.81482e-20 2.80372e-10 -6.59226e-10 -1.38599e-08 1 2.80372e-10 -6.59226e-10 -1.38599e-08 3998.86 -4.18129 -169.664 3998.4 3.88939 4000.31 +EDGE_SE3:QUAT 267 318 5.18682 6.79087 -3.1541 -0.0993063 0.0371292 0.03782 0.993644 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.05 -16.2377 339.035 3992.6 2.70944 4022.78 +EDGE_SE3:QUAT 268 317 4.7237 -6.89052 -3.26425 0.0924774 0.0914824 -0.171982 0.976474 1 7.70372e-19 7.70372e-19 -6.62364e-09 -3.269e-09 -5.55993e-08 1 7.70372e-19 -6.62364e-09 -3.269e-09 -5.55993e-08 1 -6.62364e-09 -3.269e-09 -5.55993e-08 4167.02 -0.215289 920.156 3950.7 -65.7175 4082.91 +EDGE_SE3:QUAT 269 319 5.23529 -0.0693739 -3.18981 0.000747793 -0.00492702 -0.0723774 0.997365 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.37 -0.0549655 -38.4627 3999.91 1.38109 3979.42 +EDGE_SE3:QUAT 268 319 5.07427 6.69651 -3.69294 -0.0979953 0.0594218 0.211392 0.970659 1 1.15556e-18 1.15556e-18 2.75848e-08 -1.77481e-08 -5.3893e-08 1 1.15556e-18 2.75848e-08 -1.77481e-08 -5.3893e-08 1 2.75848e-08 -1.77481e-08 -5.3893e-08 4079.15 -5.81632 697.715 3969.12 70.0076 3938.82 +EDGE_SE3:QUAT 269 318 4.73288 -7.02994 -3.0972 0.182849 0.164003 0.00959478 0.969318 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4266.5 158.88 1328.23 3931.04 129.599 4399.87 +EDGE_SE3:QUAT 270 320 5.34409 0.177763 -3.82458 0.0479172 -0.00270099 0.0378752 0.998129 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.27 -1.18765 -43.2167 3999.84 -0.928818 3994.72 +EDGE_SE3:QUAT 269 320 5.06485 6.68404 -3.52202 0.106223 0.0899478 -0.00528494 0.990252 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4085.46 41.2038 734.484 3969.85 19.2163 4130.48 +EDGE_SE3:QUAT 270 319 4.54917 -7.04513 -3.34924 0.185897 -0.0810856 -0.0962762 0.974473 1 7.70372e-19 7.70372e-19 -2.14315e-09 1.11391e-08 5.43561e-08 1 7.70372e-19 -2.14315e-09 1.11391e-08 5.43561e-08 1 -2.14315e-09 1.11391e-08 5.43561e-08 3898.74 -38.0584 -397.949 3997.41 30.3994 3999.89 +EDGE_SE3:QUAT 271 321 5.18502 0.19674 -3.35327 0.0819004 0.0174114 -0.0655404 0.994331 1 3.85186e-19 3.85186e-19 -2.6863e-08 3.91473e-09 2.6863e-08 1 3.85186e-19 -2.6863e-08 3.91473e-09 2.6863e-08 1 -2.6863e-08 3.91473e-09 2.6863e-08 3983.19 8.2712 201.458 3997.01 -6.22855 3992.84 +EDGE_SE3:QUAT 270 321 4.73109 6.81095 -3.25767 -0.0694007 -0.0347407 -0.0156369 0.996861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.67 9.84436 -290.163 3994.75 0.173712 4019.96 +EDGE_SE3:QUAT 271 320 4.77139 -6.78955 -3.22354 0.0968808 0.170282 -0.0881135 0.976655 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4532.73 27.1624 1614.49 3871 -9.7515 4539.22 +EDGE_SE3:QUAT 272 322 5.23395 -0.0094002 -3.49988 0.219145 -0.0861194 0.212894 0.94828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4150.57 -74.7747 -1224.85 3909.7 -66.9158 4161.37 +EDGE_SE3:QUAT 271 322 5.12446 7.01616 -3.43676 0.0161567 0.0733497 0.183761 0.980097 1 2.40741e-19 2.40741e-19 -8.51002e-09 -2.98131e-08 2.89054e-10 1 2.40741e-19 -8.51002e-09 -2.98131e-08 2.89054e-10 1 -8.51002e-09 -2.98131e-08 2.89054e-10 4067.59 24.8951 529.365 3987.32 50.9128 3933.56 +EDGE_SE3:QUAT 272 321 4.76197 -6.95023 -3.6305 -0.0363541 -0.0401005 -0.162076 0.985293 1 8.66668e-19 8.66668e-19 1.31856e-08 1.02468e-08 5.45563e-08 1 8.66668e-19 1.31856e-08 1.02468e-08 5.45563e-08 1 1.31856e-08 1.02468e-08 5.45563e-08 4030.51 -0.882438 -380.329 3991.03 31.166 3930.72 +EDGE_SE3:QUAT 273 323 5.4407 -0.173241 -3.00835 0.164662 -0.0621777 0.171343 0.969362 1 7.70372e-19 7.70372e-19 -5.49196e-08 -8.14904e-09 6.26772e-09 1 7.70372e-19 -5.49196e-08 -8.14904e-09 6.26772e-09 1 -5.49196e-08 -8.14904e-09 6.26772e-09 4049.7 -44.4395 -814.764 3955.71 -49.1116 4040.72 +EDGE_SE3:QUAT 272 323 4.77587 7.03731 -3.35352 0.172704 0.0827377 0.0851549 0.977792 1 7.70372e-19 7.70372e-19 -5.46277e-08 -6.10321e-09 -2.63915e-09 1 7.70372e-19 -5.46277e-08 -6.10321e-09 -2.63915e-09 1 -5.46277e-08 -6.10321e-09 -2.63915e-09 3930.24 43.1964 455.199 3994.42 33.8274 4020.55 +EDGE_SE3:QUAT 273 322 4.86108 -7.39873 -3.34511 0.212794 0.0216949 0.0173159 0.976703 1 1.20371e-20 1.20371e-20 8.68355e-11 1.48258e-09 6.78028e-09 1 1.20371e-20 8.68355e-11 1.48258e-09 6.78028e-09 1 8.68355e-11 1.48258e-09 6.78028e-09 3822.3 10.8141 118.992 3999.6 2.2648 4002.23 +EDGE_SE3:QUAT 274 324 5.25523 0.105639 -2.98981 0.135071 -0.0291649 -0.0719224 0.987792 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3929.61 -5.17616 -110.299 3999.85 3.4417 3981.9 +EDGE_SE3:QUAT 273 324 5.08958 6.74722 -3.87297 -0.0036833 0.0407535 -0.0271778 0.998793 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4026.39 -1.69469 326.33 3993.46 -4.65135 4023.49 +EDGE_SE3:QUAT 274 323 4.78095 -7.09574 -2.98776 0.12216 0.00162443 -0.143141 0.982133 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3951.09 15.9917 217.798 3995.04 -19.25 3928.82 +EDGE_SE3:QUAT 275 325 5.29344 -0.0146701 -3.5461 0.136923 -0.0331601 0.0191772 0.989841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3945.95 -20.0863 -290.238 3994.87 1.30243 4019.47 +EDGE_SE3:QUAT 274 325 4.6203 7.24749 -3.57851 0.108319 -0.00497332 0.16638 0.980082 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.45 -14.8101 -248.986 3993.92 -25.0446 3903.66 +EDGE_SE3:QUAT 275 324 4.76728 -7.18227 -3.39904 0.0453414 0.147551 -0.0856284 0.984297 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4386.39 -15.1273 1316.89 3908.81 -42.7512 4365.28 +EDGE_SE3:QUAT 276 326 5.24089 -0.176957 -3.1701 0.00698536 0.110064 -0.0459233 0.992838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4201.42 -10.5824 920.394 3951.81 -21.7086 4193.18 +EDGE_SE3:QUAT 275 326 5.01847 7.27362 -3.57063 0.0232088 0.209978 -0.0611084 0.975519 1 7.73381e-19 7.73381e-19 6.85678e-09 5.39519e-08 9.26365e-10 1 7.73381e-19 6.85678e-09 5.39519e-08 9.26365e-10 1 6.85678e-09 5.39519e-08 9.26365e-10 4817.59 -47.5138 1987.7 3824.13 -59.3611 4804.81 +EDGE_SE3:QUAT 276 325 4.83047 -6.66003 -3.18304 -0.0531097 0.00283268 -0.188456 0.98064 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.65 3.27648 -95.7099 3998.87 12.7378 3859.87 +EDGE_SE3:QUAT 277 327 5.56589 -0.00829261 -3.56496 -0.0449483 -0.169436 0.12259 0.976853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4411.63 124.085 -1362.96 3921.8 -136.845 4359.6 +EDGE_SE3:QUAT 276 327 4.86246 7.17989 -3.56497 0.0767765 0.0617549 0.126784 0.987025 1 7.70372e-19 7.70372e-19 -2.20781e-09 -5.03576e-09 -5.5017e-08 1 7.70372e-19 -2.20781e-09 -5.03576e-09 -5.5017e-08 1 -2.20781e-09 -5.03576e-09 -5.5017e-08 4008.73 20.093 364.206 3994.86 25.4223 3968.01 +EDGE_SE3:QUAT 277 326 4.53492 -7.19966 -3.58907 -0.0666847 0.0220934 -0.120745 0.990195 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.37 -1.85419 76.2686 3999.95 -2.80787 3942.84 +EDGE_SE3:QUAT 278 328 5.7725 0.0724417 -3.28492 -0.0288329 0.164666 -0.11299 0.979432 1 4.81482e-20 4.81482e-20 1.42983e-08 -1.88255e-09 2.23366e-09 1 4.81482e-20 1.42983e-08 -1.88255e-09 2.23366e-09 1 1.42983e-08 -1.88255e-09 2.23366e-09 4415.95 -102.003 1361.66 3916.13 -116.85 4368.21 +EDGE_SE3:QUAT 277 328 4.99495 7.21976 -3.40291 -0.0233624 0.00913166 0.1061 0.994039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.36 -0.934645 101.34 3999.26 5.80665 3957.52 +EDGE_SE3:QUAT 278 327 4.51607 -7.4108 -3.5316 -0.0702523 0.0335928 -0.123985 0.989224 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.07 -5.79399 157.447 3999.32 -8.37038 3944.32 +EDGE_SE3:QUAT 279 329 5.04601 -0.202102 -3.2409 0.0852588 0.0633141 0.0912609 0.990148 1 1.92593e-19 1.92593e-19 -2.76223e-08 -2.82697e-09 -1.27613e-09 1 1.92593e-19 -2.76223e-08 -2.82697e-09 -1.27613e-09 1 -2.76223e-08 -2.82697e-09 -1.27613e-09 4011.12 22.6269 404.873 3992.6 23.3619 4006.89 +EDGE_SE3:QUAT 278 329 4.9798 7.03921 -3.34002 0.00620601 -0.0594164 -0.0440843 0.99724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4055.79 -5.27167 -476.357 3986.37 11.3791 4048.17 +EDGE_SE3:QUAT 279 328 5.0447 -6.97236 -3.42265 0.0543151 -0.00133276 -0.0493355 0.997303 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.29 0.871227 21.4648 3999.94 -0.790663 3990.35 +EDGE_SE3:QUAT 280 330 5.3033 0.0643207 -3.4636 0.121757 -0.0736116 0.0326323 0.989288 1 1.92593e-19 1.92593e-19 2.78003e-08 3.96013e-10 -2.22679e-09 1 1.92593e-19 2.78003e-08 3.96013e-10 -2.22679e-09 1 2.78003e-08 3.96013e-10 -2.22679e-09 4039.44 -37.0218 -636.199 3976.23 6.72198 4094.48 +EDGE_SE3:QUAT 279 330 4.74645 7.42976 -3.44117 -0.0632678 0.0394231 0.100114 0.992179 1 1.92593e-19 1.92593e-19 1.42071e-09 -1.51598e-09 2.76677e-08 1 1.92593e-19 1.42071e-09 -1.51598e-09 2.76677e-08 1 1.42071e-09 -1.51598e-09 2.76677e-08 4021.09 -8.04833 387.579 3990 17.6821 3997.01 +EDGE_SE3:QUAT 280 329 4.69333 -7.07344 -3.32509 -0.108911 -0.0801162 -0.0655853 0.988645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4082.22 31.802 -732.009 3967.63 5.95733 4112.46 +EDGE_SE3:QUAT 281 331 5.09979 0.448029 -3.02875 -0.127498 0.0253902 0.0524243 0.990127 1 7.70372e-19 7.70372e-19 -5.50966e-08 -2.46967e-09 -2.09729e-09 1 7.70372e-19 -5.50966e-08 -2.46967e-09 -2.09729e-09 1 -5.50966e-08 -2.46967e-09 -2.09729e-09 3954.07 -18.1247 277.899 3994.6 4.71857 4008.1 +EDGE_SE3:QUAT 280 331 4.80371 7.37854 -3.37564 0.0837512 0.0650444 0.0329047 0.993817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.29 23.6965 486.876 3986.96 15.8185 4054.02 +EDGE_SE3:QUAT 281 330 4.59826 -6.40207 -3.29354 0.00977704 -0.0835325 -0.163455 0.982959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4098 -28.8634 -635.467 3980.18 55.8279 3991.51 +EDGE_SE3:QUAT 282 332 5.202 0.0444095 -3.56509 -0.0763749 -0.0805118 0.132723 0.984921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4039.08 33.047 -506.566 3989.68 -40.5349 3991.95 +EDGE_SE3:QUAT 281 332 4.86351 7.06948 -3.72045 -0.112538 -0.134035 0.151798 0.972793 1 1.92593e-19 1.92593e-19 5.05251e-09 -2.68561e-08 -4.18726e-09 1 1.92593e-19 5.05251e-09 -2.68561e-08 -4.18726e-09 1 5.05251e-09 -2.68561e-08 -4.18726e-09 4113.39 94.5739 -833.771 3980.62 -99.7042 4071.88 +EDGE_SE3:QUAT 282 331 4.87737 -7.00313 -3.4798 0.119085 0.109189 -0.334628 0.928397 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4309.76 -84.0369 1265.42 3932.58 -209.258 3918.58 +EDGE_SE3:QUAT 283 333 5.18946 0.0633345 -3.48222 -0.0811804 0.015369 0.123022 0.988959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.43 -9.18565 237.948 3995.44 15.7153 3953.25 +EDGE_SE3:QUAT 282 333 5.01372 7.2342 -3.58993 0.166382 -0.0820507 0.0240394 0.982348 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.21 -58.3981 -693.853 3974.03 20.5466 4114.63 +EDGE_SE3:QUAT 283 332 4.55699 -7.24816 -3.25727 -0.0455612 -0.131036 -0.150895 0.978767 1 7.82409e-19 7.82409e-19 1.50518e-08 5.33532e-08 -7.23566e-10 1 7.82409e-19 1.50518e-08 5.33532e-08 -7.23566e-10 1 1.50518e-08 5.33532e-08 -7.23566e-10 4308.54 -41.4794 -1169.52 3929.65 84.5797 4225.76 +EDGE_SE3:QUAT 284 334 5.01905 0.203714 -3.27814 0.0550235 -0.0835094 -0.0549659 0.993467 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4087.34 -26.9778 -638.713 3977.59 26.9675 4087.36 +EDGE_SE3:QUAT 283 334 4.83212 7.12647 -3.68619 -0.0492908 -0.055789 0.0457717 0.996174 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.88 13.5346 -420.02 3989.96 -13.0305 4035.22 +EDGE_SE3:QUAT 284 333 4.77635 -7.15223 -3.28767 0.0274971 0.0341351 -0.263917 0.963549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.01 -5.46461 329.997 3994.27 -45.6896 3748.42 +EDGE_SE3:QUAT 285 335 5.12356 -0.138922 -3.36901 -0.0459498 0.168192 0.104971 0.979072 1 2.0463e-19 2.0463e-19 2.0951e-09 1.02589e-09 -2.76315e-08 1 2.0463e-19 2.0951e-09 1.02589e-09 -2.76315e-08 1 2.0951e-09 1.02589e-09 -2.76315e-08 4514.1 39.7004 1537.29 3883.64 69.1155 4478.47 +EDGE_SE3:QUAT 284 335 5.06516 7.10041 -3.45126 0.0781949 0.121766 -0.148789 0.978223 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4281.3 -14.0089 1147.6 3928.54 -67.5644 4217.2 +EDGE_SE3:QUAT 285 334 4.72817 -7.20276 -3.19262 0.0979318 0.0563724 -0.0589201 0.991847 1 2.40741e-19 2.40741e-19 2.84137e-08 1.24532e-08 5.91942e-10 1 2.40741e-19 2.84137e-08 1.24532e-08 5.91942e-10 1 2.84137e-08 1.24532e-08 5.91942e-10 4027.78 21.7802 518.872 3982.97 -7.14297 4052.25 +EDGE_SE3:QUAT 286 336 5.57511 0.263011 -3.22265 -0.141518 0.0452911 0.109801 0.982784 1 7.70372e-19 7.70372e-19 5.50476e-08 5.22712e-09 4.09707e-09 1 7.70372e-19 5.50476e-08 5.22712e-09 4.09707e-09 1 5.50476e-08 5.22712e-09 4.09707e-09 3990.21 -33.0534 537.183 3980.01 20.3496 4022.1 +EDGE_SE3:QUAT 285 336 5.04109 6.90483 -3.43437 0.0995665 0.0653273 0.131467 0.984142 1 1.92593e-19 1.92593e-19 2.74173e-08 3.97361e-09 9.94418e-10 1 1.92593e-19 2.74173e-08 3.97361e-09 9.94418e-10 1 2.74173e-08 3.97361e-09 9.94418e-10 3989.34 22.3019 347.855 3996.33 25.2499 3959.86 +EDGE_SE3:QUAT 286 335 4.91188 -7.02364 -3.48024 0.0318919 -0.256576 -0.130671 0.957119 1 1.92593e-19 1.92593e-19 -3.01569e-08 5.28658e-09 7.4387e-09 1 1.92593e-19 -3.01569e-08 5.28658e-09 7.4387e-09 1 -3.01569e-08 5.28658e-09 7.4387e-09 5120.67 -325.738 -2401.92 3827.79 329.664 5056.44 +EDGE_SE3:QUAT 287 337 5.64864 -0.439854 -3.32545 0.00468636 -0.0660573 0.103183 0.992455 1 1.88079e-22 1.88079e-22 -8.684e-10 -9.05396e-11 5.7407e-11 1 1.88079e-22 -8.684e-10 -9.05396e-11 5.7407e-11 1 -8.684e-10 -9.05396e-11 5.7407e-11 4069.93 9.70282 -533.854 3983.55 -28.2711 4027.43 +EDGE_SE3:QUAT 286 337 5.01688 7.05367 -3.28474 0.0379565 0.0609541 0.154665 0.985354 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4034.07 17.7498 402.678 3992.85 32.3866 3944.15 +EDGE_SE3:QUAT 287 336 4.70243 -7.26547 -3.37815 0.132371 -0.200915 0.0190585 0.970437 1 7.73381e-19 7.73381e-19 -5.78591e-08 1.67227e-09 8.33424e-09 1 7.73381e-19 -5.78591e-08 1.67227e-09 8.33424e-09 1 -5.78591e-08 1.67227e-09 8.33424e-09 4650.97 -153.82 -1845.14 3856.94 131.504 4719.61 +EDGE_SE3:QUAT 288 338 5.06579 -0.102622 -3.36062 0.0779078 -0.0940698 0.159045 0.979687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4170.27 4.57276 -903.74 3952.94 -60.9771 4093.37 +EDGE_SE3:QUAT 287 338 4.80705 7.40396 -3.41863 0.175826 0.0124585 0.0747405 0.981501 1 7.70372e-19 7.70372e-19 5.44857e-08 4.13112e-09 -7.91105e-10 1 7.70372e-19 5.44857e-08 4.13112e-09 -7.91105e-10 1 5.44857e-08 4.13112e-09 -7.91105e-10 3876.55 -10.0142 -59.6052 3999.19 -4.24 3977.86 +EDGE_SE3:QUAT 288 337 4.53262 -7.05806 -3.31229 -0.0349809 -0.05728 -0.225833 0.971851 1 1.20371e-20 1.20371e-20 6.803e-09 -1.56141e-09 -4.6744e-10 1 1.20371e-20 6.803e-09 -1.56141e-09 -4.6744e-10 1 6.803e-09 -1.56141e-09 -4.6744e-10 4062.28 -12.5463 -522.723 3985.42 60.2308 3863.17 +EDGE_SE3:QUAT 289 339 5.07357 -0.286891 -3.51428 -0.193574 -0.0357342 0.130545 0.971705 1 7.73381e-19 7.73381e-19 -5.34565e-08 -1.08221e-08 -1.64447e-09 1 7.73381e-19 -5.34565e-08 -1.08221e-08 -1.64447e-09 1 -5.34565e-08 -1.08221e-08 -1.64447e-09 3847.57 -13.4389 29.7011 3998.87 9.05522 3929.28 +EDGE_SE3:QUAT 288 339 5.12739 7.28088 -3.44107 -0.02064 -0.0156967 -0.139208 0.989924 1 1.20371e-20 1.20371e-20 -6.87429e-09 9.6198e-10 1.44218e-10 1 1.20371e-20 -6.87429e-09 9.6198e-10 1.44218e-10 1 -6.87429e-09 9.6198e-10 1.44218e-10 4004.36 0.546566 -156.12 3998.38 11.4421 3928.55 +EDGE_SE3:QUAT 289 338 4.43514 -7.23508 -3.53055 0.021847 -0.126669 0.0187055 0.991528 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4269.87 -5.95855 -1077.49 3935.3 -2.65513 4270.38 +EDGE_SE3:QUAT 290 340 5.03367 0.0376443 -3.37828 -0.0869318 0.0396373 0.0109592 0.995365 1 2.40741e-19 2.40741e-19 2.77738e-08 -1.37043e-08 -5.81569e-11 1 2.40741e-19 2.77738e-08 -1.37043e-08 -5.81569e-11 1 2.77738e-08 -1.37043e-08 -5.81569e-11 3996.29 -14.1249 326.756 3993.49 -1.60904 4026.04 +EDGE_SE3:QUAT 289 340 4.84188 7.24874 -3.35587 -0.0557755 -0.114236 0.00283718 0.991883 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4201.71 31.0315 -949.992 3949.55 -19.9742 4214.12 +EDGE_SE3:QUAT 290 339 4.6614 -7.49255 -3.57462 0.0236437 -0.111659 -0.157344 0.980926 1 4.81482e-20 4.81482e-20 -1.3908e-08 2.35864e-09 1.3936e-09 1 4.81482e-20 -1.3908e-08 2.35864e-09 1.3936e-09 1 -1.3908e-08 2.35864e-09 1.3936e-09 4168.14 -54.4546 -843.816 3967.28 78.9696 4071.35 +EDGE_SE3:QUAT 291 341 4.98589 0.0224822 -3.34444 0.0539346 -0.107751 0.159958 0.979742 1 4.81482e-20 4.81482e-20 1.39846e-08 2.16168e-09 -1.69861e-09 1 4.81482e-20 1.39846e-08 2.16168e-09 -1.69861e-09 1 1.39846e-08 2.16168e-09 -1.69861e-09 4213.72 23.7618 -975.873 3948.33 -72.401 4123.01 +EDGE_SE3:QUAT 290 341 4.60832 7.37119 -3.5487 -0.0141669 -0.0243716 -0.029172 0.999177 1 3.00927e-21 3.00927e-21 -3.47092e-09 9.90191e-11 8.73573e-11 1 3.00927e-21 -3.47092e-09 9.90191e-11 8.73573e-11 1 -3.47092e-09 9.90191e-11 8.73573e-11 4009.18 1.00428 -200.065 3997.48 2.74927 4006.58 +EDGE_SE3:QUAT 291 340 4.66575 -7.34826 -3.35 0.0130434 0.0412332 -0.0615525 0.997166 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.96 -0.358233 339.674 3992.88 -10.1682 4013.48 +EDGE_SE3:QUAT 292 342 5.23091 0.07371 -3.6769 0.0856181 -0.016892 -0.0727604 0.993524 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3971.36 -1.55477 -58.4316 3999.96 1.3716 3979.51 +EDGE_SE3:QUAT 291 342 5.11693 7.10278 -3.32513 0.183936 0.216528 -0.0405567 0.957934 1 1.69271e-21 1.69271e-21 6.22838e-10 5.3141e-10 2.7603e-09 1 1.69271e-21 6.22838e-10 5.3141e-10 2.7603e-09 1 6.22838e-10 5.3141e-10 2.7603e-09 4737.65 232.533 2062.76 3845.61 205.251 4866.4 +EDGE_SE3:QUAT 292 341 4.72018 -7.09052 -3.40895 -0.0797131 0.0319959 0.0340124 0.995723 1 9.62965e-20 9.62965e-20 -1.17361e-10 -1.2742e-08 -1.49301e-08 1 9.62965e-20 -1.17361e-10 -1.2742e-08 -1.49301e-08 1 -1.17361e-10 -1.2742e-08 -1.49301e-08 3995.03 -10.9659 286.838 3994.67 2.75755 4015.82 +EDGE_SE3:QUAT 293 343 5.31237 -0.0562192 -3.00871 0.101351 0.0393821 -0.0663679 0.991853 1 4.81482e-20 4.81482e-20 -7.20012e-10 -1.33336e-09 -1.38307e-08 1 4.81482e-20 -7.20012e-10 -1.33336e-09 -1.38307e-08 1 -7.20012e-10 -1.33336e-09 -1.38307e-08 3996.79 18.0146 391.71 3989.74 -8.73541 4020.26 +EDGE_SE3:QUAT 292 343 4.55006 7.12394 -3.67202 -0.0335953 0.0422172 0.164052 0.984975 1 6.01853e-20 6.01853e-20 9.11071e-09 -1.25485e-08 1.01028e-10 1 6.01853e-20 9.11071e-09 -1.25485e-08 1.01028e-10 1 9.11071e-09 -1.25485e-08 1.01028e-10 4033.53 1.96644 392.118 3990.63 32.4775 3930.39 +EDGE_SE3:QUAT 293 342 4.26534 -7.26967 -3.39181 0.118257 0.111662 0.0352979 0.986053 1 3.85186e-19 3.85186e-19 -2.62532e-08 -2.90861e-08 7.45019e-10 1 3.85186e-19 -2.62532e-08 -2.90861e-08 7.45019e-10 1 -2.62532e-08 -2.90861e-08 7.45019e-10 4117.94 65.0439 852.499 3964.23 49.5491 4168.89 +EDGE_SE3:QUAT 294 344 5.05483 -0.00120677 -3.84513 0.103229 -0.0675119 -0.0658439 0.990177 1 1.92593e-19 1.92593e-19 -2.76568e-08 2.20344e-09 1.44785e-09 1 1.92593e-19 -2.76568e-08 2.20344e-09 1.44785e-09 1 -2.76568e-08 2.20344e-09 1.44785e-09 4007.32 -28.0932 -451.12 3990.37 23.0479 4032.6 +EDGE_SE3:QUAT 293 344 4.89259 7.14261 -3.81161 -0.0838776 0.0828713 -0.00766632 0.992995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.93 -30.8516 663.193 3975.04 -16.5385 4106.84 +EDGE_SE3:QUAT 294 343 4.59397 -6.77581 -3.32052 -0.068961 0.0878473 -0.00929726 0.993701 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4102.63 -27.9684 708.121 3971.34 -16.4394 4121.3 +EDGE_SE3:QUAT 295 345 5.02419 0.366792 -3.38794 -0.067854 0.148933 -0.0929857 0.982124 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4293.94 -94.5564 1161.5 3938.99 -99.013 4277.77 +EDGE_SE3:QUAT 294 345 4.84896 7.55473 -3.45398 0.0848767 -0.0377964 0.147255 0.984725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.04 -11.7353 -441.887 3986.37 -31.2727 3961.12 +EDGE_SE3:QUAT 295 344 4.49772 -7.12223 -3.73442 0.0280281 0.119507 0.00543428 0.992423 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4233.94 18.148 1002.26 3943.63 13.3881 4236.96 +EDGE_SE3:QUAT 296 346 5.27239 -0.164573 -3.99012 -0.0632468 0.114699 -0.00326141 0.99138 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4199.05 -35.2942 952.095 3949.65 -22.7989 4215.01 +EDGE_SE3:QUAT 295 346 5.30093 7.12865 -3.36188 0.00813599 0.0450659 0.00644434 0.99893 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.3 1.82101 362.398 3991.92 1.59117 4032.4 +EDGE_SE3:QUAT 296 345 4.62245 -7.24272 -3.31486 -0.128212 -0.0213255 -0.0449948 0.990496 1 7.70372e-19 7.70372e-19 5.50792e-08 -2.12106e-09 -1.77854e-09 1 7.70372e-19 5.50792e-08 -2.12106e-09 -1.77854e-09 1 5.50792e-08 -2.12106e-09 -1.77854e-09 3947.93 15.7293 -235.095 3996.11 3.4485 4005.58 +EDGE_SE3:QUAT 297 347 5.05666 0.396528 -3.74771 0.0203856 -0.0274074 -0.117023 0.992542 1 2.0463e-19 2.0463e-19 7.50285e-09 -1.54988e-09 -2.77308e-08 1 2.0463e-19 7.50285e-09 -1.54988e-09 -2.77308e-08 1 7.50285e-09 -1.54988e-09 -2.77308e-08 4006.98 -3.46006 -186.571 3998.23 10.6278 3953.87 +EDGE_SE3:QUAT 296 347 4.9066 7.28282 -3.8318 -0.0725203 0.100209 0.0752503 0.989463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4168.31 -15.3862 890.764 3953.59 17.5408 4166.7 +EDGE_SE3:QUAT 297 346 4.31502 -7.34653 -3.67008 -0.00961038 -0.12277 0.109557 0.986323 1 2.0463e-19 2.0463e-19 3.68724e-09 -2.34044e-10 2.73426e-08 1 2.0463e-19 3.68724e-09 -2.34044e-10 2.73426e-08 1 3.68724e-09 -2.34044e-10 2.73426e-08 4235.59 46.2318 -999.899 3948.4 -66.3726 4187.95 +EDGE_SE3:QUAT 298 348 5.1351 -0.140415 -3.48694 -0.0375365 -0.0591094 -0.114568 0.990945 1 1.20371e-20 1.20371e-20 -6.93413e-09 7.74468e-10 4.61808e-10 1 1.20371e-20 -6.93413e-09 7.74468e-10 4.61808e-10 1 -6.93413e-09 7.74468e-10 4.61808e-10 4061.27 -0.798423 -521.737 3983.39 28.2274 4014.4 +EDGE_SE3:QUAT 297 348 4.91873 7.86556 -3.70992 0.0912202 0.011081 -0.175447 0.980191 1 1.92593e-19 1.92593e-19 2.7268e-08 -4.74729e-09 1.15759e-09 1 1.92593e-19 2.7268e-08 -4.74729e-09 1.15759e-09 1 2.7268e-08 -4.74729e-09 1.15759e-09 3984.33 11.7443 271.832 3993.48 -27.6032 3894.49 +EDGE_SE3:QUAT 298 347 4.30578 -7.52225 -3.5846 0.177486 -0.0743434 0.0929927 0.976895 1 7.70372e-19 7.70372e-19 -5.52486e-08 -3.5176e-09 5.72178e-09 1 7.70372e-19 -5.52486e-08 -3.5176e-09 5.72178e-09 1 -5.52486e-08 -3.5176e-09 5.72178e-09 4020.29 -60.5032 -779.909 3962.87 -5.10218 4111.71 +EDGE_SE3:QUAT 299 349 5.06448 0.0316117 -3.16662 0.0528007 0.101996 0.0249789 0.993068 1 2.52778e-19 2.52778e-19 1.37519e-08 2.84849e-08 6.78896e-09 1 2.52778e-19 1.37519e-08 2.84849e-08 6.78896e-09 1 1.37519e-08 2.84849e-08 6.78896e-09 4151.85 30.2171 823.794 3961.95 24.6454 4160.5 +EDGE_SE3:QUAT 298 349 5.16792 7.61812 -3.8031 0.0871082 0.0504292 -0.0942581 0.990447 1 2.40741e-19 2.40741e-19 2.88779e-08 1.13902e-08 7.58607e-10 1 2.40741e-19 2.88779e-08 1.13902e-08 7.58607e-10 1 2.88779e-08 1.13902e-08 7.58607e-10 4030.63 15.6678 498.332 3983.7 -18.23 4025.45 +EDGE_SE3:QUAT 299 348 4.52569 -7.04025 -3.46724 -0.0281413 0.0232849 -0.0428005 0.998416 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.15 -2.84277 171.371 3998.3 -3.9003 3999.99 +EDGE_SE3:QUAT 300 350 5.43844 -0.123675 -3.56699 0.152133 0.0111683 -0.0498022 0.987041 1 7.70372e-19 7.70372e-19 5.48446e-08 -2.45382e-09 1.42027e-09 1 7.70372e-19 5.48446e-08 -2.45382e-09 1.42027e-09 1 5.48446e-08 -2.45382e-09 1.42027e-09 3914.95 15.1594 175.653 3997.52 -3.70088 3997.6 +EDGE_SE3:QUAT 299 350 4.66758 7.38137 -3.78406 0.0819735 0.0810063 -0.0199253 0.993137 1 1.92593e-19 1.92593e-19 -1.8199e-10 -2.757e-08 2.21448e-09 1 1.92593e-19 -1.8199e-10 -2.757e-08 2.21448e-09 1 -1.8199e-10 -2.757e-08 2.21448e-09 4084.62 26.5541 677.067 3973.05 6.53869 4109.91 +EDGE_SE3:QUAT 300 349 4.76293 -7.45007 -3.55424 -0.209428 0.0502123 0.0152322 0.976415 1 7.52316e-22 7.52316e-22 -9.07808e-11 3.64517e-10 -1.70329e-09 1 7.52316e-22 -9.07808e-11 3.64517e-10 -1.70329e-09 1 -9.07808e-11 3.64517e-10 -1.70329e-09 3867.49 -44.2732 416.648 3991.09 -10.4065 4042 +EDGE_SE3:QUAT 301 351 5.06744 -0.396447 -3.38529 -0.133281 -0.168501 0.109179 0.970528 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4247.8 155.01 -1178.5 3957.31 -151.833 4271.18 +EDGE_SE3:QUAT 300 351 4.61172 7.52589 -3.84158 -0.107834 0.0384726 0.0897101 0.989365 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.42 -19.7349 417.82 3987.95 14.4797 4010.74 +EDGE_SE3:QUAT 301 350 4.71804 -7.18394 -3.52389 0.0190029 -0.200857 -0.0302563 0.978969 1 7.70372e-19 7.70372e-19 -2.27542e-09 -5.4322e-08 1.86262e-09 1 7.70372e-19 -2.27542e-09 -5.4322e-08 1.86262e-09 1 -2.27542e-09 -5.4322e-08 1.86262e-09 4720.22 -60.7052 -1845.94 3843.72 62.4093 4718 +EDGE_SE3:QUAT 302 352 5.21313 0.0395328 -3.51733 0.0435922 0.0361373 0.077145 0.995411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.44 7.00848 246.225 3996.82 10.1157 3991.23 +EDGE_SE3:QUAT 301 352 4.88434 7.62066 -3.64451 -0.0658258 -0.0360358 0.0167781 0.997039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.36 9.4562 -274.147 3995.61 -4.18809 4017.57 +EDGE_SE3:QUAT 302 351 4.37035 -7.35836 -3.44757 -0.102057 0.123835 0.0102786 0.986987 1 1.88079e-22 1.88079e-22 1.1036e-10 -9.19094e-11 8.83283e-10 1 1.88079e-22 1.1036e-10 -9.19094e-11 8.83283e-10 1 1.1036e-10 -9.19094e-11 8.83283e-10 4213.9 -57.8535 1042.88 3941.97 -34.3019 4255.14 +EDGE_SE3:QUAT 303 353 5.37724 -0.366414 -3.83228 -0.00430084 -0.0121451 -0.123266 0.99229 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.49 -0.248233 -101.309 3999.38 6.32254 3941.79 +EDGE_SE3:QUAT 302 353 4.95116 7.45739 -3.83159 0.0167651 0.121791 -0.0332939 0.991856 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4249.82 -2.81723 1032.85 3940.11 -13.4766 4246.51 +EDGE_SE3:QUAT 303 352 4.67938 -7.33677 -3.84381 0.107164 0.0246789 -0.0602082 0.99211 1 2.0463e-19 2.0463e-19 -2.79723e-08 -5.39395e-09 -3.0357e-10 1 2.0463e-19 -2.79723e-08 -5.39395e-09 -3.0357e-10 1 -2.79723e-08 -5.39395e-09 -3.0357e-10 3972.2 14.4852 270.866 3994.8 -6.34585 4003.64 +EDGE_SE3:QUAT 304 354 5.22131 -0.033756 -3.28183 -0.00237739 -0.0338418 0.00824021 0.99939 1 3.19734e-21 3.19734e-21 7.51292e-10 -2.90758e-12 3.4459e-09 1 3.19734e-21 7.51292e-10 -2.90758e-12 3.4459e-09 1 7.51292e-10 -2.90758e-12 3.4459e-09 4018.33 0.553983 -271.554 3995.43 -1.19753 4018.08 +EDGE_SE3:QUAT 303 354 4.70641 7.18534 -3.55489 0.129178 -0.0218973 0.02257 0.991123 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.79 -13.6919 -205.79 3997.26 -0.517326 4008.5 +EDGE_SE3:QUAT 304 353 4.62338 -7.17793 -3.3991 -0.124844 0.224124 -0.0885984 0.962462 1 7.70372e-19 7.70372e-19 1.13234e-08 -1.0743e-08 5.8062e-08 1 7.70372e-19 1.13234e-08 -1.0743e-08 5.8062e-08 1 1.13234e-08 -1.0743e-08 5.8062e-08 4636.27 -275.525 1815 3905.41 -272.567 4667.22 +EDGE_SE3:QUAT 305 355 5.21745 0.186702 -3.38492 -0.155048 0.231249 0.0314594 0.959945 1 7.8918e-19 7.8918e-19 5.7536e-08 -1.18094e-09 4.9426e-09 1 7.8918e-19 5.7536e-08 -1.18094e-09 4.9426e-09 1 5.7536e-08 -1.18094e-09 4.9426e-09 4909.28 -225.841 2243.53 3817.61 -207.565 5001.48 +EDGE_SE3:QUAT 304 355 4.95588 7.47877 -3.96324 -0.182331 -0.0314515 0.00789798 0.982702 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3879.34 19.741 -222.786 3997.66 -4.4957 4012.07 +EDGE_SE3:QUAT 305 354 4.53071 -7.71637 -3.85363 -0.0293744 -0.0200894 -0.146194 0.988616 1 7.70372e-19 7.70372e-19 -1.53963e-09 -1.24145e-09 5.49536e-08 1 7.70372e-19 -1.53963e-09 -1.24145e-09 5.49536e-08 1 -1.53963e-09 -1.24145e-09 5.49536e-08 4007.16 1.14001 -206.704 3997.13 15.8925 3925.12 +EDGE_SE3:QUAT 306 356 5.1658 -0.00697347 -3.73286 -0.0940414 -0.0902172 -0.0685711 0.989098 1 2.40741e-19 2.40741e-19 -3.16357e-12 -2.6316e-08 -1.62878e-08 1 2.40741e-19 -3.16357e-12 -2.6316e-08 -1.62878e-08 1 -3.16357e-12 -2.6316e-08 -1.62878e-08 4123.42 26.7904 -812.838 3960.69 9.18079 4139.99 +EDGE_SE3:QUAT 305 356 4.44705 7.31162 -3.27072 0.0302581 0.074719 -0.0619293 0.99482 1 1.92593e-19 1.92593e-19 -1.60969e-09 -2.76184e-08 5.84683e-10 1 1.92593e-19 -1.60969e-09 -2.76184e-08 5.84683e-10 1 -1.60969e-09 -2.76184e-08 5.84683e-10 4092.99 1.22288 629.264 3976.14 -16.4862 4081.31 +EDGE_SE3:QUAT 306 355 4.88676 -7.78385 -3.42995 0.0377749 0.0838677 0.0866488 0.991984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4092.73 26.0064 635.47 3978.31 34.6018 4068.4 +EDGE_SE3:QUAT 307 357 5.05059 0.0337133 -3.57556 0.0576534 -0.20722 -0.0237477 0.976305 1 7.70372e-19 7.70372e-19 -2.84423e-09 -5.41372e-08 4.07363e-09 1 7.70372e-19 -2.84423e-09 -5.41372e-08 4.07363e-09 1 -2.84423e-09 -5.41372e-08 4.07363e-09 4742.76 -109.28 -1896.33 3842.66 104.56 4753.8 +EDGE_SE3:QUAT 306 357 4.81472 7.95013 -3.6926 0.0643198 0.116515 0.150255 0.979648 1 3.85186e-19 3.85186e-19 -2.30795e-08 -3.18644e-08 1.57093e-10 1 3.85186e-19 -2.30795e-08 -3.18644e-08 1.57093e-10 1 -2.30795e-08 -3.18644e-08 1.57093e-10 4137.44 66.7822 802.477 3974.34 80.6008 4063.68 +EDGE_SE3:QUAT 307 356 4.92969 -7.42831 -3.47576 -0.141054 0.0707201 0.0454728 0.986425 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.57 -42.4603 637.673 3975.89 -4.73383 4090.88 +EDGE_SE3:QUAT 308 358 5.10479 -0.0340162 -3.68859 0.0117568 -0.039059 -0.0976757 0.994382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.16 -5.02367 -295.585 3995.05 14.7515 3983.55 +EDGE_SE3:QUAT 307 358 4.73978 7.06113 -3.64934 0.2123 0.0701783 0.0521927 0.973283 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3857.11 40.9128 394.393 3995.99 24.2785 4026.5 +EDGE_SE3:QUAT 308 357 4.53725 -7.71286 -3.24441 -0.230216 0.096734 -0.190945 0.949307 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3783.72 -1.5611 168.899 4003.86 -3.65342 3849.87 +EDGE_SE3:QUAT 309 359 5.29742 -0.238259 -3.99502 -0.106315 -0.0128334 -0.113465 0.987754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.94 13.537 -242.307 3995.01 14.6969 3962.65 +EDGE_SE3:QUAT 308 359 4.51387 7.83384 -3.59087 0.0756664 -0.041262 0.0189778 0.996098 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.9 -12.7019 -346.573 3992.55 -0.0538945 4028.36 +EDGE_SE3:QUAT 309 358 4.5949 -7.44229 -3.56088 0.0102716 -0.105533 -0.0258746 0.994026 1 3.00927e-21 3.00927e-21 3.52654e-09 -1.01681e-10 -3.71869e-10 1 3.00927e-21 3.52654e-09 -1.01681e-10 -3.71869e-10 1 3.52654e-09 -1.01681e-10 -3.71869e-10 4181.98 -12.252 -873.422 3956.26 15.4864 4179.72 +EDGE_SE3:QUAT 310 360 5.25245 -0.135237 -3.43761 0.101122 -0.0382119 -0.0424243 0.993234 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.53 -12.921 -249.776 3996.94 7.58012 4008.23 +EDGE_SE3:QUAT 309 360 4.55296 7.42813 -3.7595 0.0634404 -0.086867 0.0472569 0.993074 1 1.92593e-19 1.92593e-19 -1.01357e-09 2.75759e-08 -1.55159e-09 1 1.92593e-19 -1.01357e-09 2.75759e-08 -1.55159e-09 1 -1.01357e-09 2.75759e-08 -1.55159e-09 4118.6 -16.4483 -746.32 3966.8 -6.55205 4125.76 +EDGE_SE3:QUAT 310 359 4.69527 -7.20174 -3.23875 -0.0207127 -0.053316 0.0392198 0.997592 1 1.20371e-20 1.20371e-20 6.9598e-09 2.90383e-10 -3.59089e-10 1 1.20371e-20 6.9598e-09 2.90383e-10 -3.59089e-10 1 6.9598e-09 2.90383e-10 -3.59089e-10 4041.78 7.03725 -419.403 3989.51 -9.76751 4037.34 +EDGE_SE3:QUAT 311 361 5.32382 0.0338426 -3.46743 -0.00876405 -0.114049 -0.142296 0.983193 1 7.73381e-19 7.73381e-19 -9.87423e-09 1.88858e-09 5.64215e-08 1 7.73381e-19 -9.87423e-09 1.88858e-09 5.64215e-08 1 -9.87423e-09 1.88858e-09 5.64215e-08 4209.87 -42.0813 -940.792 3954.62 73.0665 4129.19 +EDGE_SE3:QUAT 310 361 4.60067 7.37605 -3.45543 0.111203 0.135182 0.0380285 0.983826 1 1.01111e-18 1.01111e-18 2.61382e-08 5.83e-08 1.06679e-08 1 1.01111e-18 2.61382e-08 5.83e-08 1.06679e-08 1 2.61382e-08 5.83e-08 1.06679e-08 4215.61 84.8691 1063.84 3945.97 71.0972 4259.29 +EDGE_SE3:QUAT 311 360 4.54126 -7.92908 -3.15045 -0.0181767 0.0322465 -0.154097 0.987362 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.25 -4.81824 216.084 3997.81 -16.0432 3916.58 +EDGE_SE3:QUAT 312 362 4.99967 0.21823 -3.52456 -0.127046 -0.0660309 -0.0795129 0.986497 1 5.77779e-19 5.77779e-19 2.7088e-08 2.24339e-08 2.86233e-08 1 5.77779e-19 2.7088e-08 2.24339e-08 2.86233e-08 1 2.7088e-08 2.24339e-08 2.86233e-08 4036.87 34.1253 -645.639 3973.8 10.1873 4076.15 +EDGE_SE3:QUAT 311 362 4.67216 7.38581 -3.2646 -0.0111306 -0.110644 0.170203 0.979114 1 7.70372e-19 7.70372e-19 -5.68596e-09 -2.75397e-09 5.55622e-08 1 7.70372e-19 -5.68596e-09 -2.75397e-09 5.55622e-08 1 -5.68596e-09 -2.75397e-09 5.55622e-08 4174.1 53.1231 -854.432 3966.3 -83.063 4058.72 +EDGE_SE3:QUAT 312 361 4.58495 -7.40055 -3.18422 0.00716145 0.088281 -0.139075 0.986313 1 7.70372e-19 7.70372e-19 -4.89505e-09 9.93086e-10 -5.56136e-08 1 7.70372e-19 -4.89505e-09 9.93086e-10 -5.56136e-08 1 -4.89505e-09 9.93086e-10 -5.56136e-08 4124.28 -23.9926 716.614 3972.41 -52.3909 4047.12 +EDGE_SE3:QUAT 313 363 5.27455 -0.0488488 -3.55483 0.159858 0.121707 -0.0926911 0.975213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4221.6 71.3147 1183.62 3924.02 9.95065 4289.45 +EDGE_SE3:QUAT 312 363 4.92381 7.55534 -3.15711 0.0236093 0.0684717 0.124602 0.98956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4060.69 18.545 506.026 3986.69 34.3037 4000.82 +EDGE_SE3:QUAT 313 362 4.54228 -7.41306 -3.31111 -0.0929725 -0.020765 -0.0769461 0.992474 1 1.20371e-20 1.20371e-20 4.9887e-10 6.8893e-09 6.16431e-10 1 1.20371e-20 4.9887e-10 6.8893e-09 6.16431e-10 1 4.9887e-10 6.8893e-09 6.16431e-10 3980.64 11.3771 -248.493 3995.43 8.83088 3991.53 +EDGE_SE3:QUAT 314 364 4.70504 -0.0316614 -3.39858 -0.0220969 -0.0387738 -0.149602 0.987739 1 4.81482e-20 4.81482e-20 -2.05777e-09 -1.37104e-08 -1.34369e-10 1 4.81482e-20 -2.05777e-09 -1.37104e-08 -1.34369e-10 1 -2.05777e-09 -1.37104e-08 -1.34369e-10 4026.9 -2.38622 -340.976 3993.02 25.7524 3939.33 +EDGE_SE3:QUAT 313 364 4.84999 7.54756 -3.49861 -0.0316298 0.0854163 0.0388675 0.995084 1 4.81482e-20 4.81482e-20 -1.23275e-09 3.56535e-10 -1.40222e-08 1 4.81482e-20 -1.23275e-09 3.56535e-10 -1.40222e-08 1 -1.23275e-09 3.56535e-10 -1.40222e-08 4119.82 -4.9893 714.594 3969.6 9.14811 4117.78 +EDGE_SE3:QUAT 314 363 4.64895 -7.76296 -3.80436 0.0553931 -0.0776474 -0.175837 0.979788 1 1.92593e-19 1.92593e-19 -2.73908e-08 5.17554e-09 1.47894e-09 1 1.92593e-19 -2.73908e-08 5.17554e-09 1.47894e-09 1 -2.73908e-08 5.17554e-09 1.47894e-09 4043.54 -30.0363 -479.391 3991.74 45.3116 3932.14 +EDGE_SE3:QUAT 315 365 4.93476 -0.058667 -3.52015 -0.0836943 -0.0499029 0.0237512 0.994958 1 2.0463e-19 2.0463e-19 2.80503e-08 1.49068e-09 -8.19277e-09 1 2.0463e-19 2.80503e-08 1.49068e-09 -8.19277e-09 1 2.80503e-08 1.49068e-09 -8.19277e-09 4006.54 16.9008 -373.593 3992.16 -8.96011 4032.31 +EDGE_SE3:QUAT 314 365 4.60559 7.75296 -3.71865 0.19066 0.0323903 -0.051235 0.979783 1 7.70372e-19 7.70372e-19 5.46159e-08 -1.97921e-09 2.73553e-09 1 7.70372e-19 5.46159e-08 -1.97921e-09 2.73553e-09 1 5.46159e-08 -1.97921e-09 2.73553e-09 3886.79 36.032 361.289 3991.36 -1.93817 4021.7 +EDGE_SE3:QUAT 315 364 4.45434 -7.29734 -3.44048 -0.136157 -0.0307666 0.0287934 0.989791 1 7.82409e-19 7.82409e-19 5.47584e-08 8.87147e-09 -2.54378e-10 1 7.82409e-19 5.47584e-08 8.87147e-09 -2.54378e-10 1 5.47584e-08 8.87147e-09 -2.54378e-10 3935.02 12.4527 -192.851 3998.33 -4.69326 4005.86 +EDGE_SE3:QUAT 316 366 4.84581 0.218426 -3.60646 0.0167985 -0.0611925 -0.101999 0.992759 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4052.51 -12.5247 -466.455 3987.94 25.596 4012.02 +EDGE_SE3:QUAT 315 366 4.5873 7.55258 -3.78773 0.0906931 0.156332 0.0600141 0.981699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4324.57 104.225 1248.75 3929.05 98.7955 4343.06 +EDGE_SE3:QUAT 316 365 4.78227 -7.66262 -3.78287 0.00790969 0.0275193 -0.061334 0.997707 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.4 -0.253075 225.333 3996.85 -6.86422 3997.61 +EDGE_SE3:QUAT 317 367 5.42741 0.0563642 -3.19846 0.0916453 -0.0337925 -0.148629 0.984057 1 1.92593e-19 1.92593e-19 2.73184e-08 -4.23168e-09 -1.34733e-10 1 1.92593e-19 2.73184e-08 -4.23168e-09 -1.34733e-10 1 2.73184e-08 -4.23168e-09 -1.34733e-10 3967.91 -2.82115 -97.6712 4000.11 3.55298 3913.14 +EDGE_SE3:QUAT 316 367 4.83082 7.76646 -3.78947 0.0980743 0.00613101 0.130767 0.986531 1 1.92593e-19 1.92593e-19 2.73891e-08 3.59327e-09 -5.41368e-10 1 1.92593e-19 2.73891e-08 3.59327e-09 -5.41368e-10 1 2.73891e-08 3.59327e-09 -5.41368e-10 3963.61 -7.42094 -104.109 3998.5 -10.0306 3933.69 +EDGE_SE3:QUAT 317 366 4.77813 -7.34433 -3.35638 0.124991 -0.110173 -0.0413443 0.985155 1 4.81482e-20 4.81482e-20 -1.35548e-09 1.93597e-09 1.3952e-08 1 4.81482e-20 -1.35548e-09 1.93597e-09 1.3952e-08 1 -1.35548e-09 1.93597e-09 1.3952e-08 4099.92 -66.565 -823.047 3967.64 51.3979 4155.57 +EDGE_SE3:QUAT 318 368 5.21069 0.0151496 -3.91427 -0.0506717 -0.0554822 -0.103866 0.991749 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4052.44 4.30524 -504.998 3983.98 23.5585 4019.56 +EDGE_SE3:QUAT 317 368 4.91038 7.7965 -3.70413 0.0217164 0.0296174 0.161008 0.98627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.71 4.24377 186.651 3998.5 14.0734 3904.9 +EDGE_SE3:QUAT 318 367 4.68256 -7.71487 -3.68581 -0.0494905 0.0930932 -0.0156866 0.994303 1 2.40741e-19 2.40741e-19 1.33351e-08 -2.79478e-08 -1.94261e-10 1 2.40741e-19 1.33351e-08 -2.79478e-08 -1.94261e-10 1 1.33351e-08 -2.79478e-08 -1.94261e-10 4127.66 -23.5588 754.155 3967.38 -16.8786 4136.47 +EDGE_SE3:QUAT 319 369 5.0859 -0.198878 -3.72387 0.00451331 -0.124586 -0.0327401 0.991658 1 3.00927e-21 3.00927e-21 3.55006e-09 -1.25073e-10 -4.43904e-10 1 3.00927e-21 3.55006e-09 -1.25073e-10 -4.43904e-10 1 3.55006e-09 -1.25073e-10 -4.43904e-10 4258.4 -15.8504 -1049.17 3938.87 21.7929 4254.2 +EDGE_SE3:QUAT 318 369 4.90029 7.54704 -3.66479 -0.0402673 0.124328 0.162849 0.977958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4274.2 44.2837 1096.14 3938.7 88.7005 4174.6 +EDGE_SE3:QUAT 319 368 4.66455 -7.17605 -3.89599 -0.120116 0.0486442 0.0164041 0.991432 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.44 -24.4333 407.793 3990.11 -3.90592 4040.07 +EDGE_SE3:QUAT 320 370 5.33957 -0.143847 -3.94763 -0.00367626 -0.152636 0.140198 0.978281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4370.28 86.4942 -1272.51 3925.19 -112.299 4291.71 +EDGE_SE3:QUAT 319 370 4.7438 7.80445 -3.75382 0.0338538 -0.0240625 0.00624937 0.999118 1 4.81482e-20 4.81482e-20 -1.3882e-08 -6.40894e-11 3.39422e-10 1 4.81482e-20 -1.3882e-08 -6.40894e-11 3.39422e-10 1 -1.3882e-08 -6.40894e-11 3.39422e-10 4004.91 -3.24658 -195.103 3997.62 -0.135206 4009.34 +EDGE_SE3:QUAT 320 369 4.45838 -7.28898 -3.5375 0.137376 -0.0845578 -0.0492826 0.985672 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.49 -47.0927 -583.572 3984.49 33.4546 4073.27 +EDGE_SE3:QUAT 321 371 5.28721 0.131919 -3.72226 -0.060774 0.0212437 0.0839601 0.994387 1 2.0463e-19 2.0463e-19 2.82062e-08 -4.65365e-09 4.68773e-10 1 2.0463e-19 2.82062e-08 -4.65365e-09 4.68773e-10 1 2.82062e-08 -4.65365e-09 4.68773e-10 3998.18 -6.12159 228.758 3996.27 9.42418 3984.76 +EDGE_SE3:QUAT 320 371 4.30488 7.86939 -3.81342 0.0640969 -0.0233701 -0.0748982 0.994855 1 1.20371e-20 1.20371e-20 5.36487e-10 6.90191e-09 -4.64254e-10 1 1.20371e-20 5.36487e-10 6.90191e-09 -4.64254e-10 1 5.36487e-10 6.90191e-09 -4.64254e-10 3987.49 -3.99631 -127.046 3999.34 4.49638 3981.49 +EDGE_SE3:QUAT 321 370 4.55047 -7.46724 -3.63203 -0.000117175 0.0377045 -0.0775276 0.996277 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.41 -2.6502 300.271 3994.59 -11.7802 3998.37 +EDGE_SE3:QUAT 322 372 5.1792 0.134627 -3.70483 -0.00559796 0.0943521 -0.0433348 0.99458 1 4.81482e-20 4.81482e-20 -1.32067e-09 1.97175e-10 -1.40498e-08 1 4.81482e-20 -1.32067e-09 1.97175e-10 -1.40498e-08 1 -1.32067e-09 1.97175e-10 -1.40498e-08 4144.16 -11.9353 773.271 3965.37 -19.5243 4136.77 +EDGE_SE3:QUAT 321 372 4.64964 7.78188 -4.21844 -0.111562 0.030974 0.0575686 0.991605 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.58 -17.4299 320.242 3992.99 6.13808 4012.11 +EDGE_SE3:QUAT 322 371 4.32027 -7.57183 -3.2184 0.0513135 0.130838 -0.122191 0.982506 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4308.08 -23.2572 1173.05 3926.53 -61.7005 4258.89 +EDGE_SE3:QUAT 323 373 5.33907 0.209323 -3.55947 0.13372 0.0526787 -0.0601601 0.987788 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.6 31.8133 510.98 3983.38 -4.60499 4049.64 +EDGE_SE3:QUAT 322 373 4.60952 7.61588 -3.46668 -0.0782651 0.154824 0.146294 0.973911 1 4.81482e-20 4.81482e-20 -1.43269e-08 -1.87524e-09 -2.50003e-09 1 4.81482e-20 -1.43269e-08 -1.87524e-09 -2.50003e-09 1 -1.43269e-08 -1.87524e-09 -2.50003e-09 4458.25 33.9427 1471.16 3892.04 82.4047 4397.14 +EDGE_SE3:QUAT 323 372 4.86785 -7.74547 -3.44944 -0.10448 0.0238819 -0.0192314 0.994054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3963.03 -8.34904 164.103 3998.59 -2.63732 4005.22 +EDGE_SE3:QUAT 324 374 4.71682 -0.108325 -3.81634 0.145945 0.223388 0.055207 0.962159 1 1.54074e-18 1.54074e-18 5.12039e-08 6.07741e-08 1.40982e-09 1 1.54074e-18 5.12039e-08 6.07741e-08 1.40982e-09 1 5.12039e-08 6.07741e-08 1.40982e-09 4647.01 271.937 1863.82 3894.41 263.94 4720.01 +EDGE_SE3:QUAT 323 374 4.81592 7.57733 -4.07128 -0.0517042 0.0323759 0.0655409 0.995983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.4 -6.07601 298.348 3994.13 8.69084 4004.91 +EDGE_SE3:QUAT 324 373 4.53284 -7.52214 -3.77946 -0.142098 0.0840983 0.0438052 0.9853 1 4.81482e-20 4.81482e-20 1.31082e-09 -1.9248e-09 1.39073e-08 1 4.81482e-20 1.31082e-09 -1.9248e-09 1.39073e-08 1 1.31082e-09 -1.9248e-09 1.39073e-08 4054.15 -49.9725 746.99 3967.94 -10.4359 4127.25 +EDGE_SE3:QUAT 325 375 5.02788 -0.246021 -3.56844 -0.0187482 -0.0960721 -0.104764 0.989668 1 3.88195e-19 3.88195e-19 3.59286e-09 2.71548e-08 2.76153e-08 1 3.88195e-19 3.59286e-09 2.71548e-08 2.76153e-08 1 3.59286e-09 2.71548e-08 2.76153e-08 4154.9 -16.6343 -806.021 3963.35 42.1865 4112.41 +EDGE_SE3:QUAT 324 375 5.00835 7.42893 -4.13925 -0.0134517 0.0750055 0.0380718 0.996365 1 3.00927e-21 3.00927e-21 -3.49687e-09 -1.27963e-10 -2.66016e-10 1 3.00927e-21 -3.49687e-09 -1.27963e-10 -2.66016e-10 1 -3.49687e-09 -1.27963e-10 -2.66016e-10 4092.32 0.944297 617.101 3977.15 10.5904 4087.24 +EDGE_SE3:QUAT 325 374 4.30202 -8.02975 -3.47506 -0.0398089 -0.0486951 0.0302796 0.997561 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.77 9.19959 -376.428 3991.64 -7.90305 4031.44 +EDGE_SE3:QUAT 326 376 4.75159 0.171558 -3.63433 0.089227 -0.092809 -0.121299 0.984231 1 9.62965e-19 9.62965e-19 -7.1396e-11 -3.34571e-08 -5.21801e-08 1 9.62965e-19 -7.1396e-11 -3.34571e-08 -5.21801e-08 1 -7.1396e-11 -3.34571e-08 -5.21801e-08 4054.62 -44.5015 -597.51 3985.58 49.1022 4027.61 +EDGE_SE3:QUAT 325 376 4.72431 7.62891 -3.86989 -0.225119 0.00787019 0.0440474 0.973303 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3804.51 -23.4425 173.216 3997.47 2.7391 3999.47 +EDGE_SE3:QUAT 326 375 4.46748 -7.3886 -3.56237 0.0322056 -0.13226 -0.124944 0.982781 1 8.1852e-19 8.1852e-19 -2.09047e-08 5.74623e-09 5.79861e-08 1 8.1852e-19 -2.09047e-08 5.74623e-09 5.79861e-08 1 -2.09047e-08 5.74623e-09 5.79861e-08 4247.44 -70.0542 -1034.86 3949.5 87.4759 4189.14 +EDGE_SE3:QUAT 327 377 4.97975 -0.0257023 -3.52716 0.167464 -0.0370047 -0.0098003 0.985135 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3905.28 -21.8654 -265.219 3996.55 5.97299 4017.07 +EDGE_SE3:QUAT 326 377 4.92659 7.79633 -3.60209 0.0828129 0.0982738 0.0666822 0.989463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4099.62 45.3453 724.824 3973.6 42.4939 4109.26 +EDGE_SE3:QUAT 327 376 4.45927 -7.73863 -3.48189 -0.0159141 -0.0935942 0.0734699 0.992768 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4134.83 21.9024 -749.618 3968.49 -33.1203 4114.26 +EDGE_SE3:QUAT 328 378 5.22869 -0.248577 -3.99599 0.0730274 -0.141321 -0.0235072 0.986987 1 7.70372e-19 7.70372e-19 5.69508e-08 -2.62083e-09 -7.84678e-09 1 7.70372e-19 5.69508e-08 -2.62083e-09 -7.84678e-09 1 5.69508e-08 -2.62083e-09 -7.84678e-09 4298.33 -63.3552 -1175.18 3929.07 53.4988 4317.45 +EDGE_SE3:QUAT 327 378 4.04758 7.59505 -3.62761 0.0329597 -0.180282 0.207508 0.960912 1 7.70372e-19 7.70372e-19 -1.05748e-08 -2.66454e-09 5.71499e-08 1 7.70372e-19 -1.05748e-08 -2.66454e-09 5.71499e-08 1 -1.05748e-08 -2.66454e-09 5.71499e-08 4560.72 156.649 -1606.54 3901.08 -196.932 4392.83 +EDGE_SE3:QUAT 328 377 4.11733 -7.64211 -3.35886 -0.150916 -0.150586 -0.0158546 0.976881 1 3.00927e-21 3.00927e-21 5.39109e-10 5.56938e-10 -3.55043e-09 1 3.00927e-21 5.39109e-10 5.56938e-10 -3.55043e-09 1 5.39109e-10 5.56938e-10 -3.55043e-09 4289.25 111.537 -1290.91 3921.64 -78.7206 4379.35 +EDGE_SE3:QUAT 329 379 5.15355 0.0509706 -4.01906 0.175831 0.12549 0.0357349 0.975735 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4075.26 100.77 915.885 3966.29 76.6852 4193.82 +EDGE_SE3:QUAT 328 379 4.81046 8.15041 -3.55263 -0.253651 -0.0252949 0.206955 0.944558 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3777.21 -74.8355 417.547 3976 58.4524 3863.25 +EDGE_SE3:QUAT 329 378 4.39186 -7.45471 -3.1889 -0.0745623 0.124609 0.157217 0.97683 1 4.81482e-20 4.81482e-20 -1.4099e-08 -2.05181e-09 -2.03355e-09 1 4.81482e-20 -1.4099e-08 -2.05181e-09 -2.03355e-09 1 -1.4099e-08 -2.05181e-09 -2.03355e-09 4295.61 22.2207 1171.66 3926.81 76.4977 4218.98 +EDGE_SE3:QUAT 330 380 5.48743 0.209675 -3.97509 -0.00406136 -0.0957451 0.0107551 0.995339 1 1.95602e-19 1.95602e-19 -3.1917e-09 -2.76674e-08 1.65209e-10 1 1.95602e-19 -3.1917e-09 -2.76674e-08 1.65209e-10 1 -3.1917e-09 -2.76674e-08 1.65209e-10 4150.46 4.23146 -790.426 3963.45 -5.5947 4150.07 +EDGE_SE3:QUAT 329 380 4.68047 7.71132 -3.86316 -0.0895144 0.0500619 -0.0322865 0.994202 1 1.92593e-19 1.92593e-19 2.7708e-08 -1.1391e-09 1.20849e-09 1 1.92593e-19 2.7708e-08 -1.1391e-09 1.20849e-09 1 2.7708e-08 -1.1391e-09 1.20849e-09 4000.55 -17.7009 362.918 3992.85 -10.4252 4028.43 +EDGE_SE3:QUAT 330 379 4.30511 -7.94205 -3.67369 -0.0249422 -0.135041 -0.0771065 0.98752 1 3.00927e-21 3.00927e-21 3.55998e-09 -2.63384e-10 -4.94663e-10 1 3.00927e-21 3.55998e-09 -2.63384e-10 -4.94663e-10 1 3.55998e-09 -2.63384e-10 -4.94663e-10 4314.17 -20.2976 -1169.14 3926.33 41.9724 4292.87 +EDGE_SE3:QUAT 331 381 5.22141 0.0946486 -3.6543 -0.198672 -0.0331506 -0.0258823 0.979163 1 7.70372e-19 7.70372e-19 5.45245e-08 -6.10821e-10 -2.26022e-09 1 7.70372e-19 5.45245e-08 -6.10821e-10 -2.26022e-09 1 5.45245e-08 -6.10821e-10 -2.26022e-09 3866.18 31.9777 -311.284 3994.29 -2.60407 4021.38 +EDGE_SE3:QUAT 330 381 4.62526 7.77795 -3.6791 0.1238 -0.139434 0.10381 0.976962 1 9.62965e-19 9.62965e-19 3.23859e-08 -5.23606e-08 7.7406e-10 1 9.62965e-19 3.23859e-08 -5.23606e-08 7.7406e-10 1 3.23859e-08 -5.23606e-08 7.7406e-10 4346.8 -41.132 -1341.53 3904.38 -11.7478 4365 +EDGE_SE3:QUAT 331 380 4.34723 -7.71051 -3.78846 0.0987062 0.0832782 -0.0690606 0.989218 1 1.92593e-19 1.92593e-19 -2.79329e-08 1.47502e-09 -2.67163e-09 1 1.92593e-19 -2.79329e-08 1.47502e-09 -2.67163e-09 1 -2.79329e-08 1.47502e-09 -2.67163e-09 4099.28 27.5457 756.602 3965.49 -9.03053 4119.17 +EDGE_SE3:QUAT 332 382 4.85353 -0.0949802 -3.9011 -0.053628 -0.0239436 -0.0474884 0.997144 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.67 5.41194 -221.175 3996.74 4.59211 4003.15 +EDGE_SE3:QUAT 331 382 4.60207 7.72989 -3.7944 0.189186 -0.0623892 0.0958001 0.975263 1 9.62965e-19 9.62965e-19 5.23533e-08 8.70751e-09 2.22636e-08 1 9.62965e-19 5.23533e-08 8.70751e-09 2.22636e-08 1 5.23533e-08 8.70751e-09 2.22636e-08 3974.42 -60.4316 -697.399 3969.18 -7.78155 4080.87 +EDGE_SE3:QUAT 332 381 4.45191 -7.76741 -3.57793 0.0469149 0.0472481 -0.185114 0.980459 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4044.51 -2.11023 465.286 3986.76 -43.4267 3916.25 +EDGE_SE3:QUAT 333 383 4.86298 0.351034 -4.00018 0.0968641 0.00967917 0.0039953 0.995243 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3963.75 3.39337 71.7482 3999.71 0.334123 4001.22 +EDGE_SE3:QUAT 332 383 4.29968 7.83871 -3.80468 0.0875683 0.0640373 0.239856 0.964728 1 1.92593e-19 1.92593e-19 2.68099e-08 6.90144e-09 4.0895e-10 1 1.92593e-19 2.68099e-08 6.90144e-09 4.0895e-10 1 2.68099e-08 6.90144e-09 4.0895e-10 3978.61 12.7451 220.406 4001.09 17.4255 3779.16 +EDGE_SE3:QUAT 333 382 4.2213 -7.82619 -4.08354 0.0474689 0.151544 -0.187563 0.96933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4415.33 -84.0007 1370.22 3913.94 -132.4 4283.62 +EDGE_SE3:QUAT 334 384 4.9401 -0.036502 -3.79861 0.0667558 -0.0447437 0.0154872 0.996645 1 4.81482e-20 4.81482e-20 1.30934e-10 -1.38323e-08 9.1061e-10 1 4.81482e-20 1.30934e-10 -1.38323e-08 9.1061e-10 1 1.30934e-10 -1.38323e-08 9.1061e-10 4016.22 -11.9644 -370.603 3991.54 0.431048 4033.09 +EDGE_SE3:QUAT 333 384 4.91703 8.00678 -3.90911 -0.233237 -0.0208424 -0.0855378 0.968426 1 7.70372e-19 7.70372e-19 -5.40136e-08 3.73308e-09 3.17868e-09 1 7.70372e-19 -5.40136e-08 3.73308e-09 3.17868e-09 1 -5.40136e-08 3.73308e-09 3.17868e-09 3818.18 50.4997 -384.845 3988.42 9.6896 4006.51 +EDGE_SE3:QUAT 334 383 4.51104 -7.85617 -3.80656 -0.108411 0.010781 -0.179471 0.977712 1 1.92593e-19 1.92593e-19 2.71509e-08 -4.92923e-09 -7.83377e-10 1 1.92593e-19 2.71509e-08 -4.92923e-09 -7.83377e-10 1 2.71509e-08 -4.92923e-09 -7.83377e-10 3956.93 11.6607 -146.135 3996.87 19.9188 3875.1 +EDGE_SE3:QUAT 335 385 4.72587 -0.109299 -3.85942 0.0222011 -0.181815 0.110178 0.976889 1 3.8086e-21 3.8086e-21 4.08744e-09 4.58262e-10 -7.62315e-10 1 3.8086e-21 4.08744e-09 4.58262e-10 -7.62315e-10 1 4.08744e-09 4.58262e-10 -7.62315e-10 4587.27 79.4677 -1644.46 3874.57 -102.632 4540.69 +EDGE_SE3:QUAT 334 385 4.84411 7.84612 -4.31732 0.07719 -0.13826 0.253073 0.9544 1 4.81482e-20 4.81482e-20 -1.39436e-08 -3.50972e-09 2.30589e-09 1 4.81482e-20 -1.39436e-08 -3.50972e-09 2.30589e-09 1 -1.39436e-08 -3.50972e-09 2.30589e-09 4380.81 92.9266 -1335.04 3923.19 -167.877 4148.46 +EDGE_SE3:QUAT 335 384 4.58846 -7.30176 -3.69586 -0.022537 -0.0253071 -0.141826 0.989311 1 1.20371e-20 1.20371e-20 9.76844e-10 6.86577e-09 1.00974e-10 1 1.20371e-20 9.76844e-10 6.86577e-09 1.00974e-10 1 9.76844e-10 6.86577e-09 1.00974e-10 4011.69 0.00489776 -234.833 3996.51 17.1044 3933.26 +EDGE_SE3:QUAT 336 386 5.01867 0.224795 -4.02171 -0.206941 0.0663181 0.0307664 0.975618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3911.5 -60.9575 581.432 3982.08 -16.0674 4079.02 +EDGE_SE3:QUAT 335 386 4.66783 7.72331 -4.24053 -0.0160927 0.164982 0.169873 0.971424 1 7.70372e-19 7.70372e-19 9.42273e-09 2.44016e-09 5.69967e-08 1 7.70372e-19 9.42273e-09 2.44016e-09 5.69967e-08 1 9.42273e-09 2.44016e-09 5.69967e-08 4453.51 110.249 1423.25 3912.24 144.257 4339.12 +EDGE_SE3:QUAT 336 385 4.385 -7.7101 -3.80309 0.0363336 -0.163709 -0.0575624 0.984157 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4432.98 -72.6543 -1394.77 3904.69 76.5975 4425.01 +EDGE_SE3:QUAT 337 387 4.98684 0.222957 -3.63967 -0.0838472 -0.0495492 0.136484 0.985843 1 1.92593e-19 1.92593e-19 2.74132e-08 3.98459e-09 -6.75452e-10 1 1.92593e-19 2.74132e-08 3.98459e-09 -6.75452e-10 1 2.74132e-08 3.98459e-09 -6.75452e-10 3986.26 12.3813 -246.296 3998.31 -16.0657 3939.87 +EDGE_SE3:QUAT 336 387 4.71618 7.85585 -3.98157 -0.103771 -0.0835443 0.0360811 0.990429 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.7 38.9846 -623.412 3979.72 -27.3425 4089.57 +EDGE_SE3:QUAT 337 386 4.32608 -7.72477 -3.70501 -0.0838103 0.0444329 0.103236 0.990123 1 4.33334e-19 4.33334e-19 2.72968e-08 -9.05523e-09 -2.69972e-08 1 4.33334e-19 2.72968e-08 -9.05523e-09 -2.69972e-08 1 2.72968e-08 -9.05523e-09 -2.69972e-08 4022.68 -13.6277 454.37 3986.17 19.8405 4008.14 +EDGE_SE3:QUAT 338 388 5.10426 -0.0355228 -3.56862 0.113226 -0.134069 -0.160892 0.971246 1 7.70372e-19 7.70372e-19 4.87912e-09 -8.72353e-09 -5.50079e-08 1 7.70372e-19 4.87912e-09 -8.72353e-09 -5.50079e-08 1 4.87912e-09 -8.72353e-09 -5.50079e-08 4104.79 -94.2478 -813.859 3983.32 100.195 4052.53 +EDGE_SE3:QUAT 337 388 4.98305 7.62196 -3.70929 -0.082638 -0.173321 0.0326552 0.980849 1 7.70372e-19 7.70372e-19 3.55245e-09 -5.43623e-08 -5.51158e-09 1 7.70372e-19 3.55245e-09 -5.43623e-08 -5.51158e-09 1 3.55245e-09 -5.43623e-08 -5.51158e-09 4457.84 105.107 -1475.35 3898.99 -96.4105 4480.89 +EDGE_SE3:QUAT 338 387 4.37689 -8.0308 -3.48923 0.161224 -0.0296892 0.11369 0.979898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.77 -35.232 -443.654 3985.04 -19.9628 3996.04 +EDGE_SE3:QUAT 339 389 5.25156 -0.260847 -3.75566 -0.0349531 0.0888669 0.0965859 0.990733 1 2.0463e-19 2.0463e-19 9.54205e-09 -2.68636e-08 1.74229e-10 1 2.0463e-19 9.54205e-09 -2.68636e-08 1.74229e-10 1 9.54205e-09 -2.68636e-08 1.74229e-10 4135.9 5.74784 763.551 3965.97 33.2226 4103.47 +EDGE_SE3:QUAT 338 389 4.66443 7.45474 -3.73352 -0.0256831 0.13916 0.133452 0.9809 1 1.20371e-20 1.20371e-20 -7.09154e-09 -9.50589e-10 -1.01902e-09 1 1.20371e-20 -7.09154e-09 -9.50589e-10 -1.01902e-09 1 -7.09154e-09 -9.50589e-10 -1.01902e-09 4333.39 51.2967 1207.08 3926.42 84.5257 4264.79 +EDGE_SE3:QUAT 339 388 4.26548 -7.78464 -3.64131 0.0481682 -0.159262 -0.00828764 0.986026 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4422.35 -47.9201 -1383.06 3902.2 40.1403 4431.35 +EDGE_SE3:QUAT 340 390 4.90782 0.030902 -3.95181 0.1223 0.180897 -0.0664883 0.973601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4576.98 79.0435 1718.39 3860.84 44.103 4619.13 +EDGE_SE3:QUAT 339 390 4.80846 7.86263 -3.84747 -0.0211339 -0.05619 0.264977 0.962384 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4026.29 16.8751 -340.045 3997.25 -42.1163 3747.22 +EDGE_SE3:QUAT 340 389 4.3748 -7.84292 -3.69901 0.0174096 -0.00658769 0.0448377 0.998821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.74 -0.505382 -61.8859 3999.74 -1.43341 3992.91 +EDGE_SE3:QUAT 341 391 5.11759 -0.0901388 -4.07596 0.0242949 0.197657 -0.143885 0.96935 1 7.52316e-22 7.52316e-22 1.82573e-09 -2.75028e-10 3.69499e-10 1 7.52316e-22 1.82573e-09 -2.75028e-10 3.69499e-10 1 1.82573e-09 -2.75028e-10 3.69499e-10 4697.41 -133.623 1813.6 3862.32 -159.157 4616.96 +EDGE_SE3:QUAT 340 391 4.59703 8.02663 -3.70647 0.044132 -0.123114 -0.0463723 0.990326 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4229.36 -42.6033 -1002.51 3946.17 43.0564 4228.55 +EDGE_SE3:QUAT 341 390 4.39598 -7.96325 -4.1378 -0.194433 0.0198071 -0.07142 0.978112 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3848 7.05189 -13.5541 3999.69 2.57808 3978.82 +EDGE_SE3:QUAT 342 392 4.91602 -0.132236 -3.88287 -0.0405529 0.0123288 0.124439 0.991322 1 4.81482e-20 4.81482e-20 -1.37679e-08 -1.70953e-09 -3.04395e-10 1 4.81482e-20 -1.37679e-08 -1.70953e-09 -3.04395e-10 1 -1.37679e-08 -1.70953e-09 -3.04395e-10 3999.43 -2.60162 156.217 3998.16 10.6359 3944.07 +EDGE_SE3:QUAT 341 392 4.72979 8.00208 -3.71459 -0.057105 0.130408 0.310303 0.939917 1 3.00927e-21 3.00927e-21 3.40187e-09 1.10824e-09 5.0207e-10 1 3.00927e-21 3.40187e-09 1.10824e-09 5.0207e-10 1 3.40187e-09 1.10824e-09 5.0207e-10 4305.46 117.458 1173.43 3955.29 194.943 3933.35 +EDGE_SE3:QUAT 342 391 4.46145 -7.834 -4.11973 0.0086709 -0.0814361 -0.130543 0.988054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4097.82 -22.948 -634.313 3978.65 44.8661 4029.95 +EDGE_SE3:QUAT 343 393 4.93509 -0.268958 -4.13514 -0.0994999 -0.0637913 0.0985196 0.988091 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.8 23.5993 -381.045 3994.18 -23.4907 3996.57 +EDGE_SE3:QUAT 342 393 4.68536 7.56602 -3.81181 -0.048141 -0.0465346 -0.00685114 0.997732 1 2.40741e-19 2.40741e-19 2.78479e-08 1.37808e-08 -6.47514e-10 1 2.40741e-19 2.78479e-08 1.37808e-08 -6.47514e-10 1 2.78479e-08 1.37808e-08 -6.47514e-10 4026.11 8.96099 -377.83 3991.25 -1.23266 4035.19 +EDGE_SE3:QUAT 343 392 4.3879 -7.69094 -3.52073 0.0738881 -0.0514539 0.114614 0.989321 1 4.81482e-20 4.81482e-20 1.47929e-09 -1.3742e-08 8.42488e-10 1 4.81482e-20 1.47929e-09 -1.3742e-08 8.42488e-10 1 1.47929e-09 -1.3742e-08 8.42488e-10 4041.61 -10.3394 -508.403 3983.17 -25.3182 4010.9 +EDGE_SE3:QUAT 344 394 4.94477 0.077002 -4.00974 0.0155144 -0.153168 0.0440304 0.987097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4405.85 15.04 -1338.94 3905.91 -27.0915 4399.06 +EDGE_SE3:QUAT 343 394 4.48243 8.09592 -3.77207 0.0238162 0.187413 0.143221 0.971492 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4540.44 155.072 1571.02 3902.25 172.915 4460.66 +EDGE_SE3:QUAT 344 393 4.46073 -7.92163 -3.88619 0.252024 -0.0974931 0.151041 0.950876 1 1.92593e-19 1.92593e-19 4.50474e-09 -6.33174e-09 -2.75703e-08 1 1.92593e-19 4.50474e-09 -6.33174e-09 -2.75703e-08 1 4.50474e-09 -6.33174e-09 -2.75703e-08 4083.25 -123.264 -1212.06 3918.37 2.67871 4246.06 +EDGE_SE3:QUAT 345 395 4.76651 0.331527 -4.03888 0.00608707 0.0180642 0.0970096 0.995101 1 1.50463e-20 1.50463e-20 -2.77943e-09 -7.24243e-09 8.24279e-12 1 1.50463e-20 -2.77943e-09 -7.24243e-09 8.24279e-12 1 -2.77943e-09 -7.24243e-09 8.24279e-12 4004.44 1.09593 135.558 3998.95 6.49174 3966.94 +EDGE_SE3:QUAT 344 395 4.81747 7.69379 -4.02768 0.0530822 0.086312 0.0921393 0.990577 1 4.81482e-20 4.81482e-20 -1.39156e-08 -1.43474e-09 -1.04559e-09 1 4.81482e-20 -1.39156e-08 -1.43474e-09 -1.04559e-09 1 -1.39156e-08 -1.43474e-09 -1.04559e-09 4086.16 31.7976 632.475 3979.5 38.4278 4063.48 +EDGE_SE3:QUAT 345 394 4.36922 -7.78049 -3.56733 -0.0160242 -0.0760732 0.023173 0.996704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4091.55 8.48262 -615.535 3977.48 -9.80207 4090.43 +EDGE_SE3:QUAT 346 396 4.99234 -0.453229 -3.88679 -0.0529799 0.0467332 -0.0527192 0.996107 1 9.62965e-20 9.62965e-20 1.30742e-08 -1.46221e-08 -2.36767e-10 1 9.62965e-20 1.30742e-08 -1.46221e-08 -2.36767e-10 1 1.30742e-08 -1.46221e-08 -2.36767e-10 4017.3 -11.2315 339.247 3993.61 -11.1998 4017.41 +EDGE_SE3:QUAT 345 396 4.3864 8.02275 -3.53238 -0.0410659 -0.102207 0.103041 0.988559 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4137.71 40.8998 -774.275 3969.54 -52.3091 4101.99 +EDGE_SE3:QUAT 346 395 4.04428 -8.19483 -3.4455 -0.0312283 -0.160297 -0.0160692 0.986444 1 1.20371e-20 1.20371e-20 -7.21849e-09 4.75428e-11 1.17779e-09 1 1.20371e-20 -7.21849e-09 4.75428e-11 1.17779e-09 1 -7.21849e-09 4.75428e-11 1.17779e-09 4444.25 16.8571 -1411.9 3896.71 -7.5166 4447.12 +EDGE_SE3:QUAT 347 397 4.88962 0.208757 -3.79955 -0.178479 -0.0656099 0.00407709 0.981745 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3933.49 45.7191 -497.722 3987.83 -18.2679 4060.84 +EDGE_SE3:QUAT 346 397 4.86039 7.98604 -4.08082 -0.131395 0.077316 0.130046 0.979717 1 1.92593e-19 1.92593e-19 2.77508e-08 3.03706e-09 3.00656e-09 1 1.92593e-19 2.77508e-08 3.03706e-09 3.00656e-09 1 2.77508e-08 3.03706e-09 3.00656e-09 4091.81 -33.0432 819.492 3958.04 32.097 4093.22 +EDGE_SE3:QUAT 347 396 4.14277 -7.76432 -3.92902 0.0214867 0.0374616 0.131262 0.990407 1 1.20371e-20 1.20371e-20 6.88688e-09 9.25383e-10 2.12248e-10 1 1.20371e-20 6.88688e-09 9.25383e-10 2.12248e-10 1 6.88688e-09 9.25383e-10 2.12248e-10 4014.81 6.23665 259.134 3996.63 16.8888 3947.73 +EDGE_SE3:QUAT 348 398 4.72827 -0.349047 -3.92659 -0.0373205 -0.0130492 0.0804975 0.99597 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.52 1.19765 -67.3053 3999.82 -2.29149 3975.17 +EDGE_SE3:QUAT 347 398 4.85789 8.03351 -4.02778 -0.0406291 -0.0346989 -0.0514886 0.997243 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.12 4.68416 -302.418 3994.12 6.75076 4012.12 +EDGE_SE3:QUAT 348 397 4.30117 -8.04557 -3.56174 -0.142792 -0.173954 0.0243947 0.974041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4377.33 150.442 -1431.26 3915.28 -131.104 4456.51 +EDGE_SE3:QUAT 349 399 5.038 0.0526581 -3.4742 -0.0229237 0.01287 -0.0183304 0.999486 1 3.00927e-21 3.00927e-21 6.55958e-11 3.46763e-09 8.11402e-11 1 3.00927e-21 6.55958e-11 3.46763e-09 8.11402e-11 1 6.55958e-11 3.46763e-09 8.11402e-11 4000.29 -1.17081 97.8365 3999.43 -0.966583 4001.05 +EDGE_SE3:QUAT 348 399 4.61363 8.03383 -3.87658 -0.0609255 -0.0162764 0.165969 0.984113 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.72 -1.07893 -5.30812 3999.93 3.06801 3889.38 +EDGE_SE3:QUAT 349 398 4.32941 -7.58491 -3.73954 -0.0311099 0.0541739 -0.050936 0.996746 1 9.62965e-20 9.62965e-20 5.03389e-11 1.43415e-08 -1.3398e-08 1 9.62965e-20 5.03389e-11 1.43415e-08 -1.3398e-08 1 5.03389e-11 1.43415e-08 -1.3398e-08 4038.88 -9.91277 415.796 3989.95 -12.7738 4032.37 +EDGE_SE3:QUAT 350 400 5.11796 0.159318 -4.02574 0.302403 -0.134422 0.0746454 0.940697 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.72 -202.968 -1285.66 3940.18 118.877 4355.22 +EDGE_SE3:QUAT 349 400 4.57013 7.87186 -4.03309 0.0578639 -0.0190811 -0.0883326 0.994226 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.48 -2.32359 -89.215 3999.75 3.23915 3970.66 +EDGE_SE3:QUAT 350 399 4.43773 -7.62817 -3.69562 0.0501728 -0.253995 -0.0473246 0.964743 1 3.27408e-18 3.27408e-18 -2.14506e-08 1.09452e-07 -1.5094e-09 1 3.27408e-18 -2.14506e-08 1.09452e-07 -1.5094e-09 1 -2.14506e-08 1.09452e-07 -1.5094e-09 5187.6 -204.487 -2495.16 3776.78 204.326 5188.71 +EDGE_SE3:QUAT 351 401 4.91414 0.393087 -4.04602 0.0699221 0.0964097 -0.0441172 0.991902 1 4.33334e-19 4.33334e-19 2.75203e-08 2.57853e-08 -1.29106e-08 1 4.33334e-19 2.75203e-08 2.57853e-08 -1.29106e-08 1 2.75203e-08 2.57853e-08 -1.29106e-08 4145.85 21.3789 830.089 3959.65 -2.99918 4157.62 +EDGE_SE3:QUAT 350 401 4.40278 8.07334 -3.97204 0.10877 -0.128734 -0.121926 0.978126 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4126.69 -86.7532 -856.389 3973.62 88.7198 4114.55 +EDGE_SE3:QUAT 351 400 4.30888 -7.65955 -3.92652 -0.188923 -0.0848349 -0.143353 0.967761 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4088.52 67.5529 -991.56 3940.21 25.4945 4149.08 +EDGE_SE3:QUAT 352 402 4.82851 0.405435 -4.119 0.0487499 0.225465 0.127509 0.96464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4783.79 247.096 1951.4 3872.81 254.354 4728.26 +EDGE_SE3:QUAT 351 402 4.486 8.16643 -3.87802 0.105684 -0.0531085 -0.0482801 0.991806 1 2.40741e-19 2.40741e-19 -2.82158e-08 3.1783e-09 1.49745e-08 1 2.40741e-19 -2.82158e-08 3.1783e-09 1.49745e-08 1 -2.82158e-08 3.1783e-09 1.49745e-08 3986.88 -20.6538 -357.602 3993.7 13.8151 4022.23 +EDGE_SE3:QUAT 352 401 4.28985 -8.00509 -4.01808 0.00866341 0.0491423 -0.0710385 0.996225 1 7.52316e-22 7.52316e-22 -1.73679e-09 1.22951e-10 -8.69451e-11 1 7.52316e-22 -1.73679e-09 1.22951e-10 -8.69451e-11 1 -1.73679e-09 1.22951e-10 -8.69451e-11 4039.5 -2.46199 400.983 3990.25 -14.145 4019.61 +EDGE_SE3:QUAT 353 403 5.3816 0.131378 -4.15802 0.0187093 -0.0385992 -0.015703 0.998956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.95 -3.4548 -306.535 3994.25 3.09504 4022.37 +EDGE_SE3:QUAT 352 403 4.55035 7.91177 -3.64751 0.0612336 -0.0949939 -0.131647 0.984833 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4088.19 -43.1705 -652.539 3981.18 54.3399 4033.86 +EDGE_SE3:QUAT 353 402 4.58311 -7.75756 -3.91438 -0.0202936 0.00175443 -0.100372 0.994741 1 1.20371e-20 1.20371e-20 -6.90241e-09 6.9639e-10 1.62008e-11 1 1.20371e-20 -6.90241e-09 6.9639e-10 1.62008e-11 1 -6.90241e-09 6.9639e-10 1.62008e-11 3998.36 0.188841 -10.4569 3999.98 0.93725 3959.71 +EDGE_SE3:QUAT 354 404 4.9196 0.0173359 -3.56321 -0.0524987 -0.0980102 -0.0693052 0.99138 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4162.41 6.9766 -850.829 3957.61 19.3829 4154.22 +EDGE_SE3:QUAT 353 404 4.49809 7.96781 -4.05584 -0.173257 0.0066259 -0.00190581 0.984852 1 7.52316e-22 7.52316e-22 7.03065e-12 1.70844e-09 3.00618e-10 1 7.52316e-22 7.03065e-12 1.70844e-09 3.00618e-10 1 7.03065e-12 1.70844e-09 3.00618e-10 3880.47 -3.86925 46.7601 3999.89 -0.19526 4000.53 +EDGE_SE3:QUAT 354 403 4.33565 -8.28431 -4.07759 0.048713 -0.114044 0.113145 0.985809 1 4.33334e-19 4.33334e-19 -1.35126e-08 2.52467e-08 -2.7071e-08 1 4.33334e-19 -1.35126e-08 2.52467e-08 -2.7071e-08 1 -1.35126e-08 2.52467e-08 -2.7071e-08 4230.91 12.6204 -1009.69 3943.24 -48.7513 4189.19 +EDGE_SE3:QUAT 355 405 5.34989 0.133656 -3.83388 -0.0318884 0.179362 -0.0222901 0.983014 1 4.81482e-20 4.81482e-20 -1.45643e-08 5.30153e-10 -2.62596e-09 1 4.81482e-20 -1.45643e-08 5.30153e-10 -2.62596e-09 1 -1.45643e-08 5.30153e-10 -2.62596e-09 4553.88 -54.0712 1594.72 3876.18 -52.3728 4555.96 +EDGE_SE3:QUAT 354 405 4.58228 8.4402 -4.08734 0.0155935 0.0227567 0.113653 0.993137 1 1.20371e-20 1.20371e-20 -6.89667e-09 -7.94511e-10 -1.29385e-10 1 1.20371e-20 -6.89667e-09 -7.94511e-10 -1.29385e-10 1 -6.89667e-09 -7.94511e-10 -1.29385e-10 4005.2 2.30873 157.574 3998.71 8.68061 3954.51 +EDGE_SE3:QUAT 355 404 4.26404 -7.94193 -3.59729 -0.00853344 0.132438 -0.14272 0.980825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4267.95 -66.6044 1070.38 3945.33 -92.7912 4186.77 +EDGE_SE3:QUAT 356 406 4.74313 -0.281989 -4.2502 -0.0316049 -0.0676239 0.0122827 0.997135 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4068.62 10.3305 -543.835 3982.32 -6.97779 4072.02 +EDGE_SE3:QUAT 355 406 4.13363 8.09941 -3.98771 0.128501 0.0476718 0.184166 0.973292 1 1.55278e-18 1.55278e-18 5.25099e-08 2.49287e-08 5.28789e-08 1 1.55278e-18 5.25099e-08 2.49287e-08 5.28789e-08 1 5.25099e-08 2.49287e-08 5.28789e-08 3932.74 -0.348159 77.5642 4000.41 -1.50649 3863.12 +EDGE_SE3:QUAT 356 405 4.65747 -8.20316 -3.78777 -0.0276339 0.0279189 -0.211757 0.976533 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.61 -3.57732 140.178 3999.57 -12.1468 3825.3 +EDGE_SE3:QUAT 357 407 4.90045 0.0802158 -3.74322 -0.126402 -0.0885389 -0.132105 0.979148 1 1.92593e-19 1.92593e-19 2.78599e-08 -3.07257e-09 -3.30349e-09 1 1.92593e-19 2.78599e-08 -3.07257e-09 -3.30349e-09 1 2.78599e-08 -3.07257e-09 -3.30349e-09 4133.72 30.2749 -911.871 3949.69 34.9322 4127.82 +EDGE_SE3:QUAT 356 407 4.38892 8.12606 -4.05577 0.0202207 -0.011588 0.0427328 0.998815 1 1.20371e-20 1.20371e-20 6.93296e-09 2.93209e-10 -9.2061e-11 1 1.20371e-20 6.93296e-09 2.93209e-10 -9.2061e-11 1 6.93296e-09 2.93209e-10 -9.2061e-11 4001 -0.91281 -102.81 3999.3 -2.19509 3995.33 +EDGE_SE3:QUAT 357 406 4.41173 -7.75731 -3.69428 -0.0223792 0.171905 -0.0714588 0.982263 1 1.92593e-19 1.92593e-19 -4.89655e-09 1.44648e-09 -2.89013e-08 1 1.92593e-19 -4.89655e-09 1.44648e-09 -2.89013e-08 1 -4.89655e-09 1.44648e-09 -2.89013e-08 4489.6 -78.2062 1486.05 3894.19 -87.0177 4471.17 +EDGE_SE3:QUAT 358 408 4.90136 -0.153826 -3.4999 -0.0113408 0.0787492 0.0813018 0.993509 1 1.92593e-19 1.92593e-19 2.23606e-09 4.35828e-11 2.79294e-08 1 1.92593e-19 2.23606e-09 4.35828e-11 2.79294e-08 1 2.23606e-09 4.35828e-11 2.79294e-08 4102.16 8.73354 649.037 3975.36 26.438 4076.24 +EDGE_SE3:QUAT 357 408 4.45966 8.08291 -3.81071 0.20452 -0.126675 0.013325 0.97054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4084.86 -117.8 -1036.02 3953.36 74.7181 4251.46 +EDGE_SE3:QUAT 358 407 4.32143 -8.34419 -3.78856 0.00894706 0.0362764 0.0720912 0.996698 1 1.95602e-19 1.95602e-19 -4.4293e-09 -6.46023e-10 -2.78526e-08 1 1.95602e-19 -4.4293e-09 -6.46023e-10 -2.78526e-08 1 -4.4293e-09 -6.46023e-10 -2.78526e-08 4019.37 3.43533 281.378 3995.32 10.4269 3998.9 +EDGE_SE3:QUAT 359 409 4.76838 -0.000896094 -4.22029 -0.00924429 -0.343088 -0.0743549 0.93631 1 2.0463e-19 2.0463e-19 2.07936e-08 -2.64205e-09 -3.69951e-08 1 2.0463e-19 2.07936e-08 -2.64205e-09 -3.69951e-08 1 2.07936e-08 -2.64205e-09 -3.69951e-08 6792.2 -353.834 -4355.32 3568.87 341.043 6770.43 +EDGE_SE3:QUAT 358 409 4.43653 8.07151 -4.15368 0.0567827 0.0176651 -0.0838477 0.994703 1 2.52778e-19 2.52778e-19 1.36413e-08 4.29784e-09 -2.7638e-08 1 2.52778e-19 1.36413e-08 4.29784e-09 -2.7638e-08 1 1.36413e-08 4.29784e-09 -2.7638e-08 3996.65 5.05311 196.372 3997.2 -8.3172 3981.42 +EDGE_SE3:QUAT 359 408 4.17226 -8.21915 -4.09604 0.0516804 0.0162487 -0.111013 0.992341 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.77 4.27505 195.714 3997.16 -11.4948 3960.15 +EDGE_SE3:QUAT 360 410 4.96704 -0.172401 -3.78113 0.192953 -0.179055 0.0351668 0.964091 1 7.76061e-19 7.76061e-19 -5.64193e-08 1.18327e-09 5.70574e-09 1 7.76061e-19 -5.64193e-08 1.18327e-09 5.70574e-09 1 -5.64193e-08 1.18327e-09 5.70574e-09 4418.96 -179.386 -1610.85 3894.99 140.058 4562.94 +EDGE_SE3:QUAT 359 410 4.62597 8.03899 -3.87754 0.198442 0.043158 0.19598 0.959349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3841 -30.5639 -137.039 3994.13 -30.1879 3844.89 +EDGE_SE3:QUAT 360 409 4.34639 -7.92536 -4.00476 -0.00707245 0.0803745 -0.0610876 0.994866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4102.23 -12.0126 648.244 3975.56 -22.1529 4087.5 +EDGE_SE3:QUAT 361 411 5.25723 0.0277167 -3.59834 0.0748729 -0.222796 -0.137221 0.962251 1 1.92593e-19 1.92593e-19 2.90194e-08 -5.58825e-09 -5.66255e-09 1 1.92593e-19 2.90194e-08 -5.58825e-09 -5.66255e-09 1 2.90194e-08 -5.58825e-09 -5.66255e-09 4674.18 -268.492 -1811.85 3904.72 273.767 4621.29 +EDGE_SE3:QUAT 360 411 4.55433 8.08588 -4.52764 0.0221705 -0.00608885 0.0849664 0.996119 1 2.07639e-19 2.07639e-19 -6.93602e-09 2.2908e-09 -2.76567e-08 1 2.07639e-19 -6.93602e-09 2.2908e-09 -2.76567e-08 1 -6.93602e-09 2.2908e-09 -2.76567e-08 3999.27 -0.726914 -70.6597 3999.63 -3.27975 3972.36 +EDGE_SE3:QUAT 361 410 4.58602 -8.1857 -3.82142 0.0165612 0.0310475 -0.173738 0.984163 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.33 -2.36578 272.126 3995.68 -24.1309 3897.69 +EDGE_SE3:QUAT 362 412 4.83633 0.0938195 -4.0027 -0.0448288 0.0538735 -0.048664 0.996353 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.61 -12.2149 405.415 3990.63 -12.7524 4031.18 +EDGE_SE3:QUAT 361 412 4.38653 8.08034 -3.67026 -0.00158011 0.00377545 0.0970753 0.995269 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.24 0.0104788 31.6084 3999.94 1.55668 3962.56 +EDGE_SE3:QUAT 362 411 4.18032 -8.09959 -3.87516 0.0994401 0.0573847 -0.17102 0.978555 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4062.19 13.0938 647.765 3972.6 -49.6185 3984.75 +EDGE_SE3:QUAT 363 413 5.0143 -0.260365 -3.70027 0.0787597 -0.115269 -0.00641016 0.990186 1 1.92593e-19 1.92593e-19 -2.82133e-08 7.11473e-10 3.21256e-09 1 1.92593e-19 -2.82133e-08 7.11473e-10 3.21256e-09 1 -2.82133e-08 7.11473e-10 3.21256e-09 4189.1 -44.5444 -949.452 3950.79 29.6312 4213.74 +EDGE_SE3:QUAT 362 413 4.46547 7.95678 -3.95017 0.0827349 -0.0947838 0.0549468 0.990531 1 1.92593e-19 1.92593e-19 -2.80624e-08 -1.11627e-09 2.89372e-09 1 1.92593e-19 -2.80624e-08 -1.11627e-09 2.89372e-09 1 -2.80624e-08 -1.11627e-09 2.89372e-09 4138.63 -24.8974 -831.71 3959.33 -5.0454 4153.94 +EDGE_SE3:QUAT 363 412 4.32128 -7.95505 -3.50906 0.0884653 0.0435907 -0.105808 0.989484 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.69 14.7887 455.493 3985.99 -20.3644 4006.21 +EDGE_SE3:QUAT 364 414 5.04567 0.136503 -4.32705 -0.187023 0.0382056 0.0560985 0.980008 1 4.81482e-20 4.81482e-20 -7.80791e-10 2.54421e-09 -1.36752e-08 1 4.81482e-20 -7.80791e-10 2.54421e-09 -1.36752e-08 1 -7.80791e-10 2.54421e-09 -1.36752e-08 3902.61 -39.8624 415.535 3988.74 2.02839 4029.93 +EDGE_SE3:QUAT 363 414 4.305 8.47035 -3.68714 -0.0669035 -0.109005 -0.00265286 0.991784 1 1.92593e-19 1.92593e-19 -2.81947e-08 -3.44701e-10 3.08073e-09 1 1.92593e-19 -2.81947e-08 -3.44701e-10 3.08073e-09 1 -2.81947e-08 -3.44701e-10 3.08073e-09 4177.45 33.2649 -905.306 3953.97 -18.7772 4195.32 +EDGE_SE3:QUAT 364 413 4.29736 -8.18613 -3.9801 0.109913 0.0418749 -0.0271775 0.992687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.05 19.7971 366.955 3991.63 0.139681 4030.42 +EDGE_SE3:QUAT 365 415 4.71445 0.063328 -4.19456 0.0320139 -0.242248 0.0237326 0.969395 1 7.82409e-19 7.82409e-19 8.17234e-09 -5.37485e-08 -6.02291e-10 1 7.82409e-19 8.17234e-09 -5.37485e-08 -6.02291e-10 1 8.17234e-09 -5.37485e-08 -6.02291e-10 5138.53 -18.6806 -2424.08 3764.14 13.8806 5140.38 +EDGE_SE3:QUAT 364 415 4.59769 8.15623 -3.94957 -0.0100965 0.100605 0.0281934 0.994476 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4167.62 2.55065 836.871 3959.31 10.4885 4164.85 +EDGE_SE3:QUAT 365 414 4.43752 -7.86407 -3.60535 0.118412 0.124864 -0.253015 0.952035 1 1.92593e-19 1.92593e-19 -2.78614e-08 6.63191e-09 -4.8278e-09 1 1.92593e-19 -2.78614e-08 6.63191e-09 -4.8278e-09 1 -2.78614e-08 6.63191e-09 -4.8278e-09 4359.71 -52.1094 1355.63 3910.73 -149.421 4159.72 +EDGE_SE3:QUAT 366 416 4.9588 -0.0890129 -3.8135 -0.0091975 -0.206395 -0.0613369 0.976501 1 7.52316e-22 7.52316e-22 -1.8518e-09 1.19474e-10 3.90495e-10 1 7.52316e-22 -1.8518e-09 1.19474e-10 3.90495e-10 1 -1.8518e-09 1.19474e-10 3.90495e-10 4776.72 -64.8364 -1926.68 3833.76 75.0201 4762.01 +EDGE_SE3:QUAT 365 416 4.5405 8.15296 -3.80389 -0.0649602 0.114853 -0.0110714 0.991194 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4195.42 -38.4504 945.678 3950.73 -27.3355 4211.81 +EDGE_SE3:QUAT 366 415 4.06715 -8.44866 -3.4978 0.0445936 0.0519676 -0.100421 0.992586 1 1.92593e-19 1.92593e-19 1.66748e-09 9.36993e-10 2.77367e-08 1 1.92593e-19 1.66748e-09 9.36993e-10 2.77367e-08 1 1.66748e-09 9.36993e-10 2.77367e-08 4045.9 3.25656 467.406 3986.27 -21.526 4013.51 +EDGE_SE3:QUAT 367 417 5.02324 0.235648 -3.66402 -0.213979 0.0991755 -0.059685 0.969956 1 1.92593e-19 1.92593e-19 1.78899e-09 -6.39351e-09 2.72202e-08 1 1.92593e-19 1.78899e-09 -6.39351e-09 2.72202e-08 1 1.78899e-09 -6.39351e-09 2.72202e-08 3901.23 -70.1042 593.584 3990.83 -50.4527 4070.13 +EDGE_SE3:QUAT 366 417 4.01212 8.17746 -4.54554 -0.026838 -0.110138 -0.0450265 0.992533 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4203.9 -0.0203375 -932.672 3950.19 15.3542 4198.67 +EDGE_SE3:QUAT 367 416 4.00664 -8.11681 -4.13857 -0.0943135 -0.0591842 -0.0122046 0.993707 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.87 22.8817 -487.049 3985.91 -5.20409 4057.85 +EDGE_SE3:QUAT 368 418 4.70912 -0.0665753 -3.80994 0.0564139 -0.0698118 -0.0509813 0.994658 1 2.40741e-19 2.40741e-19 1.22834e-08 -2.84214e-08 8.85468e-10 1 2.40741e-19 1.22834e-08 -2.84214e-08 8.85468e-10 1 1.22834e-08 -2.84214e-08 8.85468e-10 4055.36 -20.6369 -526.513 3984.59 19.7556 4057.69 +EDGE_SE3:QUAT 367 418 4.5111 7.96506 -3.89586 -0.157114 -0.0655057 0.206073 0.963617 1 7.82409e-19 7.82409e-19 5.19703e-08 1.86922e-08 1.52874e-09 1 7.82409e-19 5.19703e-08 1.86922e-08 1.52874e-09 1 5.19703e-08 1.86922e-08 1.52874e-09 3898.29 -1.12351 -98.7102 4000.99 2.95325 3827.16 +EDGE_SE3:QUAT 368 417 4.60757 -8.05323 -3.71112 -0.0122947 -0.152483 0.0899073 0.984131 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4378.49 64.0404 -1288.55 3917.49 -79.1051 4346.76 +EDGE_SE3:QUAT 369 419 4.8153 0.336465 -3.85556 0.208682 -0.00370237 0.0533319 0.976521 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3831.6 -20.6653 -157.248 3997.64 -4.03928 3994.41 +EDGE_SE3:QUAT 368 419 4.038 8.016 -3.9428 0.0978967 0.0384936 0.120998 0.987063 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.11 6.87086 156.764 3999.6 7.78979 3946.88 +EDGE_SE3:QUAT 369 418 4.17018 -8.16231 -4.04171 -0.0946122 -0.143059 -0.00161949 0.98518 1 1.92593e-19 1.92593e-19 -2.84926e-08 -7.56292e-10 4.06947e-09 1 1.92593e-19 -2.84926e-08 -7.56292e-10 4.06947e-09 1 -2.84926e-08 -7.56292e-10 4.06947e-09 4303.97 68.9063 -1214.35 3924.43 -49.4297 4339.76 +EDGE_SE3:QUAT 370 420 4.5877 -0.0722082 -3.87776 -0.00240827 -0.0337639 0.193203 0.980575 1 3.00927e-21 3.00927e-21 3.40893e-09 6.73726e-10 -1.05412e-10 1 3.00927e-21 3.40893e-09 6.73726e-10 -1.05412e-10 1 3.40893e-09 6.73726e-10 -1.05412e-10 4015.57 5.08634 -250.492 3996.97 -23.8527 3866.28 +EDGE_SE3:QUAT 369 420 4.57825 7.97157 -3.92481 -0.141473 0.0460114 0.144664 0.978233 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.49 -32.9421 598.042 3974.77 34.4177 4002.84 +EDGE_SE3:QUAT 370 419 4.4979 -8.47573 -3.89832 -0.00925591 -0.0669743 -0.00556845 0.997696 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.55 2.02818 -544.871 3982.02 0.56932 4072.77 +EDGE_SE3:QUAT 371 421 4.72875 0.102533 -3.85542 0.0128388 0.0630761 -0.125334 0.990024 1 7.70372e-19 7.70372e-19 3.59833e-09 -1.81615e-10 5.54184e-08 1 7.70372e-19 3.59833e-09 -1.81615e-10 5.54184e-08 1 3.59833e-09 -1.81615e-10 5.54184e-08 4065.67 -9.09029 519.326 3984.51 -32.8206 4003.49 +EDGE_SE3:QUAT 370 421 4.56939 8.22097 -4.1209 -0.0965495 -0.0102185 -0.0115095 0.995209 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3964.91 4.69828 -93.8914 3999.42 0.261863 4001.67 +EDGE_SE3:QUAT 371 420 4.32577 -8.27555 -4.11735 0.045553 0.0381387 -0.148036 0.987196 1 4.81482e-20 4.81482e-20 1.37616e-08 -2.01417e-09 6.9258e-10 1 4.81482e-20 1.37616e-08 -2.01417e-09 6.9258e-10 1 1.37616e-08 -2.01417e-09 6.9258e-10 4026.85 1.98275 377.087 3990.81 -27.951 3947.49 +EDGE_SE3:QUAT 372 422 5.41783 0.13741 -4.01664 -0.0146407 -0.00206918 0.0183443 0.999722 1 3.05629e-21 3.05629e-21 -3.46052e-09 -4.97388e-10 -1.07013e-12 1 3.05629e-21 -3.46052e-09 -4.97388e-10 -1.07013e-12 1 -3.46052e-09 -4.97388e-10 -1.07013e-12 3999.19 0.090954 -13.3182 3999.99 -0.113346 3998.7 +EDGE_SE3:QUAT 371 422 4.33701 8.146 -4.49432 0.266348 0.104748 -0.18186 0.940752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4156.7 136.249 1401.85 3893.99 -5.04224 4308.17 +EDGE_SE3:QUAT 372 421 4.00477 -8.715 -3.70763 0.0310477 0.155531 -0.0935845 0.982898 1 1.92593e-19 1.92593e-19 4.63224e-09 5.81294e-11 2.87241e-08 1 1.92593e-19 4.63224e-09 5.81294e-11 2.87241e-08 1 4.63224e-09 5.81294e-11 2.87241e-08 4426.63 -35.943 1381.04 3902.75 -61.1977 4395.46 +EDGE_SE3:QUAT 373 423 4.52435 -0.290658 -4.08267 0.0349781 -0.0384163 -0.058002 0.996964 1 9.62965e-20 9.62965e-20 1.47123e-08 1.29888e-08 -1.01826e-09 1 9.62965e-20 1.47123e-08 1.29888e-08 -1.01826e-09 1 1.47123e-08 1.29888e-08 -1.01826e-09 4014.88 -6.65108 -282.062 3995.49 9.12621 4006.31 +EDGE_SE3:QUAT 372 423 4.36548 8.571 -4.34873 0.0582858 -0.0548621 0.00505621 0.996778 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.3 -13.0192 -444.9 3988.03 3.13794 4048.78 +EDGE_SE3:QUAT 373 422 3.90655 -8.5873 -3.92109 0.0751564 -0.211226 0.155529 0.962053 1 7.70372e-19 7.70372e-19 -1.37719e-08 5.6585e-10 5.93238e-08 1 7.70372e-19 -1.37719e-08 5.6585e-10 5.93238e-08 1 -1.37719e-08 5.6585e-10 5.93238e-08 4889.04 109.239 -2116.04 3816.24 -141.945 4814.87 +EDGE_SE3:QUAT 374 424 4.68237 -0.388494 -4.01473 -0.10037 -0.058491 0.152004 0.981529 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.91 15.6607 -265.429 3998.74 -18.983 3923.79 +EDGE_SE3:QUAT 373 424 4.40218 8.07543 -4.24006 -0.0269894 -0.0787889 0.14478 0.985953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4077.23 26.6684 -572.611 3984.04 -45.7555 3996.3 +EDGE_SE3:QUAT 374 423 4.28519 -8.31291 -3.83917 0.0470686 0.0573146 -0.123589 0.989558 1 4.81482e-20 4.81482e-20 -1.385e-08 1.65941e-09 -9.36777e-10 1 4.81482e-20 -1.385e-08 1.65941e-09 -9.36777e-10 1 -1.385e-08 1.65941e-09 -9.36777e-10 4058.54 1.20472 523.816 3983.02 -30.2803 4006.31 +EDGE_SE3:QUAT 375 425 4.49162 -0.233403 -4.24497 -0.0683016 0.132889 0.0782801 0.985671 1 4.81482e-20 4.81482e-20 1.42343e-08 8.94398e-10 2.03697e-09 1 4.81482e-20 1.42343e-08 8.94398e-10 2.03697e-09 1 1.42343e-08 8.94398e-10 2.03697e-09 4309.74 -10.1259 1192.3 3922.23 22.3652 4303.89 +EDGE_SE3:QUAT 374 425 4.23042 8.20691 -4.10982 -0.0482819 -0.0148126 0.135528 0.989485 1 4.81482e-20 4.81482e-20 1.37321e-08 1.8922e-09 -1.72597e-11 1 4.81482e-20 1.37321e-08 1.8922e-09 -1.72597e-11 1 1.37321e-08 1.8922e-09 -1.72597e-11 3990.84 0.393294 -37.377 4000.02 -0.730923 3926.69 +EDGE_SE3:QUAT 375 424 4.27121 -8.0296 -4.05427 0.00368108 -0.000915254 -0.0676249 0.997704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.95 -0.00666266 -4.29366 4000 0.110976 3981.71 +EDGE_SE3:QUAT 376 426 4.95883 0.341692 -4.02613 0.0290947 0.0354684 -0.0580295 0.99726 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.54 2.62054 303.747 3994.14 -8.14003 4009.46 +EDGE_SE3:QUAT 375 426 4.35681 8.45885 -3.83731 0.103821 0.0481255 0.0645529 0.991331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3978.67 16.6443 297.731 3996.04 12.7662 4005.12 +EDGE_SE3:QUAT 376 425 4.13469 -8.02901 -4.05818 0.0679411 -0.0600115 0.00124778 0.995882 1 1.88079e-22 1.88079e-22 5.20888e-11 -5.96547e-11 -8.70025e-10 1 1.88079e-22 5.20888e-11 -5.96547e-11 -8.70025e-10 1 5.20888e-11 -5.96547e-11 -8.70025e-10 4039.22 -16.923 -483.804 3986.05 5.63163 4057.68 +EDGE_SE3:QUAT 377 427 4.65427 0.00174552 -3.96426 0.216487 -0.0314532 -0.141368 0.965484 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3812.65 27.6239 124.184 3995.93 -18.031 3920.18 +EDGE_SE3:QUAT 376 427 4.29867 7.99313 -4.14318 0.0858931 0.0902966 0.172297 0.97713 1 7.70372e-19 7.70372e-19 -3.01883e-09 -6.30877e-09 -5.4685e-08 1 7.70372e-19 -3.01883e-09 -6.30877e-09 -5.4685e-08 1 -3.01883e-09 -6.30877e-09 -5.4685e-08 4033.43 40.7846 512.644 3992.62 50.7698 3944.2 +EDGE_SE3:QUAT 377 426 4.27237 -8.51422 -3.79565 -0.0313811 -0.102596 -0.0613677 0.992332 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4177.84 -1.60201 -871.873 3956.04 21.3433 4166.71 +EDGE_SE3:QUAT 378 428 4.93757 0.133197 -3.70238 0.156314 0.0740857 0.0326024 0.984385 1 1.01111e-18 1.01111e-18 -5.74486e-08 2.19801e-08 -2.16408e-08 1 1.01111e-18 -5.74486e-08 2.19801e-08 -2.16408e-08 1 -5.74486e-08 2.19801e-08 -2.16408e-08 3967.52 43.6834 516.27 3987.79 25.2488 4061.01 +EDGE_SE3:QUAT 377 428 4.20092 8.61976 -4.12511 -0.0373695 -0.226866 0.164521 0.959202 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4768.95 278.623 -1925.32 3890.9 -289.243 4666.26 +EDGE_SE3:QUAT 378 427 4.29139 -8.64925 -3.82695 -0.0245536 0.0549442 -0.183288 0.981215 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.65 -14.5335 366.553 3994.31 -33.4944 3898.68 +EDGE_SE3:QUAT 379 429 4.81663 0.0585057 -3.82809 -0.0959749 0.039828 -0.0452468 0.993557 1 2.40741e-19 2.40741e-19 -2.69125e-08 1.52344e-08 5.3787e-10 1 2.40741e-19 -2.69125e-08 1.52344e-08 5.3787e-10 1 -2.69125e-08 1.52344e-08 5.3787e-10 3980.18 -13.1224 262.297 3996.59 -8.3108 4008.83 +EDGE_SE3:QUAT 378 429 4.50832 8.27931 -3.98775 -0.108769 -0.121485 -0.0137671 0.98652 1 2.38038e-22 2.38038e-22 -1.22279e-10 -1.09313e-10 9.92304e-10 1 2.38038e-22 -1.22279e-10 -1.09313e-10 9.92304e-10 1 -1.22279e-10 -1.09313e-10 9.92304e-10 4200.09 59.3688 -1025.14 3943.88 -33.5664 4246.66 +EDGE_SE3:QUAT 379 428 4.23418 -8.24846 -3.98505 -0.0471476 -0.0388302 -0.101849 0.992923 1 4.81482e-20 4.81482e-20 -1.38369e-08 1.36698e-09 6.60983e-10 1 4.81482e-20 -1.38369e-08 1.36698e-09 6.60983e-10 1 -1.38369e-08 1.36698e-09 6.60983e-10 4024.05 4.4011 -364.812 3991.33 17.6082 3991.45 +EDGE_SE3:QUAT 380 430 5.06295 0.13747 -3.95394 -0.123899 0.0080212 0.0798698 0.989043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3946.3 -12.8459 179.488 3997.13 7.63377 3982.19 +EDGE_SE3:QUAT 379 430 4.4811 8.08746 -4.09643 -0.136647 0.0862869 0.142892 0.976455 1 7.70372e-19 7.70372e-19 5.56055e-08 6.64389e-09 6.75171e-09 1 7.70372e-19 5.56055e-08 6.64389e-09 6.75171e-09 1 5.56055e-08 6.64389e-09 6.75171e-09 4127.62 -33.7341 923.459 3948 38.9287 4120.63 +EDGE_SE3:QUAT 380 429 4.32029 -7.93109 -3.97686 -0.0901838 0.00557711 -0.202559 0.975093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.6 9.89999 -170.91 3996.38 24.3212 3842.01 +EDGE_SE3:QUAT 381 431 4.71471 -0.136628 -3.98261 -0.0505854 0.138016 -0.0255748 0.988807 1 7.70372e-19 7.70372e-19 2.26314e-09 5.48615e-08 3.31533e-09 1 7.70372e-19 2.26314e-09 5.48615e-08 3.31533e-09 1 2.26314e-09 5.48615e-08 3.31533e-09 4299.51 -47.3263 1155.42 3929.49 -42.2485 4307.12 +EDGE_SE3:QUAT 380 431 4.38293 8.09569 -4.10314 0.0994252 -0.0649968 0.114204 0.98633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4064.01 -19.6294 -652.704 3972.79 -27.1892 4051.38 +EDGE_SE3:QUAT 381 430 4.25755 -8.29354 -3.74689 0.0985236 -0.0546597 -0.011322 0.993568 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.07 -21.8273 -421.414 3989.94 9.11623 4043.38 +EDGE_SE3:QUAT 382 432 4.95383 0.284291 -4.12287 0.0137491 0.057074 0.0168018 0.998134 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.15 4.57344 458.618 3987.24 5.05581 4050.78 +EDGE_SE3:QUAT 381 432 4.28242 8.54967 -4.15465 -0.0866455 -0.0295071 -0.0275055 0.995422 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.13 11.186 -262.634 3995.56 1.61915 4014.13 +EDGE_SE3:QUAT 382 431 4.32953 -8.25969 -3.75925 -0.0547042 0.053148 0.0479227 0.995935 1 9.62965e-20 9.62965e-20 -1.31031e-08 -1.28182e-09 1.31031e-08 1 9.62965e-20 -1.31031e-08 -1.28182e-09 1.31031e-08 1 -1.31031e-08 -1.28182e-09 1.31031e-08 4039.91 -9.54739 458.561 3986.82 7.3929 4042.69 +EDGE_SE3:QUAT 383 433 4.6914 0.0378866 -4.10746 -0.023127 0.00327431 -0.0209476 0.999508 1 1.22251e-20 1.22251e-20 -2.32524e-12 -1.02822e-09 6.91541e-09 1 1.22251e-20 -2.32524e-12 -1.02822e-09 6.91541e-09 1 -2.32524e-12 -1.02822e-09 6.91541e-09 3997.96 -0.216424 20.3469 3999.98 -0.196758 3998.35 +EDGE_SE3:QUAT 382 433 4.73547 8.63677 -4.09518 0.0195779 -0.040455 0.0158049 0.998865 1 3.00927e-21 3.00927e-21 1.42811e-10 -6.38825e-11 -3.47714e-09 1 3.00927e-21 1.42811e-10 -6.38825e-11 -3.47714e-09 1 1.42811e-10 -6.38825e-11 -3.47714e-09 4025.34 -2.65135 -328.983 3993.28 -1.86585 4025.88 +EDGE_SE3:QUAT 383 432 4.33189 -7.9674 -3.76665 -0.0929507 -0.0304953 0.00090833 0.995203 1 1.20371e-20 1.20371e-20 -4.54259e-11 6.90546e-09 6.46542e-10 1 1.20371e-20 -4.54259e-11 6.90546e-09 6.46542e-10 1 -4.54259e-11 6.90546e-09 6.46542e-10 3979.85 11.2426 -240.549 3996.58 -2.1471 4014.41 +EDGE_SE3:QUAT 384 434 4.77711 -0.116644 -4.17975 0.00279219 0.0617806 0.105062 0.992541 1 5.11575e-20 5.11575e-20 1.9953e-09 1.41438e-08 -9.27191e-12 1 5.11575e-20 1.9953e-09 1.41438e-08 -9.27191e-12 1 1.9953e-09 1.41438e-08 -9.27191e-12 4058.8 10.1959 488.709 3986.39 26.7349 4014.68 +EDGE_SE3:QUAT 383 434 4.54796 8.28282 -3.99344 0.17399 -0.0282656 -0.0354399 0.983703 1 4.81482e-20 4.81482e-20 1.98918e-10 -2.44046e-09 -1.36602e-08 1 4.81482e-20 1.98918e-10 -2.44046e-09 -1.36602e-08 1 1.98918e-10 -2.44046e-09 -1.36602e-08 3883.79 -10.3999 -143.096 3999.43 3.76506 3999.86 +EDGE_SE3:QUAT 384 433 4.68871 -8.42281 -3.56919 0.0460528 0.264553 -0.054298 0.961739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5430.94 -18.5474 2798.14 3715.83 -22.7244 5427.63 +EDGE_SE3:QUAT 385 435 4.37897 0.210745 -4.05422 -0.026768 0.00712637 -0.0212109 0.999391 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.76 -0.661348 50.1093 3999.86 -0.534015 3998.83 +EDGE_SE3:QUAT 384 435 4.58616 8.26193 -4.12967 -0.0496909 0.051732 0.276117 0.958444 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4059.44 12.7715 531.358 3985.14 76.6715 3764.36 +EDGE_SE3:QUAT 385 434 4.16473 -8.30338 -3.6062 0.165405 0.25521 -0.026985 0.952251 1 7.70372e-19 7.70372e-19 6.07261e-08 4.03548e-09 1.58909e-08 1 7.70372e-19 6.07261e-08 4.03548e-09 1.58909e-08 1 6.07261e-08 4.03548e-09 1.58909e-08 5130.6 308.536 2549.47 3797.44 299.142 5237.12 +EDGE_SE3:QUAT 386 436 4.94566 0.139181 -4.1258 0.0130854 0.180542 -0.0403233 0.982653 1 7.73381e-19 7.73381e-19 5.767e-09 5.44113e-08 7.47121e-10 1 7.73381e-19 5.767e-09 5.44113e-08 7.47121e-10 1 5.767e-09 5.44113e-08 7.47121e-10 4579.2 -22.8775 1629.66 3869.79 -32.4117 4573.38 +EDGE_SE3:QUAT 385 436 4.23536 8.1854 -4.39993 -0.0807984 -0.118929 0.164484 0.975844 1 7.70372e-19 7.70372e-19 -4.73174e-09 -6.64248e-09 5.51428e-08 1 7.70372e-19 -4.73174e-09 -6.64248e-09 5.51428e-08 1 -4.73174e-09 -6.64248e-09 5.51428e-08 4113.11 72.5366 -764.069 3980.63 -84.5532 4031.01 +EDGE_SE3:QUAT 386 435 4.46274 -8.08367 -3.83615 -0.0309618 0.0616802 -0.170355 0.982963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.94 -18.154 412.401 3992.64 -36.0329 3925.69 +EDGE_SE3:QUAT 387 437 5.01953 0.0653131 -4.06611 -0.00425061 -0.0230109 -0.0463959 0.998649 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.58 -0.201421 -186.206 3997.85 4.30261 4000.04 +EDGE_SE3:QUAT 386 437 4.13265 8.28094 -4.26984 0.0167735 0.0819671 0.0545524 0.995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4103.71 14.6311 656.033 3975.12 21.7084 4092.93 +EDGE_SE3:QUAT 387 436 4.48473 -8.35239 -3.86035 -0.0318226 0.221801 -0.0240495 0.974276 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4898.48 -87.3935 2103.5 3811.49 -86.465 4900.21 +EDGE_SE3:QUAT 388 438 4.57606 -0.0232072 -4.24614 -0.0631688 -0.00517299 -0.00171326 0.997988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.49 1.35061 -42.4358 3999.89 -0.00561109 4000.44 +EDGE_SE3:QUAT 387 438 4.44147 8.45101 -4.12696 0.0596348 -0.236281 0.0431147 0.968894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5080.94 -36.077 -2362.22 3772.99 26.04 5087.73 +EDGE_SE3:QUAT 388 437 4.2096 -8.83702 -4.16122 -0.0320349 0.168807 -0.180463 0.968458 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4385.03 -145.538 1309.05 3938.76 -168.394 4258.86 +EDGE_SE3:QUAT 389 439 4.64888 -0.154083 -4.17279 -0.157052 -0.0615437 -0.0193654 0.985481 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.21 40.9255 -517.52 3984.95 -10.3047 4064.37 +EDGE_SE3:QUAT 388 439 4.55225 8.71442 -4.35572 -0.0245804 0.11319 0.108351 0.987342 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4218.59 23.1458 965.841 3948.8 51.6411 4174.04 +EDGE_SE3:QUAT 389 438 3.70471 -8.18782 -4.04021 -0.11623 -0.0893386 -0.0855226 0.985492 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4116.29 34.5679 -843.203 3957.49 12.1746 4141.07 +EDGE_SE3:QUAT 390 440 4.72245 0.104471 -3.88502 -0.0476606 0.0232691 0.00704458 0.998568 1 4.81482e-20 4.81482e-20 1.38735e-08 6.67299e-11 3.31117e-10 1 4.81482e-20 1.38735e-08 6.67299e-11 3.31117e-10 1 1.38735e-08 6.67299e-11 3.31117e-10 3999.91 -4.48426 189.907 3997.75 0.0373504 4008.8 +EDGE_SE3:QUAT 389 440 4.36826 8.48032 -4.34998 0.16579 0.00226415 -0.0623012 0.984189 1 7.70372e-19 7.70372e-19 -5.46648e-08 3.22931e-09 -1.2472e-09 1 7.70372e-19 -5.46648e-08 3.22931e-09 -1.2472e-09 1 -5.46648e-08 3.22931e-09 -1.2472e-09 3894.5 14.6237 138.785 3998.06 -4.81983 3988.92 +EDGE_SE3:QUAT 390 439 4.22909 -8.62209 -4.17909 0.137725 -0.111948 0.00178737 0.984122 1 3.00927e-21 3.00927e-21 -3.84351e-10 5.00887e-10 3.49924e-09 1 3.00927e-21 -3.84351e-10 5.00887e-10 3.49924e-09 1 -3.84351e-10 5.00887e-10 3.49924e-09 4121.52 -69.8955 -910.394 3957.55 41.7399 4197.38 +EDGE_SE3:QUAT 391 441 4.95608 -0.093148 -3.69065 0.0276114 0.214607 -0.10681 0.97045 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4857.43 -108.793 2045.1 3824.12 -126.435 4814.85 +EDGE_SE3:QUAT 390 441 4.06126 8.27805 -3.97594 0.13773 0.0590305 0.0749028 0.985868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3951.18 24.1118 334.099 3996.02 18.0039 4004.62 +EDGE_SE3:QUAT 391 440 3.9969 -8.43389 -3.96176 0.0432237 -0.0572005 0.0386485 0.996678 1 4.81482e-20 4.81482e-20 -1.39304e-08 -4.72463e-10 8.41081e-10 1 4.81482e-20 -1.39304e-08 -4.72463e-10 8.41081e-10 1 -1.39304e-08 -4.72463e-10 8.41081e-10 4049.65 -7.62708 -481.42 3985.66 -6.08378 4051.14 +EDGE_SE3:QUAT 392 442 4.86736 -0.389104 -3.88102 -0.0646793 0.0400177 0.0187455 0.996927 1 1.92593e-19 1.92593e-19 -2.77667e-08 -3.75235e-10 -1.1721e-09 1 1.92593e-19 -2.77667e-08 -3.75235e-10 -1.1721e-09 1 -2.77667e-08 -3.75235e-10 -1.1721e-09 4011.05 -10.3721 334.556 3993.03 0.564291 4026.38 +EDGE_SE3:QUAT 391 442 4.24869 8.3894 -4.78659 -0.0512753 0.045339 -0.0427924 0.996737 1 4.81482e-20 4.81482e-20 -1.3881e-08 6.59936e-10 -5.64478e-10 1 4.81482e-20 -1.3881e-08 6.59936e-10 -5.64478e-10 1 -1.3881e-08 6.59936e-10 -5.64478e-10 4017.47 -10.4147 335.929 3993.59 -9.37498 4020.66 +EDGE_SE3:QUAT 392 441 3.907 -8.134 -3.81186 -0.0514183 -0.164988 -0.304566 0.936683 1 7.72065e-19 7.72065e-19 1.43558e-08 5.2828e-08 -2.63225e-09 1 7.72065e-19 1.43558e-08 5.2828e-08 -2.63225e-09 1 1.43558e-08 5.2828e-08 -2.63225e-09 4461.41 -191.022 -1454.41 3943.38 253.3 4100.94 +EDGE_SE3:QUAT 393 443 4.92167 0.0275073 -4.28957 -0.0697703 -0.0334797 0.035114 0.996383 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.46 8.75623 -236.741 3996.93 -5.5697 4009 +EDGE_SE3:QUAT 392 443 4.10615 8.35057 -4.50912 0.204132 0.0324371 0.129064 0.969856 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3831.53 -18.4571 -66.9068 3998 -11.7329 3931.58 +EDGE_SE3:QUAT 393 442 4.34574 -8.37014 -3.94261 -0.0269085 0.0727752 -0.23295 0.969389 1 4.81482e-20 4.81482e-20 -1.3547e-08 3.33597e-09 -7.31623e-10 1 4.81482e-20 -1.3547e-08 3.33597e-09 -7.31623e-10 1 -1.3547e-08 3.33597e-09 -7.31623e-10 4050.03 -27.7037 466.369 3993.11 -54.4215 3835.87 +EDGE_SE3:QUAT 394 444 4.46452 0.173975 -4.22187 -0.0716011 -0.0902108 0.112754 0.986925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4071.92 39.748 -616.732 3982.71 -46.1635 4041.57 +EDGE_SE3:QUAT 393 444 4.36094 8.32629 -3.99556 -0.0822367 -0.0470156 -0.0908049 0.991353 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4025.55 13.9838 -462.308 3985.9 16.7733 4019.61 +EDGE_SE3:QUAT 394 443 3.84657 -8.80307 -3.80706 0.0472327 -0.0458828 -0.0501263 0.99657 1 4.81482e-20 4.81482e-20 -1.38793e-08 7.58184e-10 5.66803e-10 1 4.81482e-20 -1.38793e-08 7.58184e-10 5.66803e-10 1 -1.38793e-08 7.58184e-10 5.66803e-10 4019.41 -10.1338 -338.048 3993.55 10.4887 4018.29 +EDGE_SE3:QUAT 395 445 4.30713 0.131435 -4.30392 -0.00457183 0.112259 -0.176082 0.977943 1 2.0463e-19 2.0463e-19 1.1982e-08 2.58262e-08 1.95644e-09 1 2.0463e-19 1.1982e-08 2.58262e-08 1.95644e-09 1 1.1982e-08 2.58262e-08 1.95644e-09 4184.79 -54.4674 880.177 3964.21 -87.3442 4060.86 +EDGE_SE3:QUAT 394 445 4.50993 8.61542 -4.32177 -0.113757 0.0745245 0.15348 0.978749 1 7.70372e-19 7.70372e-19 -5.87836e-09 4.93571e-09 -5.53943e-08 1 7.70372e-19 -5.87836e-09 4.93571e-09 -5.53943e-08 1 -5.87836e-09 4.93571e-09 -5.53943e-08 4101.08 -19.7337 798.106 3960.11 46.6002 4058.62 +EDGE_SE3:QUAT 395 444 4.00414 -8.33639 -4.17147 -0.0383539 -0.0517387 -0.0676827 0.995626 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4043.26 4.10027 -446.164 3987.55 13.0983 4030.82 +EDGE_SE3:QUAT 396 446 4.47705 -0.0390359 -4.03187 0.025031 -0.0308767 -0.00820386 0.999176 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.45 -3.27176 -245.086 3996.31 1.57724 4014.69 +EDGE_SE3:QUAT 395 446 4.26988 8.48539 -4.38624 -0.0918789 0.0539564 0.109891 0.988216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4039.66 -16.5803 547.778 3980.33 23.8907 4025.12 +EDGE_SE3:QUAT 396 445 3.86381 -8.72888 -4.23564 -0.0612308 -0.0323723 -0.135035 0.988417 1 4.81482e-20 4.81482e-20 -1.81144e-09 -1.37254e-08 -7.0111e-10 1 4.81482e-20 -1.81144e-09 -1.37254e-08 -7.0111e-10 1 -1.81144e-09 -1.37254e-08 -7.0111e-10 4015.39 6.26639 -350.95 3991.53 23.5947 3957.45 +EDGE_SE3:QUAT 397 447 5.02894 -0.0729954 -4.04373 -0.016806 -0.149625 -0.104073 0.983107 1 7.52316e-22 7.52316e-22 -1.78647e-09 1.8857e-10 2.7226e-10 1 7.52316e-22 -1.78647e-09 1.8857e-10 2.7226e-10 1 -1.78647e-09 1.8857e-10 2.7226e-10 4383.79 -49.4475 -1299.19 3914.48 73.9208 4341.6 +EDGE_SE3:QUAT 396 447 4.13788 8.53042 -4.38189 -0.065119 -0.213317 0.0103296 0.974756 1 1.92593e-19 1.92593e-19 2.97047e-08 1.25084e-09 -6.39241e-09 1 1.92593e-19 2.97047e-08 1.25084e-09 -6.39241e-09 1 2.97047e-08 1.25084e-09 -6.39241e-09 4800.42 110.349 -1984.38 3830.51 -103.157 4816.95 +EDGE_SE3:QUAT 397 446 4.33513 -8.32685 -4.17159 0.0469157 -0.0431288 -0.0144197 0.997863 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.5 -8.62193 -337.712 3993.17 4.48506 4027.48 +EDGE_SE3:QUAT 398 448 4.81723 0.075897 -4.14606 0.156513 0.0428346 0.0639207 0.984674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3912.48 14.5117 210.325 3998.83 8.75985 3994.12 +EDGE_SE3:QUAT 397 448 4.10835 8.04632 -3.79156 -0.0659741 -0.155004 0.122431 0.978076 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4302.8 112.077 -1177.83 3942.88 -121.414 4260.26 +EDGE_SE3:QUAT 398 447 3.78329 -8.79833 -3.84863 -0.172101 0.133616 0.0564381 0.974342 1 7.70372e-19 7.70372e-19 -5.64293e-08 -4.98911e-10 -8.37185e-09 1 7.70372e-19 -5.64293e-08 -4.98911e-10 -8.37185e-09 1 -5.64293e-08 -4.98911e-10 -8.37185e-09 4224.69 -99.4426 1220.85 3925.17 -48.5637 4330.43 +EDGE_SE3:QUAT 399 449 4.71256 -0.0460011 -3.78707 -0.0138748 -0.0718004 0.23274 0.969786 1 7.70372e-19 7.70372e-19 3.22041e-09 2.53061e-09 -5.42616e-08 1 7.70372e-19 3.22041e-09 2.53061e-09 -5.42616e-08 1 3.22041e-09 2.53061e-09 -5.42616e-08 4059.48 27.0458 -496.439 3990.94 -58.557 3843.58 +EDGE_SE3:QUAT 398 449 4.44157 8.78729 -4.51388 0.0560629 0.0486129 0.23171 0.969951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.84 9.41696 205.884 3999.89 18.1025 3794.66 +EDGE_SE3:QUAT 399 448 3.8593 -8.27921 -4.239 -0.00112359 0.0923623 -0.163653 0.982184 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4127.78 -33.4166 726.559 3973.68 -64.049 4020.65 +EDGE_SE3:QUAT 400 450 4.70657 -0.091783 -4.20413 0.0343673 0.0452951 0.167162 0.984289 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4014.5 10.0431 279.839 3996.85 22.5612 3907.45 +EDGE_SE3:QUAT 399 450 4.35716 8.47336 -4.36455 -0.130534 -0.0724966 -0.0164185 0.988653 1 7.70372e-19 7.70372e-19 5.54968e-08 1.61891e-10 -4.16886e-09 1 7.70372e-19 5.54968e-08 1.61891e-10 -4.16886e-09 1 5.54968e-08 1.61891e-10 -4.16886e-09 4020.52 39.5957 -602.134 3979.43 -12.2911 4087.6 +EDGE_SE3:QUAT 400 449 3.87132 -8.68788 -3.81299 -0.0257145 0.234295 -0.0178143 0.971662 1 4.81482e-20 4.81482e-20 -1.51313e-08 5.15899e-10 -3.62409e-09 1 4.81482e-20 -1.51313e-08 5.15899e-10 -3.62409e-09 1 -1.51313e-08 5.15899e-10 -3.62409e-09 5032.4 -77.981 2282.87 3786.18 -77.1984 5033.77 +EDGE_SE3:QUAT 401 451 4.77066 -0.020858 -3.93012 0.0228551 -0.0047852 0.00618943 0.999708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.31 -0.459352 -39.9499 3999.9 -0.111953 4000.25 +EDGE_SE3:QUAT 400 451 4.22072 8.38953 -4.23522 0.0866966 -0.0713053 0.0573817 0.992021 1 1.92593e-19 1.92593e-19 -2.78735e-08 -1.25712e-09 2.24156e-09 1 1.92593e-19 -2.78735e-08 -1.25712e-09 2.24156e-09 1 -2.78735e-08 -1.25712e-09 2.24156e-09 4068.18 -21.6195 -634.699 3975.28 -7.27789 4085.08 +EDGE_SE3:QUAT 401 450 4.33864 -8.67307 -4.35053 0.024914 0.0454029 -0.0474164 0.997532 1 4.81482e-20 4.81482e-20 -6.62307e-10 -2.87071e-10 -1.39051e-08 1 4.81482e-20 -6.62307e-10 -2.87071e-10 -1.39051e-08 1 -6.62307e-10 -2.87071e-10 -1.39051e-08 4033.07 2.37372 378.813 3991.05 -7.96844 4026.56 +EDGE_SE3:QUAT 402 452 4.77568 -0.00355023 -4.25845 0.0103992 -0.175266 -0.0588222 0.982707 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4527.05 -60.3333 -1545.39 3883.86 69.0539 4513.64 +EDGE_SE3:QUAT 401 452 4.14628 8.68178 -4.15808 -0.137262 0.0215228 -0.0329914 0.989751 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3927.74 -6.64743 113.462 3999.55 -2.37804 3998.75 +EDGE_SE3:QUAT 402 451 4.21396 -8.41045 -4.12599 0.133996 0.00243113 -0.0988869 0.986033 1 7.70372e-19 7.70372e-19 -5.47852e-08 5.2617e-09 -1.57957e-09 1 7.70372e-19 -5.47852e-08 5.2617e-09 -1.57957e-09 1 -5.47852e-08 5.2617e-09 -1.57957e-09 3935.21 14.5473 175.032 3996.87 -10.2819 3967.92 +EDGE_SE3:QUAT 403 453 4.7126 0.517036 -4.29539 -0.0674743 -0.0939478 -0.102396 0.987996 1 4.81482e-20 4.81482e-20 1.40085e-08 -1.2854e-09 -1.49031e-09 1 4.81482e-20 1.40085e-08 -1.2854e-09 -1.49031e-09 1 1.40085e-08 -1.2854e-09 -1.49031e-09 4154.76 6.16988 -849.765 3957.45 31.9154 4131.03 +EDGE_SE3:QUAT 402 453 3.88057 8.68589 -4.44665 0.208157 -0.0534072 -0.0294088 0.976193 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3853.18 -32.8796 -329.239 3996.26 14.2556 4023.04 +EDGE_SE3:QUAT 403 452 4.06952 -8.5301 -3.92726 0.242165 -0.14955 0.02777 0.958238 1 1.54375e-18 1.54375e-18 -5.36321e-08 5.67813e-08 -1.70777e-09 1 1.54375e-18 -5.36321e-08 5.67813e-08 -1.70777e-09 1 -5.36321e-08 5.67813e-08 -1.70777e-09 4130.77 -173.69 -1263.71 3940.97 122.813 4362.26 +EDGE_SE3:QUAT 404 454 4.24327 0.187492 -4.44057 -0.0537938 0.00991991 0.101658 0.993314 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.43 -3.79368 143.023 3998.36 8.03463 3963.67 +EDGE_SE3:QUAT 403 454 4.13104 8.71297 -3.8026 0.228875 0.132609 0.0075425 0.964352 1 7.70372e-19 7.70372e-19 5.51883e-08 3.87076e-09 6.56333e-09 1 7.70372e-19 5.51883e-08 3.87076e-09 6.56333e-09 1 5.51883e-08 3.87076e-09 6.56333e-09 4027.73 134.217 1004.74 3964.35 95.3743 4237.04 +EDGE_SE3:QUAT 404 453 4.26638 -8.26486 -4.08208 0.200751 -0.0462444 0.0352606 0.977915 1 4.81482e-20 4.81482e-20 1.99009e-10 -1.35787e-08 2.74988e-09 1 4.81482e-20 1.99009e-10 -1.35787e-08 2.74988e-09 1 1.99009e-10 -1.35787e-08 2.74988e-09 3885.45 -44.5424 -434.659 3989.04 5.31095 4041.68 +EDGE_SE3:QUAT 405 455 4.77337 -0.104395 -4.30621 0.159054 0.137685 -0.0998432 0.97251 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4312.64 74.7297 1351.83 3904.67 13.3859 4373.95 +EDGE_SE3:QUAT 404 455 4.10726 8.65096 -4.35258 -0.0564656 -0.0223211 0.124811 0.990321 1 7.70372e-19 7.70372e-19 -4.16853e-10 -3.34615e-09 5.49864e-08 1 7.70372e-19 -4.16853e-10 -3.34615e-09 5.49864e-08 1 -4.16853e-10 -3.34615e-09 5.49864e-08 3989.04 2.26564 -90.0108 3999.85 -4.02012 3939.48 +EDGE_SE3:QUAT 405 454 3.94897 -8.209 -4.0152 -0.130673 0.0774274 -0.118371 0.981284 1 4.81482e-20 4.81482e-20 -1.87599e-09 -1.35879e-08 -2.02716e-09 1 4.81482e-20 -1.87599e-09 -1.35879e-08 -2.02716e-09 1 -1.87599e-09 -1.35879e-08 -2.02716e-09 3971.75 -32.5571 409.946 3995.42 -31.3501 3984.01 +EDGE_SE3:QUAT 406 456 4.3205 -0.288534 -4.30083 -0.0194442 -0.0455273 -0.0576701 0.997107 1 4.81482e-20 4.81482e-20 7.78606e-10 1.38389e-08 1.96235e-10 1 4.81482e-20 7.78606e-10 1.38389e-08 1.96235e-10 1 7.78606e-10 1.38389e-08 1.96235e-10 4034.01 0.752988 -378.613 3991.11 10.2476 4022.22 +EDGE_SE3:QUAT 405 456 4.3233 8.50875 -4.48601 0.203923 0.0701241 0.147376 0.965287 1 7.70372e-19 7.70372e-19 -1.41573e-10 -1.20038e-08 -5.35948e-08 1 7.70372e-19 -1.41573e-10 -1.20038e-08 -5.35948e-08 1 -1.41573e-10 -1.20038e-08 -5.35948e-08 3835.14 5.78697 160.451 4001.64 6.40121 3914.6 +EDGE_SE3:QUAT 406 455 3.86748 -8.70234 -4.22247 -0.0304916 0.192143 -0.0459751 0.979815 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4634.61 -84.1588 1720.75 3863.37 -86.6332 4629.88 +EDGE_SE3:QUAT 407 457 4.78677 -0.0368613 -4.05966 0.0304087 0.038195 0.148797 0.987662 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.76 7.09548 242.14 3997.42 17.3724 3925.9 +EDGE_SE3:QUAT 406 457 3.97925 8.54276 -4.19574 0.163427 0.00506588 -0.0108708 0.986483 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3894.05 5.41592 59.8589 3999.74 -0.16918 4000.41 +EDGE_SE3:QUAT 407 456 3.81081 -8.43695 -4.17299 -0.0660885 -0.0811297 -0.22635 0.968409 1 7.70372e-19 7.70372e-19 -5.75312e-09 -1.36615e-09 5.48336e-08 1 7.70372e-19 -5.75312e-09 -1.36615e-09 5.48336e-08 1 -5.75312e-09 -1.36615e-09 5.48336e-08 4135.72 -20.4531 -797.927 3965.51 88.5242 3948.26 +EDGE_SE3:QUAT 408 458 4.73171 0.138564 -4.4196 0.103532 0.0550665 0.0775255 0.99007 1 1.92593e-19 1.92593e-19 2.75763e-08 2.44007e-09 1.03582e-09 1 1.92593e-19 2.75763e-08 2.44007e-09 1.03582e-09 1 2.75763e-08 2.44007e-09 1.03582e-09 3984.71 19.6962 335.569 3995.18 16.962 4003.54 +EDGE_SE3:QUAT 407 458 4.12057 8.40702 -4.35169 0.0439539 0.089422 0.0897386 0.990969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4102.11 31.1875 672.288 3976.27 39.315 4077.62 +EDGE_SE3:QUAT 408 457 4.24951 -8.86924 -4.30803 -0.0372728 -0.164527 -0.03444 0.985066 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4474.31 9.42497 -1466.2 3889.83 4.58848 4475.12 +EDGE_SE3:QUAT 409 459 4.4392 0.0492354 -4.18353 0.0177034 -0.0153047 0.0341724 0.999142 1 1.20371e-20 1.20371e-20 -6.93657e-09 -2.33449e-10 1.14337e-10 1 1.20371e-20 -6.93657e-09 -2.33449e-10 1.14337e-10 1 -6.93657e-09 -2.33449e-10 1.14337e-10 4002.94 -0.960367 -129.542 3998.92 -2.15025 3999.52 +EDGE_SE3:QUAT 408 459 4.14936 8.67664 -4.57552 0.0187936 -0.0392797 0.115143 0.992394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4026.56 1.48376 -335.725 3993.12 -19.2692 3974.95 +EDGE_SE3:QUAT 409 458 4.15687 -8.72288 -3.87627 -0.0712856 0.00665786 -0.0502186 0.996169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.65 0.157514 9.91357 4000 0.106136 3989.88 +EDGE_SE3:QUAT 410 460 4.31895 -0.0280538 -4.22609 0.0351921 0.028044 -0.0212938 0.99876 1 6.01853e-20 6.01853e-20 1.40181e-08 6.66226e-09 1.73301e-10 1 6.01853e-20 1.40181e-08 6.66226e-09 1.73301e-10 1 1.40181e-08 6.66226e-09 1.73301e-10 4008.63 3.76542 233.477 3996.55 -1.83014 4011.77 +EDGE_SE3:QUAT 409 460 4.04514 8.146 -4.29498 0.0652363 0.146429 0.0418491 0.98618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4319.7 70.1299 1208.59 3926.7 65.5996 4329.72 +EDGE_SE3:QUAT 410 459 3.97976 -8.73081 -4.13596 -0.0671587 0.0463861 -0.0802091 0.993431 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.47 -12.5722 301.969 3995.56 -13.9286 3996.77 +EDGE_SE3:QUAT 411 461 4.9492 0.0808609 -4.26648 -0.0239549 -0.0734676 -0.0511838 0.995695 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4089.19 0.761824 -611.811 3977.44 13.3801 4081 +EDGE_SE3:QUAT 410 461 4.15155 8.38792 -4.32103 0.0293447 0.113281 0.0528992 0.99172 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4198.31 31.8124 920.769 3953.45 36.5984 4190.56 +EDGE_SE3:QUAT 411 460 4.04203 -8.69021 -4.16993 -0.0047682 -0.00903575 -0.122319 0.992438 1 1.92593e-19 1.92593e-19 2.75468e-10 6.75194e-11 -2.7551e-08 1 1.92593e-19 2.75468e-10 6.75194e-11 -2.7551e-08 1 2.75468e-10 6.75194e-11 -2.7551e-08 4001.41 -0.0805603 -77.6235 3999.63 4.85057 3941.66 +EDGE_SE3:QUAT 412 462 5.09902 -0.0963145 -4.15702 0.0217819 0.14701 -0.0430784 0.987956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4372.88 -7.94878 1280.47 3912.61 -21.3513 4367.36 +EDGE_SE3:QUAT 411 462 4.19073 8.53102 -4.51046 -0.036015 -0.0166688 0.147925 0.988202 1 4.81482e-20 4.81482e-20 -1.37157e-08 -2.06504e-09 7.43861e-11 1 4.81482e-20 -1.37157e-08 -2.06504e-09 7.43861e-11 1 -1.37157e-08 -2.06504e-09 7.43861e-11 3995.76 1.13553 -65.7788 3999.93 -3.26761 3913.42 +EDGE_SE3:QUAT 412 461 4.05892 -8.41825 -3.52317 -0.000252794 -0.173416 -0.0396154 0.984052 1 4.89006e-20 4.89006e-20 4.36783e-09 -2.86037e-10 -1.48465e-08 1 4.89006e-20 4.36783e-09 -2.86037e-10 -1.48465e-08 1 4.36783e-09 -2.86037e-10 -1.48465e-08 4525.61 -32.8722 -1542.31 3881.54 40.2352 4519.34 +EDGE_SE3:QUAT 413 463 4.81881 -0.174099 -4.03338 -0.144274 -0.00282434 -0.173134 0.97427 1 7.70372e-19 7.70372e-19 -5.4241e-08 9.19495e-09 2.85146e-09 1 7.70372e-19 -5.4241e-08 9.19495e-09 2.85146e-09 1 -5.4241e-08 9.19495e-09 2.85146e-09 3939.01 25.765 -312.307 3990.04 32.4103 3902.37 +EDGE_SE3:QUAT 412 463 4.07148 8.5519 -4.31794 -0.0424462 -0.0191186 0.0229862 0.998651 1 4.81482e-20 4.81482e-20 1.38677e-08 3.4079e-10 -2.37161e-10 1 4.81482e-20 1.38677e-08 3.4079e-10 -2.37161e-10 1 1.38677e-08 3.4079e-10 -2.37161e-10 3997.74 3.0912 -140.866 3998.85 -1.90603 4002.84 +EDGE_SE3:QUAT 413 462 3.8303 -8.57452 -4.16803 -0.00236213 0.0661858 -0.0730128 0.99513 1 7.52316e-22 7.52316e-22 -1.74125e-09 1.2943e-10 -1.13954e-10 1 7.52316e-22 -1.74125e-09 1.2943e-10 -1.13954e-10 1 -1.74125e-09 1.2943e-10 -1.13954e-10 4069.28 -8.36729 531.066 3983.43 -20.4479 4047.98 +EDGE_SE3:QUAT 414 464 4.28915 0.482104 -4.2299 -0.0984614 0.0467726 -0.0943902 0.989549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.82 -13.4916 253.954 3997.66 -13.1708 3979.96 +EDGE_SE3:QUAT 413 464 4.53624 8.74583 -4.05996 0.0806769 -0.070652 -0.170605 0.979486 1 2.40741e-19 2.40741e-19 -2.47972e-08 1.86136e-08 -3.24242e-10 1 2.40741e-19 -2.47972e-08 1.86136e-08 -3.24242e-10 1 -2.47972e-08 1.86136e-08 -3.24242e-10 4007.49 -24.2914 -374.81 3996.29 32.8171 3917.1 +EDGE_SE3:QUAT 414 463 3.89782 -8.65403 -3.94181 -0.0443204 -0.023861 -0.0942961 0.994271 1 1.92593e-19 1.92593e-19 -8.8055e-10 -1.08746e-09 2.76457e-08 1 1.92593e-19 -8.8055e-10 -1.08746e-09 2.76457e-08 1 -8.8055e-10 -1.08746e-09 2.76457e-08 4006.25 3.82903 -238.406 3996.11 11.2026 3978.54 +EDGE_SE3:QUAT 415 465 4.82451 -0.280593 -4.29797 -0.168052 0.118077 0.135461 0.969261 1 1.92593e-19 1.92593e-19 4.4397e-09 -3.92845e-09 2.81208e-08 1 1.92593e-19 4.4397e-09 -3.92845e-09 2.81208e-08 1 4.4397e-09 -3.92845e-09 2.81208e-08 4242.82 -61.0715 1245.91 3914.21 18.6238 4282.39 +EDGE_SE3:QUAT 414 465 4.14583 8.49827 -4.44998 -0.0378592 0.0349682 0.0173089 0.998521 1 4.81482e-20 4.81482e-20 -1.38931e-08 -2.03862e-10 -5.0312e-10 1 4.81482e-20 -1.38931e-08 -2.03862e-10 -5.0312e-10 1 -1.38931e-08 -2.03862e-10 -5.0312e-10 4014.92 -5.04085 288.196 3994.8 1.38409 4019.46 +EDGE_SE3:QUAT 415 464 3.78491 -8.72696 -4.23713 0.123758 0.0291048 -0.0121082 0.991812 1 1.92593e-19 1.92593e-19 2.7581e-08 -1.27936e-10 8.67171e-10 1 1.92593e-19 2.7581e-08 -1.27936e-10 8.67171e-10 1 2.7581e-08 -1.27936e-10 8.67171e-10 3953.82 15.3638 246.104 3996.34 1.23411 4014.5 +EDGE_SE3:QUAT 416 466 4.74706 0.160751 -4.09392 -0.0131418 0.0237923 -0.0124956 0.999552 1 3.00927e-21 3.00927e-21 -3.47174e-09 4.56083e-11 -8.14412e-11 1 3.00927e-21 -3.47174e-09 4.56083e-11 -8.14412e-11 1 -3.47174e-09 4.56083e-11 -8.14412e-11 4008.19 -1.40965 188.637 3997.8 -1.35723 4008.25 +EDGE_SE3:QUAT 415 466 4.09597 8.98148 -4.35946 -0.00801037 0.0317918 0.126052 0.991482 1 4.81482e-20 4.81482e-20 -1.74579e-09 1.376e-08 -2.65329e-12 1 4.81482e-20 -1.74579e-09 1.376e-08 -2.65329e-12 1 -1.74579e-09 1.376e-08 -2.65329e-12 4016.73 2.14609 261.255 3995.97 16.5704 3953.43 +EDGE_SE3:QUAT 416 465 4.09932 -8.78165 -3.99963 -0.193207 -0.185168 -0.0932049 0.959008 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4585.37 152.698 -1865.12 3850.8 -99.8939 4699.94 +EDGE_SE3:QUAT 417 467 4.92998 -0.0226689 -4.43457 0.00824301 -0.0652434 0.0349015 0.997225 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4069.38 1.37305 -532.41 3982.84 -8.85835 4064.78 +EDGE_SE3:QUAT 416 467 4.02043 8.58665 -4.50034 -0.00814643 -0.0319373 0.151895 0.987847 1 3.00927e-21 3.00927e-21 -3.43318e-09 -5.30656e-10 9.73268e-11 1 3.00927e-21 -3.43318e-09 -5.30656e-10 9.73268e-11 1 -3.43318e-09 -5.30656e-10 9.73268e-11 4013.2 4.17958 -232.692 3997.21 -17.4161 3921.17 +EDGE_SE3:QUAT 417 466 3.7732 -8.57126 -4.0748 0.0604148 0.141101 -0.142385 0.977838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4368.01 -35.0236 1294.96 3913.83 -79.6837 4301.51 +EDGE_SE3:QUAT 418 468 4.69216 0.311833 -4.00182 -0.161955 -0.0837742 -0.0318317 0.98272 1 1.92593e-19 1.92593e-19 9.85372e-11 2.72901e-08 4.40858e-09 1 1.92593e-19 9.85372e-11 2.72901e-08 4.40858e-09 1 9.85372e-11 2.72901e-08 4.40858e-09 4022.21 58.2491 -724.354 3971.11 -18.4152 4123.08 +EDGE_SE3:QUAT 417 468 4.06773 8.81567 -4.5169 0.0987436 0.0548184 -0.0157914 0.993476 1 1.95602e-19 1.95602e-19 2.75539e-08 -4.73626e-10 -1.88118e-09 1 1.95602e-19 2.75539e-08 -4.73626e-10 -1.88118e-09 1 2.75539e-08 -4.73626e-10 -1.88118e-09 4012.27 22.233 455.763 3987.56 3.83489 4050.27 +EDGE_SE3:QUAT 418 467 3.83205 -8.78908 -4.15522 0.106547 0.11318 -0.047334 0.986711 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4189.61 44.8001 997.689 3944.28 10.5852 4226.06 +EDGE_SE3:QUAT 419 469 4.46825 -0.206321 -4.35922 -0.0761111 -0.0474497 0.125917 0.987978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.42 11.9923 -254.269 3997.78 -15.864 3952.17 +EDGE_SE3:QUAT 418 469 4.31355 8.77408 -4.23739 -0.0780826 0.188975 -0.079341 0.975652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4514.83 -153.465 1565.36 3899.79 -153.65 4514.04 +EDGE_SE3:QUAT 419 468 3.63676 -8.56475 -3.83972 -0.0472318 0.031994 -0.103609 0.992981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.24 -5.7649 193.016 3998.33 -9.73897 3966.23 +EDGE_SE3:QUAT 420 470 4.53378 0.305202 -4.19455 -0.0510324 -0.0205766 0.0857929 0.994792 1 1.92593e-19 1.92593e-19 -3.17806e-10 -1.49462e-09 2.76213e-08 1 1.92593e-19 -3.17806e-10 -1.49462e-09 2.76213e-08 1 -3.17806e-10 -1.49462e-09 2.76213e-08 3992.52 2.82718 -109.991 3999.52 -4.23075 3973.49 +EDGE_SE3:QUAT 419 470 4.09087 8.65052 -4.35977 0.280011 0.0826184 0.207153 0.933732 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3672.98 -52.9593 -98.7094 3991.96 -39.3987 3814.95 +EDGE_SE3:QUAT 420 469 3.72054 -8.60676 -4.27753 -0.0600678 0.05674 -0.0404908 0.995757 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.21 -15.6695 425.108 3989.8 -12.8549 4038.09 +EDGE_SE3:QUAT 421 471 4.90549 -0.298608 -4.38057 -0.0852058 0.0736443 0.0333308 0.993079 1 1.92593e-19 1.92593e-19 -2.7897e-08 -5.79136e-10 -2.19488e-09 1 1.92593e-19 -2.7897e-08 -5.79136e-10 -2.19488e-09 1 -2.7897e-08 -5.79136e-10 -2.19488e-09 4067.58 -24.0122 629.166 3976.23 -1.01479 4092.17 +EDGE_SE3:QUAT 420 471 4.19102 8.87148 -3.9256 0.233951 0.189098 0.002543 0.953678 1 7.70372e-19 7.70372e-19 5.6463e-08 5.52359e-09 9.80068e-09 1 7.70372e-19 5.6463e-08 5.52359e-09 9.80068e-09 1 5.6463e-08 5.52359e-09 9.80068e-09 4297.52 242.799 1530.13 3934.15 212.087 4516.43 +EDGE_SE3:QUAT 421 470 3.57347 -8.52928 -4.50432 -0.0177644 -0.146029 -0.0192988 0.988932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4365.15 2.78772 -1264.88 3914.23 4.85845 4364.93 +EDGE_SE3:QUAT 422 472 4.56398 -0.0958511 -4.19814 0.00995415 -0.0833046 -0.356653 0.930462 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.31 -44.3267 -508.976 4000.02 86.6199 3552.9 +EDGE_SE3:QUAT 421 472 3.94053 8.48652 -4.14825 0.00894734 0.073499 -0.0076665 0.997226 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4087.75 1.81619 600.035 3978.33 -1.23901 4087.84 +EDGE_SE3:QUAT 422 471 3.61565 -8.81979 -4.43734 0.07874 0.0046329 -0.175474 0.981319 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.28 8.19095 197.214 3996.24 -21.3563 3885.91 +EDGE_SE3:QUAT 423 473 4.60639 -0.162147 -4.28374 0.0715113 -0.107888 -0.0471111 0.990468 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4149.49 -45.67 -842.077 3962.53 40.969 4161.06 +EDGE_SE3:QUAT 422 473 4.19594 8.69677 -4.1318 0.21594 -0.0254875 -0.037879 0.975339 1 7.82409e-19 7.82409e-19 5.38422e-08 -9.27101e-09 1.11629e-09 1 7.82409e-19 5.38422e-08 -9.27101e-09 1.11629e-09 1 5.38422e-08 -9.27101e-09 1.11629e-09 3815.32 -6.33345 -94.2837 4000.02 2.21813 3996.1 +EDGE_SE3:QUAT 423 472 3.817 -9.1583 -4.19693 -0.176052 -0.0660351 -0.130087 0.97351 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.08 55.3143 -786.206 3959.94 24.7735 4080.37 +EDGE_SE3:QUAT 424 474 4.381 0.198625 -4.47442 -0.0749738 -0.125959 0.137032 0.979661 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4160.5 78.3705 -877.587 3969.35 -88.3977 4107.87 +EDGE_SE3:QUAT 423 474 3.84517 8.87573 -3.74094 0.0478966 -0.0869884 0.0275032 0.994677 1 1.20371e-20 1.20371e-20 -6.28365e-10 3.08338e-10 7.01235e-09 1 1.20371e-20 -6.28365e-10 3.08338e-10 7.01235e-09 1 -6.28365e-10 3.08338e-10 7.01235e-09 4119.45 -13.6385 -728.732 3968.5 -1.59033 4125.6 +EDGE_SE3:QUAT 424 473 4.07326 -9.08191 -4.12814 0.0176931 -0.0417988 -0.130865 0.990361 1 1.20371e-20 1.20371e-20 -6.89144e-09 9.23293e-10 2.48604e-10 1 1.20371e-20 -6.89144e-09 9.23293e-10 2.48604e-10 1 -6.89144e-09 9.23293e-10 2.48604e-10 4021 -7.25535 -299.522 3995.35 19.7508 3953.75 +EDGE_SE3:QUAT 425 475 4.25783 -0.366214 -4.40133 -0.0315603 -0.241554 0.0222034 0.96962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5102.4 103.139 -2376.91 3776.07 -102.343 5104.42 +EDGE_SE3:QUAT 424 475 3.9128 9.16105 -4.3213 -0.0369645 0.176327 0.0884418 0.979653 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4561.92 39.576 1609.81 3874.02 62.794 4536.1 +EDGE_SE3:QUAT 425 474 3.82264 -9.03959 -4.18105 -0.0133873 -0.0608159 -0.231742 0.970782 1 4.23178e-22 4.23178e-22 -1.27286e-09 3.04037e-10 7.907e-11 1 4.23178e-22 -1.27286e-09 3.04037e-10 7.907e-11 1 -1.27286e-09 3.04037e-10 7.907e-11 4058.4 -17.9315 -490.07 3988.84 57.7552 3844.3 +EDGE_SE3:QUAT 426 476 4.49111 0.0319184 -4.65637 0.0196215 0.100407 -0.0131211 0.994666 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4165.85 5.7281 835.202 3959.4 -1.05842 4166.7 +EDGE_SE3:QUAT 425 476 4.31657 8.93753 -4.43303 -0.116224 -0.0249453 -0.00546676 0.992895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3956.3 11.8926 -203.549 3997.53 -1.23825 4010.21 +EDGE_SE3:QUAT 426 475 3.71824 -8.9296 -4.30335 0.14068 -0.0688946 0.0875698 0.983765 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.3 -40.4921 -693.235 3969.9 -10.9839 4085.79 +EDGE_SE3:QUAT 427 477 4.56803 0.0578912 -4.25709 0.0234029 -0.175177 0.117557 0.977213 1 1.88079e-22 1.88079e-22 -9.04158e-10 -1.07969e-10 1.6259e-10 1 1.88079e-22 -9.04158e-10 -1.07969e-10 1.6259e-10 1 -9.04158e-10 -1.07969e-10 1.6259e-10 4541.62 77.7332 -1571.96 3884.15 -103.378 4488.53 +EDGE_SE3:QUAT 426 477 4.28954 9.21506 -4.31227 -0.0828889 -0.0620222 0.151127 0.983079 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.16 19.1618 -327.372 3996.87 -25.205 3934.29 +EDGE_SE3:QUAT 427 476 3.88774 -8.87579 -4.3931 -0.0642222 0.147599 -0.104009 0.981464 1 1.15556e-18 1.15556e-18 -2.49508e-08 6.07867e-08 -2.66138e-08 1 1.15556e-18 -2.49508e-08 6.07867e-08 -2.66138e-08 1 -2.49508e-08 6.07867e-08 -2.66138e-08 4284.94 -94.9166 1139.75 3942.2 -101.909 4258.17 +EDGE_SE3:QUAT 428 478 4.7299 0.0545949 -4.29902 0.168057 -0.0758505 0.0413558 0.981984 1 2.0463e-19 2.0463e-19 -2.05941e-10 -2.6127e-08 1.14497e-08 1 2.0463e-19 -2.05941e-10 -2.6127e-08 1.14497e-08 1 -2.05941e-10 -2.6127e-08 1.14497e-08 3999.12 -55.7371 -679 3973.88 12.5506 4105.26 +EDGE_SE3:QUAT 427 478 4.10049 8.87156 -4.5344 -0.218725 -0.0174539 0.170952 0.960536 1 1.20371e-20 1.20371e-20 -1.12457e-09 6.67574e-09 1.47003e-09 1 1.20371e-20 -1.12457e-09 6.67574e-09 1.47003e-09 1 -1.12457e-09 6.67574e-09 1.47003e-09 3826.81 -47.4298 303.098 3987.43 35.7071 3901.27 +EDGE_SE3:QUAT 428 477 3.95 -9.06717 -4.09911 0.123366 0.125183 -0.0342451 0.983838 1 7.70372e-19 7.70372e-19 -5.65116e-08 1.6713e-10 -7.44835e-09 1 7.70372e-19 -5.65116e-08 1.6713e-10 -7.44835e-09 1 -5.65116e-08 1.6713e-10 -7.44835e-09 4217.53 65.0041 1091.39 3936.56 30.7879 4273.71 +EDGE_SE3:QUAT 429 479 4.82684 -0.138222 -4.45756 -0.0747148 0.120151 -0.0617526 0.988012 1 1.92593e-19 1.92593e-19 -2.81265e-08 2.30734e-09 -3.08341e-09 1 1.92593e-19 -2.81265e-08 2.30734e-09 -3.08341e-09 1 -2.81265e-08 2.30734e-09 -3.08341e-09 4183.18 -59.1767 930.137 3956.47 -56.7146 4190.26 +EDGE_SE3:QUAT 428 479 4.18482 9.30014 -4.18288 0.0138847 0.00549353 0.104248 0.994439 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.39 0.173594 25.9796 3999.98 1.04453 3956.69 +EDGE_SE3:QUAT 429 478 3.82991 -9.13642 -4.50829 -0.0303653 0.0118859 -0.27829 0.959943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.03 0.757036 -11.9855 3999.86 6.90685 3689.94 +EDGE_SE3:QUAT 430 480 4.55699 -0.0227713 -4.5436 -0.0646853 0.00732735 0.0995645 0.992899 1 3.88195e-19 3.88195e-19 2.73601e-08 9.91721e-10 -2.72357e-08 1 3.88195e-19 2.73601e-08 9.91721e-10 -2.72357e-08 1 2.73601e-08 9.91721e-10 -2.72357e-08 3987.61 -4.64864 134.097 3998.45 7.61404 3964.69 +EDGE_SE3:QUAT 429 480 4.37354 9.10558 -4.16712 -0.0478598 0.0283588 -0.130279 0.989916 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996 -4.20105 146.52 3999.27 -8.31224 3937.27 +EDGE_SE3:QUAT 430 479 4.03408 -9.03984 -4.15153 -0.0665256 0.18403 0.0410688 0.979806 1 1.20371e-20 1.20371e-20 -1.39959e-09 4.12584e-10 -7.31115e-09 1 1.20371e-20 -1.39959e-09 4.12584e-10 -7.31115e-09 1 -1.39959e-09 4.12584e-10 -7.31115e-09 4604.72 -37.0702 1696.21 3861.17 -18.0137 4615.68 +EDGE_SE3:QUAT 431 481 4.46733 -0.179802 -4.29497 0.128237 0.0502948 0.0256672 0.990135 1 4.81482e-20 4.81482e-20 5.24008e-10 -1.37355e-08 1.82067e-09 1 4.81482e-20 5.24008e-10 -1.37355e-08 1.82067e-09 1 5.24008e-10 -1.37355e-08 1.82067e-09 3965.41 23.5288 355.144 3993.6 10.9292 4028.56 +EDGE_SE3:QUAT 430 481 4.20031 8.71925 -4.31405 -0.00695824 0.0445334 -0.012677 0.998903 1 7.52316e-22 7.52316e-22 -1.73968e-09 2.32462e-11 -7.72175e-11 1 7.52316e-22 -1.73968e-09 2.32462e-11 -7.72175e-11 1 -1.73968e-09 2.32462e-11 -7.72175e-11 4031.52 -1.8746 357.553 3992.14 -2.64368 4031.07 +EDGE_SE3:QUAT 431 480 3.90714 -8.88624 -4.36657 -0.0407614 -0.0448417 -0.0749818 0.995342 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.93 4.24743 -394.838 3990.1 13.2734 4016.09 +EDGE_SE3:QUAT 432 482 4.71586 0.0269939 -4.5347 0.113542 0.00858257 -0.0613123 0.991602 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3953.87 9.66918 149.781 3998.1 -4.69487 3990.4 +EDGE_SE3:QUAT 431 482 4.37508 8.97626 -4.42346 -0.165135 0.0124196 0.0165868 0.986053 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3894.98 -11.2621 127.676 3998.92 0.214872 4002.96 +EDGE_SE3:QUAT 432 481 3.60254 -8.65278 -3.86787 -0.146785 -0.150828 0.00608575 0.977583 1 7.70372e-19 7.70372e-19 -5.66823e-08 -2.98234e-09 8.24136e-09 1 7.70372e-19 -5.66823e-08 -2.98234e-09 8.24136e-09 1 -5.66823e-08 -2.98234e-09 8.24136e-09 4269.29 115.372 -1244.69 3929.48 -88.9368 4355.32 +EDGE_SE3:QUAT 433 483 4.38369 0.0227023 -4.43301 -0.094008 0.0564151 -0.151848 0.982304 1 1.92593e-19 1.92593e-19 -2.73206e-08 4.45953e-09 -6.82203e-10 1 1.92593e-19 -2.73206e-08 4.45953e-09 -6.82203e-10 1 -2.73206e-08 4.45953e-09 -6.82203e-10 3980.58 -14.8255 261.998 3998.61 -18.6551 3923.69 +EDGE_SE3:QUAT 432 483 4.09512 8.31471 -4.77019 0.0811422 -0.0811507 0.211 0.970726 1 1.15556e-18 1.15556e-18 -2.69978e-08 1.90368e-08 -5.31709e-08 1 1.15556e-18 -2.69978e-08 1.90368e-08 -5.31709e-08 1 -2.69978e-08 1.90368e-08 -5.31709e-08 4139.57 11.1871 -831.999 3960.51 -82.3343 3987.82 +EDGE_SE3:QUAT 433 482 4.18331 -9.30989 -4.31608 0.0700903 0.206125 -0.0769694 0.972972 1 1.92593e-19 1.92593e-19 -6.50619e-09 -1.28314e-09 -2.96853e-08 1 1.92593e-19 -6.50619e-09 -1.28314e-09 -2.96853e-08 1 -6.50619e-09 -1.28314e-09 -2.96853e-08 4806.48 1.30223 1996.77 3821.23 -20.7602 4802.43 +EDGE_SE3:QUAT 434 484 4.3804 0.157366 -4.75538 -0.101543 -0.0700546 0.0175103 0.992207 1 1.20371e-20 1.20371e-20 -4.54871e-10 -7.34535e-10 6.94644e-09 1 1.20371e-20 -4.54871e-10 -7.34535e-10 6.94644e-09 1 -4.54871e-10 -7.34535e-10 6.94644e-09 4029.87 30.0978 -538.24 3984.02 -16.1298 4069.89 +EDGE_SE3:QUAT 433 484 4.37822 9.04111 -4.48104 -0.0308673 0.174425 -0.0686278 0.981791 1 1.92593e-19 1.92593e-19 -4.94185e-09 1.695e-09 -2.89218e-08 1 1.92593e-19 -4.94185e-09 1.695e-09 -2.89218e-08 1 -4.94185e-09 1.695e-09 -2.89218e-08 4498.25 -86.0741 1503.56 3893.06 -92.7128 4483.22 +EDGE_SE3:QUAT 434 483 4.05852 -9.17397 -4.15554 0.000662063 -0.0829237 -0.0601353 0.99474 1 1.95602e-19 1.95602e-19 1.80357e-09 -2.78228e-08 8.42424e-12 1 1.95602e-19 1.80357e-09 -2.78228e-08 8.42424e-12 1 1.80357e-09 -2.78228e-08 8.42424e-12 4110.91 -10.4189 -675.251 3973.38 21.8449 4096.45 +EDGE_SE3:QUAT 435 485 4.45298 0.0294644 -4.08403 0.175013 -0.109472 -0.00399465 0.978453 1 9.62965e-19 9.62965e-19 5.43658e-08 -2.95305e-08 -7.47345e-10 1 9.62965e-19 5.43658e-08 -2.95305e-08 -7.47345e-10 1 5.43658e-08 -2.95305e-08 -7.47345e-10 4053.71 -84.06 -858.429 3965.61 51.2676 4176.17 +EDGE_SE3:QUAT 434 485 3.86689 9.10438 -4.38601 -0.0262866 -0.0700163 0.0387451 0.996446 1 2.40741e-19 2.40741e-19 1.27718e-08 2.82516e-08 -6.17541e-11 1 2.40741e-19 1.27718e-08 2.82516e-08 -6.17541e-11 1 1.27718e-08 2.82516e-08 -6.17541e-11 4072.79 12.0854 -554.92 3981.92 -14.2439 4069.55 +EDGE_SE3:QUAT 435 484 3.59856 -9.04829 -3.89426 -0.0595636 0.0111137 -0.218423 0.973971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.33 3.58746 -68.6338 3999.06 13.4099 3809.69 +EDGE_SE3:QUAT 436 486 4.65413 0.7038 -4.14481 -0.0238862 0.132375 -0.0399412 0.990107 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4284.46 -33.5096 1108.72 3933.7 -36.8199 4280.36 +EDGE_SE3:QUAT 435 486 4.17708 9.02553 -4.45016 -0.250933 -0.0720388 0.0559881 0.963695 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3778.24 40.5966 -359.089 3998.8 -24.273 4017.57 +EDGE_SE3:QUAT 436 485 3.87979 -9.28895 -4.43065 -0.0787357 -0.0818689 -0.125593 0.985558 1 1.92593e-19 1.92593e-19 -2.77403e-09 -1.6066e-09 2.78572e-08 1 1.92593e-19 -2.77403e-09 -1.6066e-09 2.78572e-08 1 -2.77403e-09 -1.6066e-09 2.78572e-08 4120.57 7.97636 -776.712 3963.53 38.3917 4082.28 +EDGE_SE3:QUAT 437 487 4.54293 -0.348617 -4.37833 0.1423 -0.0166807 -0.142237 0.979409 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3920.49 13.7063 110.943 3997.64 -13.7001 3920.56 +EDGE_SE3:QUAT 436 487 3.95539 9.21069 -4.10589 0.0926385 0.076936 -0.0835489 0.989201 1 1.92593e-19 1.92593e-19 -2.78818e-08 1.9424e-09 -2.54009e-09 1 1.92593e-19 -2.78818e-08 1.9424e-09 -2.54009e-09 1 -2.78818e-08 1.9424e-09 -2.54009e-09 4089 21.7086 713.451 3968.73 -16.4768 4095.41 +EDGE_SE3:QUAT 437 486 3.70188 -9.07304 -4.23081 0.0136592 0.0643918 -0.115698 0.991101 1 3.88195e-19 3.88195e-19 -4.81542e-09 -2.71507e-08 2.7478e-08 1 3.88195e-19 -4.81542e-09 -2.71507e-08 2.7478e-08 1 -4.81542e-09 -2.71507e-08 2.7478e-08 4068.7 -8.32741 531.592 3983.6 -30.874 4015.9 +EDGE_SE3:QUAT 438 488 4.61032 0.207274 -4.80687 0.119172 0.00767894 0.012141 0.99277 1 1.95602e-19 1.95602e-19 -2.75406e-08 3.61458e-11 3.31728e-09 1 1.95602e-19 -2.75406e-08 3.61458e-11 3.31728e-09 1 -2.75406e-08 3.61458e-11 3.31728e-09 3943.64 2.19721 42.9195 3999.92 0.322055 3999.86 +EDGE_SE3:QUAT 437 488 3.95748 8.59618 -4.54505 0.0275673 -0.134895 0.0698989 0.988007 1 1.20371e-20 1.20371e-20 7.12344e-09 4.67478e-10 -9.90217e-10 1 1.20371e-20 7.12344e-09 4.67478e-10 -9.90217e-10 1 7.12344e-09 4.67478e-10 -9.90217e-10 4313.88 14.892 -1169.67 3925.85 -35.6493 4297.38 +EDGE_SE3:QUAT 438 487 4.12952 -9.16274 -4.26931 0.0478184 -0.0981251 -0.23288 0.96636 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4076.51 -50.5213 -597.801 3991.12 74.6652 3868.72 +EDGE_SE3:QUAT 439 489 4.63344 0.189021 -4.2997 -6.27776e-06 -0.0385232 -0.0749015 0.996447 1 1.88079e-22 1.88079e-22 -8.66824e-10 6.53514e-11 3.31355e-11 1 1.88079e-22 -8.66824e-10 6.53514e-11 3.31355e-11 1 -8.66824e-10 6.53514e-11 3.31355e-11 4023.45 -2.65826 -307.163 3994.33 11.6497 4001.01 +EDGE_SE3:QUAT 438 489 4.11983 9.10329 -4.23328 -0.023307 -0.140296 0.248155 0.958224 1 4.81482e-20 4.81482e-20 1.37044e-08 3.77713e-09 -1.57917e-09 1 4.81482e-20 1.37044e-08 3.77713e-09 -1.57917e-09 1 1.37044e-08 3.77713e-09 -1.57917e-09 4229.13 113.659 -993.839 3973.56 -148.291 3984.98 +EDGE_SE3:QUAT 439 488 4.35572 -9.37049 -4.03004 -0.0913831 0.102881 -0.144444 0.979898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.37 -54.3673 640.94 3985.6 -61.6876 4015.31 +EDGE_SE3:QUAT 440 490 4.40745 0.295582 -4.75345 0.0472905 -0.197572 0.062541 0.977148 1 9.62965e-20 9.62965e-20 -1.77949e-08 -3.48115e-10 1.77949e-08 1 9.62965e-20 -1.77949e-08 -3.48115e-10 1.77949e-08 1 -1.77949e-08 -3.48115e-10 1.77949e-08 4721.83 10.387 -1859.34 3839.47 -27.9986 4715.13 +EDGE_SE3:QUAT 439 490 4.09962 8.89256 -4.74044 -0.0464891 -0.124162 0.190724 0.972649 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4166.68 79.1608 -858.911 3973.92 -102.085 4029.82 +EDGE_SE3:QUAT 440 489 3.49345 -9.25057 -4.35976 -0.0493374 -0.0563687 -0.0404235 0.996371 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4046.6 9.01215 -478.099 3985.81 6.02964 4049.81 +EDGE_SE3:QUAT 441 491 4.5035 -0.144626 -4.43672 -0.0544991 -0.00930945 -0.139153 0.988726 1 4.81482e-20 4.81482e-20 1.37325e-08 -1.90789e-09 -3.31892e-10 1 4.81482e-20 1.37325e-08 -1.90789e-09 -3.31892e-10 1 1.37325e-08 -1.90789e-09 -3.31892e-10 3994.48 4.15842 -161.919 3997.81 12.9287 3928.9 +EDGE_SE3:QUAT 440 491 3.90972 9.20336 -4.7125 -0.136816 0.0190748 0.111542 0.984112 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3951 -23.1156 327.11 3991.28 17.3981 3976.11 +EDGE_SE3:QUAT 441 490 3.90966 -9.21977 -4.18227 0.125798 -0.0406456 -0.00183798 0.991221 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3961.57 -20.0889 -316.41 3994.37 5.1077 4024.85 +EDGE_SE3:QUAT 442 492 4.51453 -0.196879 -4.69317 0.011889 -0.0390591 -0.0928467 0.994843 1 3.00927e-21 3.00927e-21 3.46106e-09 -3.27106e-10 -1.25823e-10 1 3.00927e-21 3.46106e-09 -3.27106e-10 -1.25823e-10 1 3.46106e-09 -3.27106e-10 -1.25823e-10 4021.29 -4.90233 -296.553 3994.98 14.1093 3987.37 +EDGE_SE3:QUAT 441 492 4.08894 9.13758 -4.3127 -0.0244091 -0.126891 -0.0212834 0.991388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4270.99 6.50917 -1080.84 3934.93 3.20684 4271.56 +EDGE_SE3:QUAT 442 491 3.96961 -9.07237 -4.34995 0.0287577 -0.0834025 0.0697605 0.993655 1 1.20371e-20 1.20371e-20 -6.9983e-09 -4.63544e-10 6.09303e-10 1 1.20371e-20 -6.9983e-09 -4.63544e-10 6.09303e-10 1 -6.9983e-09 -4.63544e-10 6.09303e-10 4116.96 1.64897 -703.973 3970.6 -21.4392 4100.81 +EDGE_SE3:QUAT 443 493 4.88649 0.0830082 -4.74167 -0.0789471 -0.0714834 0.03837 0.993572 1 1.92593e-19 1.92593e-19 -2.78219e-08 -1.38864e-09 1.79941e-09 1 1.92593e-19 -2.78219e-08 -1.38864e-09 1.79941e-09 1 -2.78219e-08 -1.38864e-09 1.79941e-09 4045.77 25.9469 -536.728 3984.23 -19.3326 4064.81 +EDGE_SE3:QUAT 442 493 4.18554 9.09998 -4.29954 0.0524773 -0.166628 0.0824975 0.98116 1 1.92593e-19 1.92593e-19 -5.08865e-09 7.75356e-10 2.89406e-08 1 1.92593e-19 -5.08865e-09 7.75356e-10 2.89406e-08 1 -5.08865e-09 7.75356e-10 2.89406e-08 4502.28 13.8694 -1522.07 3883.46 -40.4986 4486.07 +EDGE_SE3:QUAT 443 492 3.55879 -9.15377 -4.54 0.103671 -0.00066156 -0.283865 0.953243 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.58 15.9988 329.187 3988.74 -61.0641 3702.25 +EDGE_SE3:QUAT 444 494 4.38292 0.027907 -4.25345 -0.0151738 -0.204691 -0.0115414 0.978641 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4765.74 6.77658 -1911.65 3832.14 -2.81627 4766.13 +EDGE_SE3:QUAT 443 494 4.12239 8.82775 -4.87904 -0.0266781 -0.00469904 0.126871 0.991549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.11 -0.231242 3.51315 3999.98 1.10179 3935.57 +EDGE_SE3:QUAT 444 493 3.92347 -9.32033 -4.33012 0.0456228 -0.0832567 0.0360612 0.99483 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4110.8 -10.8463 -700.512 3970.67 -5.50231 4113.92 +EDGE_SE3:QUAT 445 495 4.43264 -0.246654 -4.56321 -0.068653 -0.0364992 0.0892868 0.992966 1 1.92593e-19 1.92593e-19 -2.75995e-08 -2.6024e-09 6.4913e-10 1 1.92593e-19 -2.75995e-08 -2.6024e-09 6.4913e-10 1 -2.75995e-08 -2.6024e-09 6.4913e-10 3992.35 8.30339 -213.811 3998.03 -9.84325 3979.32 +EDGE_SE3:QUAT 444 495 3.98964 9.12758 -4.33953 -0.123447 -0.0758355 0.0370877 0.988754 1 8.1852e-19 8.1852e-19 5.44949e-08 1.2631e-09 1.02581e-08 1 8.1852e-19 5.44949e-08 1.2631e-09 1.02581e-08 1 5.44949e-08 1.2631e-09 1.02581e-08 4011.74 38.3561 -544.869 3985.21 -24.7644 4067.19 +EDGE_SE3:QUAT 445 494 3.82238 -9.10515 -4.46007 0.0427162 -0.0366075 -0.125039 0.990556 1 6.01853e-20 6.01853e-20 1.28803e-08 -8.64953e-09 7.33413e-12 1 6.01853e-20 1.28803e-08 -8.64953e-09 7.33413e-12 1 1.28803e-08 -8.64953e-09 7.33413e-12 4004.85 -6.95757 -222.251 3997.85 13.4545 3949.61 +EDGE_SE3:QUAT 446 496 4.23049 -0.0805415 -4.51211 -0.0782633 0.000851916 0.0870273 0.993127 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.25 -4.34005 87.7012 3999.19 4.85959 3971.45 +EDGE_SE3:QUAT 445 496 3.79283 8.96565 -4.5429 -0.0748216 -0.0474525 0.000813313 0.996067 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.13 14.4926 -378.613 3991.45 -4.19014 4035.52 +EDGE_SE3:QUAT 446 495 3.80428 -9.4705 -4.23564 -0.0179213 0.0253177 0.0570875 0.997887 1 6.01853e-20 6.01853e-20 7.31193e-09 1.83037e-10 1.40572e-08 1 6.01853e-20 7.31193e-09 1.83037e-10 1.40572e-08 1 7.31193e-09 1.83037e-10 1.40572e-08 4010.16 -1.00699 214.26 3997.08 5.96498 3998.41 +EDGE_SE3:QUAT 447 497 4.66648 -0.203575 -4.17944 0.0899056 0.0317181 0.155731 0.983188 1 2.0463e-19 2.0463e-19 2.61882e-08 1.12321e-08 -6.03808e-10 1 2.0463e-19 2.61882e-08 1.12321e-08 -6.03808e-10 1 2.61882e-08 1.12321e-08 -6.03808e-10 3968.23 1.52986 76.9017 4000.15 1.76219 3903.55 +EDGE_SE3:QUAT 446 497 3.60902 9.29733 -4.32052 -0.0814767 0.135156 0.0930045 0.983079 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4326.37 -12.1405 1239.56 3916.65 27.1465 4318.32 +EDGE_SE3:QUAT 447 496 3.78017 -9.03671 -4.45208 -0.0568397 -0.196929 -0.0770653 0.97573 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4724.37 -14.779 -1868.91 3838.49 36.5176 4713.54 +EDGE_SE3:QUAT 448 498 4.34811 -0.499484 -4.63936 0.14582 -0.118174 0.170387 0.967336 1 7.70372e-19 7.70372e-19 -5.62277e-08 -7.81052e-09 9.0893e-09 1 7.70372e-19 -5.62277e-08 -7.81052e-09 9.0893e-09 1 -5.62277e-08 -7.81052e-09 9.0893e-09 4284.22 -25.6986 -1271.43 3910.73 -58.6781 4253.15 +EDGE_SE3:QUAT 447 498 3.57879 9.01788 -4.68614 -0.00814033 0.0284499 0.00841044 0.999527 1 6.01853e-21 6.01853e-21 3.37415e-09 5.4325e-11 -3.37415e-09 1 6.01853e-21 3.37415e-09 5.4325e-11 -3.37415e-09 1 3.37415e-09 5.4325e-11 -3.37415e-09 4012.81 -0.776295 229.029 3996.73 0.812821 4012.79 +EDGE_SE3:QUAT 448 497 4.07023 -8.75878 -4.59367 0.0552578 0.00353402 -0.0427569 0.99755 1 4.81482e-20 4.81482e-20 1.13996e-10 7.59974e-10 1.38451e-08 1 4.81482e-20 1.13996e-10 7.59974e-10 1.38451e-08 1 1.13996e-10 7.59974e-10 1.38451e-08 3988.56 1.77602 56.3365 3999.73 -1.35338 3993.46 +EDGE_SE3:QUAT 449 499 4.84842 0.0867105 -4.4581 -0.0959409 -0.0708353 0.0649736 0.990735 1 3.85186e-19 3.85186e-19 2.92766e-08 5.12123e-09 -2.92766e-08 1 3.85186e-19 2.92766e-08 5.12123e-09 -2.92766e-08 1 2.92766e-08 5.12123e-09 -2.92766e-08 4021.18 29.2067 -486.234 3988.44 -24.7615 4041.11 +EDGE_SE3:QUAT 448 499 3.96296 9.13091 -4.45922 0.0415493 0.0020257 0.304735 0.951528 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.77 -2.61349 -128.518 3998.16 -27.2526 3632.22 +EDGE_SE3:QUAT 449 498 3.94931 -9.24611 -4.63715 -0.0324227 -0.122293 0.0406893 0.991129 1 1.92593e-19 1.92593e-19 1.38555e-09 -2.74977e-08 -1.20588e-09 1 1.92593e-19 1.38555e-09 -2.74977e-08 -1.20588e-09 1 1.38555e-09 -2.74977e-08 -1.20588e-09 4235.38 33.977 -1007.88 3944.59 -35.6766 4232.97 +EDGE_SE3:QUAT 450 500 4.47502 0.0117127 -4.48025 0.138362 -0.0300478 0.0273038 0.989549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3942.8 -19.6672 -279.283 3995.06 -0.195257 4016.4 +EDGE_SE3:QUAT 449 500 4.33316 9.0567 -4.40418 0.0699174 -0.012803 0.0201478 0.997267 1 3.00927e-21 3.00927e-21 6.30493e-11 -3.4601e-09 2.40689e-10 1 3.00927e-21 6.30493e-11 -3.4601e-09 2.40689e-10 1 6.30493e-11 -3.4601e-09 2.40689e-10 3983.95 -4.24052 -118.556 3999.06 -0.903436 4001.88 +EDGE_SE3:QUAT 450 499 3.83245 -9.22612 -4.28927 -0.113302 0.14698 0.103514 0.977161 1 9.62965e-19 9.62965e-19 3.26062e-08 -5.23022e-08 7.30667e-11 1 9.62965e-19 3.26062e-08 -5.23022e-08 7.30667e-11 1 3.26062e-08 -5.23022e-08 7.30667e-11 4392.93 -32.1765 1405.39 3896.71 16.6763 4401.42 +EDGE_SE3:QUAT 451 501 4.28768 -0.0528326 -4.46942 -0.0531188 -0.00100077 0.0828382 0.995146 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.14 -1.61968 44.5766 3999.76 2.55603 3972.97 +EDGE_SE3:QUAT 450 501 3.54454 9.30421 -4.83191 -0.00948139 -0.0195445 -0.0446902 0.998765 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.12 0.344619 -161.178 3998.36 3.55957 3998.49 +EDGE_SE3:QUAT 451 500 3.92496 -9.2804 -4.54689 -0.0731529 -0.000706008 0.203667 0.976303 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.92 -7.04211 168.22 3996.91 22.7663 3840.4 +EDGE_SE3:QUAT 452 502 4.83393 0.21505 -4.41507 0.0198511 -0.00382452 -0.0825688 0.99638 1 4.83363e-20 4.83363e-20 1.37559e-08 -2.01131e-09 1.05493e-11 1 4.83363e-20 1.37559e-08 -2.01131e-09 1.05493e-11 1 1.37559e-08 -2.01131e-09 1.05493e-11 3998.44 -0.0468737 -10.691 4000 0.167811 3972.75 +EDGE_SE3:QUAT 451 502 3.88189 9.04367 -4.51665 -0.119466 0.219628 0.127743 0.959778 1 1.92593e-19 1.92593e-19 -3.00192e-08 -2.57221e-09 -7.47608e-09 1 1.92593e-19 -3.00192e-08 -2.57221e-09 -7.47608e-09 1 -3.00192e-08 -2.57221e-09 -7.47608e-09 4996.59 -1.62189 2307.7 3781.05 31.2552 4988.4 +EDGE_SE3:QUAT 452 501 3.64371 -9.36648 -4.76422 -0.00294484 0.160856 -0.130748 0.978275 1 4.81482e-20 4.81482e-20 1.42833e-08 -2.02713e-09 2.25195e-09 1 4.81482e-20 1.42833e-08 -2.02713e-09 2.25195e-09 1 1.42833e-08 -2.02713e-09 2.25195e-09 4419.44 -90.9507 1361.8 3914.41 -114.615 4351.09 +EDGE_SE3:QUAT 453 503 4.479 -0.210302 -4.66382 -0.208207 0.00622428 0.0835061 0.974494 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3841.1 -31.7718 248.687 3994.17 9.93841 3986.6 +EDGE_SE3:QUAT 452 503 3.91583 9.06706 -4.42701 0.135178 0.135184 0.092198 0.977216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4127.66 100.133 922.074 3969.08 93.5779 4166.75 +EDGE_SE3:QUAT 453 502 3.9086 -9.11955 -4.69697 0.0802832 -0.163915 -0.203438 0.961925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4238.38 -148.491 -1069.94 3975.76 163.033 4098.61 +EDGE_SE3:QUAT 454 504 4.27644 0.0882781 -4.22435 0.0192156 -0.0843295 -0.0506527 0.994964 1 1.20371e-20 1.20371e-20 6.99945e-09 -3.84157e-10 -5.75797e-10 1 1.20371e-20 6.99945e-09 -3.84157e-10 -5.75797e-10 1 6.99945e-09 -3.84157e-10 -5.75797e-10 4109.59 -15.5715 -675.758 3973.64 21.5286 4100.81 +EDGE_SE3:QUAT 453 504 3.67648 9.37349 -4.54346 -0.0901185 -0.0335528 0.183321 0.978338 1 1.92593e-19 1.92593e-19 2.71529e-08 5.17527e-09 4.58041e-11 1 1.92593e-19 2.71529e-08 5.17527e-09 4.58041e-11 1 2.71529e-08 5.17527e-09 4.58041e-11 3967.09 0.140924 -58.7568 4000.18 0.830497 3865.15 +EDGE_SE3:QUAT 454 503 3.99631 -9.32493 -4.46272 -0.203857 -0.0571059 -0.027167 0.976956 1 7.70372e-19 7.70372e-19 5.46656e-08 -1.21885e-10 -3.53506e-09 1 7.70372e-19 5.46656e-08 -1.21885e-10 -3.53506e-09 1 5.46656e-08 -1.21885e-10 -3.53506e-09 3895.31 51.7294 -499.934 3986.52 -11.5056 4058.58 +EDGE_SE3:QUAT 455 505 4.48245 0.0584844 -4.36386 -0.0781944 -0.0472186 0.0594236 0.994045 1 1.92593e-19 1.92593e-19 2.76774e-08 1.84611e-09 -1.03042e-09 1 1.92593e-19 2.76774e-08 1.84611e-09 -1.03042e-09 1 2.76774e-08 1.84611e-09 -1.03042e-09 4000.59 14.3452 -318.304 3994.85 -12.269 4010.93 +EDGE_SE3:QUAT 454 505 3.89501 8.88357 -4.66347 0.0682243 0.0721674 -0.00288639 0.995052 1 3.85374e-19 3.85374e-19 2.7777e-08 2.78744e-08 9.86446e-10 1 3.85374e-19 2.7777e-08 2.78744e-08 9.86446e-10 1 2.7777e-08 2.78744e-08 9.86446e-10 4065.53 20.7112 586.255 3979.73 7.83517 4084.12 +EDGE_SE3:QUAT 455 504 3.83216 -9.27767 -4.30023 0.00368828 0.0536227 -0.0922002 0.994289 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4046.05 -5.62686 431.893 3989 -20.237 4012.1 +EDGE_SE3:QUAT 456 506 4.45729 -0.0227492 -4.30955 0.184112 -0.0496477 -0.063859 0.979571 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3877.57 -18.9176 -237.172 3998.86 11.1299 3996.84 +EDGE_SE3:QUAT 455 506 3.79591 8.94402 -4.6167 0.0224835 -0.136692 0.0927684 0.986004 1 1.95602e-19 1.95602e-19 -7.55431e-09 -4.1215e-10 2.89607e-08 1 1.95602e-19 -7.55431e-09 -4.1215e-10 2.89607e-08 1 -7.55431e-09 -4.1215e-10 2.89607e-08 4321.32 30.5868 -1182.33 3925.91 -54.8955 4288.92 +EDGE_SE3:QUAT 456 505 3.75484 -9.14972 -4.26646 0.133649 -0.0339363 -0.0219963 0.990203 1 7.82409e-19 7.82409e-19 -5.52455e-08 2.62263e-09 8.37518e-09 1 7.82409e-19 -5.52455e-08 2.62263e-09 8.37518e-09 1 -5.52455e-08 2.62263e-09 8.37518e-09 3941.64 -15.0286 -229.75 3997.41 5.2821 4011.15 +EDGE_SE3:QUAT 457 507 4.43571 0.260485 -4.30096 0.00109597 -0.0225557 -0.00845281 0.999709 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.14 -0.202843 -180.636 3997.97 0.780733 4007.85 +EDGE_SE3:QUAT 456 507 3.86655 9.10475 -4.25161 -0.0100883 -0.13128 -0.0750673 0.988448 1 3.10404e-23 3.10404e-23 -3.60806e-10 2.73896e-11 4.79265e-11 1 3.10404e-23 -3.60806e-10 2.73896e-11 4.79265e-11 1 -3.60806e-10 2.73896e-11 4.79265e-11 4290.44 -27.2451 -1117.13 3932.72 45.1372 4268.3 +EDGE_SE3:QUAT 457 506 3.58858 -9.10087 -4.39365 -0.155107 0.0665219 -0.102962 0.980263 1 2.40741e-19 2.40741e-19 -8.07714e-10 -1.82104e-08 2.49861e-08 1 2.40741e-19 -8.07714e-10 -1.82104e-08 2.49861e-08 1 -8.07714e-10 -1.82104e-08 2.49861e-08 3927.24 -24.7819 317.304 3997.99 -20.8379 3981.07 +EDGE_SE3:QUAT 458 508 3.98134 -0.0261593 -4.57631 -0.0179287 0.0144021 -0.138115 0.990149 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.38 -1.06285 82.5658 3999.72 -5.00279 3925.37 +EDGE_SE3:QUAT 457 508 3.54005 9.58176 -4.47239 0.109456 -0.111052 0.121602 0.980255 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4222.77 -21.9252 -1075.67 3933.95 -34.6002 4211.54 +EDGE_SE3:QUAT 458 507 3.80158 -9.47551 -4.42384 0.0206162 -0.00906908 0.0347902 0.999141 1 1.50463e-20 1.50463e-20 -7.05368e-09 3.22781e-09 3.50661e-12 1 1.50463e-20 -7.05368e-09 3.22781e-09 3.50661e-12 1 -7.05368e-09 3.22781e-09 3.50661e-12 3999.94 -0.783051 -81.0034 3999.56 -1.4109 3996.8 +EDGE_SE3:QUAT 459 509 4.40053 0.227712 -4.671 -0.0571728 -0.0532164 0.0636026 0.994914 1 9.62965e-20 9.62965e-20 -1.29036e-08 -1.4772e-08 -2.55548e-10 1 9.62965e-20 -1.29036e-08 -1.4772e-08 -2.55548e-10 1 -1.29036e-08 -1.4772e-08 -2.55548e-10 4022.68 14.3383 -380.256 3992.21 -15.1723 4019.57 +EDGE_SE3:QUAT 458 509 3.61403 9.43542 -4.52943 -0.199288 0.01072 0.0632012 0.977842 1 4.81482e-20 4.81482e-20 -4.78592e-10 2.73101e-09 -1.35924e-08 1 4.81482e-20 -4.78592e-10 2.73101e-09 -1.35924e-08 1 -4.78592e-10 2.73101e-09 -1.35924e-08 3853.61 -26.6945 227.706 3995.61 5.8229 3996.49 +EDGE_SE3:QUAT 459 508 3.82706 -9.49108 -4.56176 0.0200269 0.0833855 -0.135708 0.987031 1 7.73381e-19 7.73381e-19 -8.30342e-09 6.46993e-10 -5.59138e-08 1 7.73381e-19 -8.30342e-09 6.46993e-10 -5.59138e-08 1 -8.30342e-09 6.46993e-10 -5.59138e-08 4116.92 -16.8786 698.667 3972.77 -47.7581 4044.86 +EDGE_SE3:QUAT 460 510 4.63429 -0.195951 -4.27172 0.111308 -0.020966 0.00929323 0.993521 1 1.93345e-19 1.93345e-19 -2.76422e-08 6.96772e-11 2.35033e-09 1 1.93345e-19 -2.76422e-08 6.96772e-11 2.35033e-09 1 -2.76422e-08 6.96772e-11 2.35033e-09 3958.28 -9.97679 -177.227 3998.07 0.445753 4007.49 +EDGE_SE3:QUAT 459 510 3.89506 9.11541 -4.46979 -0.0963744 -0.0598732 0.0208589 0.993324 1 2.52778e-19 2.52778e-19 2.76813e-08 1.53737e-08 -7.08347e-09 1 2.52778e-19 2.76813e-08 1.53737e-08 -7.08347e-09 1 2.76813e-08 1.53737e-08 -7.08347e-09 4013.41 23.7348 -452.731 3988.64 -12.4077 4048.82 +EDGE_SE3:QUAT 460 509 3.62993 -9.32517 -4.52458 0.0736797 -0.00919932 -0.0169339 0.997096 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.12 -1.97268 -58.0569 3999.83 0.552569 3999.69 +EDGE_SE3:QUAT 461 511 4.04591 -0.13192 -4.60928 -0.00853332 0.127739 0.167777 0.977477 1 3.00927e-21 3.00927e-21 3.50284e-09 6.13774e-10 4.41589e-10 1 3.00927e-21 3.50284e-09 6.13774e-10 4.41589e-10 1 3.50284e-09 6.13774e-10 4.41589e-10 4259.38 63.987 1051.99 3947.65 99.3818 4147.07 +EDGE_SE3:QUAT 460 511 3.79395 9.68043 -4.33654 -0.0987051 -0.00561905 -0.00441301 0.995091 1 1.93345e-19 1.93345e-19 -2.76159e-08 1.81569e-09 3.48138e-10 1 1.93345e-19 -2.76159e-08 1.81569e-09 3.48138e-10 1 -2.76159e-08 1.81569e-09 3.48138e-10 3961.64 2.51484 -49.4959 3999.84 0.0251587 4000.53 +EDGE_SE3:QUAT 461 510 3.78211 -9.47125 -4.06862 0.158478 -0.0183013 -0.00355042 0.987186 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3904.04 -10.384 -134.412 3999.07 1.36211 4004.45 +EDGE_SE3:QUAT 462 512 4.54919 0.0889408 -4.57614 0.145807 -0.0110962 -0.10805 0.983332 1 9.62965e-19 9.62965e-19 5.40246e-08 -9.93842e-09 -2.61537e-08 1 9.62965e-19 5.40246e-08 -9.93842e-09 -2.61537e-08 1 5.40246e-08 -9.93842e-09 -2.61537e-08 3916.53 11.9034 100.514 3998.31 -8.74418 3954.87 +EDGE_SE3:QUAT 461 512 3.89867 9.06093 -4.40721 -0.0940571 0.00557502 0.237012 0.966927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.27 -12.8579 297.885 3991.51 43.7784 3795.96 +EDGE_SE3:QUAT 462 511 3.47545 -9.55924 -4.36261 0.0817523 -0.0741698 -0.00366339 0.993882 1 3.00927e-21 3.00927e-21 -2.54472e-10 2.91792e-10 3.48559e-09 1 3.00927e-21 -2.54472e-10 2.91792e-10 3.48559e-09 1 -2.54472e-10 2.91792e-10 3.48559e-09 4059.82 -26.0621 -594.772 3979.58 11.9847 4086.5 +EDGE_SE3:QUAT 463 513 4.7011 -0.516202 -4.68021 0.198687 0.0792025 0.180254 0.960083 1 1.58889e-18 1.58889e-18 -5.04447e-08 -3.61544e-08 -5.02087e-08 1 1.58889e-18 -5.04447e-08 -3.61544e-08 -5.02087e-08 1 -5.04447e-08 -3.61544e-08 -5.02087e-08 3840.87 3.21538 153.282 4002.19 3.77403 3868.81 +EDGE_SE3:QUAT 462 513 3.62678 9.62995 -4.66069 0.143453 -0.0306874 0.0498228 0.987926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.58 -23.6193 -323.614 3992.92 -3.72237 4015.96 +EDGE_SE3:QUAT 463 512 3.85175 -9.05804 -4.66936 0.00144243 -0.0552698 0.0996025 0.99349 1 5.11575e-20 5.11575e-20 2.07929e-09 1.41361e-08 -5.70854e-11 1 5.11575e-20 2.07929e-09 1.41361e-08 -5.70854e-11 1 2.07929e-09 1.41361e-08 -5.70854e-11 4048.23 6.99214 -441.905 3988.64 -22.5268 4008.55 +EDGE_SE3:QUAT 464 514 4.42016 0.251144 -4.52678 0.00828885 0.0790889 -0.0332581 0.996278 1 7.52316e-22 7.52316e-22 -1.75034e-09 5.68412e-11 -1.39603e-10 1 7.52316e-22 -1.75034e-09 5.68412e-11 -1.39603e-10 1 -1.75034e-09 5.68412e-11 -1.39603e-10 4102.45 -2.3071 649.204 3974.85 -10.234 4098.3 +EDGE_SE3:QUAT 463 514 3.76829 9.07329 -4.50001 0.0627355 -0.144923 -0.00783696 0.987421 1 9.62965e-19 9.62965e-19 -2.70943e-08 5.55717e-08 3.67456e-10 1 9.62965e-19 -2.70943e-08 5.55717e-08 3.67456e-10 1 -2.70943e-08 5.55717e-08 3.67456e-10 4333.95 -51.4844 -1233.33 3920.51 40.3727 4349.44 +EDGE_SE3:QUAT 464 513 3.53893 -9.01711 -4.15316 -0.0138854 -0.0103436 0.232194 0.972515 1 7.52316e-22 7.52316e-22 4.03159e-10 -1.68696e-09 -2.95964e-11 1 7.52316e-22 4.03159e-10 -1.68696e-09 -2.95964e-11 1 4.03159e-10 -1.68696e-09 -2.95964e-11 3999.54 0.370432 -38.8258 4000.01 -2.7566 3784.66 +EDGE_SE3:QUAT 465 515 4.38236 0.139597 -4.65666 0.142495 -0.174482 -0.072695 0.971579 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4308.16 -164.864 -1310.23 3939.89 154.972 4368.24 +EDGE_SE3:QUAT 464 515 4.00802 9.26599 -4.50185 0.00398751 0.0168499 0.11675 0.99301 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.94 0.974505 126.619 3999.1 7.27404 3949.48 +EDGE_SE3:QUAT 465 514 3.69175 -9.26391 -4.39535 -0.116621 -0.0473708 -0.0617465 0.990123 1 2.40741e-19 2.40741e-19 2.69773e-08 -1.513e-08 -3.21329e-09 1 2.40741e-19 2.69773e-08 -1.513e-08 -3.21329e-09 1 2.69773e-08 -1.513e-08 -3.21329e-09 3997.78 24.5897 -460.337 3986.24 6.83216 4036.93 +EDGE_SE3:QUAT 466 516 4.11664 -0.565436 -4.59763 -0.0447244 0.0332157 0.0176233 0.998291 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.87 -5.80323 275.41 3995.24 1.22851 4017.63 +EDGE_SE3:QUAT 465 516 3.82663 9.46704 -4.5067 -0.0351734 -0.0874331 -0.0253283 0.995227 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4123.52 8.98467 -728.267 3968.54 3.17513 4125.9 +EDGE_SE3:QUAT 466 515 3.67437 -9.49189 -4.38001 -0.0371654 0.077449 -0.0544172 0.994816 1 2.40741e-19 2.40741e-19 -1.22746e-08 2.84534e-08 2.52879e-10 1 2.40741e-19 -1.22746e-08 2.84534e-08 2.52879e-10 1 -1.22746e-08 2.84534e-08 2.52879e-10 4083.19 -19.1898 602.384 3979.42 -22.2399 4076.87 +EDGE_SE3:QUAT 467 517 3.95472 -0.0213826 -4.4741 -0.0576746 0.228803 0.0682863 0.969361 1 4.81482e-20 4.81482e-20 -3.63993e-09 4.67935e-10 -1.50959e-08 1 4.81482e-20 -3.63993e-09 4.67935e-10 -1.50959e-08 1 -3.63993e-09 4.67935e-10 -1.50959e-08 5017.13 11.6834 2276.75 3784.13 25.7689 5011.79 +EDGE_SE3:QUAT 466 517 4.21513 9.19004 -4.85029 -0.0763129 -0.00933025 0.0728737 0.994374 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.59 -0.579999 -7.15326 3999.99 0.55277 3978.64 +EDGE_SE3:QUAT 467 516 3.47784 -9.45037 -4.41348 -0.187159 0.115827 -0.101528 0.970179 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3959.3 -77.226 648.941 3991.45 -67.5762 4058.18 +EDGE_SE3:QUAT 468 518 4.50151 0.385316 -4.36588 0.0468768 -0.0183124 0.165444 0.984934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.48 -3.29378 -232.09 3996.07 -20.8992 3903.78 +EDGE_SE3:QUAT 467 518 3.8843 9.64546 -4.88881 0.017186 0.0538345 0.160318 0.985446 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.27 12.7192 384.22 3992.84 31.3102 3933.65 +EDGE_SE3:QUAT 468 517 3.53521 -9.33092 -4.21482 0.0201621 0.113449 -0.0373528 0.992637 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4215.92 -1.44189 957.878 3947.74 -13.6812 4211.97 +EDGE_SE3:QUAT 469 519 4.62405 -0.0253068 -4.40145 0.0379446 0.0933204 0.0271569 0.994542 1 1.20371e-20 1.20371e-20 -6.40812e-10 -3.08271e-10 -7.01865e-09 1 1.20371e-20 -6.40812e-10 -3.08271e-10 -7.01865e-09 1 -6.40812e-10 -3.08271e-10 -7.01865e-09 4131.42 21.2253 753.361 3967.47 19.1009 4134.22 +EDGE_SE3:QUAT 468 519 3.9753 9.37994 -4.43387 -0.0454722 0.0954405 -0.009724 0.994348 1 2.40741e-19 2.40741e-19 -1.35329e-08 2.78588e-08 7.26728e-12 1 2.40741e-19 -1.35329e-08 2.78588e-08 7.26728e-12 1 -1.35329e-08 2.78588e-08 7.26728e-12 4138.36 -21.5508 779.779 3964.97 -14.3712 4146.26 +EDGE_SE3:QUAT 469 518 3.92164 -9.11492 -4.44296 0.0607563 0.0279357 -0.161895 0.98454 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.29 5.48691 331.544 3992.25 -27.9396 3922.22 +EDGE_SE3:QUAT 470 520 4.25006 0.172455 -4.94153 -0.0710911 -0.0946022 0.0487004 0.991779 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4107.24 37.2802 -725.6 3971.8 -33.1397 4117.97 +EDGE_SE3:QUAT 469 520 3.78248 9.22316 -4.70613 -0.0865482 0.222655 0.135251 0.961583 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5008.85 72.5816 2287.9 3787.74 100.22 4965.64 +EDGE_SE3:QUAT 470 519 3.59023 -9.12298 -4.17929 -0.0954396 -0.093286 -0.244681 0.960375 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4196.62 -25.4357 -993.956 3947.21 113.989 3993.58 +EDGE_SE3:QUAT 471 521 4.6557 0.0607117 -4.53524 -0.00635366 -0.126204 0.00842482 0.991948 1 7.71124e-19 7.71124e-19 -1.20307e-09 -5.50817e-08 -2.59314e-10 1 7.71124e-19 -1.20307e-09 -5.50817e-08 -2.59314e-10 1 -1.20307e-09 -5.50817e-08 -2.59314e-10 4266.92 7.44414 -1067.55 3936.48 -7.8817 4266.8 +EDGE_SE3:QUAT 470 521 3.65941 9.31938 -4.57648 -0.0123307 -0.0203732 -0.0286928 0.999305 1 1.20371e-20 1.20371e-20 -1.46132e-10 -7.74464e-11 6.94012e-09 1 1.20371e-20 -1.46132e-10 -7.74464e-11 6.94012e-09 1 -1.46132e-10 -7.74464e-11 6.94012e-09 4006.37 0.746394 -167.25 3998.24 2.30149 4003.69 +EDGE_SE3:QUAT 471 520 4.06044 -9.26903 -4.16109 -0.0251113 -0.0534932 -0.0735166 0.995542 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4047.74 0.434176 -451.219 3987.47 15.4649 4028.64 +EDGE_SE3:QUAT 472 522 4.15207 -0.239945 -4.87457 0.160339 0.168211 -0.144931 0.961765 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4568.06 50.9253 1770.73 3850.52 -15.6906 4586.87 +EDGE_SE3:QUAT 471 522 4.0226 9.45894 -4.79147 0.00375432 -0.23378 0.151075 0.960473 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4962.44 243.262 -2186.02 3835.78 -256.808 4871.2 +EDGE_SE3:QUAT 472 521 3.40312 -9.00263 -4.45534 -0.00336472 -0.0190202 -0.0789367 0.996692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.88 -0.43988 -154.115 3998.54 6.09949 3981.01 +EDGE_SE3:QUAT 473 523 4.39735 0.0352615 -4.39221 -0.0292158 0.0507647 0.0615046 0.996387 1 6.01853e-20 6.01853e-20 -6.20094e-09 -7.2958e-10 1.35303e-08 1 6.01853e-20 -6.20094e-09 -7.2958e-10 1.35303e-08 1 -6.20094e-09 -7.2958e-10 1.35303e-08 4042.11 -2.3934 429.177 3988.55 11.8004 4030.39 +EDGE_SE3:QUAT 472 523 4.24458 9.37938 -4.31376 -0.0662605 0.194472 0.0320941 0.978141 1 9.75002e-19 9.75002e-19 2.83438e-08 -5.36713e-08 -4.67632e-09 1 9.75002e-19 2.83438e-08 -5.36713e-08 -4.67632e-09 1 2.83438e-08 -5.36713e-08 -4.67632e-09 4678.73 -49.1485 1808.31 3847.21 -33.0985 4692.17 +EDGE_SE3:QUAT 473 522 3.64603 -9.2011 -4.47832 -0.0955766 0.0217483 -0.058022 0.993492 1 4.81482e-20 4.81482e-20 -1.41214e-10 1.35365e-09 -1.3792e-08 1 4.81482e-20 -1.41214e-10 1.35365e-09 -1.3792e-08 1 -1.41214e-10 1.35365e-09 -1.3792e-08 3966.06 -4.22098 104.737 3999.64 -2.88925 3989.13 +EDGE_SE3:QUAT 474 524 4.59239 0.0557815 -4.75255 -0.0314703 -0.0605969 -0.200191 0.977375 1 1.20371e-20 1.20371e-20 -6.84434e-09 1.38426e-09 4.76489e-10 1 1.20371e-20 -6.84434e-09 1.38426e-09 4.76489e-10 1 -6.84434e-09 1.38426e-09 4.76489e-10 4067.05 -12.0551 -537.691 3984.2 54.4353 3910.71 +EDGE_SE3:QUAT 473 524 4.108 9.55141 -4.81746 -0.0540777 -0.0612498 0.0721961 0.994038 1 2.88889e-19 2.88889e-19 1.4247e-08 1.66418e-08 -2.76181e-08 1 2.88889e-19 1.4247e-08 1.66418e-08 -2.76181e-08 1 1.4247e-08 1.66418e-08 -2.76181e-08 4036.37 17.4352 -441.535 3989.56 -20.02 4027.21 +EDGE_SE3:QUAT 474 523 3.92638 -9.48453 -4.7778 -0.124895 0.0343103 -0.0518627 0.990219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3946.42 -11.0637 190.361 3998.61 -6.29836 3998.05 +EDGE_SE3:QUAT 475 525 4.45611 -0.116652 -4.62703 0.0505066 0.027443 -0.0629439 0.99636 1 6.01853e-20 6.01853e-20 -4.88194e-11 6.26489e-09 -1.41801e-08 1 6.01853e-20 -4.88194e-11 6.26489e-09 -1.41801e-08 1 -4.88194e-11 6.26489e-09 -1.41801e-08 4006.13 5.38298 256.39 3995.61 -7.35527 4000.49 +EDGE_SE3:QUAT 474 525 3.37997 9.51534 -4.78162 -0.0138356 0.0301201 0.128182 0.991197 1 3.00927e-21 3.00927e-21 -3.44608e-09 -4.4346e-10 -1.13488e-10 1 3.00927e-21 -3.44608e-09 -4.4346e-10 -1.13488e-10 1 -3.44608e-09 -4.4346e-10 -1.13488e-10 4015.68 1.27968 256.996 3996 16.6328 3950.72 +EDGE_SE3:QUAT 475 524 3.73643 -9.64585 -4.63238 0.0676344 0.14406 -0.153531 0.975244 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4390.7 -39.1876 1342.92 3908.7 -88.0712 4314.71 +EDGE_SE3:QUAT 476 526 4.09682 -0.316242 -4.29756 -0.049576 0.043294 -0.0900856 0.993757 1 4.81482e-20 4.81482e-20 -1.3827e-08 1.31104e-09 -4.6545e-10 1 4.81482e-20 -1.3827e-08 1.31104e-09 -4.6545e-10 1 -1.3827e-08 1.31104e-09 -4.6545e-10 4010.78 -9.86725 288.691 3995.82 -14.0215 3988.15 +EDGE_SE3:QUAT 475 526 3.92095 9.65766 -4.47226 0.136864 0.108339 0.144891 0.973929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.49 60.2561 587.252 3992.66 61.1176 3997.44 +EDGE_SE3:QUAT 476 525 3.82298 -9.86189 -4.47454 0.108463 0.0305669 0.0238937 0.993343 1 1.92593e-19 1.92593e-19 -2.76089e-08 -8.32965e-10 -6.85094e-10 1 1.92593e-19 -2.76089e-08 -8.32965e-10 -6.85094e-10 1 -2.76089e-08 -8.32965e-10 -6.85094e-10 3963.85 11.2418 209.601 3997.73 4.3149 4008.63 +EDGE_SE3:QUAT 477 527 4.45515 0.19654 -4.51312 0.150922 0.174978 -0.0888091 0.968875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4542.61 91.6548 1713.71 3862.01 44.3347 4602.17 +EDGE_SE3:QUAT 476 527 3.59283 9.50569 -4.34861 0.0574918 -0.0600371 -0.0356763 0.9959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.37 -16.2087 -457.307 3988.06 12.8961 4046.5 +EDGE_SE3:QUAT 477 526 3.75465 -9.48904 -4.58559 -0.0843279 -0.236198 -0.149544 0.956418 1 4.81482e-20 4.81482e-20 1.51588e-08 -1.964e-09 -3.95329e-09 1 4.81482e-20 1.51588e-08 -1.964e-09 -3.95329e-09 1 1.51588e-08 -1.964e-09 -3.95329e-09 5159.01 -121.543 -2481.92 3767.76 144.535 5098 +EDGE_SE3:QUAT 478 528 4.2721 0.205126 -4.37352 0.14711 -0.00360648 0.0583899 0.987389 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3917.35 -11.7678 -129.264 3998.39 -4.13548 3990.28 +EDGE_SE3:QUAT 477 528 3.79308 9.18245 -4.49692 -0.0272355 -0.0939303 0.191158 0.976675 1 9.62965e-19 9.62965e-19 1.22225e-09 -3.05171e-08 5.32603e-08 1 9.62965e-19 1.22225e-09 -3.05171e-08 5.32603e-08 1 1.22225e-09 -3.05171e-08 5.32603e-08 4103.16 43.207 -661.913 3982.09 -69.9044 3959.96 +EDGE_SE3:QUAT 478 527 3.90089 -9.67304 -4.49597 -0.19665 -0.0922749 -0.25013 0.94353 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4230.42 36.2964 -1304.08 3901.7 110.318 4134.84 +EDGE_SE3:QUAT 479 529 4.27707 -0.100122 -4.37115 -0.0431211 -0.0813622 0.0573098 0.994101 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4089.01 22.83 -628.722 3977.92 -25.3651 4083.31 +EDGE_SE3:QUAT 478 529 3.50157 9.25399 -4.72172 -0.044216 -0.0149862 0.0817314 0.99556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.54 1.55652 -75.2258 3999.79 -2.58664 3974.64 +EDGE_SE3:QUAT 479 528 3.4127 -9.5818 -4.38891 0.122505 0.0893326 -0.0648719 0.986308 1 2.40741e-19 2.40741e-19 -2.64869e-08 2.77697e-09 1.10788e-08 1 2.40741e-19 -2.64869e-08 2.77697e-09 1.10788e-08 1 -2.64869e-08 2.77697e-09 1.10788e-08 4100.79 41.1502 818.242 3960.54 -0.879054 4143.99 +EDGE_SE3:QUAT 480 530 4.50637 -0.0837025 -4.63883 -0.0412178 0.184365 0.0668365 0.979716 1 7.70372e-19 7.70372e-19 3.08606e-09 -5.44241e-08 -9.96757e-10 1 7.70372e-19 3.08606e-09 -5.44241e-08 -9.96757e-10 1 3.08606e-09 -5.44241e-08 -9.96757e-10 4618.27 18.2779 1700.29 3860.65 37.3753 4607.19 +EDGE_SE3:QUAT 479 530 3.44613 9.40537 -5.08055 -0.157114 0.230446 0.0742421 0.957443 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5003.31 -169.53 2371.23 3786.65 -144.689 5080 +EDGE_SE3:QUAT 480 529 3.46512 -9.6793 -4.05843 -0.0688166 0.0669005 -0.124346 0.987586 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.3 -22.9892 420.514 3992.49 -29.799 3981.4 +EDGE_SE3:QUAT 481 531 3.99324 -0.112584 -4.96767 -0.0137686 -0.047619 -0.0891341 0.994785 1 2.43751e-19 2.43751e-19 3.61881e-09 -1.3971e-08 -2.79875e-08 1 2.43751e-19 3.61881e-09 -1.3971e-08 -2.79875e-08 1 3.61881e-09 -1.3971e-08 -2.79875e-08 4037.75 -2.32671 -394.336 3990.57 17.3682 4006.72 +EDGE_SE3:QUAT 480 531 3.535 9.29852 -4.79049 0.0605684 -0.0683567 0.010579 0.995764 1 4.89006e-20 4.89006e-20 1.40732e-08 -7.26105e-11 -2.71261e-09 1 4.89006e-20 1.40732e-08 -7.26105e-11 -2.71261e-09 1 1.40732e-08 -7.26105e-11 -2.71261e-09 4062.46 -16.6467 -560.807 3981.16 3.93343 4076.69 +EDGE_SE3:QUAT 481 530 3.60588 -9.63785 -4.57321 -0.138457 -0.055741 -0.0926968 0.984444 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.51 35.0396 -591.139 3977.11 14.4474 4050.82 +EDGE_SE3:QUAT 482 532 4.7988 -0.148003 -4.37665 0.195327 0.0523982 -0.0479554 0.978163 1 8.1852e-19 8.1852e-19 -5.50905e-08 -1.22192e-08 -1.07988e-09 1 8.1852e-19 -5.50905e-08 -1.22192e-08 -1.07988e-09 1 -5.50905e-08 -1.22192e-08 -1.07988e-09 3911.66 50.2599 511.435 3984.42 4.53403 4055.07 +EDGE_SE3:QUAT 481 532 3.68037 9.19369 -4.2767 -0.0897946 -0.125623 0.0281083 0.987606 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4208.35 62.7257 -1010.31 3947.47 -50.5121 4237.45 +EDGE_SE3:QUAT 482 531 3.73305 -9.49259 -4.435 -0.0212329 0.0861593 -0.32145 0.942759 1 3.08149e-18 3.08149e-18 6.14542e-09 -7.8415e-09 1.05582e-07 1 3.08149e-18 6.14542e-09 -7.8415e-09 1.05582e-07 1 6.14542e-09 -7.8415e-09 1.05582e-07 4060.86 -43.5996 512.833 3998.22 -79.4493 3649.34 +EDGE_SE3:QUAT 483 533 4.28642 0.321118 -4.84394 -0.0399843 0.0381654 0.0681471 0.996143 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.82 -4.2681 337.24 3992.7 10.392 4009.64 +EDGE_SE3:QUAT 482 533 3.54642 9.55771 -4.52245 0.0935062 -0.017063 0.141251 0.9854 1 7.70372e-19 7.70372e-19 2.34569e-09 -4.73691e-09 -5.48415e-08 1 7.70372e-19 2.34569e-09 -4.73691e-09 -5.48415e-08 1 2.34569e-09 -4.73691e-09 -5.48415e-08 3985.08 -12.4839 -287.675 3993.26 -21.7933 3940.25 +EDGE_SE3:QUAT 483 532 3.66962 -9.60004 -4.56978 0.115182 -0.169659 -0.077085 0.975708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4333.75 -143.64 -1304.52 3933.46 137.788 4363.05 +EDGE_SE3:QUAT 484 534 4.24037 -0.217127 -4.85122 -0.0717745 0.0742473 0.0730336 0.991969 1 1.92593e-19 1.92593e-19 2.79022e-08 1.75649e-09 2.34179e-09 1 1.92593e-19 2.79022e-08 1.75649e-09 2.34179e-09 1 2.79022e-08 1.75649e-09 2.34179e-09 4086.46 -14.5176 663.288 3973.01 15.1718 4085.73 +EDGE_SE3:QUAT 483 534 3.79621 9.58321 -4.83063 0.0147873 -0.0077528 -0.0133033 0.999772 1 3.00927e-21 3.00927e-21 2.55145e-11 -5.20131e-11 -3.46904e-09 1 3.00927e-21 2.55145e-11 -5.20131e-11 -3.46904e-09 1 2.55145e-11 -5.20131e-11 -3.46904e-09 4000.01 -0.453353 -59.6368 3999.78 0.411683 4000.18 +EDGE_SE3:QUAT 484 533 3.54192 -9.59398 -4.67868 0.0119216 -0.212849 -0.199872 0.956349 1 7.70372e-19 7.70372e-19 -1.13881e-08 6.11601e-09 5.76701e-08 1 7.70372e-19 -1.13881e-08 6.11601e-09 5.76701e-08 1 -1.13881e-08 6.11601e-09 5.76701e-08 4685.45 -254.692 -1795.22 3905.38 274.51 4526.22 +EDGE_SE3:QUAT 485 535 4.17807 0.274232 -4.70737 -0.125813 0.0915619 -0.0649802 0.98568 1 1.92593e-19 1.92593e-19 -2.40946e-09 -2.73114e-08 -3.84016e-09 1 1.92593e-19 -2.40946e-09 -2.73114e-08 -3.84016e-09 1 -2.40946e-09 -2.73114e-08 -3.84016e-09 4031.24 -49.9591 624.082 3982.68 -40.4896 4077.67 +EDGE_SE3:QUAT 484 535 3.80977 9.6008 -4.79394 -0.00185155 0.0540284 0.0922149 0.994271 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4046.34 6.08552 433.101 3988.98 20.3989 4012.34 +EDGE_SE3:QUAT 485 534 3.54457 -9.34757 -4.66389 0.0204529 0.0750573 -0.130549 0.988385 1 3.00927e-21 3.00927e-21 3.47113e-09 -4.52723e-10 2.73145e-10 1 3.00927e-21 3.47113e-09 -4.52723e-10 2.73145e-10 1 3.47113e-09 -4.52723e-10 2.73145e-10 4095.19 -12.2138 629.934 3977.4 -41.0553 4028.69 +EDGE_SE3:QUAT 486 536 4.08114 -0.0609272 -5.18638 -0.014475 -0.0938598 -0.12168 0.988016 1 1.88079e-22 1.88079e-22 -8.72754e-10 1.06989e-10 8.35336e-11 1 1.88079e-22 -8.72754e-10 1.06989e-10 8.35336e-11 1 -8.72754e-10 1.06989e-10 8.35336e-11 4145.68 -21.1373 -779.456 3966.41 48.7886 4087.29 +EDGE_SE3:QUAT 485 536 3.83917 9.67898 -4.60568 -0.0308447 0.0128974 0.149451 0.988204 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.08 -1.49387 154.291 3998.27 12.6115 3916.54 +EDGE_SE3:QUAT 486 535 3.68991 -9.43546 -4.45887 0.146653 -0.0770629 -0.151659 0.97445 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3935.65 -24.6483 -315.105 3999.76 24.9257 3929.68 +EDGE_SE3:QUAT 487 537 4.11259 0.129088 -4.3748 -0.084511 0.08069 -0.0377765 0.992431 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4062.39 -32.194 610.293 3979.87 -24.1048 4085.25 +EDGE_SE3:QUAT 486 537 3.54664 9.75462 -4.76094 0.0734209 -0.00834315 0.0572107 0.995624 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.74 -4.6369 -116.095 3998.92 -3.49335 3990.21 +EDGE_SE3:QUAT 487 536 3.97854 -9.72335 -4.80744 0.0834073 0.0434912 -0.0666009 0.993336 1 1.92593e-19 1.92593e-19 2.77164e-08 -1.63838e-09 1.49558e-09 1 1.92593e-19 2.77164e-08 -1.63838e-09 1.49558e-09 1 2.77164e-08 -1.63838e-09 1.49558e-09 4014.15 14.4946 412.304 3988.86 -9.77357 4024.23 +EDGE_SE3:QUAT 488 538 3.91541 0.246413 -4.91103 -0.00153452 -0.0471599 -0.0237588 0.998604 1 1.17549e-23 1.17549e-23 -2.17506e-10 5.16641e-12 1.02762e-11 1 1.17549e-23 -2.17506e-10 5.16641e-12 1.02762e-11 1 -2.17506e-10 5.16641e-12 1.02762e-11 4035.84 -0.984227 -380.356 3991.12 4.54184 4033.59 +EDGE_SE3:QUAT 487 538 3.81125 9.5523 -4.66323 -0.0217892 -0.00369146 -0.0824703 0.996348 1 1.20371e-20 1.20371e-20 6.9141e-09 -5.70665e-10 -5.0094e-11 1 1.20371e-20 6.9141e-09 -5.70665e-10 -5.0094e-11 1 6.9141e-09 -5.70665e-10 -5.0094e-11 3998.73 0.563903 -50.6773 3999.8 2.36492 3973.42 +EDGE_SE3:QUAT 488 537 3.57329 -9.39978 -4.68207 -0.0886402 0.0635543 0.0020384 0.994032 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.99 -23.3876 511.705 3984.69 -8.15091 4064.4 +EDGE_SE3:QUAT 489 539 3.74065 -0.343565 -4.49035 0.0290507 0.15365 -0.161624 0.974385 1 7.52316e-22 7.52316e-22 1.77749e-09 -2.92728e-10 2.82384e-10 1 7.52316e-22 1.77749e-09 -2.92728e-10 2.82384e-10 1 1.77749e-09 -2.92728e-10 2.82384e-10 4408.71 -80.9762 1348.46 3915.18 -118.891 4307.59 +EDGE_SE3:QUAT 488 539 3.73892 9.46647 -5.22938 0.13544 0.032162 0.0545446 0.98876 1 7.70372e-19 7.70372e-19 5.4931e-08 3.40304e-09 8.96706e-10 1 7.70372e-19 5.4931e-08 3.40304e-09 8.96706e-10 1 5.4931e-08 3.40304e-09 8.96706e-10 3932.87 9.52327 161.743 3999.18 5.2674 3994.34 +EDGE_SE3:QUAT 489 538 3.34673 -9.62712 -4.67549 0.0131586 -0.0111924 -0.192367 0.981171 1 6.01853e-21 6.01853e-21 2.73616e-09 -4.07232e-09 3.82348e-11 1 6.01853e-21 2.73616e-09 -4.07232e-09 3.82348e-11 1 2.73616e-09 -4.07232e-09 3.82348e-11 4000.02 -0.569981 -54.9699 3999.93 4.17308 3852.7 +EDGE_SE3:QUAT 490 540 4.48257 0.0466234 -4.6661 -0.0616182 -0.0771117 0.0585458 0.993393 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4066.14 25.8039 -576.462 3981.99 -25.2891 4067.62 +EDGE_SE3:QUAT 489 540 3.9044 9.58271 -4.5083 -0.063852 -0.068374 0.0695298 0.993184 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4043.28 22.416 -492.371 3987.22 -23.2729 4040.25 +EDGE_SE3:QUAT 490 539 3.35515 -9.26574 -4.25805 -0.0350553 0.072013 -0.167286 0.98265 1 7.70372e-19 7.70372e-19 3.13556e-09 -3.2053e-09 5.4955e-08 1 7.70372e-19 3.13556e-09 -3.2053e-09 5.4955e-08 1 3.13556e-09 -3.2053e-09 5.4955e-08 4053.15 -24.7068 487.044 3989.74 -43.3424 3946.13 +EDGE_SE3:QUAT 491 541 4.20156 -0.128898 -4.98161 -0.0799784 0.0579856 0.113524 0.988612 1 1.92593e-19 1.92593e-19 2.07133e-09 -1.83372e-09 2.77146e-08 1 1.92593e-19 2.07133e-09 -1.83372e-09 2.77146e-08 1 2.07133e-09 -1.83372e-09 2.77146e-08 4053.59 -12.3421 568.946 3979.2 26.6145 4027.62 +EDGE_SE3:QUAT 490 541 3.55751 9.48618 -4.5378 0.097605 -0.0317804 0.120653 0.987373 1 8.1852e-19 8.1852e-19 -5.66315e-08 7.439e-09 1.77426e-09 1 8.1852e-19 -5.66315e-08 7.439e-09 1.77426e-09 1 -5.66315e-08 7.439e-09 1.77426e-09 3998.77 -15.5766 -387.861 3989.1 -21.7549 3978.65 +EDGE_SE3:QUAT 491 540 3.83772 -9.77221 -4.41192 0.120918 -0.0691975 0.0629798 0.988243 1 2.40741e-19 2.40741e-19 2.66282e-08 2.84895e-09 1.15878e-08 1 2.40741e-19 2.66282e-08 2.84895e-09 1.15878e-08 1 2.66282e-08 2.84895e-09 1.15878e-08 4042.44 -33.586 -643.669 3974.52 -4.60264 4085.06 +EDGE_SE3:QUAT 492 542 4.01098 -0.298467 -4.68528 -0.0334279 0.138602 -0.103487 0.984359 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4283.1 -69.663 1110.79 3940.03 -83.0439 4244.73 +EDGE_SE3:QUAT 491 542 3.46902 9.81367 -5.06089 -0.143603 0.0711445 0.0165208 0.986937 1 7.52316e-22 7.52316e-22 1.27827e-10 -2.50224e-10 1.73062e-09 1 7.52316e-22 1.27827e-10 -2.50224e-10 1.73062e-09 1 1.27827e-10 -2.50224e-10 1.73062e-09 4002.89 -42.8876 590.599 3980.49 -13.4343 4084.29 +EDGE_SE3:QUAT 492 541 3.67409 -9.71595 -4.2993 0.0871661 0.0669604 0.0114557 0.993875 1 2.0463e-19 2.0463e-19 2.82673e-08 1.27227e-09 8.74381e-09 1 2.0463e-19 2.82673e-08 1.27227e-09 8.74381e-09 1 2.82673e-08 1.27227e-09 8.74381e-09 4037.36 24.8621 525.038 3984.27 12.2195 4067.23 +EDGE_SE3:QUAT 493 543 4.19705 0.0160425 -4.75091 -0.0672585 0.0410665 -0.0932612 0.992518 1 1.92593e-19 1.92593e-19 2.76006e-08 -2.73027e-09 7.63878e-10 1 1.92593e-19 2.76006e-08 -2.73027e-09 7.63878e-10 1 2.76006e-08 -2.73027e-09 7.63878e-10 3997.01 -10.0126 247.939 3997.27 -12.2301 3980.31 +EDGE_SE3:QUAT 492 543 3.5871 9.32155 -4.7486 0.123717 -0.0657757 0.170428 0.975357 1 1.92593e-19 1.92593e-19 4.20649e-09 -2.71579e-08 2.66646e-09 1 1.92593e-19 4.20649e-09 -2.71579e-08 2.66646e-09 1 4.20649e-09 -2.71579e-08 2.66646e-09 4078.96 -22.6125 -764.054 3962.24 -52.4276 4024 +EDGE_SE3:QUAT 493 542 3.45957 -9.35341 -4.3746 -0.0784775 -0.107997 -0.125612 0.983056 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4214 1.72099 -1005.97 3942.36 46.2752 4175.52 +EDGE_SE3:QUAT 494 544 4.27012 0.00375278 -4.94523 -0.0277254 -0.0181847 -0.104061 0.994018 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.78 1.48159 -177.65 3997.87 9.5373 3964.54 +EDGE_SE3:QUAT 493 544 3.77962 9.49871 -4.64708 -0.0822474 0.106759 0.127977 0.982578 1 1.92593e-19 1.92593e-19 -3.10907e-09 2.73261e-08 1.50344e-09 1 1.92593e-19 -3.10907e-09 2.73261e-08 1.50344e-09 1 -3.10907e-09 2.73261e-08 1.50344e-09 4209.94 -3.41054 1002.38 3942.57 46.3966 4171.49 +EDGE_SE3:QUAT 494 543 3.71089 -9.54956 -4.75078 0.0335148 -0.155764 0.0180496 0.987061 1 4.81482e-20 4.81482e-20 1.44036e-08 1.18168e-10 -2.28482e-09 1 4.81482e-20 1.44036e-08 1.18168e-10 -2.28482e-09 1 1.44036e-08 1.18168e-10 -2.28482e-09 4417.51 -16.9714 -1366.05 3902.3 6.61236 4420.7 +EDGE_SE3:QUAT 495 545 4.36045 0.0861258 -4.58156 0.0149509 0.0104501 0.114006 0.993313 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.04 0.596499 61.682 3999.83 3.12343 3948.95 +EDGE_SE3:QUAT 494 545 3.96901 9.6277 -5.13075 0.145754 -0.0156154 0.0889742 0.985188 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3933.11 -21.7718 -273.417 3993.84 -11.2852 3986.42 +EDGE_SE3:QUAT 495 544 3.57009 -9.31718 -4.19848 0.0314664 0.119212 -0.0303323 0.991906 1 1.20371e-20 1.20371e-20 -7.0884e-09 1.67965e-10 -8.62701e-10 1 1.20371e-20 -7.0884e-09 1.67965e-10 -8.62701e-10 1 -7.0884e-09 1.67965e-10 -8.62701e-10 4238.27 7.15692 1013.71 3941.97 -6.07052 4238.55 +EDGE_SE3:QUAT 496 546 4.38376 -0.0798094 -4.48247 0.0152043 0.127113 0.100365 0.98668 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4251.35 49.085 1035.88 3944.76 66.1661 4211.98 +EDGE_SE3:QUAT 495 546 3.75425 9.51941 -4.75025 -0.021932 -0.0333693 -0.0175743 0.999048 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.54 2.55383 -272.37 3995.36 1.83005 4017.23 +EDGE_SE3:QUAT 496 545 3.55859 -9.27987 -4.7042 -0.0759514 -0.0976033 -0.204218 0.971082 1 8.1852e-19 8.1852e-19 -2.06553e-08 9.31378e-10 5.71076e-08 1 8.1852e-19 -2.06553e-08 9.31378e-10 5.71076e-08 1 -2.06553e-08 9.31378e-10 5.71076e-08 4192.8 -22.3536 -954.309 3950.6 90.2959 4049.06 +EDGE_SE3:QUAT 497 547 4.33635 -0.273921 -4.45279 0.0368726 -0.108718 -0.0209481 0.993168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4185.05 -24.5998 -893.464 3954.97 21.3209 4188.74 +EDGE_SE3:QUAT 496 547 4.12201 9.56649 -4.45911 0.0398661 0.0456994 0.171473 0.983321 1 8.1852e-19 8.1852e-19 -1.53096e-08 -5.39149e-09 -5.51177e-08 1 8.1852e-19 -1.53096e-08 -5.39149e-09 -5.51177e-08 1 -1.53096e-08 -5.39149e-09 -5.51177e-08 4011.31 10.28 268.991 3997.34 21.8631 3900.05 +EDGE_SE3:QUAT 497 546 3.46915 -9.79014 -4.5735 0.0643992 -0.0201359 0.0322966 0.997198 1 1.92593e-19 1.92593e-19 -2.77075e-08 -8.18803e-10 6.69077e-10 1 1.92593e-19 -2.77075e-08 -8.18803e-10 6.69077e-10 1 -2.77075e-08 -8.18803e-10 6.69077e-10 3991.94 -5.8522 -185.084 3997.72 -2.34973 4004.36 +EDGE_SE3:QUAT 498 548 4.14401 0.129468 -4.72036 0.147165 0.0924635 -0.131326 0.975985 1 7.70372e-19 7.70372e-19 -5.57295e-08 5.7773e-09 -7.07975e-09 1 7.70372e-19 -5.57295e-08 5.7773e-09 -7.07975e-09 1 -5.57295e-08 5.7773e-09 -7.07975e-09 4137.84 43.371 975.03 3943.11 -29.1121 4155.48 +EDGE_SE3:QUAT 497 548 3.2765 9.68652 -4.95627 -0.040194 -0.0902618 0.22859 0.968496 1 8.1852e-19 8.1852e-19 1.70634e-08 7.66379e-09 -5.51794e-08 1 8.1852e-19 1.70634e-08 7.66379e-09 -5.51794e-08 1 1.70634e-08 7.66379e-09 -5.51794e-08 4070.45 42.6273 -564.72 3990.88 -67.9481 3867.9 +EDGE_SE3:QUAT 498 547 3.32055 -9.30475 -4.54885 0.0965526 -0.0599905 0.0622691 0.991565 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.3 -22.1169 -551.597 3980.85 -8.18382 4059.08 +EDGE_SE3:QUAT 499 549 4.111 -0.146412 -4.71361 -0.038031 0.0134117 -0.140845 0.98921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.49 -0.500805 40.5043 4000 -1.30707 3920.93 +EDGE_SE3:QUAT 498 549 3.97708 9.50398 -4.81285 0.0485101 -0.0367613 0.0822929 0.994748 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.24 -5.37666 -340.006 3992.44 -12.8464 4001.56 +EDGE_SE3:QUAT 499 548 3.53742 -9.34067 -4.75716 0.131542 -0.179664 -0.0587632 0.973121 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4381.13 -164.661 -1417.41 3923.51 153.958 4436.53 +EDGE_SE3:QUAT 500 550 4.05509 0.308469 -4.8861 -0.0218337 0.0562253 0.164294 0.984566 1 5.11575e-20 5.11575e-20 5.70079e-09 -1.30979e-08 1.76101e-10 1 5.11575e-20 5.70079e-09 -1.30979e-08 1.76101e-10 1 5.70079e-09 -1.30979e-08 1.76101e-10 4054.85 8.43459 479.866 3986.97 39.6732 3948.79 +EDGE_SE3:QUAT 499 550 3.7387 9.87123 -4.60089 -0.0193172 -0.0334185 -0.0365732 0.998585 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.5 1.69428 -276.3 3995.21 4.61656 4013.64 +EDGE_SE3:QUAT 500 549 3.49711 -9.57249 -4.81218 0.0108392 -0.0225214 -0.0251933 0.99937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.35 -1.25627 -176.99 3998.08 2.35484 4005.28 +EDGE_SE3:QUAT 501 551 4.36237 0.0903248 -4.66159 0.117916 -0.157596 0.129018 0.971912 1 3.85186e-19 3.85186e-19 3.40782e-08 4.64633e-10 -3.40782e-08 1 3.85186e-19 3.40782e-08 4.64633e-10 -3.40782e-08 1 3.40782e-08 4.64633e-10 -3.40782e-08 4478.85 -16.9523 -1557.05 3877.86 -37.6402 4467.88 +EDGE_SE3:QUAT 500 551 3.74229 9.56215 -4.62696 0.168537 -0.104189 0.0224201 0.979917 1 1.93345e-19 1.93345e-19 1.89168e-10 2.75001e-08 -2.91194e-09 1 1.93345e-19 1.89168e-10 2.75001e-08 -2.91194e-09 1 1.89168e-10 2.75001e-08 -2.91194e-09 4070.12 -76.6854 -876.805 3960.61 36.8511 4181.73 +EDGE_SE3:QUAT 501 550 3.33843 -9.66067 -4.70976 -0.108383 -0.136898 0.0385548 0.983883 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4226.44 85.3206 -1081.48 3944.08 -72.1716 4267.48 +EDGE_SE3:QUAT 502 552 4.14455 0.0424411 -4.70295 -0.0290692 0.042602 0.137056 0.98922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.61 1.33295 381.24 3991.08 26.0435 3960.86 +EDGE_SE3:QUAT 501 552 3.71755 9.41481 -5.04337 0.0882395 0.0746007 0.077089 0.990306 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.4 30.326 509.418 3987.5 28.6998 4039.78 +EDGE_SE3:QUAT 502 551 3.62944 -9.68598 -4.75165 -0.10052 0.202383 0.159552 0.960979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4840.97 67.7107 2074.3 3816.71 109.512 4779.56 +EDGE_SE3:QUAT 503 553 4.29969 0.0238274 -4.79808 0.233974 -0.0560409 -0.20456 0.948826 1 1.54074e-18 1.54074e-18 5.00917e-08 -2.46049e-08 -5.00917e-08 1 1.54074e-18 5.00917e-08 -2.46049e-08 -5.00917e-08 1 5.00917e-08 -2.46049e-08 -5.00917e-08 3777.32 43.3359 153.142 3991.59 -37.972 3828.92 +EDGE_SE3:QUAT 502 553 3.72225 9.67811 -4.46139 0.0447083 0.0430034 0.0020136 0.998072 1 9.70488e-20 9.70488e-20 1.38948e-08 1.40109e-08 1.70666e-09 1 9.70488e-20 1.38948e-08 1.40109e-08 1.70666e-09 1 1.38948e-08 1.40109e-08 1.70666e-09 4021.39 7.91465 344.104 3992.79 2.33728 4029.37 +EDGE_SE3:QUAT 503 552 3.19077 -10.1709 -4.25221 -0.111528 -0.0471525 -0.113702 0.986109 1 1.92593e-19 1.92593e-19 -2.76018e-08 2.82911e-09 1.95811e-09 1 1.92593e-19 -2.76018e-08 2.82911e-09 1.95811e-09 1 -2.76018e-08 2.82911e-09 1.95811e-09 4016.67 22.3884 -521.275 3981.51 23.2214 4014.72 +EDGE_SE3:QUAT 504 554 4.07982 -0.123989 -4.8744 0.107715 -0.218144 -0.0392612 0.969159 1 7.70372e-19 7.70372e-19 -5.11715e-09 -5.35995e-08 7.56232e-09 1 7.70372e-19 -5.11715e-09 -5.35995e-08 7.56232e-09 1 -5.11715e-09 -5.35995e-08 7.56232e-09 4732.54 -206.417 -1930.04 3859.91 198.806 4772.78 +EDGE_SE3:QUAT 503 554 3.21448 9.73217 -4.99355 0.0593679 0.0688483 0.0491979 0.994643 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.8 20.7794 517.845 3985.11 19.1465 4056.22 +EDGE_SE3:QUAT 504 553 3.23512 -9.9258 -4.68166 -0.0294509 0.0162736 -0.036772 0.998757 1 1.20371e-20 1.20371e-20 -6.93323e-09 2.61598e-10 -9.74387e-11 1 1.20371e-20 -6.93323e-09 2.61598e-10 -9.74387e-11 1 -6.93323e-09 2.61598e-10 -9.74387e-11 3999.94 -1.8572 116.857 3999.22 -2.23017 3998 +EDGE_SE3:QUAT 505 555 3.9938 0.0534991 -4.62851 0.0629667 -0.0539962 -0.0522364 0.995184 1 4.81482e-20 4.81482e-20 6.50718e-10 -9.56718e-10 -1.38766e-08 1 4.81482e-20 6.50718e-10 -9.56718e-10 -1.38766e-08 1 6.50718e-10 -9.56718e-10 -1.38766e-08 4021.98 -15.3399 -391.238 3991.63 13.9087 4026.93 +EDGE_SE3:QUAT 504 555 3.44771 9.4085 -5.04658 -0.0961241 0.104535 -0.00500945 0.989852 1 1.92593e-19 1.92593e-19 7.03697e-10 2.74653e-08 2.75572e-09 1 1.92593e-19 7.03697e-10 2.74653e-08 2.75572e-09 1 7.03697e-10 2.74653e-08 2.75572e-09 4135.95 -46.5582 849.491 3960.62 -28.1669 4172.81 +EDGE_SE3:QUAT 505 554 3.54366 -9.46007 -4.64316 -0.0168989 -0.140827 0.0166436 0.98975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4333.22 20.9899 -1203.84 3921.87 -20.9371 4333.25 +EDGE_SE3:QUAT 506 556 4.07335 -0.249319 -4.64277 -0.00727038 0.107986 0.0380891 0.993396 1 4.81482e-20 4.81482e-20 1.53794e-09 1.3424e-11 1.41169e-08 1 4.81482e-20 1.53794e-09 1.3424e-11 1.41169e-08 1 1.53794e-09 1.3424e-11 1.41169e-08 4193.77 7.63859 901.98 3953.42 17.1585 4188.18 +EDGE_SE3:QUAT 505 556 3.443 9.52333 -4.76182 0.0852702 0.118204 0.0877667 0.985421 1 1.92593e-19 1.92593e-19 -3.02469e-09 2.72921e-08 -2.96917e-09 1 1.92593e-19 -3.02469e-09 2.72921e-08 -2.96917e-09 1 -3.02469e-09 2.72921e-08 -2.96917e-09 4149.14 65.8577 864.199 3965.46 66.2968 4147.41 +EDGE_SE3:QUAT 506 555 3.06268 -9.44947 -4.67372 -0.00965691 -0.0277577 -0.229976 0.972752 1 1.88079e-22 1.88079e-22 -8.45208e-10 1.99665e-10 2.53218e-11 1 1.88079e-22 -8.45208e-10 1.99665e-10 2.53218e-11 1 -8.45208e-10 1.99665e-10 2.53218e-11 4012.93 -3.50825 -231.071 3997.33 26.9322 3801.75 +EDGE_SE3:QUAT 507 557 3.89163 0.139387 -4.39011 0.0361834 -0.187856 0.0579459 0.979818 1 7.70372e-19 7.70372e-19 2.66005e-09 -5.44209e-08 8.73778e-10 1 7.70372e-19 2.66005e-09 -5.44209e-08 8.73778e-10 1 2.66005e-09 -5.44209e-08 8.73778e-10 4641.1 16.305 -1732.95 3856.23 -32.4927 4632.91 +EDGE_SE3:QUAT 506 557 3.58415 9.72295 -4.98819 -0.0180846 0.0427458 -0.0607117 0.997076 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4025.5 -5.48606 328.614 3993.66 -10.75 4012.07 +EDGE_SE3:QUAT 507 556 3.16305 -9.73193 -4.3361 -0.106166 -0.0063992 -0.171018 0.97951 1 7.70372e-19 7.70372e-19 2.30637e-09 5.44264e-09 -5.44864e-08 1 7.70372e-19 2.30637e-09 5.44264e-09 -5.44864e-08 1 2.30637e-09 5.44264e-09 -5.44864e-08 3970.85 14.7371 -261.211 3993.47 26.7073 3898.95 +EDGE_SE3:QUAT 508 558 4.03934 -0.0877641 -4.34066 0.0396092 -0.116865 -0.0294287 0.991921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4212.49 -31.6233 -960.711 3949.02 29.5271 4215.3 +EDGE_SE3:QUAT 507 558 3.69912 9.68055 -5.15899 0.171889 -0.160512 0.149766 0.960344 1 1.54074e-18 1.54074e-18 -4.57574e-08 -1.31311e-08 -4.57574e-08 1 1.54074e-18 -4.57574e-08 -1.31311e-08 -4.57574e-08 1 -4.57574e-08 -1.31311e-08 -4.57574e-08 4515.97 -61.0072 -1714.95 3857.54 -13.0824 4544.44 +EDGE_SE3:QUAT 508 557 3.29932 -9.58136 -4.86 0.023667 -0.123882 0.00896259 0.991974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4256.01 -10.8781 -1048.67 3938.46 3.95864 4257.93 +EDGE_SE3:QUAT 509 559 4.01788 -0.270227 -4.67112 0.0785391 0.0698176 0.00831212 0.994428 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.73 23.656 554.367 3982.24 11.4901 4075.12 +EDGE_SE3:QUAT 508 559 3.3758 9.94864 -4.98556 0.036684 0.0301508 0.150984 0.987395 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.42 4.55211 167.236 3998.98 11.2775 3915.61 +EDGE_SE3:QUAT 509 558 3.69683 -9.96099 -4.58941 -0.0654605 0.0744416 0.103876 0.989638 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4095.39 -7.46657 680.554 3971.66 28.1763 4069.37 +EDGE_SE3:QUAT 510 560 4.02291 -0.134406 -4.68333 -0.00525413 -0.0449703 0.0792715 0.995824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.93 4.69715 -353.731 3992.62 -14.4501 4005.9 +EDGE_SE3:QUAT 509 560 3.96208 9.83612 -5.24361 -0.0746001 -0.0470901 -0.0123194 0.996025 1 1.95602e-19 1.95602e-19 2.7943e-08 1.11863e-10 -4.82122e-09 1 1.95602e-19 2.7943e-08 1.11863e-10 -4.82122e-09 1 2.7943e-08 1.11863e-10 -4.82122e-09 4014.96 14.2188 -387.673 3990.83 -1.69569 4036.62 +EDGE_SE3:QUAT 510 559 3.40974 -9.53778 -4.50712 -0.0662495 -0.0757059 -0.0523559 0.993548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4087.24 15.3897 -655.957 3973.85 8.2912 4093.83 +EDGE_SE3:QUAT 511 561 3.94908 -0.0139449 -4.54317 0.104765 0.0173439 -0.0762522 0.991418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3969.17 12.5069 230.853 3995.9 -8.28018 3989.82 +EDGE_SE3:QUAT 510 561 3.04 10.0704 -4.61765 0.110151 -0.0254399 -0.00508173 0.993576 1 3.00927e-21 3.00927e-21 8.23437e-11 -3.83974e-10 -3.45123e-09 1 3.00927e-21 8.23437e-11 -3.83974e-10 -3.45123e-09 1 8.23437e-11 -3.83974e-10 -3.45123e-09 3960.8 -10.6094 -193.535 3997.87 2.07793 4009.23 +EDGE_SE3:QUAT 511 560 3.14603 -9.94927 -4.55213 0.270709 -0.21758 0.15721 0.924479 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4986.15 -277.404 -2598.91 3777.75 219.162 5180.42 +EDGE_SE3:QUAT 512 562 3.97015 0.237781 -5.03233 0.0386099 -0.0566023 -0.169439 0.983156 1 9.62965e-20 9.62965e-20 1.12833e-08 -1.60603e-08 2.1057e-10 1 9.62965e-20 1.12833e-08 -1.60603e-08 2.1057e-10 1 1.12833e-08 -1.60603e-08 2.1057e-10 4025.33 -15.6656 -357.271 3994.85 30.354 3916.45 +EDGE_SE3:QUAT 511 562 3.56699 9.85992 -4.90495 -0.388324 -0.00725166 0.08354 0.9177 1 1.92593e-19 1.92593e-19 1.51891e-09 -1.0687e-08 2.55496e-08 1 1.92593e-19 1.51891e-09 -1.0687e-08 2.55496e-08 1 1.51891e-09 -1.0687e-08 2.55496e-08 3417.6 -83.6606 305.179 3989.67 10.1693 3992.87 +EDGE_SE3:QUAT 512 561 3.35427 -9.90442 -4.87595 0.0407059 0.118971 -0.0341745 0.991474 1 1.20371e-20 1.20371e-20 8.65973e-10 2.39497e-10 7.08644e-09 1 1.20371e-20 8.65973e-10 2.39497e-10 7.08644e-09 1 8.65973e-10 2.39497e-10 7.08644e-09 4236.75 11.1934 1016.25 3941.67 -4.91387 4238.71 +EDGE_SE3:QUAT 513 563 4.31704 -0.173157 -4.7093 0.137846 0.103934 0.0808215 0.981664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.56 63.0295 680.566 3981.91 54.5071 4085.44 +EDGE_SE3:QUAT 512 563 3.5738 9.37966 -4.88041 0.121987 -0.175088 0.0701744 0.974443 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4539.48 -72.4642 -1659.8 3867.71 35.4401 4579.3 +EDGE_SE3:QUAT 513 562 3.23538 -9.78941 -4.65611 0.0268137 -0.0536041 -0.204657 0.976997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4025.33 -14.3262 -339.252 3995.78 33.6567 3860.67 +EDGE_SE3:QUAT 514 564 4.20011 -0.188852 -5.16775 -0.11659 0.0750462 0.0341481 0.989752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4048.41 -35.7453 649.407 3975.14 -5.86556 4098.11 +EDGE_SE3:QUAT 513 564 3.83003 9.555 -4.9514 0.115522 -0.16642 0.112225 0.972813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4523.9 -27.1135 -1625.73 3869.32 -20.5115 4526.91 +EDGE_SE3:QUAT 514 563 2.67668 -9.65213 -4.74634 -0.0653712 -0.0998741 -0.0282859 0.992447 1 1.92593e-19 1.92593e-19 2.81334e-08 -4.36491e-10 -2.90913e-09 1 1.92593e-19 2.81334e-08 -4.36491e-10 -2.90913e-09 1 2.81334e-08 -4.36491e-10 -2.90913e-09 4154.54 23.4754 -846.162 3958.52 -3.68991 4168.43 +EDGE_SE3:QUAT 515 565 4.32192 0.0195578 -4.89947 -0.00797411 0.0883584 -0.0658145 0.99388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4123.56 -15.5831 714.561 3970.71 -26.8253 4106.48 +EDGE_SE3:QUAT 514 565 3.52374 9.87859 -4.76695 -0.0527941 -0.0232997 0.0260543 0.997994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.99 4.62824 -169.201 3998.37 -2.73305 4004.42 +EDGE_SE3:QUAT 515 564 3.5239 -9.71615 -4.53718 0.142804 -0.0496035 -0.089557 0.984442 1 9.62965e-19 9.62965e-19 -5.53294e-08 9.73623e-09 2.85586e-08 1 9.62965e-19 -5.53294e-08 9.73623e-09 2.85586e-08 1 -5.53294e-08 9.73623e-09 2.85586e-08 3930.64 -14.9436 -229.295 3998.84 11.6957 3980.13 +EDGE_SE3:QUAT 516 566 4.43289 -0.0237832 -4.6206 -0.012615 0.0696912 0.0140801 0.997389 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.76 -2.08842 569.096 3980.42 2.70305 4078.6 +EDGE_SE3:QUAT 515 566 3.42965 9.64211 -5.4167 0.000898982 0.0548534 -0.0581457 0.9968 1 4.81482e-20 4.81482e-20 7.62091e-10 -7.67711e-11 1.39168e-08 1 4.81482e-20 7.62091e-10 -7.67711e-11 1.39168e-08 1 7.62091e-10 -7.67711e-11 1.39168e-08 4048.22 -4.03877 441.835 3988.25 -13.171 4034.7 +EDGE_SE3:QUAT 516 565 3.21467 -9.71089 -4.67639 0.00126197 -0.0401281 -0.175445 0.98367 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.12 -6.55428 -305.204 3995.24 26.7376 3900 +EDGE_SE3:QUAT 517 567 3.77343 -0.0429499 -4.76177 0.0660146 -0.0213469 -0.091629 0.993373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.68 -2.75868 -95.5293 3999.74 3.54035 3968.53 +EDGE_SE3:QUAT 516 567 3.39704 9.73313 -4.70052 -0.143267 0.0732819 -0.0144607 0.986861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.56 -42.3118 551.961 3984.4 -21.0708 4073.83 +EDGE_SE3:QUAT 517 566 3.52371 -9.78783 -4.66318 -0.0103403 0.0866282 -0.248795 0.964619 1 4.81482e-20 4.81482e-20 -1.35475e-08 3.56963e-09 -9.92232e-10 1 4.81482e-20 -1.35475e-08 3.56963e-09 -9.92232e-10 1 -1.35475e-08 3.56963e-09 -9.92232e-10 4090.02 -41.226 610.472 3987.32 -78.8905 3842.85 +EDGE_SE3:QUAT 518 568 4.09129 -0.141309 -4.95335 -0.0730019 -0.0540869 0.0188131 0.995686 1 1.20371e-20 1.20371e-20 3.53761e-10 5.26049e-10 -6.94609e-09 1 1.20371e-20 3.53761e-10 5.26049e-10 -6.94609e-09 1 3.53761e-10 5.26049e-10 -6.94609e-09 4021.54 16.6411 -416.311 3990 -8.8035 4041.44 +EDGE_SE3:QUAT 517 568 3.70168 10.0307 -4.95726 0.0234684 -0.0808042 0.0496869 0.995214 1 1.20371e-20 1.20371e-20 7.00058e-09 3.26904e-10 -5.81573e-10 1 1.20371e-20 7.00058e-09 3.26904e-10 -5.81573e-10 1 7.00058e-09 3.26904e-10 -5.81573e-10 4108.17 -0.229004 -673.573 3972.91 -14.0989 4100.5 +EDGE_SE3:QUAT 518 567 3.07371 -9.59392 -4.86653 0.0391775 0.155971 -0.161074 0.973752 1 1.20371e-20 1.20371e-20 7.12781e-09 -1.14641e-09 1.17279e-09 1 1.20371e-20 7.12781e-09 -1.14641e-09 1.17279e-09 1 7.12781e-09 -1.14641e-09 1.17279e-09 4433.29 -76.7998 1396.73 3908.17 -117.082 4335.65 +EDGE_SE3:QUAT 519 569 4.37527 0.185015 -4.85075 -0.0454494 0.0810092 0.0199407 0.995477 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4101.78 -13.11 672.512 3973.02 -0.352115 4108.45 +EDGE_SE3:QUAT 518 569 3.39745 9.94071 -5.25674 -0.0295669 -0.0657114 0.0380197 0.996676 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4062.38 11.7555 -517.569 3984.26 -13.1633 4060.09 +EDGE_SE3:QUAT 519 568 3.23391 -9.82799 -4.61844 -0.0107232 0.010683 0.00777191 0.999855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.41 -0.444284 86.4769 3999.53 0.307805 4001.63 +EDGE_SE3:QUAT 520 570 4.20063 -0.127491 -4.4867 0.143286 -0.203048 0.135233 0.959142 1 1.73334e-18 1.73334e-18 5.67678e-08 -4.56545e-08 2.07694e-08 1 1.73334e-18 5.67678e-08 -4.56545e-08 2.07694e-08 1 5.67678e-08 -4.56545e-08 2.07694e-08 4848.67 -35.4891 -2142.54 3802.68 -10.1215 4857.64 +EDGE_SE3:QUAT 519 570 3.28246 10.0027 -4.67032 0.0745561 -0.0482038 -0.10872 0.9901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.92 -13.068 -280.108 3996.83 16.1339 3971.87 +EDGE_SE3:QUAT 520 569 3.06719 -10.01 -4.4415 0.0238551 0.0268592 -0.0839541 0.995822 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.72 1.23605 237.109 3996.39 -9.8569 3985.8 +EDGE_SE3:QUAT 521 571 4.06342 -0.128431 -4.95887 0.0500309 0.0968776 -0.0222063 0.99379 1 1.20371e-20 1.20371e-20 6.97355e-10 3.29653e-10 7.03163e-09 1 1.20371e-20 6.97355e-10 3.29653e-10 7.03163e-09 1 6.97355e-10 3.29653e-10 7.03163e-09 4148.68 17.1063 812.373 3961.5 2.09852 4156.72 +EDGE_SE3:QUAT 520 571 3.55152 9.62364 -5.12743 -0.203762 0.0601272 -0.0694452 0.974702 1 4.81482e-20 4.81482e-20 -1.22e-09 -1.3506e-08 -2.92504e-09 1 4.81482e-20 -1.22e-09 -1.3506e-08 -2.92504e-09 1 -1.22e-09 -1.3506e-08 -2.92504e-09 3852.51 -25.3661 283.183 3998.82 -15.9805 3999.3 +EDGE_SE3:QUAT 521 570 3.42447 -9.58409 -4.48792 0.0359779 -0.162605 -0.102067 0.980738 1 4.81482e-20 4.81482e-20 1.42953e-08 -1.7411e-09 -2.19785e-09 1 4.81482e-20 1.42953e-08 -1.7411e-09 -2.19785e-09 1 1.42953e-08 -1.7411e-09 -2.19785e-09 4401.49 -97.749 -1339.11 3917.72 109.511 4365 +EDGE_SE3:QUAT 522 572 3.99256 0.22545 -4.47942 0.23269 0.025407 -0.112038 0.965742 1 8.1852e-19 8.1852e-19 -5.52544e-08 -8.47284e-09 -9.69475e-10 1 8.1852e-19 -5.52544e-08 -8.47284e-09 -9.69475e-10 1 -5.52544e-08 -8.47284e-09 -9.69475e-10 3841.01 61.8168 489.84 3981.23 -17.219 4007.38 +EDGE_SE3:QUAT 521 572 3.23333 9.94597 -4.57579 0.108466 -0.00235529 0.106582 0.988367 1 3.88195e-19 3.88195e-19 -2.71144e-08 -2.37728e-09 -2.71211e-08 1 3.88195e-19 -2.71144e-08 -2.37728e-09 -2.71211e-08 1 -2.71144e-08 -2.37728e-09 -2.71211e-08 3958.46 -10.2921 -155.003 3997.55 -10.0914 3960.08 +EDGE_SE3:QUAT 522 571 3.45112 -9.77652 -4.94573 -0.0940763 -0.185727 -0.0842404 0.974453 1 1.92593e-19 1.92593e-19 2.92782e-08 -1.57667e-09 -5.90676e-09 1 1.92593e-19 2.92782e-08 -1.57667e-09 -5.90676e-09 1 2.92782e-08 -1.57667e-09 -5.90676e-09 4643.12 27.5993 -1781.76 3849.55 4.62055 4650.13 +EDGE_SE3:QUAT 523 573 4.08041 -0.0882878 -4.65385 -0.0403834 -0.0456347 0.155907 0.98589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.35 10.2986 -277.454 3996.9 -20.9905 3921.65 +EDGE_SE3:QUAT 522 573 3.66354 9.88325 -5.02692 0.0680345 0.0517761 0.0232481 0.996067 1 2.40741e-19 2.40741e-19 -2.81996e-08 1.29781e-08 -2.3218e-09 1 2.40741e-19 -2.81996e-08 1.29781e-08 -2.3218e-09 1 -2.81996e-08 1.29781e-08 -2.3218e-09 4020.15 14.944 395.25 3991 8.70803 4036.5 +EDGE_SE3:QUAT 523 572 2.93242 -9.34006 -4.916 -0.0208902 -0.0567366 -0.330029 0.942033 1 1.17549e-21 1.17549e-21 -2.05783e-09 7.20666e-10 1.2532e-10 1 1.17549e-21 -2.05783e-09 7.20666e-10 1.2532e-10 1 -2.05783e-09 7.20666e-10 1.2532e-10 4051.21 -22.8178 -463.95 3993.29 77.893 3617.28 +EDGE_SE3:QUAT 524 574 3.75456 -0.0251417 -4.8188 -0.0245581 -0.0855809 -0.0187114 0.995853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4119.06 5.93833 -707.577 3970.25 2.62656 4120.08 +EDGE_SE3:QUAT 523 574 3.52128 9.91522 -4.94963 0.0616228 0.0680618 0.147829 0.984742 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.59 23.2315 418.789 3993.09 33.5345 3955.36 +EDGE_SE3:QUAT 524 573 3.29078 -10.0751 -4.97008 -0.0939993 0.0637659 0.0880802 0.989616 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4055.12 -20.0897 608.803 3976.5 17.3407 4059.43 +EDGE_SE3:QUAT 525 575 4.04273 0.172062 -4.81979 0.0376384 -0.00106439 0.137689 0.98976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.45 -1.53669 -69.6204 3999.5 -6.17098 3925.28 +EDGE_SE3:QUAT 524 575 3.63138 9.97452 -5.01834 -0.0414283 0.021994 0.0101889 0.998847 1 4.81482e-20 4.81482e-20 1.3876e-08 1.15885e-10 3.16157e-10 1 4.81482e-20 1.3876e-08 1.15885e-10 3.16157e-10 1 1.3876e-08 1.15885e-10 3.16157e-10 4001.3 -3.67415 180.86 3997.94 0.431666 4007.75 +EDGE_SE3:QUAT 525 574 3.43859 -10.1421 -4.90335 -0.117586 -0.172876 -0.054182 0.976397 1 1.92593e-19 1.92593e-19 2.89758e-08 -4.10916e-10 -5.35291e-09 1 1.92593e-19 2.89758e-08 -4.10916e-10 -5.35291e-09 1 2.89758e-08 -4.10916e-10 -5.35291e-09 4508.98 79.1211 -1604.86 3875.79 -46.1855 4552.54 +EDGE_SE3:QUAT 526 576 3.80248 -0.051101 -4.74562 0.00909193 0.0316514 -0.0275424 0.999078 1 5.11575e-20 5.11575e-20 3.84831e-09 1.37713e-08 9.57953e-12 1 5.11575e-20 3.84831e-09 1.37713e-08 9.57953e-12 1 3.84831e-09 1.37713e-08 9.57953e-12 4016.09 0.50722 256.823 3995.89 -3.36342 4013.39 +EDGE_SE3:QUAT 525 576 3.13874 9.94345 -4.93721 0.0528598 0.186257 0.0677649 0.978735 1 1.92593e-19 1.92593e-19 5.20494e-09 2.45278e-09 2.90257e-08 1 1.92593e-19 5.20494e-09 2.45278e-09 2.90257e-08 1 5.20494e-09 2.45278e-09 2.90257e-08 4549.58 119.381 1599.51 3886.34 121.75 4542.39 +EDGE_SE3:QUAT 526 575 3.49013 -10.122 -4.6893 -0.0381099 -0.0326383 0.0568046 0.997124 1 1.08334e-19 1.08334e-19 1.38398e-08 8.32037e-09 -1.39619e-08 1 1.08334e-19 1.38398e-08 8.32037e-09 -1.39619e-08 1 1.38398e-08 8.32037e-09 -1.39619e-08 4007.81 5.55563 -234 3996.94 -7.27307 4000.71 +EDGE_SE3:QUAT 527 577 3.93594 0.056716 -4.81606 0.00855824 0.00681696 -0.176708 0.984202 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.92 0.0238701 69.7859 3999.68 -6.6128 3876.31 +EDGE_SE3:QUAT 526 577 3.40755 9.72902 -5.32967 0.0580834 -0.220766 -0.130532 0.964806 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4716.67 -245.439 -1860.3 3887.09 252.376 4662.01 +EDGE_SE3:QUAT 527 576 3.50492 -9.93135 -4.81554 -0.0092591 0.060401 -0.103761 0.992723 1 3.00927e-21 3.00927e-21 3.46776e-09 -3.6892e-10 1.99643e-10 1 3.00927e-21 3.46776e-09 -3.6892e-10 1.99643e-10 1 3.46776e-09 -3.6892e-10 1.99643e-10 4053.95 -10.9389 469.267 3987.6 -25.6891 4011.23 +EDGE_SE3:QUAT 528 578 3.59474 0.0612898 -4.89156 -0.0887909 -0.0792413 0.144715 0.98229 1 1.92593e-19 1.92593e-19 2.74418e-08 4.4115e-09 -1.36742e-09 1 1.92593e-19 2.74418e-08 4.4115e-09 -1.36742e-09 1 2.74418e-08 4.4115e-09 -1.36742e-09 4019.11 32.188 -458.083 3992.97 -38.6344 3966.88 +EDGE_SE3:QUAT 527 578 3.14602 9.72115 -5.40066 0.0111285 -0.0360906 0.142295 0.989104 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.91 3.05889 -300.213 3994.75 -21.5369 3941.42 +EDGE_SE3:QUAT 528 577 3.54836 -10.0759 -4.60813 0.0395324 0.102177 -0.113768 0.987448 1 2.0463e-19 2.0463e-19 -1.00077e-08 -2.666e-08 -3.2787e-10 1 2.0463e-19 -1.00077e-08 -2.666e-08 -3.2787e-10 1 -1.00077e-08 -2.666e-08 -3.2787e-10 4182.76 -12.6027 889.841 3955.21 -46.017 4137.24 +EDGE_SE3:QUAT 529 579 3.98822 -0.0448274 -4.77321 -0.0738799 -0.0895679 -0.123616 0.985514 1 1.92593e-19 1.92593e-19 -2.79291e-08 3.15115e-09 2.95476e-09 1 1.92593e-19 -2.79291e-08 3.15115e-09 2.95476e-09 1 -2.79291e-08 3.15115e-09 2.95476e-09 4145.11 4.70034 -834.362 3958.75 40.4383 4105.82 +EDGE_SE3:QUAT 528 579 3.41867 9.84032 -5.25205 -0.0677469 -0.0714141 -0.00335588 0.995138 1 7.70419e-19 7.70419e-19 5.57795e-08 3.27428e-10 -3.55766e-09 1 7.70419e-19 5.57795e-08 3.27428e-10 -3.55766e-09 1 5.57795e-08 3.27428e-10 -3.55766e-09 4064.15 20.286 -580.387 3980.1 -7.46611 4082.46 +EDGE_SE3:QUAT 529 578 3.1404 -10.3435 -4.91078 -0.0272605 -0.0285349 -0.100359 0.994168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.61 1.29478 -258.193 3995.7 12.9232 3976.29 +EDGE_SE3:QUAT 530 580 4.07345 -0.0666802 -4.53395 -0.00641746 0.160203 -0.0504593 0.985773 1 5.11575e-20 5.11575e-20 1.28365e-09 1.41786e-10 -1.38316e-08 1 5.11575e-20 1.28365e-09 1.41786e-10 -1.38316e-08 1 1.28365e-09 1.41786e-10 -1.38316e-08 4437.43 -40.6151 1393.53 3900.98 -49.1803 4427.41 +EDGE_SE3:QUAT 529 580 3.58657 10.1104 -4.80713 -0.0800463 -0.0626696 0.127184 0.986656 1 1.92593e-19 1.92593e-19 -2.7499e-08 -3.80013e-09 1.10136e-09 1 1.92593e-19 -2.7499e-08 -3.80013e-09 1.10136e-09 1 -2.7499e-08 -3.80013e-09 1.10136e-09 4006.86 20.7407 -365.544 3994.95 -25.715 3967.79 +EDGE_SE3:QUAT 530 579 2.92546 -9.78693 -4.73932 -0.0799102 -0.0664806 -0.031416 0.994086 1 1.20371e-20 1.20371e-20 4.94361e-10 5.34645e-10 -6.96568e-09 1 1.20371e-20 4.94361e-10 5.34645e-10 -6.96568e-09 1 4.94361e-10 5.34645e-10 -6.96568e-09 4052.96 20.3823 -565.857 3980.56 0.116829 4074.55 +EDGE_SE3:QUAT 531 581 3.74872 -0.181772 -4.77647 -0.0883358 0.0219257 -0.0745225 0.993057 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3970.78 -3.27665 93.5789 3999.78 -2.88332 3979.78 +EDGE_SE3:QUAT 530 581 3.43713 9.68663 -4.82726 -0.020261 0.043656 0.0194893 0.998651 1 1.20371e-20 1.20371e-20 -6.95673e-09 -1.23823e-10 -3.09156e-10 1 1.20371e-20 -6.95673e-09 -1.23823e-10 -3.09156e-10 1 -6.95673e-09 -1.23823e-10 -3.09156e-10 4029.8 -2.77706 356.026 3992.14 2.59999 4029.92 +EDGE_SE3:QUAT 531 580 3.60482 -10.3968 -4.99419 -0.109805 0.17417 0.0409838 0.977716 1 9.75002e-19 9.75002e-19 2.78188e-08 -5.34847e-08 -7.60446e-09 1 9.75002e-19 2.78188e-08 -5.34847e-08 -7.60446e-09 1 2.78188e-08 -5.34847e-08 -7.60446e-09 4509.54 -81.5692 1594.43 3877.76 -53.2727 4551.05 +EDGE_SE3:QUAT 532 582 4.20121 -0.315415 -5.06501 -0.161376 0.109955 0.0481581 0.979565 1 7.70372e-19 7.70372e-19 -5.59517e-08 -6.3839e-10 -6.81885e-09 1 7.70372e-19 -5.59517e-08 -6.3839e-10 -6.81885e-09 1 -5.59517e-08 -6.3839e-10 -6.81885e-09 4124.6 -75.5136 983.586 3948.27 -28.4841 4219.49 +EDGE_SE3:QUAT 531 582 3.4548 9.79498 -5.19125 -0.0302132 -0.143787 -0.0620036 0.987202 1 6.01853e-20 6.01853e-20 -5.03435e-09 5.90582e-10 -1.32498e-08 1 6.01853e-20 -5.03435e-09 5.90582e-10 -1.32498e-08 1 -5.03435e-09 5.90582e-10 -1.32498e-08 4358.95 -11.5856 -1257.74 3915.5 30.9224 4347.23 +EDGE_SE3:QUAT 532 581 3.36312 -10.205 -5.17429 0.0105794 0.10555 -0.0570513 0.99272 1 7.52316e-22 7.52316e-22 -1.76177e-09 9.95212e-11 -1.88227e-10 1 7.52316e-22 -1.76177e-09 9.95212e-11 -1.88227e-10 1 -1.76177e-09 9.95212e-11 -1.88227e-10 4185.36 -11.0097 881.909 3955.58 -25.1728 4172.79 +EDGE_SE3:QUAT 533 583 4.17408 0.0705164 -4.86016 -0.0413802 0.024558 0.0304393 0.998378 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.28 -4.00705 211.315 3997.12 2.63926 4007.42 +EDGE_SE3:QUAT 532 583 3.26861 10.0202 -5.03488 0.0702697 0.0825327 0.0359228 0.993459 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4079.12 29.0168 636.781 3977.54 22.8629 4093.71 +EDGE_SE3:QUAT 533 582 3.33149 -10.1729 -4.68621 -0.0444697 0.124063 0.0848555 0.987639 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4268.63 7.31807 1087.52 3934.52 35.7263 4247.74 +EDGE_SE3:QUAT 534 584 3.99809 0.352271 -5.10731 -0.0228035 0.155311 -0.0540439 0.986123 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4397.72 -53.1451 1326.33 3910.57 -59.2307 4388.11 +EDGE_SE3:QUAT 533 584 3.5005 9.61053 -4.75952 -0.0229638 0.0726149 0.135861 0.987796 1 9.65974e-19 9.65974e-19 2.91119e-09 -2.68051e-08 -5.528e-08 1 9.65974e-19 2.91119e-09 -2.68051e-08 -5.528e-08 1 2.91119e-09 -2.68051e-08 -5.528e-08 4090.02 11.3068 614.003 3978.47 41.4702 4018.29 +EDGE_SE3:QUAT 534 583 3.16965 -10.1274 -4.57223 0.0352454 0.190107 0.0146559 0.981021 1 9.62965e-19 9.62965e-19 2.76628e-08 5.53328e-08 3.19692e-09 1 9.62965e-19 2.76628e-08 5.53328e-08 3.19692e-09 1 2.76628e-08 5.53328e-08 3.19692e-09 4632.8 57.1683 1719.84 3859.97 53.765 4636.91 +EDGE_SE3:QUAT 535 585 3.65057 0.29477 -4.79349 0.0819272 0.135057 -0.00277943 0.987441 1 1.95602e-19 1.95602e-19 -2.89164e-08 -8.74491e-10 -7.40309e-09 1 1.95602e-19 -2.89164e-08 -8.74491e-10 -7.40309e-09 1 -2.89164e-08 -8.74491e-10 -7.40309e-09 4276.79 54.5106 1143.15 3930.88 36.9884 4303.61 +EDGE_SE3:QUAT 534 585 3.36352 9.97578 -4.97529 0.0302974 -0.125523 0.00601461 0.99161 1 7.82409e-19 7.82409e-19 7.01694e-09 -5.50577e-08 7.50377e-10 1 7.82409e-19 7.01694e-09 -5.50577e-08 7.50377e-10 1 7.01694e-09 -5.50577e-08 7.50377e-10 4261.31 -16.3548 -1063.09 3937.08 8.66835 4264.84 +EDGE_SE3:QUAT 535 584 3.25626 -10.1495 -4.64233 -0.221162 -0.0564725 -0.0586026 0.971835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3886.24 64.624 -578.696 3980.38 -6.76236 4068.15 +EDGE_SE3:QUAT 536 586 3.7174 -0.167157 -4.75221 -0.113756 0.11513 -0.0123576 0.986738 1 1.92593e-19 1.92593e-19 -2.80846e-08 1.10724e-09 -3.10652e-09 1 1.92593e-19 -2.80846e-08 1.10724e-09 -3.10652e-09 1 -2.80846e-08 1.10724e-09 -3.10652e-09 4151.54 -63.066 924.601 3955.77 -42.8674 4202.69 +EDGE_SE3:QUAT 535 586 3.17499 10.358 -5.31526 0.0358887 -0.02053 -0.00350678 0.999139 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.45 -2.9553 -162.643 3998.37 0.643067 4006.55 +EDGE_SE3:QUAT 536 585 3.11733 -10.3109 -4.61681 0.112695 0.00704838 -0.0799178 0.990385 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3955.45 10.5583 161.751 3997.65 -7.08337 3980.7 +EDGE_SE3:QUAT 537 587 4.06702 -0.294984 -4.89751 -0.0788682 -0.0189343 0.0151468 0.99659 1 1.92593e-19 1.92593e-19 -2.76769e-08 -4.98414e-10 4.52856e-10 1 1.92593e-19 -2.76769e-08 -4.98414e-10 4.52856e-10 1 -2.76769e-08 -4.98414e-10 4.52856e-10 3979.72 5.27814 -135.86 3998.97 -1.56823 4003.68 +EDGE_SE3:QUAT 536 587 3.36791 9.74001 -4.88436 -0.0679924 0.0493829 -0.108218 0.990569 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.42 -13.4366 298.985 3996.16 -17.3463 3975.07 +EDGE_SE3:QUAT 537 586 3.13997 -9.6614 -4.86089 0.163103 -0.177112 0.110212 0.964304 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4582.74 -89.7191 -1797.86 3850.25 35.0823 4640.57 +EDGE_SE3:QUAT 538 588 3.8546 0.0678378 -5.11726 -0.140953 0.112327 0.000622442 0.983623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4117.8 -71.8416 910.137 3957.94 -43.4101 4197.27 +EDGE_SE3:QUAT 537 588 3.58672 9.97184 -4.97529 -0.166197 0.00620203 -0.156178 0.973627 1 7.70372e-19 7.70372e-19 -5.41468e-08 8.31531e-09 2.50125e-09 1 7.70372e-19 -5.41468e-08 8.31531e-09 2.50125e-09 1 -5.41468e-08 8.31531e-09 2.50125e-09 3903.52 27.9514 -255.755 3992.2 26.0062 3916.44 +EDGE_SE3:QUAT 538 587 3.70302 -10.2276 -4.67964 0.0399547 0.0883087 -0.0930793 0.99093 1 4.81482e-20 4.81482e-20 1.39942e-08 -1.23157e-09 1.32775e-09 1 4.81482e-20 1.39942e-08 -1.23157e-09 1.32775e-09 1 1.39942e-08 -1.23157e-09 1.32775e-09 4134.43 -2.82179 763.661 3965.73 -30.7713 4106.17 +EDGE_SE3:QUAT 539 589 3.79734 -0.163324 -4.80459 0.278811 0.0413509 0.00251484 0.959452 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3709.24 38.342 286.132 3997.43 9.84581 4020.16 +EDGE_SE3:QUAT 538 589 3.28374 9.91662 -5.1517 0.00481489 0.0342706 0.0797631 0.996213 1 7.52316e-22 7.52316e-22 1.73204e-09 1.39567e-10 5.74858e-11 1 7.52316e-22 1.73204e-09 1.39567e-10 5.74858e-11 1 1.73204e-09 1.39567e-10 5.74858e-11 4017.78 2.82284 267.978 3995.75 10.8511 3992.42 +EDGE_SE3:QUAT 539 588 3.20208 -9.67687 -4.96973 -0.0259656 -0.101263 0.120399 0.987206 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4142.86 38.798 -777.23 3969.32 -56.4351 4087.58 +EDGE_SE3:QUAT 540 590 4.05081 -0.305979 -5.08424 -0.0280447 -0.0106908 -0.152565 0.987838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.23 1.22642 -133.131 3998.69 11.2433 3911.27 +EDGE_SE3:QUAT 539 590 3.15946 10.1882 -4.93084 0.0189746 0.0809683 0.273439 0.958288 1 3.08149e-18 3.08149e-18 -6.55414e-09 -6.64185e-09 -1.0734e-07 1 3.08149e-18 -6.55414e-09 -6.64185e-09 -1.0734e-07 1 -6.55414e-09 -6.64185e-09 -1.0734e-07 4064.68 37.0032 522.704 3993.33 71.4663 3767.04 +EDGE_SE3:QUAT 540 589 3.22778 -10.0852 -4.63784 0.0619775 -0.162581 -0.0720338 0.982109 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4387.76 -98.9175 -1332.72 3917.68 100.701 4382.36 +EDGE_SE3:QUAT 541 591 3.91819 0.473598 -5.24711 -0.00176496 -0.161319 0.00380302 0.986893 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4451.19 4.30443 -1417.18 3895.95 -4.70397 4451.15 +EDGE_SE3:QUAT 540 591 2.88569 9.97921 -5.21528 -0.0840695 -0.0232841 0.118479 0.989117 1 1.95602e-19 1.95602e-19 3.47387e-10 -5.85176e-09 2.71529e-08 1 1.95602e-19 3.47387e-10 -5.85176e-09 2.71529e-08 1 3.47387e-10 -5.85176e-09 2.71529e-08 3972.26 1.22448 -62.4715 4000.03 -1.47903 3944.38 +EDGE_SE3:QUAT 541 590 3.29822 -10.2474 -4.76164 0.0430659 -0.102611 -0.0992706 0.988818 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4138.37 -41.1616 -777.94 3969.16 51.5268 4106.37 +EDGE_SE3:QUAT 542 592 4.33425 0.213644 -4.92553 -0.0232936 -0.233241 0.0209041 0.971915 1 1.20371e-20 1.20371e-20 -7.55893e-09 -2.7432e-10 1.80128e-09 1 1.20371e-20 -7.55893e-09 -2.7432e-10 1.80128e-09 1 -7.55893e-09 -2.7432e-10 1.80128e-09 5021.31 78.0168 -2267.48 3788.29 -77.7758 5021.73 +EDGE_SE3:QUAT 541 592 3.38885 9.99598 -5.11615 0.0211425 -0.0816576 -0.0182799 0.996268 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4105.21 -10.4604 -662.909 3974.04 9.91498 4105.66 +EDGE_SE3:QUAT 542 591 3.18414 -10.0456 -4.73309 0.0754164 -0.00750656 -0.255688 0.963784 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.97 7.95384 166.893 3996.38 -31.0873 3744.21 +EDGE_SE3:QUAT 543 593 3.90244 0.278753 -4.97384 -0.0657645 -0.15536 0.00238346 0.985664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4391.34 56.9557 -1342.23 3907.91 -44.4497 4408.61 +EDGE_SE3:QUAT 542 593 3.5976 10.0168 -4.8738 -0.00271653 -0.0258777 0.00347217 0.999655 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.69 0.339548 -207.387 3997.33 -0.406266 4010.68 +EDGE_SE3:QUAT 543 592 2.71063 -9.97872 -5.07451 0.0080096 -0.173937 -0.123653 0.97693 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4493.54 -107.135 -1489.9 3900.65 127.167 4432.63 +EDGE_SE3:QUAT 544 594 3.66937 0.228774 -4.77214 0.173986 0.299702 -0.0986648 0.932831 1 7.70372e-19 7.70372e-19 6.46955e-08 3.93477e-10 2.17584e-08 1 7.70372e-19 6.46955e-08 3.93477e-10 2.17584e-08 1 6.46955e-08 3.93477e-10 2.17584e-08 6047.78 291.02 3657.79 3646.71 303.696 6129.92 +EDGE_SE3:QUAT 543 594 3.23242 9.99968 -5.28235 -0.0153517 -0.0144816 0.149498 0.988537 1 3.00927e-21 3.00927e-21 5.20107e-10 -3.42946e-09 -6.57505e-11 1 3.00927e-21 5.20107e-10 -3.42946e-09 -6.57505e-11 1 5.20107e-10 -3.42946e-09 -6.57505e-11 4000.82 1.04715 -84.8424 3999.71 -5.61515 3912.37 +EDGE_SE3:QUAT 544 593 3.28413 -10.2495 -4.63552 -0.0593723 -0.142898 -0.188747 0.969757 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4381.65 -66.6376 -1318.94 3916.92 120.688 4253.25 +EDGE_SE3:QUAT 545 595 3.59971 0.186412 -4.8547 0.0747767 0.020036 0.109157 0.991005 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3978.22 1.21307 59.2372 4000 1.56247 3952.92 +EDGE_SE3:QUAT 544 595 3.54127 10.299 -4.71526 0.0669661 0.0689107 0.0679856 0.993048 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.32 23.2088 495.183 3987.12 23.3628 4041.77 +EDGE_SE3:QUAT 545 594 2.93837 -10.1603 -4.89774 -0.120753 0.0578063 -0.152926 0.979128 1 7.70372e-19 7.70372e-19 9.41892e-10 -7.39357e-09 5.44243e-08 1 7.70372e-19 9.41892e-10 -7.39357e-09 5.44243e-08 1 9.41892e-10 -7.39357e-09 5.44243e-08 3951.83 -12.7598 219.463 3999.89 -14.1068 3916.6 +EDGE_SE3:QUAT 546 596 3.65972 0.387315 -4.95435 0.0208236 -0.0499423 -0.152476 0.986825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.53 -11.0759 -349.936 3994.07 26.9812 3937.27 +EDGE_SE3:QUAT 545 596 3.59821 10.0431 -5.16923 0.0934735 0.0444557 -0.00527019 0.994615 1 4.70198e-23 4.70198e-23 -1.94459e-11 -4.06584e-11 -4.33084e-10 1 4.70198e-23 -1.94459e-11 -4.06584e-11 -4.33084e-10 1 -1.94459e-11 -4.06584e-11 -4.33084e-10 3997.08 16.9144 359.377 3992.3 3.55258 4031.92 +EDGE_SE3:QUAT 546 595 3.2742 -9.98968 -5.15094 -0.0319957 0.00288231 -0.232195 0.972139 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.76 1.34119 -64.7139 3999.45 11.0108 3785.2 +EDGE_SE3:QUAT 547 597 3.62504 0.303046 -5.01498 -0.168855 -0.186925 -0.0979745 0.962781 1 1.54074e-18 1.54074e-18 6.02939e-08 5.16119e-08 -4.70139e-09 1 1.54074e-18 6.02939e-08 5.16119e-08 -4.70139e-09 1 6.02939e-08 5.16119e-08 -4.70139e-09 4634.81 115.343 -1885.9 3842.12 -66.3195 4710.47 +EDGE_SE3:QUAT 546 597 3.39798 10.2841 -5.08447 -0.0776 -0.169697 -0.0924565 0.978076 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4531.68 2.44534 -1591.26 3874.12 31.2917 4521.57 +EDGE_SE3:QUAT 547 596 2.96764 -10.2103 -4.83919 0.0422787 0.0506554 -0.121246 0.990427 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.43 1.21225 461.816 3986.68 -26.7128 3993.78 +EDGE_SE3:QUAT 548 598 3.82399 -0.00107359 -4.5738 -0.0292239 -0.143247 0.0366808 0.988575 1 4.81482e-20 4.81482e-20 -1.42894e-08 -6.76488e-10 2.02847e-09 1 4.81482e-20 -1.42894e-08 -6.76488e-10 2.02847e-09 1 -1.42894e-08 -6.76488e-10 2.02847e-09 4335 40.9584 -1211.72 3922.63 -42.4676 4333.04 +EDGE_SE3:QUAT 547 598 3.43309 10.1562 -5.15612 0.224121 0.0592587 0.0196242 0.97256 1 4.81482e-20 4.81482e-20 6.21675e-10 3.1753e-09 1.35632e-08 1 4.81482e-20 6.21675e-10 3.1753e-09 1.35632e-08 1 6.21675e-10 3.1753e-09 1.35632e-08 3836.37 42.9477 390.046 3994.53 18.0208 4035.75 +EDGE_SE3:QUAT 548 597 2.66105 -9.91353 -4.93656 -0.0430078 0.0897609 -0.0544633 0.993543 1 9.62965e-20 9.62965e-20 1.51787e-08 -1.63699e-09 1.51787e-08 1 9.62965e-20 1.51787e-08 -1.63699e-09 1.51787e-08 1 1.51787e-08 -1.63699e-09 1.51787e-08 4112.21 -26.2432 702.083 3972.57 -28.3887 4107.74 +EDGE_SE3:QUAT 549 599 4.23021 0.177655 -4.98756 0.191949 -0.0987629 -0.00555983 0.976407 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.26 -79.0517 -755.389 3974.36 44.852 4137.51 +EDGE_SE3:QUAT 548 599 3.31246 10.0948 -4.75804 0.0597135 0.0320007 -0.0155223 0.997582 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.44 7.74187 266.7 3995.54 -0.5521 4016.74 +EDGE_SE3:QUAT 549 598 2.82447 -10.0958 -4.75588 -0.00551184 0.00573578 -0.100042 0.994951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.25 -0.160766 38.6269 3999.92 -1.81414 3960.34 +EDGE_SE3:QUAT 550 600 3.40744 0.131044 -5.05717 -0.0847072 0.192383 -0.0458798 0.97658 1 3.85186e-19 3.85186e-19 -2.37176e-08 -7.87785e-10 2.37176e-08 1 3.85186e-19 -2.37176e-08 -7.87785e-10 2.37176e-08 1 -2.37176e-08 -7.87785e-10 2.37176e-08 4566.94 -141.343 1654.9 3882.78 -135.522 4587.23 +EDGE_SE3:QUAT 549 600 3.47213 9.94057 -5.20525 -0.0212806 -0.0707055 0.0697682 0.994827 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.94 14.1548 -551.978 3982.57 -22.4282 4055.28 +EDGE_SE3:QUAT 550 599 3.31263 -10.2994 -4.78311 -0.0141934 -0.0877359 0.0153844 0.995924 1 1.20371e-20 1.20371e-20 6.14541e-10 1.20765e-10 -7.01774e-09 1 1.20371e-20 6.14541e-10 1.20765e-10 -7.01774e-09 1 6.14541e-10 1.20765e-10 -7.01774e-09 4124.11 8.42971 -717.811 3969.66 -8.66432 4123.97 +EDGE_SE3:QUAT 551 601 3.92247 0.0749116 -4.98398 -0.135072 -0.0103067 0.124752 0.982897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3929.51 -12.4655 119.403 3997.81 11.4738 3940.23 +EDGE_SE3:QUAT 550 601 3.28039 10.1804 -5.5594 0.0436299 0.0151667 0.0209326 0.998713 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.41 2.42221 110.031 3999.3 1.3218 4001.27 +EDGE_SE3:QUAT 551 600 2.83949 -10.4136 -5.06256 -0.0932352 -0.0256003 -0.00771094 0.995285 1 7.52316e-22 7.52316e-22 4.61832e-11 1.6148e-10 -1.72896e-09 1 7.52316e-22 4.61832e-11 1.6148e-10 -1.72896e-09 1 4.61832e-11 1.6148e-10 -1.72896e-09 3976.35 9.88191 -211.223 3997.27 -0.71713 4010.88 +EDGE_SE3:QUAT 552 602 3.48147 -0.058651 -4.95246 -0.194497 0.025111 0.0351666 0.979951 1 7.70372e-19 7.70372e-19 -5.45262e-08 -1.27813e-09 -2.03547e-09 1 7.70372e-19 -5.45262e-08 -1.27813e-09 -2.03547e-09 1 -5.45262e-08 -1.27813e-09 -2.03547e-09 3866.81 -27.9568 270.428 3995.24 0.376663 4013.18 +EDGE_SE3:QUAT 551 602 3.34999 9.79057 -5.07608 0.0774808 0.0662227 0.220866 0.969964 1 2.40741e-19 2.40741e-19 2.38077e-08 1.98238e-08 -6.64849e-10 1 2.40741e-19 2.38077e-08 1.98238e-08 -6.64849e-10 1 2.38077e-08 1.98238e-08 -6.64849e-10 3994.62 18.0342 288.206 3999.67 26.8282 3823.5 +EDGE_SE3:QUAT 552 601 2.92824 -9.9245 -4.68537 -0.124099 0.166366 -0.0402867 0.977394 1 7.70372e-19 7.70372e-19 -5.70096e-08 4.89409e-09 -8.73488e-09 1 7.70372e-19 -5.70096e-08 4.89409e-09 -8.73488e-09 1 -5.70096e-08 4.89409e-09 -8.73488e-09 4345.91 -131.587 1341.05 3923.06 -117.487 4401.02 +EDGE_SE3:QUAT 553 603 3.83196 -0.137579 -5.14141 0.0400316 -0.00177093 -0.0513536 0.997876 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.6 0.375454 10.5221 3999.98 -0.481817 3989.46 +EDGE_SE3:QUAT 552 603 3.34888 10.1375 -5.04199 0.164133 0.0994652 0.130174 0.972739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3949.33 50.4543 495.189 3996.38 47.383 3989.31 +EDGE_SE3:QUAT 553 602 3.27967 -9.88856 -5.08617 -0.0698123 0.0263058 0.0381382 0.996484 1 2.0463e-19 2.0463e-19 2.79453e-08 -5.96568e-09 4.00142e-10 1 2.0463e-19 2.79453e-08 -5.96568e-09 4.00142e-10 1 2.79453e-08 -5.96568e-09 4.00142e-10 3994.96 -8.05015 241.096 3996.16 3.38744 4008.64 +EDGE_SE3:QUAT 554 604 3.78446 -0.0792436 -5.23185 -0.161142 -0.0872955 -0.0539849 0.981579 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4049.72 60.1415 -798.841 3963.74 -12.3959 4141.93 +EDGE_SE3:QUAT 553 604 3.1124 10.0306 -4.99102 0.16541 -0.0584741 -0.00369767 0.984483 1 3.00927e-21 3.00927e-21 -1.88648e-10 5.82905e-10 3.4371e-09 1 3.00927e-21 -1.88648e-10 5.82905e-10 3.4371e-09 1 -1.88648e-10 5.82905e-10 3.4371e-09 3939.65 -37.716 -446.085 3989.82 13.6055 4049.03 +EDGE_SE3:QUAT 554 603 3.27325 -10.014 -4.82542 0.0235096 -0.109129 -0.0433987 0.992801 1 1.20371e-20 1.20371e-20 -7.05128e-09 3.5239e-10 7.56298e-10 1 1.20371e-20 -7.05128e-09 3.5239e-10 7.56298e-10 1 -7.05128e-09 3.5239e-10 7.56298e-10 4187.98 -24.5129 -892.743 3955.36 28.5852 4182.66 +EDGE_SE3:QUAT 555 605 3.73609 -0.158899 -4.94863 -0.10308 0.206896 0.211411 0.94967 1 4.81482e-20 4.81482e-20 -1.47338e-08 -2.85316e-09 -3.56078e-09 1 4.81482e-20 -1.47338e-08 -2.85316e-09 -3.56078e-09 1 -1.47338e-08 -2.85316e-09 -3.56078e-09 4908.86 152.711 2170.39 3819.21 200.217 4772.58 +EDGE_SE3:QUAT 554 605 3.24297 9.90357 -4.97828 -0.107516 -0.0696759 0.0690255 0.989354 1 1.92593e-19 1.92593e-19 1.46659e-09 3.26935e-09 -2.76405e-08 1 1.92593e-19 1.46659e-09 3.26935e-09 -2.76405e-08 1 1.46659e-09 3.26935e-09 -2.76405e-08 4005.55 29.9313 -459.719 3990.26 -24.7536 4032.73 +EDGE_SE3:QUAT 555 604 3.12333 -10.1329 -5.00677 0.0303962 0.0882089 -0.123111 0.987997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4134.47 -13.0227 756.154 3967.41 -44.8729 4077.54 +EDGE_SE3:QUAT 556 606 3.69916 0.110146 -4.952 0.196913 0.0260588 0.0275176 0.979688 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3849.12 10.8306 132.942 3999.55 3.15608 4001.19 +EDGE_SE3:QUAT 555 606 3.18846 10.1083 -5.2587 0.0761663 0.0376701 -0.0451888 0.995358 1 2.40741e-19 2.40741e-19 -2.82694e-08 -1.27285e-08 -2.15509e-10 1 2.40741e-19 -2.82694e-08 -1.27285e-08 -2.15509e-10 1 -2.82694e-08 -1.27285e-08 -2.15509e-10 4005.66 11.8247 341.228 3992.45 -4.96656 4020.7 +EDGE_SE3:QUAT 556 605 3.15932 -10.4086 -4.88234 -0.0492824 0.0613914 -0.0648642 0.994784 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4040.79 -16.3821 452.594 3988.74 -18.6764 4033.68 +EDGE_SE3:QUAT 557 607 3.60288 -0.383373 -4.67982 -0.0571756 -0.0441697 0.0282633 0.996986 1 1.20371e-20 1.20371e-20 2.82474e-10 4.16371e-10 -6.94195e-09 1 1.20371e-20 2.82474e-10 4.16371e-10 -6.94195e-09 1 2.82474e-10 4.16371e-10 -6.94195e-09 4014.57 10.7318 -333.762 3993.55 -7.15969 4024.45 +EDGE_SE3:QUAT 556 607 3.26621 10.2563 -5.0834 -0.165489 0.0701314 0.0503519 0.982425 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.29 -51.623 649.758 3975.26 -6.85364 4092.7 +EDGE_SE3:QUAT 557 606 3.00304 -9.9946 -4.90086 0.136012 -0.0572658 0.072676 0.986377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.34 -34.679 -569.6 3979.29 -7.64495 4058.21 +EDGE_SE3:QUAT 558 608 3.5416 0.348631 -5.11017 0.101757 -0.0608277 -0.166897 0.978821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.71 -15.6068 -259.712 3999.26 19.3388 3903.7 +EDGE_SE3:QUAT 557 608 2.98953 10.17 -5.21884 0.147247 -0.113152 0.0224049 0.982351 1 9.62965e-19 9.62965e-19 5.63517e-08 2.66089e-08 -1.05966e-08 1 9.62965e-19 5.63517e-08 2.66089e-08 -1.05966e-08 1 5.63517e-08 2.66089e-08 -1.05966e-08 4131.18 -73.248 -958.735 3952.06 37.352 4215.9 +EDGE_SE3:QUAT 558 607 3.42264 -10.1407 -4.30354 -0.0933212 0.0376658 -0.167398 0.98074 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3966.56 -2.89838 101.617 4000.22 -3.57316 3889.3 +EDGE_SE3:QUAT 559 609 3.31186 0.0873686 -5.07127 -0.158887 -0.00371741 0.00904087 0.987248 1 3.00927e-21 3.00927e-21 2.40329e-12 5.51401e-10 -3.42522e-09 1 3.00927e-21 2.40329e-12 5.51401e-10 -3.42522e-09 1 2.40329e-12 5.51401e-10 -3.42522e-09 3899.04 0.441134 -11.6696 4000 -0.0395415 3999.7 +EDGE_SE3:QUAT 558 609 3.0469 10.4689 -4.94472 0.0973304 -0.258337 0.252394 0.927408 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5451.87 405.659 -2860.08 3791.9 -419.453 5234.95 +EDGE_SE3:QUAT 559 608 3.13423 -10.2829 -4.85383 -0.126644 0.0614028 -0.0947287 0.985504 1 7.70372e-19 7.70372e-19 -5.48925e-08 5.99711e-09 -1.91778e-09 1 7.70372e-19 -5.48925e-08 5.99711e-09 -1.91778e-09 1 -5.48925e-08 5.99711e-09 -1.91778e-09 3962.36 -22.9729 332.001 3996.42 -20.0361 3990.62 +EDGE_SE3:QUAT 560 610 3.61351 0.319872 -5.02315 -0.063929 0.0962394 -0.0467237 0.992204 1 2.40741e-19 2.40741e-19 2.92583e-08 -2.72555e-09 1.65113e-08 1 2.40741e-19 2.92583e-08 -2.72555e-09 1.65113e-08 1 2.92583e-08 -2.72555e-09 1.65113e-08 4118.67 -35.5517 747.395 3969.69 -32.3061 4126.28 +EDGE_SE3:QUAT 559 610 2.86818 10.179 -4.50455 0.14988 -0.138736 -0.00877518 0.978883 1 1.54074e-18 1.54074e-18 5.35146e-08 -5.7205e-08 1.32029e-09 1 1.54074e-18 5.35146e-08 -5.7205e-08 1.32029e-09 1 5.35146e-08 -5.7205e-08 1.32029e-09 4203.43 -103.695 -1122.59 3941.7 76.6321 4292.98 +EDGE_SE3:QUAT 560 609 3.31063 -10.119 -4.91424 0.00321904 -0.038162 -0.0565927 0.997663 1 4.89006e-20 4.89006e-20 -9.44577e-10 1.39442e-08 -3.91639e-11 1 4.89006e-20 -9.44577e-10 1.39442e-08 -3.91639e-11 1 -9.44577e-10 1.39442e-08 -3.91639e-11 4022.8 -2.45127 -303.139 3994.44 8.78451 4010.03 +EDGE_SE3:QUAT 561 611 3.40443 -0.171852 -4.97178 -0.0645795 -0.00451134 -0.0349318 0.997291 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.28 2.27417 -62.7885 3999.68 1.17472 3996.09 +EDGE_SE3:QUAT 560 611 2.87286 11.0047 -4.97086 -0.0373766 -0.0322519 0.124288 0.991017 1 4.81482e-20 4.81482e-20 1.37698e-08 1.75842e-09 -3.04707e-10 1 4.81482e-20 1.37698e-08 1.75842e-09 -3.04707e-10 1 1.37698e-08 1.75842e-09 -3.04707e-10 4003.93 5.39163 -196.669 3998.29 -11.653 3947.73 +EDGE_SE3:QUAT 561 610 3.13469 -10.2592 -5.05175 0.0991605 0.161532 -0.0557291 0.98029 1 4.81482e-20 4.81482e-20 -2.48388e-09 -1.25776e-09 -1.44183e-08 1 4.81482e-20 -2.48388e-09 -1.25776e-09 -1.44183e-08 1 -2.48388e-09 -1.25776e-09 -1.44183e-08 4448.24 53.2675 1479.21 3889.45 21.8266 4475.15 +EDGE_SE3:QUAT 562 612 3.75679 0.236712 -5.04412 -0.00243882 -0.0686635 0.0651345 0.995508 1 3.00927e-21 3.00927e-21 -3.48623e-09 -2.3144e-10 2.37271e-10 1 3.00927e-21 -3.48623e-09 -2.3144e-10 2.37271e-10 1 -3.48623e-09 -2.3144e-10 2.37271e-10 4074.96 8.14395 -552.776 3981.98 -19.111 4058.01 +EDGE_SE3:QUAT 561 612 3.33753 10.3387 -5.02811 0.0392868 0.0360212 0.133254 0.989648 1 4.81482e-20 4.81482e-20 1.37546e-08 1.88942e-09 3.36748e-10 1 4.81482e-20 1.37546e-08 1.88942e-09 3.36748e-10 1 1.37546e-08 1.88942e-09 3.36748e-10 4005.53 6.61401 218.208 3997.96 13.9123 3940.68 +EDGE_SE3:QUAT 562 611 3.15685 -10.5663 -4.93086 -0.0374269 0.0108611 -0.143838 0.988834 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.37 -0.0237222 20.3661 4000.01 0.136886 3917.22 +EDGE_SE3:QUAT 563 613 3.70502 0.220584 -4.86611 0.134317 0.101756 0.0740552 0.982914 1 1.92593e-19 1.92593e-19 -2.1603e-09 -4.23577e-09 -2.76705e-08 1 1.92593e-19 -2.1603e-09 -4.23577e-09 -2.76705e-08 1 -2.1603e-09 -4.23577e-09 -2.76705e-08 4039.66 60.653 680.733 3980.92 51.3632 4089.89 +EDGE_SE3:QUAT 562 613 2.75856 10.4257 -5.50855 -0.0129886 0.0505789 0.0604155 0.996806 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.05 1.07906 415.617 3989.43 12.1416 4028.13 +EDGE_SE3:QUAT 563 612 3.23753 -10.2246 -4.89834 -0.0907069 -0.126914 -0.130545 0.979093 1 3.85186e-19 3.85186e-19 -3.24991e-08 1.51928e-09 3.24991e-08 1 3.85186e-19 -3.24991e-08 1.51928e-09 3.24991e-08 1 -3.24991e-08 1.51928e-09 3.24991e-08 4302.02 1.37012 -1205.21 3920.74 50.9312 4266.76 +EDGE_SE3:QUAT 564 614 3.67246 0.191588 -5.16236 -0.0102763 0.027267 0.0884201 0.995657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.42 0.494952 227.052 3996.82 10.0472 3981.57 +EDGE_SE3:QUAT 563 614 3.3961 10.171 -5.26294 0.0737062 -0.0429656 0.00553441 0.996339 1 1.92593e-19 1.92593e-19 -2.77582e-08 2.33836e-11 1.20668e-09 1 1.92593e-19 -2.77582e-08 2.33836e-11 1.20668e-09 1 -2.77582e-08 2.33836e-11 1.20668e-09 4008.33 -12.8554 -348.081 3992.66 2.3514 4029.94 +EDGE_SE3:QUAT 564 613 2.99525 -10.1783 -4.96504 0.0962307 -0.113332 -0.107866 0.982985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4106.8 -65.4534 -774.592 3975.02 67.3137 4097.3 +EDGE_SE3:QUAT 565 615 3.40688 -0.187339 -5.10317 -0.215633 -0.127424 -0.121017 0.960531 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4230.18 114.148 -1356.43 3905.79 -27.088 4357.59 +EDGE_SE3:QUAT 564 615 3.19994 10.1526 -5.05542 -0.14705 -0.0213681 0.0701285 0.986408 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3913.48 0.0566778 -42.5469 4000.05 -0.233642 3980.31 +EDGE_SE3:QUAT 565 614 3.01264 -10.5024 -4.88272 0.03509 -0.139181 0.00330963 0.98964 1 1.88079e-22 1.88079e-22 1.25481e-10 -3.20831e-11 -8.92972e-10 1 1.88079e-22 1.25481e-10 -3.20831e-11 -8.92972e-10 1 1.25481e-10 -3.20831e-11 -8.92972e-10 4323.59 -23.5614 -1192.47 3923.08 15.5655 4328.47 +EDGE_SE3:QUAT 566 616 3.63124 0.14293 -4.92388 -0.0403453 -0.146131 -0.0767976 0.985454 1 2.0463e-19 2.0463e-19 -1.15287e-08 -4.61512e-11 2.97297e-08 1 2.0463e-19 -1.15287e-08 -4.61512e-11 2.97297e-08 1 -1.15287e-08 -4.61512e-11 2.97297e-08 4375.78 -13.1555 -1294.35 3911.33 37.8169 4358.7 +EDGE_SE3:QUAT 565 616 3.36182 10.5152 -5.12964 -0.0738479 0.0198405 0.125332 0.989164 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.33 -8.39637 264.403 3994.67 17.298 3954.31 +EDGE_SE3:QUAT 566 615 3.23936 -10.2265 -4.96184 -0.0246864 0.255718 0.0332932 0.965863 1 1.20371e-20 1.20371e-20 7.71858e-09 1.93701e-10 2.05109e-09 1 1.20371e-20 7.71858e-09 1.93701e-10 2.05109e-09 1 7.71858e-09 1.93701e-10 2.05109e-09 5301.27 17.6803 2629.54 3737.23 21.1463 5299.27 +EDGE_SE3:QUAT 567 617 3.57886 -0.409727 -4.66401 0.19269 0.138308 -0.0532343 0.970004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4214.37 120.66 1258.27 3924.66 67.1399 4351.55 +EDGE_SE3:QUAT 566 617 3.4044 10.2936 -5.33518 0.0582212 0.00590892 -0.0259283 0.997949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.49 2.0318 65.0668 3999.69 -0.839399 3998.36 +EDGE_SE3:QUAT 567 616 3.18253 -10.7415 -5.02077 -0.0293038 0.18255 -0.0358232 0.982107 1 8.66668e-19 8.66668e-19 -1.44934e-08 5.58893e-08 -1.47427e-08 1 8.66668e-19 -1.44934e-08 5.58893e-08 -1.47427e-08 1 -1.44934e-08 5.58893e-08 -1.47427e-08 4571.54 -65.3039 1621.91 3873.99 -66.4274 4569.84 +EDGE_SE3:QUAT 568 618 3.48709 0.134368 -4.94523 -0.150332 0.135658 -0.128493 0.970818 1 1.92593e-19 1.92593e-19 4.62252e-09 2.67846e-08 5.10476e-09 1 1.92593e-19 4.62252e-09 2.67846e-08 5.10476e-09 1 4.62252e-09 2.67846e-08 5.10476e-09 4064.42 -99.8445 811.337 3984.4 -97.2121 4088.78 +EDGE_SE3:QUAT 567 618 3.48255 10.595 -5.21312 -0.00607317 -0.0236793 0.0403627 0.998886 1 7.52316e-22 7.52316e-22 -1.73467e-09 -7.06662e-11 4.01325e-11 1 7.52316e-22 -1.73467e-09 -7.06662e-11 4.01325e-11 1 -1.73467e-09 -7.06662e-11 4.01325e-11 4008.52 1.0956 -186.37 3997.88 -3.83967 4002.15 +EDGE_SE3:QUAT 568 617 2.89681 -10.4371 -4.99542 -0.0279876 0.0946019 -0.172321 0.980088 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4108.95 -41.7599 680.23 3979.67 -66.0374 3993.31 +EDGE_SE3:QUAT 569 619 3.7359 -0.106435 -4.58643 -0.0480049 0.040183 -0.0479746 0.996885 1 4.81482e-20 4.81482e-20 4.89783e-10 -7.20583e-10 1.38715e-08 1 4.81482e-20 4.89783e-10 -7.20583e-10 1.38715e-08 1 4.89783e-10 -7.20583e-10 1.38715e-08 4012.09 -8.51309 292.93 3995.17 -8.50975 4012.1 +EDGE_SE3:QUAT 568 619 3.45564 10.3892 -4.98582 0.184577 0.0273199 0.097254 0.977613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3862.33 -7.48232 -4.86368 3999.64 -3.87779 3960.77 +EDGE_SE3:QUAT 569 618 3.51855 -10.2391 -4.99939 -0.0825829 0.0317489 0.0398773 0.99528 1 2.40741e-19 2.40741e-19 2.72234e-08 1.47667e-08 2.16183e-09 1 2.40741e-19 2.72234e-08 1.47667e-08 2.16183e-09 1 2.72234e-08 1.47667e-08 2.16183e-09 3993.83 -11.4875 291.553 3994.43 3.63692 4014.75 +EDGE_SE3:QUAT 570 620 3.59013 -0.243574 -5.27072 -0.0525198 -0.0263216 -0.104971 0.992739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.43 5.12608 -273.044 3994.85 14.2281 3974.39 +EDGE_SE3:QUAT 569 620 3.16954 10.5599 -5.08694 -0.0192837 0.171841 0.0741547 0.98214 1 7.52316e-22 7.52316e-22 1.81227e-09 1.32618e-10 3.18806e-10 1 7.52316e-22 1.81227e-09 1.32618e-10 3.18806e-10 1 1.81227e-09 1.32618e-10 3.18806e-10 4521.36 41.9727 1537.77 3883.29 59.4625 4500.85 +EDGE_SE3:QUAT 570 619 3.27084 -10.2522 -4.86872 0.104994 0.093378 -0.077277 0.987059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4132.32 31.1372 858.617 3956.36 -10.3955 4152.53 +EDGE_SE3:QUAT 571 621 3.63494 0.223805 -4.97636 0.0771475 -0.0673361 0.00168932 0.994742 1 1.92781e-19 1.92781e-19 2.78023e-08 -1.76994e-10 -9.99997e-10 1 1.92781e-19 2.78023e-08 -1.76994e-10 -9.99997e-10 1 2.78023e-08 -1.76994e-10 -9.99997e-10 4048.84 -21.7558 -543.934 3982.61 8.04544 4072.63 +EDGE_SE3:QUAT 570 621 3.00315 10.4778 -5.24447 -0.0744921 -0.033626 0.0927857 0.992326 1 1.20371e-20 1.20371e-20 -6.72122e-10 6.88294e-09 5.51732e-10 1 1.20371e-20 -6.72122e-10 6.88294e-09 5.51732e-10 1 -6.72122e-10 6.88294e-09 5.51732e-10 3985.76 7.10925 -181.263 3998.75 -8.23179 3973.52 +EDGE_SE3:QUAT 571 620 2.92275 -10.323 -4.85473 -0.0459226 0.00994086 -0.0529585 0.997491 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.16 -0.980716 49.8537 3999.9 -1.1129 3989.38 +EDGE_SE3:QUAT 572 622 3.62906 -0.139183 -4.94825 -0.00355048 0.120737 -0.0959587 0.988029 1 3.00927e-21 3.00927e-21 -3.52793e-09 3.56003e-10 -4.20413e-10 1 3.00927e-21 -3.52793e-09 3.56003e-10 -4.20413e-10 1 -3.52793e-09 3.56003e-10 -4.20413e-10 4234.46 -37.175 996.575 3947.15 -56.1728 4197.68 +EDGE_SE3:QUAT 571 622 3.28033 10.2891 -5.25961 0.190008 0.154168 -0.100036 0.964428 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4381.89 115.57 1543.66 3885.58 50.3548 4486.28 +EDGE_SE3:QUAT 572 621 3.0781 -10.6504 -4.93174 -0.160821 -0.224919 0.0182944 0.96084 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4710.5 267.682 -1980.78 3872.26 -254.245 4812.62 +EDGE_SE3:QUAT 573 623 3.81576 -0.211729 -5.02619 -0.122568 -0.124065 -0.0384849 0.983923 1 9.75002e-19 9.75002e-19 -2.77476e-08 -5.36026e-08 -9.81623e-09 1 9.75002e-19 -2.77476e-08 -5.36026e-08 -9.81623e-09 1 -2.77476e-08 -5.36026e-08 -9.81623e-09 4216.72 62.5745 -1088.07 3936.5 -27.3208 4270.89 +EDGE_SE3:QUAT 572 623 3.31506 10.3543 -5.11444 -0.0172858 0.0926556 0.0557172 0.993988 1 3.00927e-21 3.00927e-21 -3.51036e-09 -1.88682e-10 -3.31896e-10 1 3.00927e-21 -3.51036e-09 -1.88682e-10 -3.31896e-10 1 -3.51036e-09 -1.88682e-10 -3.31896e-10 4142.92 4.88352 772.822 3965.08 19.8057 4131.7 +EDGE_SE3:QUAT 573 622 3.05886 -10.1938 -5.06953 0.0254102 0.0698598 0.112233 0.990897 1 1.92593e-19 1.92593e-19 3.23737e-09 -2.74888e-08 1.12877e-09 1 1.92593e-19 3.23737e-09 -2.74888e-08 1.12877e-09 1 3.23737e-09 -2.74888e-08 1.12877e-09 4064.04 18.5924 520.846 3985.61 32.4427 4016.24 +EDGE_SE3:QUAT 574 624 3.61155 -0.089652 -5.29414 -0.13519 -0.0613391 -0.0751977 0.986056 1 9.62965e-19 9.62965e-19 5.6934e-08 2.42256e-08 -9.2511e-10 1 9.62965e-19 5.6934e-08 2.42256e-08 -9.2511e-10 1 5.6934e-08 2.42256e-08 -9.2511e-10 4016.61 35.9 -606.394 3976.73 8.09653 4067.09 +EDGE_SE3:QUAT 573 624 3.02713 10.4207 -5.01647 0.105233 -0.00753091 -0.00415459 0.99441 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3956.43 -2.74039 -54.0479 3999.84 0.229845 4000.66 +EDGE_SE3:QUAT 574 623 2.98435 -10.3302 -4.97796 -0.00993748 0.0540424 0.0044026 0.998479 1 3.00927e-21 3.00927e-21 3.48457e-09 1.16871e-11 1.88864e-10 1 3.00927e-21 3.48457e-09 1.16871e-11 1.88864e-10 1 3.48457e-09 1.16871e-11 1.88864e-10 4046.85 -1.92675 437.262 3988.29 0.284809 4047.16 +EDGE_SE3:QUAT 575 625 3.76342 0.268894 -4.90399 -0.00682769 -0.0531302 0.0715149 0.996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4043.4 6.22287 -419.82 3989.6 -15.7939 4023.13 +EDGE_SE3:QUAT 574 625 3.07934 10.3048 -4.95166 0.0113086 -0.126774 0.131587 0.9831 1 7.71124e-19 7.71124e-19 -5.4232e-09 -1.05879e-09 5.61609e-08 1 7.71124e-19 -5.4232e-09 -1.05879e-09 5.61609e-08 1 -5.4232e-09 -1.05879e-09 5.61609e-08 4264.8 47.6398 -1063.85 3942.2 -77.2227 4196.05 +EDGE_SE3:QUAT 575 624 3.26899 -10.5454 -4.94983 0.0500818 0.0181913 -0.0795528 0.995406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.07 4.21953 191.572 3997.4 -7.64638 3983.79 +EDGE_SE3:QUAT 576 626 3.63588 0.00342381 -5.06243 -0.0208983 0.0938934 -0.0854601 0.991687 1 2.0463e-19 2.0463e-19 4.49057e-09 4.07406e-10 -2.73561e-08 1 2.0463e-19 4.49057e-09 4.07406e-10 -2.73561e-08 1 4.49057e-09 4.07406e-10 -2.73561e-08 4131.21 -26.0607 741.413 3969.83 -38.4239 4103.74 +EDGE_SE3:QUAT 575 626 3.243 10.9145 -5.19278 -0.122112 -0.198225 -0.127405 0.964139 1 1.92593e-19 1.92593e-19 -2.95318e-08 2.57522e-09 6.70506e-09 1 1.92593e-19 -2.95318e-08 2.57522e-09 6.70506e-09 1 -2.95318e-08 2.57522e-09 6.70506e-09 4790.31 13.4706 -2030.5 3817.13 28.7473 4785.03 +EDGE_SE3:QUAT 576 625 3.29876 -10.2817 -4.84558 -0.00322817 -0.0303838 -0.00372142 0.999526 1 1.88079e-22 1.88079e-22 2.64222e-11 2.61351e-12 -8.68556e-10 1 1.88079e-22 2.64222e-11 2.61351e-12 -8.68556e-10 1 2.64222e-11 2.61351e-12 -8.68556e-10 4014.79 0.31483 -243.995 3996.3 0.386587 4014.77 +EDGE_SE3:QUAT 577 627 3.70242 0.478925 -4.89184 -0.127835 -0.0153691 0.0461416 0.990602 1 7.70372e-19 7.70372e-19 -5.49927e-08 -2.69467e-09 1.72584e-10 1 7.70372e-19 -5.49927e-08 -2.69467e-09 1.72584e-10 1 -5.49927e-08 -2.69467e-09 1.72584e-10 3935.09 1.66794 -49.6288 3999.99 -0.781166 3991.94 +EDGE_SE3:QUAT 576 627 3.14128 10.4614 -5.08257 -0.0479891 -0.0438434 0.0418002 0.997009 1 4.81482e-20 4.81482e-20 1.38821e-08 6.401e-10 -5.49495e-10 1 4.81482e-20 1.38821e-08 6.401e-10 -5.49495e-10 1 1.38821e-08 6.401e-10 -5.49495e-10 4017.22 9.49398 -326.358 3993.91 -8.74827 4019.44 +EDGE_SE3:QUAT 577 626 2.94407 -9.59617 -5.03031 -0.172727 0.098158 -0.0969249 0.975262 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3951.99 -56.7512 547.357 3992.51 -48.1689 4033.75 +EDGE_SE3:QUAT 578 628 3.65041 0.0190293 -5.4045 -0.156763 0.0053426 -0.111115 0.981351 1 7.73381e-19 7.73381e-19 5.48879e-08 -2.55354e-09 -1.08946e-09 1 7.73381e-19 5.48879e-08 -2.55354e-09 -1.08946e-09 1 5.48879e-08 -2.55354e-09 -1.08946e-09 3907.3 17.7899 -163.702 3996.66 12.2054 3956.21 +EDGE_SE3:QUAT 577 628 3.24279 10.2376 -5.24679 0.00660369 0.132798 0.25226 0.958481 1 4.81482e-20 4.81482e-20 -1.37036e-08 -3.76125e-09 -1.5999e-09 1 4.81482e-20 -1.37036e-08 -3.76125e-09 -1.5999e-09 1 -1.37036e-08 -3.76125e-09 -1.5999e-09 4228.63 102.015 986.569 3970.15 143.604 3974.26 +EDGE_SE3:QUAT 578 627 3.24633 -10.1929 -5.16873 -0.0416307 -0.195156 -0.0668651 0.977604 1 8.1852e-19 8.1852e-19 6.2892e-11 5.40518e-08 1.56734e-08 1 8.1852e-19 6.2892e-11 5.40518e-08 1.56734e-08 1 6.2892e-11 5.40518e-08 1.56734e-08 4701.68 -21.9991 -1826.64 3844.23 39.7068 4690.73 +EDGE_SE3:QUAT 579 629 3.64424 0.261898 -5.04358 -6.99159e-05 -0.0660957 -0.184008 0.9807 1 1.95602e-19 1.95602e-19 1.72005e-09 2.7861e-08 -4.50423e-10 1 1.95602e-19 1.72005e-09 2.7861e-08 -4.50423e-10 1 1.72005e-09 2.7861e-08 -4.50423e-10 4063.71 -18.4561 -509.115 3987.22 48.1048 3928.27 +EDGE_SE3:QUAT 578 629 2.99167 10.3891 -5.23169 -0.141264 -0.178812 -0.100656 0.968472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4593.91 70.5274 -1774.65 3852.06 -23.4112 4633.21 +EDGE_SE3:QUAT 579 628 2.80952 -10.7834 -4.98955 -0.0258719 -0.196181 0.0653943 0.978043 1 8.1852e-19 8.1852e-19 -1.01424e-08 -5.54465e-08 -1.92999e-10 1 8.1852e-19 -1.01424e-08 -5.54465e-08 -1.92999e-10 1 -1.01424e-08 -5.54465e-08 -1.92999e-10 4658.03 102.551 -1754.9 3861.93 -108.593 4643.6 +EDGE_SE3:QUAT 580 630 3.9085 0.263359 -4.94195 0.0201893 0.0986457 0.0161537 0.994787 1 2.16667e-19 2.16667e-19 7.16141e-09 2.79222e-08 7.06953e-09 1 2.16667e-19 7.16141e-09 2.79222e-08 7.06953e-09 1 7.16141e-09 2.79222e-08 7.06953e-09 4156.72 12.9332 811.465 3961.87 12.1102 4157.31 +EDGE_SE3:QUAT 579 630 3.34622 10.4835 -4.9621 -0.0316441 -0.0819385 -0.102989 0.990797 1 1.92593e-19 1.92593e-19 -2.43974e-09 -4.07148e-10 2.79122e-08 1 1.92593e-19 -2.43974e-09 -4.07148e-10 2.79122e-08 1 -2.43974e-09 -4.07148e-10 2.79122e-08 4115.43 -6.37441 -701.447 3971.15 33.6572 4077.01 +EDGE_SE3:QUAT 580 629 3.17176 -10.4214 -5.1143 -0.159146 -0.0462313 -0.0374863 0.985459 1 8.30557e-19 8.30557e-19 -5.49301e-08 -1.14106e-08 -5.94065e-09 1 8.30557e-19 -5.49301e-08 -1.14106e-08 -5.94065e-09 1 -5.49301e-08 -1.14106e-08 -5.94065e-09 3944.38 34.2051 -430.145 3988.69 -1.84152 4040.07 +EDGE_SE3:QUAT 581 631 3.48155 0.46678 -5.22159 0.145744 -0.0315618 0.0219277 0.988576 1 7.70372e-19 7.70372e-19 5.50168e-08 6.63798e-10 -2.0328e-09 1 7.70372e-19 5.50168e-08 6.63798e-10 -2.0328e-09 1 5.50168e-08 6.63798e-10 -2.0328e-09 3935.01 -21.0036 -283.449 3995.06 0.967426 4018.05 +EDGE_SE3:QUAT 580 631 3.11442 10.0013 -5.61885 -0.119045 -0.177139 -0.0147455 0.976848 1 1.95602e-19 1.95602e-19 -2.82801e-08 -3.99502e-10 1.58063e-09 1 1.95602e-19 -2.82801e-08 -3.99502e-10 1.58063e-09 1 -2.82801e-08 -3.99502e-10 1.58063e-09 4489.11 112.77 -1575.2 3885.6 -89.0348 4544.92 +EDGE_SE3:QUAT 581 630 2.89171 -10.3 -5.15761 0.224414 -0.00837451 -0.00648902 0.974436 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3799.04 -4.22082 -45.1093 3999.95 0.335649 4000.32 +EDGE_SE3:QUAT 582 632 3.54033 0.147764 -5.04522 0.136807 -0.0268023 -0.1081 0.984317 1 3.00927e-21 3.00927e-21 -3.86157e-10 -3.4138e-09 4.83469e-10 1 3.00927e-21 -3.86157e-10 -3.4138e-09 4.83469e-10 1 -3.86157e-10 -3.4138e-09 4.83469e-10 3924.41 1.98444 -30.688 4000.01 -1.4782 3952.53 +EDGE_SE3:QUAT 581 632 2.89985 10.5584 -5.03658 0.0914013 -0.0299963 0.0684629 0.993005 1 2.40741e-19 2.40741e-19 2.67842e-08 1.55129e-08 -2.3634e-09 1 2.40741e-19 2.67842e-08 1.55129e-08 -2.3634e-09 1 2.67842e-08 1.55129e-08 -2.3634e-09 3990.6 -13.2466 -311.596 3993.28 -8.60102 4005.26 +EDGE_SE3:QUAT 582 631 2.91073 -10.4302 -4.96415 -0.00665525 -0.0312426 0.0166617 0.999351 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.3 1.22519 -249.327 3996.16 -2.24949 4014.37 +EDGE_SE3:QUAT 583 633 3.44252 0.45128 -5.33752 0.0212244 -0.0605074 0.156674 0.985567 1 1.95602e-19 1.95602e-19 7.75628e-09 -2.68184e-08 -1.82328e-10 1 1.95602e-19 7.75628e-09 -2.68184e-08 -1.82328e-10 1 7.75628e-09 -2.68184e-08 -1.82328e-10 4062.88 9.46899 -512.757 3985.12 -40.3508 3966.5 +EDGE_SE3:QUAT 582 633 3.14117 10.3639 -5.32554 0.00626601 -0.0724304 0.157451 0.984847 1 7.70372e-19 7.70372e-19 3.96976e-09 9.35928e-10 -5.52442e-08 1 7.70372e-19 3.96976e-09 9.35928e-10 -5.52442e-08 1 3.96976e-09 9.35928e-10 -5.52442e-08 4082.19 18.1383 -579.909 3982.13 -47.1406 3983.19 +EDGE_SE3:QUAT 583 632 2.92038 -10.4057 -4.76724 -0.134574 0.24649 -0.0833442 0.956131 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4797.87 -350.865 2062.53 3896.25 -348.678 4842.53 +EDGE_SE3:QUAT 584 634 3.72038 -0.12464 -5.35361 0.0951174 0.176629 0.120917 0.97218 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4356.98 160.4 1317.36 3939.73 163.96 4334.69 +EDGE_SE3:QUAT 583 634 2.83002 10.5536 -5.03972 -0.22211 -0.0875241 -0.0831217 0.967521 1 9.62965e-19 9.62965e-19 -5.61067e-08 -2.47695e-08 6.8333e-10 1 9.62965e-19 -5.61067e-08 -2.47695e-08 6.8333e-10 1 -5.61067e-08 -2.47695e-08 6.8333e-10 3994.22 93.6469 -896.605 3955.59 -17.8945 4163.91 +EDGE_SE3:QUAT 584 633 2.85566 -10.7988 -5.00628 -0.0344625 -0.061128 -0.0558437 0.99597 1 2.0463e-19 2.0463e-19 -8.40883e-09 -2.72864e-08 -3.16858e-10 1 2.0463e-19 -8.40883e-09 -2.72864e-08 -3.16858e-10 1 -8.40883e-09 -2.72864e-08 -3.16858e-10 4060.84 3.93419 -516.435 3983.59 11.842 4053.12 +EDGE_SE3:QUAT 585 635 3.53804 -0.206343 -4.94206 -0.00803499 0.0230753 -0.0906897 0.995579 1 1.92593e-19 1.92593e-19 5.90063e-10 -3.35666e-10 2.76591e-08 1 1.92593e-19 5.90063e-10 -3.35666e-10 2.76591e-08 1 5.90063e-10 -3.35666e-10 2.76591e-08 4007.28 -1.74816 173.888 3998.26 -7.85315 3974.64 +EDGE_SE3:QUAT 584 635 3.02984 10.3358 -5.24479 0.0255148 0.24803 0.198315 0.947893 1 1.92593e-19 1.92593e-19 -2.93562e-08 -7.39573e-09 -6.62232e-09 1 1.92593e-19 -2.93562e-08 -7.39573e-09 -6.62232e-09 1 -2.93562e-08 -7.39573e-09 -6.62232e-09 4926.24 379.985 2143.27 3899.19 386.945 4771.53 +EDGE_SE3:QUAT 585 634 2.85536 -10.0834 -5.21536 0.0103027 0.0528404 -0.0975324 0.993775 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.92 -4.49797 433.037 3988.84 -21.1336 4008.29 +EDGE_SE3:QUAT 586 636 3.71559 0.21299 -5.3176 0.00956679 0.0532485 -0.176588 0.982797 1 4.84586e-20 4.84586e-20 -3.55221e-09 -1.34411e-08 -1.92472e-10 1 4.84586e-20 -3.55221e-09 -1.34411e-08 -1.92472e-10 1 -3.55221e-09 -1.34411e-08 -1.92472e-10 4045.4 -10.2615 430.361 3990.14 -38.5006 3921.03 +EDGE_SE3:QUAT 585 636 3.1468 10.3268 -5.34903 -0.165585 0.104068 0.0155602 0.980566 1 9.64658e-19 9.64658e-19 -5.53939e-08 2.8764e-08 -3.87127e-09 1 9.64658e-19 -5.53939e-08 2.8764e-08 -3.87127e-09 1 -5.53939e-08 2.8764e-08 -3.87127e-09 4067.81 -75.3072 861.152 3962.35 -38.2536 4176.51 +EDGE_SE3:QUAT 586 635 3.07123 -10.0726 -4.6883 0.0201021 0.0591566 -0.0333713 0.997488 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4056.68 2.17571 486.415 3985.51 -6.70085 4053.84 +EDGE_SE3:QUAT 587 637 3.44669 0.294652 -5.16041 -0.0527047 0.0505718 0.0476568 0.99619 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.89 -8.7782 436.213 3988.03 7.27346 4037.92 +EDGE_SE3:QUAT 586 637 2.80873 10.5168 -5.46354 -0.0229863 -0.0985543 0.14428 0.984349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4131.49 40.115 -743.785 3973.12 -62.1299 4050.34 +EDGE_SE3:QUAT 587 636 2.86401 -10.3993 -5.03691 0.11891 0.0846933 0.0158587 0.989159 1 3.85186e-19 3.85186e-19 2.68217e-08 2.84479e-08 -1.21375e-09 1 3.85186e-19 2.68217e-08 2.84479e-08 -1.21375e-09 1 2.68217e-08 2.84479e-08 -1.21375e-09 4047.75 43.5789 654.553 3977.25 24.9627 4103.31 +EDGE_SE3:QUAT 588 638 3.57786 -0.0970183 -5.17365 -0.0368197 -0.0068486 0.158016 0.986726 1 7.70372e-19 7.70372e-19 -2.77243e-10 2.06039e-09 -5.47738e-08 1 7.70372e-19 -2.77243e-10 2.06039e-09 -5.47738e-08 1 -2.77243e-10 2.06039e-09 -5.47738e-08 3994.5 -0.739296 15.9538 3999.9 3.15763 3900.05 +EDGE_SE3:QUAT 587 638 2.72836 10.7092 -5.47825 0.0377146 0.0622223 0.156681 0.984965 1 4.81482e-20 4.81482e-20 1.37421e-08 2.26008e-09 6.585e-10 1 4.81482e-20 1.37421e-08 2.26008e-09 6.585e-10 1 1.37421e-08 2.26008e-09 6.585e-10 4035.94 18.4944 411.76 3992.56 33.6188 3943.44 +EDGE_SE3:QUAT 588 637 2.80356 -10.053 -5.18002 0.0726 -0.151882 -0.0332019 0.985169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4345.91 -75.9272 -1266.12 3920.42 68.3745 4362.59 +EDGE_SE3:QUAT 589 639 3.32872 0.0132958 -5.28078 0.0783205 -0.0757218 -0.090851 0.989888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4040.12 -29.6448 -514.013 3987.43 31.4682 4031.64 +EDGE_SE3:QUAT 588 639 3.05555 10.6883 -5.16096 -0.00558813 -0.062612 0.040385 0.997205 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4062.33 5.28861 -503.69 3984.77 -11.0906 4055.93 +EDGE_SE3:QUAT 589 638 2.69182 -10.4156 -5.19637 0.0259149 -0.0922058 -0.0646812 0.993299 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4126.98 -23.2152 -731.849 3969.99 30.6622 4112.93 +EDGE_SE3:QUAT 590 640 3.52445 0.0251781 -5.0486 -0.027891 -0.0995666 0.0224567 0.994386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4156.45 18.0043 -814.69 3961.88 -16.9018 4157.54 +EDGE_SE3:QUAT 589 640 3.25225 10.5012 -5.29843 0.0610001 0.176136 0.11696 0.975487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4426.63 141.354 1401.69 3921.12 149.972 4386.8 +EDGE_SE3:QUAT 590 639 2.96789 -10.3451 -4.9818 -0.0755074 0.008544 -0.163929 0.983541 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3978.22 4.81657 -80.2858 3998.94 10.6725 3893.53 +EDGE_SE3:QUAT 591 641 3.61292 0.324121 -5.27858 0.168042 -0.0374299 -0.0808909 0.981742 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3889.98 -6.29117 -124.301 4000.06 4.31118 3976.76 +EDGE_SE3:QUAT 590 641 2.97262 10.6803 -5.42033 -0.142228 0.00220789 0.0356746 0.989188 1 4.81482e-20 4.81482e-20 -1.68665e-10 1.96704e-09 -1.37302e-08 1 4.81482e-20 -1.68665e-10 1.96704e-09 -1.37302e-08 1 -1.68665e-10 1.96704e-09 -1.37302e-08 3920.48 -6.86258 77.1394 3999.43 1.51609 3996.31 +EDGE_SE3:QUAT 591 640 3.11705 -10.5169 -5.13141 -0.0411541 -0.0460666 0.0101297 0.998039 1 4.81482e-20 4.81482e-20 -1.39078e-08 -1.94231e-10 6.27959e-10 1 4.81482e-20 -1.39078e-08 -1.94231e-10 6.27959e-10 1 -1.39078e-08 -1.94231e-10 6.27959e-10 4026.28 8.1454 -365.132 3991.94 -3.94535 4032.65 +EDGE_SE3:QUAT 592 642 3.45681 -0.268815 -5.02745 -0.0445607 -0.0295213 -0.0894551 0.994555 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.73 4.19244 -281.497 3994.72 12.1598 3987.66 +EDGE_SE3:QUAT 591 642 2.81103 10.436 -4.93897 0.198941 0.0832558 0.0060107 0.97645 1 9.62965e-19 9.62965e-19 -5.38065e-08 -2.92397e-08 1.4523e-09 1 9.62965e-19 -5.38065e-08 -2.92397e-08 1.4523e-09 1 -5.38065e-08 -2.92397e-08 1.4523e-09 3936.83 65.576 624.948 3982.5 32.4977 4094.99 +EDGE_SE3:QUAT 592 641 2.8542 -10.3979 -5.00091 -0.138209 -0.162125 -0.293568 0.931897 1 9.62965e-19 9.62965e-19 -4.27583e-08 -4.44458e-08 4.8039e-09 1 9.62965e-19 -4.27583e-08 -4.44458e-08 4.8039e-09 1 -4.27583e-08 -4.44458e-08 4.8039e-09 4638.58 -141.46 -1836.3 3868.83 239.946 4370.26 +EDGE_SE3:QUAT 593 643 3.66226 0.2036 -5.01603 0.0259637 0.0416028 0.134436 0.989708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.15 7.91025 283.164 3996.08 19.023 3947.56 +EDGE_SE3:QUAT 592 643 3.15686 10.4747 -5.10455 0.0333458 -0.0529143 0.24466 0.967589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.74 12.3232 -485.97 3987.79 -61.127 3818.76 +EDGE_SE3:QUAT 593 642 3.00039 -10.6292 -5.2073 -0.0317507 0.0615578 -0.118647 0.990518 1 9.62965e-20 9.62965e-20 1.21213e-08 -1.54582e-08 9.48233e-11 1 9.62965e-20 1.21213e-08 -1.54582e-08 9.48233e-11 1 1.21213e-08 -1.54582e-08 9.48233e-11 4043.82 -16.1021 440.666 3990.05 -28.3949 3991.54 +EDGE_SE3:QUAT 594 644 3.52236 -0.0386884 -5.14902 -0.0231222 -0.139524 0.0634737 0.987912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4312.13 47.5444 -1164.48 3929.32 -55.6638 4298.16 +EDGE_SE3:QUAT 593 644 3.05875 10.6399 -5.32976 0.155094 0.047924 0.124904 0.978799 1 7.70372e-19 7.70372e-19 5.43526e-08 7.43025e-09 3.33e-10 1 7.70372e-19 5.43526e-08 7.43025e-09 3.33e-10 1 5.43526e-08 7.43025e-09 3.33e-10 3906.37 5.48835 133.71 4000.39 5.14164 3940.18 +EDGE_SE3:QUAT 594 643 2.94211 -10.8937 -4.84999 0.0845287 -0.089593 -0.124113 0.984593 1 1.92593e-19 1.92593e-19 -2.76085e-08 3.90384e-09 1.80485e-09 1 1.92593e-19 -2.76085e-08 3.90384e-09 1.80485e-09 1 -2.76085e-08 3.90384e-09 1.80485e-09 4051.85 -41.195 -575.865 3986.5 46.8124 4018.82 +EDGE_SE3:QUAT 595 645 3.49999 -0.274445 -5.11401 0.154878 0.156371 -0.0788158 0.972291 1 8.1852e-19 8.1852e-19 -5.47692e-08 3.74517e-09 4.18248e-09 1 8.1852e-19 -5.47692e-08 3.74517e-09 4.18248e-09 1 -5.47692e-08 3.74517e-09 4.18248e-09 4399.78 91.7307 1492.96 3890.29 41.532 4470.88 +EDGE_SE3:QUAT 594 645 3.18571 10.6445 -5.37771 -0.10342 -0.0446803 0.0461496 0.992561 1 1.92593e-19 1.92593e-19 -2.7624e-08 -1.51761e-09 9.46324e-10 1 1.92593e-19 -2.7624e-08 -1.51761e-09 9.46324e-10 1 -2.7624e-08 -1.51761e-09 9.46324e-10 3978.7 16.0583 -294.884 3995.75 -10.1442 4012.97 +EDGE_SE3:QUAT 595 644 3.23782 -10.3779 -5.24634 0.00927006 0.09912 -0.0320462 0.994516 1 4.89006e-20 4.89006e-20 3.1688e-09 -1.21837e-11 1.42564e-08 1 4.89006e-20 3.1688e-09 -1.21837e-11 1.42564e-08 1 3.1688e-09 -1.21837e-11 1.42564e-08 4162.59 -3.75044 823.576 3960.55 -12.2828 4158.82 +EDGE_SE3:QUAT 596 646 3.45939 -0.482742 -5.2694 0.0595925 0.0203635 -0.0368407 0.997335 1 4.81482e-20 4.81482e-20 1.38562e-08 -4.75007e-10 3.41056e-10 1 4.81482e-20 1.38562e-08 -4.75007e-10 3.41056e-10 1 1.38562e-08 -4.75007e-10 3.41056e-10 3994.63 5.42974 188.367 3997.63 -2.89501 4003.41 +EDGE_SE3:QUAT 595 646 2.86829 10.7515 -5.33254 -0.106207 0.0509389 -0.0540914 0.991564 1 1.92593e-19 1.92593e-19 2.76162e-08 -1.77952e-09 1.0586e-09 1 1.92593e-19 2.76162e-08 -1.77952e-09 1.0586e-09 1 2.76162e-08 -1.77952e-09 1.0586e-09 3982.06 -19.124 332.069 3994.76 -13.3524 4015.48 +EDGE_SE3:QUAT 596 645 2.72213 -10.2397 -5.001 -0.0242266 -0.0802316 -0.000899688 0.996481 1 1.20841e-20 1.20841e-20 6.9694e-09 1.04679e-11 -1.25827e-10 1 1.20841e-20 6.9694e-09 1.04679e-11 -1.25827e-10 1 6.9694e-09 1.04679e-11 -1.25827e-10 4102.57 8.34532 -656.255 3974.35 -3.54494 4104.91 +EDGE_SE3:QUAT 597 647 3.42869 0.256163 -5.32333 0.0651561 0.0396107 -0.0599787 0.995283 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.58 9.71319 362.606 3991.43 -8.47735 4018.17 +EDGE_SE3:QUAT 596 647 3.20669 10.6485 -5.28774 0.0574091 0.00703988 0.0227081 0.998068 1 4.89006e-20 4.89006e-20 -1.38111e-08 -2.05564e-09 3.92084e-11 1 4.89006e-20 -1.38111e-08 -2.05564e-09 3.92084e-11 1 -1.38111e-08 -2.05564e-09 3.92084e-11 3987.22 1.0236 40.3951 3999.93 0.439933 3998.34 +EDGE_SE3:QUAT 597 646 2.72834 -10.5016 -5.3937 -0.1727 -0.0142254 0.013318 0.984782 1 7.70372e-19 7.70372e-19 -5.46779e-08 -9.64325e-10 4.90766e-10 1 7.70372e-19 -5.46779e-08 -9.64325e-10 4.90766e-10 1 -5.46779e-08 -9.64325e-10 4.90766e-10 3882.33 6.15917 -81.6872 3999.75 -0.988344 4000.92 +EDGE_SE3:QUAT 598 648 3.29756 0.0913213 -5.40684 -0.0850842 0.0401076 -0.0205985 0.995353 1 1.20371e-20 1.20371e-20 -2.50391e-10 6.04826e-10 -6.92576e-09 1 1.20371e-20 -2.50391e-10 6.04826e-10 -6.92576e-09 1 -2.50391e-10 6.04826e-10 -6.92576e-09 3993.04 -13.2154 297.581 3995.02 -5.96153 4020.3 +EDGE_SE3:QUAT 597 648 3.21835 10.6291 -5.14293 -0.0831472 0.131919 0.139765 0.977829 1 7.70372e-19 7.70372e-19 8.62445e-09 -2.64268e-09 5.67059e-08 1 7.70372e-19 8.62445e-09 -2.64268e-09 5.67059e-08 1 8.62445e-09 -2.64268e-09 5.67059e-08 4329.41 11.256 1247.5 3916.85 63.1527 4278.93 +EDGE_SE3:QUAT 598 647 3.04906 -10.5769 -4.89432 -0.119409 -0.0220336 -0.128303 0.984274 1 1.92593e-19 1.92593e-19 -2.74241e-08 3.33408e-09 1.41824e-09 1 1.92593e-19 -2.74241e-08 3.33408e-09 1.41824e-09 1 -2.74241e-08 3.33408e-09 1.41824e-09 3972.86 19.988 -351.085 3990.2 22.159 3964.05 +EDGE_SE3:QUAT 599 649 3.38975 0.204222 -5.61921 -0.0562404 -0.0209404 -0.0402171 0.997387 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.7 5.18959 -193.812 3997.49 3.34631 4002.88 +EDGE_SE3:QUAT 598 649 3.16077 10.6721 -5.36208 0.107514 -0.041864 0.293957 0.94883 1 3.08149e-18 3.08149e-18 -1.0595e-08 7.43212e-09 1.06853e-07 1 3.08149e-18 -1.0595e-08 7.43212e-09 1.06853e-07 1 -1.0595e-08 7.43212e-09 1.06853e-07 4058.58 -3.27252 -660.169 3971.26 -103.321 3759.17 +EDGE_SE3:QUAT 599 648 2.91613 -10.991 -4.92727 0.0921557 -0.209639 -0.13859 0.96351 1 7.70372e-19 7.70372e-19 -1.00416e-08 9.3688e-09 5.72856e-08 1 7.70372e-19 -1.00416e-08 9.3688e-09 5.72856e-08 1 -1.00416e-08 9.3688e-09 5.72856e-08 4531.18 -241.806 -1610.5 3927.65 246.266 4488.32 +EDGE_SE3:QUAT 600 650 3.57215 0.146183 -5.35933 0.044187 -0.13042 0.0610173 0.988592 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4293.43 -1.77968 -1138.3 3928.59 -21.0201 4286.35 +EDGE_SE3:QUAT 599 650 2.56449 10.5607 -5.12797 -0.00928628 0.0236405 -0.0658401 0.997507 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.81 -1.6569 180.866 3998.07 -6.00947 3990.82 +EDGE_SE3:QUAT 600 649 2.57662 -10.4525 -5.05839 0.0944476 0.0231474 -0.0165691 0.995123 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.47 9.59882 201.77 3997.42 -0.331436 4009.05 +EDGE_SE3:QUAT 601 651 3.42356 0.536099 -5.13129 0.148137 -0.0870555 -0.17719 0.969062 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3935.66 -28.0895 -334.628 4001.03 29.4216 3897.85 +EDGE_SE3:QUAT 600 651 3.20705 10.5263 -5.335 0.0389174 0.0192932 -0.00133217 0.999055 1 4.81482e-20 4.81482e-20 1.38751e-08 2.39241e-12 2.68575e-10 1 4.81482e-20 1.38751e-08 2.39241e-12 2.68575e-10 1 1.38751e-08 2.39241e-12 2.68575e-10 3999.93 3.0142 154.819 3998.51 0.245926 4005.98 +EDGE_SE3:QUAT 601 650 2.5474 -10.5239 -5.20254 0.101663 0.0224973 -0.0117927 0.994495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.84 9.84502 191.849 3997.71 0.21108 4008.62 +EDGE_SE3:QUAT 602 652 3.84723 0.186983 -5.17221 -0.0484791 -0.0405169 -0.118321 0.990963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.77 3.86585 -387.788 3990.23 22.0885 3981.17 +EDGE_SE3:QUAT 601 652 2.82562 10.4626 -5.62044 0.117642 -0.0919953 0.0841303 0.9852 1 7.70372e-19 7.70372e-19 -5.59236e-08 -3.49858e-09 6.13735e-09 1 7.70372e-19 -5.59236e-08 -3.49858e-09 6.13735e-09 1 -5.59236e-08 -3.49858e-09 6.13735e-09 4123.8 -36.1552 -865.663 3955.51 -10.772 4150.85 +EDGE_SE3:QUAT 602 651 2.59324 -10.5596 -4.85755 -0.012121 -0.10912 -0.20865 0.971808 1 7.70372e-19 7.70372e-19 5.93672e-09 -1.93337e-09 -5.52353e-08 1 7.70372e-19 5.93672e-09 -1.93337e-09 -5.52353e-08 1 5.93672e-09 -1.93337e-09 -5.52353e-08 4184.27 -55.476 -880.021 3965.45 99.029 4010.72 +EDGE_SE3:QUAT 603 653 3.57728 -0.25496 -5.47849 0.135937 0.0513379 0.0693623 0.986952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3945.85 19.4537 285.574 3997.09 13.6628 4000.52 +EDGE_SE3:QUAT 602 653 2.82141 11.014 -5.59821 -0.00191872 -0.269658 0.103858 0.957337 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5406.19 262.046 -2757.39 3753.74 -264.414 5363.05 +EDGE_SE3:QUAT 603 652 2.59098 -10.7289 -5.04345 -0.00230116 0.121801 -0.119381 0.985346 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4235.36 -45.483 998.583 3948.65 -69.2654 4178.37 +EDGE_SE3:QUAT 604 654 3.46277 -0.149586 -5.42832 -0.173761 -0.119783 -0.0168795 0.97733 1 3.00927e-21 3.00927e-21 4.22551e-10 6.24788e-10 -3.49221e-09 1 3.00927e-21 4.22551e-10 6.24788e-10 -3.49221e-09 1 4.22551e-10 6.24788e-10 -3.49221e-09 4114.6 93.8393 -998.61 3951.72 -54.5955 4234.24 +EDGE_SE3:QUAT 603 654 2.66129 10.5788 -5.68155 0.135499 0.154814 0.0130144 0.978521 1 1.92593e-19 1.92593e-19 -4.21379e-09 -4.25013e-09 -2.84212e-08 1 1.92593e-19 -4.21379e-09 -4.25013e-09 -2.84212e-08 1 -4.21379e-09 -4.25013e-09 -2.84212e-08 4298.98 114.611 1276.5 3925.73 91.9901 4371.74 +EDGE_SE3:QUAT 604 653 2.94414 -10.6194 -5.32476 -0.13873 0.127219 -0.0440762 0.981135 1 9.62965e-19 9.62965e-19 5.37399e-08 -3.17009e-08 1.9558e-09 1 9.62965e-19 5.37399e-08 -3.17009e-08 1.9558e-09 1 5.37399e-08 -3.17009e-08 1.9558e-09 4137.43 -89.3894 951.836 3959.77 -72.4914 4206.64 +EDGE_SE3:QUAT 605 655 3.36504 -0.0777962 -5.20534 -0.147445 -0.0254008 0.180545 0.972121 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3913.91 -17.1003 121.073 3996.6 20.9766 3870.49 +EDGE_SE3:QUAT 604 655 2.94195 10.6927 -5.46958 -0.140629 0.0537583 0.170492 0.973789 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.19 -31.5401 698.454 3966.58 48.4834 4001.03 +EDGE_SE3:QUAT 605 654 2.68037 -10.5548 -5.42506 0.25346 0.167757 -0.196427 0.932219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4638.39 138.636 2094.97 3811.52 31.3321 4741.02 +EDGE_SE3:QUAT 606 656 3.23514 -0.422857 -4.74286 -0.0360548 0.0242765 0.0772282 0.996066 1 4.81482e-20 4.81482e-20 -1.38453e-08 -1.04782e-09 -4.09784e-10 1 4.81482e-20 -1.38453e-08 -1.04782e-09 -4.09784e-10 1 -1.38453e-08 -1.04782e-09 -4.09784e-10 4007.51 -2.9012 226.04 3996.6 8.54664 3988.85 +EDGE_SE3:QUAT 605 656 2.59616 10.7102 -5.16284 -0.0823241 0.00335299 0.192702 0.977792 1 2.0463e-19 2.0463e-19 2.84917e-08 -1.5201e-09 4.26921e-10 1 2.0463e-19 2.84917e-08 -1.5201e-09 4.26921e-10 1 2.84917e-08 -1.5201e-09 4.26921e-10 3983.13 -9.15758 210.44 3995.59 25.4859 3861.7 +EDGE_SE3:QUAT 606 655 2.68292 -10.4541 -5.08855 -0.0443253 0.00616362 -0.14915 0.987801 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.2 1.27077 -30.5246 3999.79 4.29172 3911.08 +EDGE_SE3:QUAT 607 657 3.3227 -0.0127866 -5.31244 -0.11541 -0.00851623 0.0339938 0.9927 1 1.93345e-19 1.93345e-19 -2.74923e-08 -2.69462e-09 -1.87445e-10 1 1.93345e-19 -2.74923e-08 -2.69462e-09 -1.87445e-10 1 -2.74923e-08 -2.69462e-09 -1.87445e-10 3946.76 0.233293 -20.0266 4000 -0.104915 3995.41 +EDGE_SE3:QUAT 606 657 2.79803 10.9208 -5.33218 0.00594688 0.0632368 0.156249 0.985673 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4057.11 15.5372 482.219 3988 38.9466 3959.6 +EDGE_SE3:QUAT 607 656 2.48414 -10.6623 -5.04997 0.0267357 0.0441497 -0.189016 0.980617 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4036.14 -5.1896 396.917 3990.96 -38.1882 3896.09 +EDGE_SE3:QUAT 608 658 3.80149 0.151564 -5.0797 -0.14137 -0.0321047 0.00845414 0.9894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3933.87 16.4857 -235.659 3997.07 -4.06642 4013.53 +EDGE_SE3:QUAT 607 658 2.82932 11.0171 -5.30828 0.0563269 -0.0229239 0.141685 0.988042 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.63 -5.15824 -272.611 3994.65 -20.2388 3938.02 +EDGE_SE3:QUAT 608 657 2.78437 -10.4625 -5.0988 0.150476 0.0628537 -0.190937 0.967962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4071.22 33.3847 824.348 3955.03 -62.1579 4015.96 +EDGE_SE3:QUAT 609 659 3.62606 0.217913 -5.15571 -0.0535108 0.00618306 -0.0907752 0.994414 1 2.40741e-19 2.40741e-19 1.36998e-08 -2.75342e-09 2.75501e-08 1 2.40741e-19 1.36998e-08 -2.75342e-09 2.75501e-08 1 1.36998e-08 -2.75342e-09 2.75501e-08 3988.47 0.77483 -9.2164 3999.95 1.31333 3966.97 +EDGE_SE3:QUAT 608 659 2.89836 10.5674 -5.43526 0.11192 -0.156074 0.0665553 0.979125 1 1.92593e-19 1.92593e-19 -2.87404e-08 -9.49098e-10 4.88023e-09 1 1.92593e-19 -2.87404e-08 -9.49098e-10 4.88023e-09 1 -2.87404e-08 -9.49098e-10 4.88023e-09 4416.76 -56.4552 -1444.15 3893.71 18.9124 4449.15 +EDGE_SE3:QUAT 609 658 2.73277 -10.6103 -5.28744 -0.037322 0.0513677 -0.0371158 0.997292 1 4.81482e-20 4.81482e-20 5.69554e-10 1.38381e-08 5.72144e-10 1 4.81482e-20 5.69554e-10 1.38381e-08 5.72144e-10 1 5.69554e-10 1.38381e-08 5.72144e-10 4033.21 -9.68633 395.845 3990.81 -9.6574 4033.28 +EDGE_SE3:QUAT 610 660 3.71184 0.196422 -5.33017 0.0751528 0.083964 0.0353002 0.993004 1 4.33334e-19 4.33334e-19 -2.76666e-08 -3.00504e-08 -1.38584e-08 1 4.33334e-19 -2.76666e-08 -3.00504e-08 -1.38584e-08 1 -2.76666e-08 -3.00504e-08 -1.38584e-08 4079.24 31.1393 646.478 3977.02 23.9769 4096.84 +EDGE_SE3:QUAT 609 660 2.75231 10.3671 -5.49295 0.109163 -0.197108 0.148854 0.962847 1 9.62965e-19 9.62965e-19 -3.58031e-08 5.02395e-08 3.7611e-09 1 9.62965e-19 -3.58031e-08 5.02395e-08 3.7611e-09 1 -3.58031e-08 5.02395e-08 3.7611e-09 4794.21 34.8285 -2019.12 3820.83 -78.8041 4753.25 +EDGE_SE3:QUAT 610 659 2.66958 -10.584 -5.16735 -0.118948 0.112265 -0.0965809 0.981794 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4077.36 -68.242 747.337 3977.93 -64.8066 4096.64 +EDGE_SE3:QUAT 611 661 3.56856 0.00138934 -4.99452 0.167682 0.0639269 -0.103404 0.978317 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.88 50.8403 705.804 3968.07 -14.0765 4077.58 +EDGE_SE3:QUAT 610 661 2.72113 10.3142 -5.52383 -0.0297539 0.085317 -0.0223646 0.995658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4112.12 -14.956 689.968 3972.2 -13.5338 4113.66 +EDGE_SE3:QUAT 611 660 2.5816 -10.8156 -5.52067 -0.0529135 -0.143932 -0.111834 0.981823 1 1.01111e-18 1.01111e-18 1.54539e-08 5.2499e-08 2.75049e-08 1 1.01111e-18 1.54539e-08 5.2499e-08 2.75049e-08 1 1.54539e-08 5.2499e-08 2.75049e-08 4374 -23.6882 -1299.72 3911.7 59.2082 4335.18 +EDGE_SE3:QUAT 612 662 3.35142 -0.282797 -5.06472 0.105709 -0.0412682 0.0760322 0.990627 1 1.92593e-19 1.92593e-19 1.55959e-09 -2.75391e-09 -2.7648e-08 1 1.92593e-19 1.55959e-09 -2.75391e-09 -2.7648e-08 1 1.55959e-09 -2.75391e-09 -2.7648e-08 3999.11 -19.7711 -421.707 3988.04 -11.1229 4020.69 +EDGE_SE3:QUAT 611 662 2.90368 10.5563 -4.76393 0.0106083 0.186158 -0.0199306 0.98226 1 7.52316e-22 7.52316e-22 -1.83119e-09 3.21457e-11 -3.47529e-10 1 7.52316e-22 -1.83119e-09 3.21457e-11 -3.47529e-10 1 -1.83119e-09 3.21457e-11 -3.47529e-10 4618.98 -7.42507 1691.58 3861.17 -12.6853 4617.84 +EDGE_SE3:QUAT 612 661 2.73278 -10.7897 -5.39377 0.0957257 0.191951 -0.0886621 0.972692 1 1.92593e-19 1.92593e-19 -6.14916e-09 -2.00121e-09 -2.93982e-08 1 1.92593e-19 -6.14916e-09 -2.00121e-09 -2.93982e-08 1 -6.14916e-09 -2.00121e-09 -2.93982e-08 4696.22 24.8208 1862.48 3838.99 -7.07056 4701.43 +EDGE_SE3:QUAT 613 663 3.42146 0.246326 -5.02926 0.0285923 0.301841 0.0128309 0.952843 1 6.01853e-20 6.01853e-20 -1.36022e-08 -2.33548e-10 2.98638e-09 1 6.01853e-20 -1.36022e-08 -2.33548e-10 2.98638e-09 1 -1.36022e-08 -2.33548e-10 2.98638e-09 5956.35 145.761 3417.4 3646.34 146.459 5958.96 +EDGE_SE3:QUAT 612 663 2.9366 10.5695 -5.20122 -0.0110318 -0.00693573 -0.0411367 0.999069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.44 0.290363 -60.7872 3999.76 1.27259 3994.15 +EDGE_SE3:QUAT 613 662 2.63763 -10.7584 -4.75629 -0.110187 -0.192424 -0.210857 0.952035 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4791.69 -115.987 -2016.78 3833.53 172.849 4662.41 +EDGE_SE3:QUAT 614 664 3.60149 0.157945 -5.32103 -0.0190164 -0.0498916 0.146861 0.987715 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.76 10.7169 -355.195 3993.72 -26.4994 3944.93 +EDGE_SE3:QUAT 613 664 2.79852 10.5474 -5.50439 -0.0714931 0.0641381 0.113469 0.988888 1 1.92593e-19 1.92593e-19 2.77607e-08 2.92536e-09 2.19169e-09 1 1.92593e-19 2.77607e-08 2.92536e-09 2.19169e-09 1 2.77607e-08 2.92536e-09 2.19169e-09 4069.95 -9.18669 608.531 3976.74 28.6701 4038.9 +EDGE_SE3:QUAT 614 663 2.42161 -10.8764 -5.02965 0.00762855 -0.0478891 -0.21139 0.976198 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.47 -11.1995 -340.838 3994.99 35.5557 3849.96 +EDGE_SE3:QUAT 615 665 3.55445 0.125226 -5.11119 -0.0333647 -0.163572 -0.0383456 0.985221 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4469.39 2.83 -1455.98 3891.11 11.2389 4467.96 +EDGE_SE3:QUAT 614 665 3.04074 10.8276 -5.5554 0.0446159 -0.108649 0.160873 0.979962 1 2.0463e-19 2.0463e-19 -1.12857e-08 2.61237e-08 6.05387e-10 1 2.0463e-19 -1.12857e-08 2.61237e-08 6.05387e-10 1 -1.12857e-08 2.61237e-08 6.05387e-10 4212.41 29.0019 -964.399 3950.33 -74.7231 4116.85 +EDGE_SE3:QUAT 615 664 2.33899 -10.6557 -4.91064 -0.0504282 -0.00267604 -0.228799 0.972163 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.29 3.66223 -153.282 3997.71 22.4689 3796.07 +EDGE_SE3:QUAT 616 666 3.14641 0.138177 -5.06369 -0.084629 -0.0521719 0.0464863 0.993959 1 2.40741e-19 2.40741e-19 2.71e-08 2.81681e-10 1.26446e-08 1 2.40741e-19 2.71e-08 2.81681e-10 1.26446e-08 1 2.71e-08 2.81681e-10 1.26446e-08 4004.64 17.6632 -366.936 3992.91 -12.8843 4024.64 +EDGE_SE3:QUAT 615 666 3.0079 10.5613 -5.3015 0.14197 -0.146425 0.00630722 0.978961 1 3.00927e-21 3.00927e-21 5.14621e-10 -5.30382e-10 -3.54491e-09 1 3.00927e-21 5.14621e-10 -5.30382e-10 -3.54491e-09 1 5.14621e-10 -5.30382e-10 -3.54491e-09 4269.15 -103.556 -1233.63 3927.57 74.4189 4349.61 +EDGE_SE3:QUAT 616 665 2.57262 -10.6104 -5.39087 0.0064385 0.000789202 -0.0652035 0.997851 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.87 0.0391909 11.2964 3999.99 -0.422341 3983.03 +EDGE_SE3:QUAT 617 667 3.55431 0.00428364 -4.75571 -0.00931754 -0.183293 -0.0377089 0.982291 1 4.89006e-20 4.89006e-20 -4.55719e-09 1.36908e-10 1.49583e-08 1 4.89006e-20 -4.55719e-09 1.36908e-10 1.49583e-08 1 -4.55719e-09 1.36908e-10 1.49583e-08 4597.71 -25.5349 -1658.28 3866.18 33.7755 4592.37 +EDGE_SE3:QUAT 616 667 2.52459 10.6353 -5.54318 -0.0819268 0.127864 0.0135567 0.988309 1 1.88079e-22 1.88079e-22 1.15137e-10 -7.27941e-11 8.86577e-10 1 1.88079e-22 1.15137e-10 -7.27941e-11 8.86577e-10 1 1.15137e-10 -7.27941e-11 8.86577e-10 4249.9 -46.6466 1087.94 3935.95 -26.4691 4276.02 +EDGE_SE3:QUAT 617 666 2.3937 -10.719 -4.93281 -0.0671658 0.0671763 -0.154338 0.983441 1 1.92593e-19 1.92593e-19 -2.74286e-08 4.54785e-09 -1.1909e-09 1 1.92593e-19 -2.74286e-08 4.54785e-09 -1.1909e-09 1 -2.74286e-08 4.54785e-09 -1.1909e-09 4019.74 -22.6973 394.501 3994.42 -32.3116 3942.51 +EDGE_SE3:QUAT 618 668 3.12883 0.2141 -5.75536 0.0325457 -0.100064 0.105463 0.988841 1 2.0463e-19 2.0463e-19 9.8149e-09 -2.67434e-08 -4.3117e-10 1 2.0463e-19 9.8149e-09 -2.67434e-08 -4.3117e-10 1 9.8149e-09 -2.67434e-08 -4.3117e-10 4172.74 12.5922 -859.788 3958.02 -42.154 4132.48 +EDGE_SE3:QUAT 617 668 2.65604 10.7608 -5.18163 -0.0950825 0.113182 -0.0212827 0.988785 1 4.81482e-20 4.81482e-20 -1.51846e-09 1.45471e-09 -1.40559e-08 1 4.81482e-20 -1.51846e-09 1.45471e-09 -1.40559e-08 1 -1.51846e-09 1.45471e-09 -1.40559e-08 4158.68 -54.5505 904.25 3956.93 -39.9103 4193.04 +EDGE_SE3:QUAT 618 667 2.68636 -10.82 -5.21938 -0.0323576 -0.166655 -0.105148 0.979859 1 3.00927e-21 3.00927e-21 3.60783e-09 -3.68317e-10 -6.24656e-10 1 3.00927e-21 3.60783e-09 -3.68317e-10 -6.24656e-10 1 3.60783e-09 -3.68317e-10 -6.24656e-10 4495.18 -51.2713 -1498.95 3889.76 77.8584 4455.15 +EDGE_SE3:QUAT 619 669 3.01446 0.466764 -5.27492 -0.0862339 -0.123443 0.133565 0.979534 1 3.85186e-19 3.85186e-19 -2.34312e-08 -3.15379e-08 -6.35029e-10 1 3.85186e-19 -2.34312e-08 -3.15379e-08 -6.35029e-10 1 -2.34312e-08 -3.15379e-08 -6.35029e-10 4137.39 76.9651 -837.817 3973.03 -84.3519 4095.78 +EDGE_SE3:QUAT 618 669 2.58497 10.5617 -5.73037 -0.0691353 -0.0992851 0.0417786 0.991775 1 3.85186e-19 3.85186e-19 -2.64695e-08 -2.90921e-08 4.20696e-10 1 3.85186e-19 -2.64695e-08 -2.90921e-08 4.20696e-10 1 -2.64695e-08 -2.90921e-08 4.20696e-10 4125.61 38.4347 -774.698 3967.56 -33.2138 4137.74 +EDGE_SE3:QUAT 619 668 2.89592 -10.8213 -5.17259 0.00360528 0.0260661 -0.154733 0.987606 1 1.22751e-20 1.22751e-20 1.08827e-10 7.00408e-09 6.1773e-12 1 1.22751e-20 1.08827e-10 7.00408e-09 6.1773e-12 1 1.08827e-10 7.00408e-09 6.1773e-12 4010.75 -2.16832 208.165 3997.58 -16.1393 3915.03 +EDGE_SE3:QUAT 620 670 3.39442 0.363578 -4.82524 -0.0694237 -0.0843088 -0.106876 0.988256 1 2.40741e-19 2.40741e-19 -1.66232e-08 -2.6108e-08 -4.81908e-11 1 2.40741e-19 -1.66232e-08 -2.6108e-08 -4.81908e-11 1 -1.66232e-08 -2.6108e-08 -4.81908e-11 4124.26 7.41461 -771.466 3964.25 31.4655 4097.85 +EDGE_SE3:QUAT 619 670 2.55138 10.8463 -5.50007 -0.0650763 -0.0201825 0.169548 0.983164 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.66 -0.570913 -23.98 4000.01 1.87137 3884.62 +EDGE_SE3:QUAT 620 669 2.61194 -10.6943 -4.61466 0.0354266 -0.0220138 -0.132832 0.990261 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.19 -2.51893 -115.405 3999.53 6.54875 3932.63 +EDGE_SE3:QUAT 621 671 3.55148 0.360775 -5.2312 0.0464339 0.110318 0.0128663 0.992728 1 4.81482e-20 4.81482e-20 1.41131e-08 3.34818e-10 1.54338e-09 1 4.81482e-20 1.41131e-08 3.34818e-10 1.54338e-09 1 1.41131e-08 3.34818e-10 1.54338e-09 4188.47 27.6511 909.532 3953.49 20.7101 4196.43 +EDGE_SE3:QUAT 620 671 3.06231 10.8432 -5.62309 -0.109413 0.0370482 -0.0301089 0.992849 1 7.70372e-19 7.70372e-19 5.52242e-08 -2.08754e-09 1.64222e-09 1 7.70372e-19 5.52242e-08 -2.08754e-09 1.64222e-09 1 5.52242e-08 -2.08754e-09 1.64222e-09 3967.88 -13.9167 252.207 3996.77 -6.4482 4012.14 +EDGE_SE3:QUAT 621 670 2.66343 -10.778 -5.26336 0.185885 0.0602746 -0.179587 0.964138 1 7.70372e-19 7.70372e-19 6.67124e-09 8.78876e-09 5.47412e-08 1 7.70372e-19 6.67124e-09 8.78876e-09 5.47412e-08 1 6.67124e-09 8.78876e-09 5.47412e-08 4035.28 56.2146 855.901 3950.56 -51.4903 4044.49 +EDGE_SE3:QUAT 622 672 3.43438 0.284766 -5.43601 0.00636722 0.106253 -0.067821 0.992003 1 1.88079e-22 1.88079e-22 8.80362e-10 -6.03608e-11 9.41864e-11 1 1.88079e-22 8.80362e-10 -6.03608e-11 9.41864e-11 1 8.80362e-10 -6.03608e-11 9.41864e-11 4186.47 -16.2914 883.96 3955.83 -31.7488 4168.24 +EDGE_SE3:QUAT 621 672 2.59731 10.672 -5.3902 0.0380052 -0.047316 0.215792 0.974552 1 1.20371e-20 1.20371e-20 6.80697e-09 1.48625e-09 -4.11094e-10 1 1.20371e-20 6.80697e-09 1.48625e-09 -4.11094e-10 1 6.80697e-09 1.48625e-09 -4.11094e-10 4044.73 6.42458 -452.47 3988.3 -50.0764 3864.24 +EDGE_SE3:QUAT 622 671 2.74498 -10.7018 -5.17555 0.0495695 0.0110288 -0.0226367 0.998453 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.73 2.54112 101.338 3999.31 -1.01775 4000.51 +EDGE_SE3:QUAT 623 673 3.59477 -0.110399 -5.37305 0.269673 0.192381 0.0351083 0.942886 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4118.03 259.259 1352.63 3979.38 236.952 4403.99 +EDGE_SE3:QUAT 622 673 2.81668 10.5806 -5.62499 0.059458 -0.0220217 0.265569 0.962005 1 9.62965e-20 9.62965e-20 1.70356e-08 -9.72007e-09 -1.31291e-10 1 9.62965e-20 1.70356e-08 -9.72007e-09 -1.31291e-10 1 1.70356e-08 -9.72007e-09 -1.31291e-10 4014.07 -2.36258 -339.715 3991.84 -51.0339 3746.11 +EDGE_SE3:QUAT 623 672 2.41414 -11.077 -5.36002 -0.137032 0.0106047 0.0600286 0.988689 1 3.09352e-18 3.09352e-18 -1.10258e-07 7.58709e-10 -1.99843e-09 1 3.09352e-18 -1.10258e-07 7.58709e-10 -1.99843e-09 1 -1.10258e-07 7.58709e-10 -1.99843e-09 3932.72 -13.9649 179.619 3997.33 5.06406 3993.42 +EDGE_SE3:QUAT 624 674 3.34749 0.323488 -5.49045 0.0747671 -0.0398537 0.00243301 0.996401 1 1.17549e-23 1.17549e-23 -8.65139e-12 1.6274e-11 2.1675e-10 1 1.17549e-23 -8.65139e-12 1.6274e-11 2.1675e-10 1 -8.65139e-12 1.6274e-11 2.1675e-10 4003.09 -12.0678 -320.108 3993.82 2.47748 4025.43 +EDGE_SE3:QUAT 623 674 2.83629 10.7186 -5.57619 -0.0248704 0.000791701 0.204223 0.978608 1 7.70372e-19 7.70372e-19 -5.9214e-10 1.24803e-09 -5.43306e-08 1 7.70372e-19 -5.9214e-10 1.24803e-09 -5.43306e-08 1 -5.9214e-10 1.24803e-09 -5.43306e-08 3998.5 -0.849838 65.1819 3999.57 8.69051 3834.15 +EDGE_SE3:QUAT 624 673 2.63157 -11.088 -5.0666 0.174318 -0.204715 0.0339617 0.962576 1 7.79588e-19 7.79588e-19 -5.98056e-08 3.613e-09 1.87583e-08 1 7.79588e-19 -5.98056e-08 3.613e-09 1.87583e-08 1 -5.98056e-08 3.613e-09 1.87583e-08 4640.19 -201.838 -1904.72 3859.87 172.672 4757.12 +EDGE_SE3:QUAT 625 675 3.07627 -0.0132445 -5.30035 -0.0531151 0.0251131 0.13087 0.989657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.89 -4.77901 278.59 3994.55 18.731 3950.67 +EDGE_SE3:QUAT 624 675 2.89576 11.0138 -5.43293 0.154786 0.14277 0.182913 0.960313 1 9.62965e-19 9.62965e-19 4.79879e-08 3.90457e-08 -1.67721e-09 1 9.62965e-19 4.79879e-08 3.90457e-08 -1.67721e-09 1 4.79879e-08 3.90457e-08 -1.67721e-09 4022.11 98.7512 719.034 3999.3 100.903 3984.12 +EDGE_SE3:QUAT 625 674 2.761 -10.993 -4.90116 0.00327725 -0.0139985 -0.12875 0.991573 1 7.70372e-19 7.70372e-19 7.05049e-10 -3.74573e-10 -5.50623e-08 1 7.70372e-19 7.05049e-10 -3.74573e-10 -5.50623e-08 1 7.05049e-10 -3.74573e-10 -5.50623e-08 4002.67 -0.71345 -104.264 3999.4 6.56964 3936.41 +EDGE_SE3:QUAT 626 676 3.39289 0.145744 -5.14175 -0.0104272 0.0976832 0.000445602 0.995163 1 1.17549e-23 1.17549e-23 -2.1591e-11 2.33035e-12 -2.1999e-10 1 1.17549e-23 -2.1591e-11 2.33035e-12 -2.1999e-10 1 -2.1591e-11 2.33035e-12 -2.1999e-10 4156.69 -4.53249 808.205 3961.86 -2.30341 4157.13 +EDGE_SE3:QUAT 625 676 2.70061 10.568 -5.37373 -0.145239 0.269444 0.12869 0.943263 1 9.62965e-19 9.62965e-19 -5.08619e-08 3.97604e-09 -7.26381e-08 1 9.62965e-19 -5.08619e-08 3.97604e-09 -7.26381e-08 1 -5.08619e-08 3.97604e-09 -7.26381e-08 5644.69 -54.1804 3147.45 3676.77 -45.9164 5662.83 +EDGE_SE3:QUAT 626 675 2.50322 -10.5313 -5.29889 -0.0748207 0.184988 -0.0972303 0.975053 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4474.54 -154.883 1496.11 3910.87 -158.166 4459.12 +EDGE_SE3:QUAT 627 677 3.25335 0.0794597 -5.45135 -0.121082 -0.000228645 -0.0572946 0.990988 1 2.41494e-19 2.41494e-19 -2.74135e-08 1.49246e-09 -1.35763e-08 1 2.41494e-19 -2.74135e-08 1.49246e-09 -1.35763e-08 1 -2.74135e-08 1.49246e-09 -1.35763e-08 3942.94 6.67781 -84.0667 3999.23 3.00808 3988.46 +EDGE_SE3:QUAT 626 677 2.93935 10.9912 -5.75839 0.129987 0.0690942 0.0558483 0.987527 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.93 33.2447 454.118 3990.76 23.3787 4038.05 +EDGE_SE3:QUAT 627 676 1.99826 -10.6792 -4.95887 -0.00575004 0.158569 0.115503 0.980552 1 3.00927e-21 3.00927e-21 -3.57925e-09 -4.37135e-10 -5.67646e-10 1 3.00927e-21 -3.57925e-09 -4.37135e-10 -5.67646e-10 1 -3.57925e-09 -4.37135e-10 -5.67646e-10 4421.57 72.6973 1365.61 3910 95.98 4368.34 +EDGE_SE3:QUAT 628 678 3.15205 -0.12688 -5.56308 -0.0761033 -0.0604275 0.176245 0.979538 1 1.92593e-19 1.92593e-19 5.10663e-09 -2.71481e-08 -2.57096e-09 1 1.92593e-19 5.10663e-09 -2.71481e-08 -2.57096e-09 1 5.10663e-09 -2.71481e-08 -2.57096e-09 3998.06 17.0624 -299.999 3997.98 -24.8674 3896.98 +EDGE_SE3:QUAT 627 678 2.58834 10.8414 -5.27765 0.204029 0.091512 -0.136594 0.965059 1 3.85186e-19 3.85186e-19 -1.34942e-09 2.18779e-08 -3.26073e-08 1 3.85186e-19 -1.34942e-09 2.18779e-08 -3.26073e-08 1 -1.34942e-09 2.18779e-08 -3.26073e-08 4093.71 81.9025 1054.91 3934.58 -13.6692 4185.59 +EDGE_SE3:QUAT 628 677 2.77898 -10.5843 -4.90331 -0.172282 0.0570961 -0.00387657 0.983384 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3927.52 -37.973 432.885 3990.57 -13.4232 4046.19 +EDGE_SE3:QUAT 629 679 3.39834 0.0115457 -5.03001 0.0563079 0.0293162 -0.0210518 0.997761 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.67 6.70501 248.316 3996.09 -1.41314 4013.58 +EDGE_SE3:QUAT 628 679 2.50542 11.1093 -5.50826 0.0105901 -0.187871 -0.0352033 0.981506 1 4.81482e-20 4.81482e-20 -2.78296e-09 3.77974e-10 1.46454e-08 1 4.81482e-20 -2.78296e-09 3.77974e-10 1.46454e-08 1 -2.78296e-09 3.77974e-10 1.46454e-08 4622.66 -47.708 -1697.26 3862.44 51.852 4618.15 +EDGE_SE3:QUAT 629 678 2.76645 -10.7857 -5.49178 0.03302 0.0681887 0.13909 0.987377 1 4.81482e-20 4.81482e-20 1.38011e-08 2.01956e-09 7.85327e-10 1 4.81482e-20 1.38011e-08 2.01956e-09 7.85327e-10 1 1.38011e-08 2.01956e-09 7.85327e-10 4052.13 20.7205 479.59 3988.89 36.1515 3979.1 +EDGE_SE3:QUAT 630 680 3.11924 -0.0151142 -5.21465 -0.0402877 0.00855212 0.079901 0.995952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.28 -2.10703 106.095 3999.14 4.60311 3977.24 +EDGE_SE3:QUAT 629 680 2.86899 10.8825 -5.36524 -0.0257983 0.00788397 0.0918699 0.995406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.37 -1.04102 90.5278 3999.39 4.51572 3968.27 +EDGE_SE3:QUAT 630 679 2.64064 -10.564 -5.21107 -0.154397 0.0570682 0.174277 0.970841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.11 -38.1957 758.062 3960.94 50.799 4015.97 +EDGE_SE3:QUAT 631 681 3.12292 -0.359784 -5.31192 -0.0834754 0.0449818 0.232899 0.967867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4049.14 -3.18054 562.458 3979.38 67.2397 3860.04 +EDGE_SE3:QUAT 630 681 2.68788 10.8182 -5.75372 0.126834 -0.050682 -0.00278042 0.990624 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.22 -25.5622 -394.757 3991.32 8.10994 4038.54 +EDGE_SE3:QUAT 631 680 2.47639 -10.7658 -5.15332 -0.0982517 0.10799 0.0201288 0.98908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4159.93 -44.6082 913.013 3953.58 -19.5018 4196.92 +EDGE_SE3:QUAT 632 682 3.45034 0.0590906 -5.20922 0.139413 0.0453232 -0.0867389 0.985386 1 1.92593e-19 1.92593e-19 -1.87054e-09 -3.64317e-09 -2.75623e-08 1 1.92593e-19 -1.87054e-09 -3.64317e-09 -2.75623e-08 1 -1.87054e-09 -3.64317e-09 -2.75623e-08 3983.03 31.7074 498.158 3983.22 -12.6488 4030.68 +EDGE_SE3:QUAT 631 682 2.73269 11.3734 -5.34859 0.0621711 0.0132276 0.208652 0.975922 1 1.92593e-19 1.92593e-19 2.70873e-08 5.79105e-09 -3.70555e-10 1 1.92593e-19 2.70873e-08 5.79105e-09 -3.70555e-10 1 2.70873e-08 5.79105e-09 -3.70555e-10 3984.55 -3.31867 -52.369 3999.29 -11.1421 3825.87 +EDGE_SE3:QUAT 632 681 2.44754 -10.6916 -5.17397 0.045471 -0.0127808 0.0223576 0.998634 1 3.00927e-21 3.00927e-21 7.32486e-11 -3.4648e-09 1.55681e-10 1 3.00927e-21 7.32486e-11 -3.4648e-09 1.55681e-10 1 7.32486e-11 -3.4648e-09 1.55681e-10 3994.98 -2.58483 -114.119 3999.14 -1.11009 4001.25 +EDGE_SE3:QUAT 633 683 2.93928 -0.0471417 -5.17434 -0.0228054 -0.151896 -0.182472 0.971139 1 7.73381e-19 7.73381e-19 -6.69238e-09 -5.45614e-08 1.35081e-09 1 7.73381e-19 -6.69238e-09 -5.45614e-08 1.35081e-09 1 -6.69238e-09 -5.45614e-08 1.35081e-09 4386.48 -95.0389 -1306.09 3924.53 134.985 4255.38 +EDGE_SE3:QUAT 632 683 2.62987 10.7727 -5.2553 -0.0209727 -0.112225 0.240282 0.963966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4144.95 69.3928 -783.313 3980.68 -104.781 3915.77 +EDGE_SE3:QUAT 633 682 3.05749 -10.8853 -5.38079 -0.0350387 -0.127312 0.072976 0.988554 1 4.81482e-20 4.81482e-20 -1.41433e-08 -1.20599e-09 1.72086e-09 1 4.81482e-20 -1.41433e-08 -1.20599e-09 1.72086e-09 1 -1.41433e-08 -1.20599e-09 1.72086e-09 4244.39 49.5502 -1029.42 3944.85 -57.101 4228 +EDGE_SE3:QUAT 634 684 3.61854 0.18452 -5.31607 0.0326946 -0.178507 0.131916 0.974507 1 3.00927e-21 3.00927e-21 -3.62042e-09 -4.77994e-10 6.71497e-10 1 3.00927e-21 -3.62042e-09 -4.77994e-10 6.71497e-10 1 -3.62042e-09 -4.77994e-10 6.71497e-10 4571.8 85.8198 -1623.64 3879 -115.377 4506.47 +EDGE_SE3:QUAT 633 684 2.75677 10.8427 -5.47162 0.0416658 0.0312472 -0.0184574 0.998472 1 4.81482e-20 4.81482e-20 -1.38856e-08 2.20078e-10 -4.54163e-10 1 4.81482e-20 -1.38856e-08 2.20078e-10 -4.54163e-10 1 -1.38856e-08 2.20078e-10 -4.54163e-10 4009.8 5.06201 259.387 3995.76 -1.4108 4015.39 +EDGE_SE3:QUAT 634 683 2.41754 -10.8826 -5.27038 0.028792 0.0549251 -0.1328 0.989201 1 1.20371e-20 1.20371e-20 6.91316e-09 -9.10563e-10 4.22957e-10 1 1.20371e-20 6.91316e-09 -9.10563e-10 4.22957e-10 1 6.91316e-09 -9.10563e-10 4.22957e-10 4053.19 -3.77609 478.822 3986.28 -31.2659 3985.96 +EDGE_SE3:QUAT 635 685 3.42058 -0.379591 -5.23843 0.147488 0.0582811 0.0772936 0.984315 1 7.70372e-19 7.70372e-19 -5.48063e-08 -5.08633e-09 -1.80332e-09 1 7.70372e-19 -5.48063e-08 -5.08633e-09 -1.80332e-09 1 -5.48063e-08 -5.08633e-09 -1.80332e-09 3936.58 23.3179 313.245 3996.92 17.1104 3999.69 +EDGE_SE3:QUAT 634 685 2.79464 10.8501 -5.3463 -0.125888 -0.0568867 -0.0603775 0.98857 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.42 30.9384 -541.157 3981.53 4.88262 4057.23 +EDGE_SE3:QUAT 635 684 2.3669 -10.8722 -5.15085 0.0749907 -0.00846732 -0.0445638 0.996152 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.64 -0.525597 -27.064 3999.99 0.335715 3992.19 +EDGE_SE3:QUAT 636 686 2.99849 -0.0102704 -5.67978 0.0601164 0.127686 -0.121768 0.982474 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4296.2 -15.6303 1157.29 3927.56 -56.6449 4251.35 +EDGE_SE3:QUAT 635 686 2.93553 11.0244 -5.46587 -0.06079 0.061001 0.0770747 0.993299 1 4.33334e-19 4.33334e-19 -1.39076e-08 2.51761e-08 2.82733e-08 1 4.33334e-19 -1.39076e-08 2.51761e-08 2.82733e-08 1 -1.39076e-08 2.51761e-08 2.82733e-08 4058.37 -9.61612 546.044 3981.32 16.1309 4049.39 +EDGE_SE3:QUAT 636 685 2.43749 -10.9223 -5.45511 0.06629 0.0406616 -0.133644 0.987973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4026.67 7.28782 423.905 3987.98 -27.099 3972.81 +EDGE_SE3:QUAT 637 687 3.2703 0.120626 -5.28829 0.0322186 0.112466 -0.266929 0.956589 1 1.05794e-22 1.05794e-22 6.39828e-10 -1.78406e-10 7.55138e-11 1 1.05794e-22 6.39828e-10 -1.78406e-10 7.55138e-11 1 6.39828e-10 -1.78406e-10 7.55138e-11 4208.09 -72.8888 946.089 3965.47 -134.035 3927.24 +EDGE_SE3:QUAT 636 687 2.70167 10.8348 -5.16527 -0.159477 0.0295144 0.0946075 0.982215 1 9.62965e-19 9.62965e-19 5.64018e-08 2.78625e-10 3.05956e-08 1 9.62965e-19 5.64018e-08 2.78625e-10 3.05956e-08 1 5.64018e-08 2.78625e-10 3.05956e-08 3938.32 -32.5541 405.225 3987.8 14.0029 4004.25 +EDGE_SE3:QUAT 637 686 2.47903 -10.9143 -5.33129 0.074423 -0.083071 0.0711777 0.991208 1 9.62965e-19 9.62965e-19 5.75721e-08 -2.42043e-08 -3.44596e-09 1 9.62965e-19 5.75721e-08 -2.42043e-08 -3.44596e-09 1 5.75721e-08 -2.42043e-08 -3.44596e-09 4110 -16.4859 -739.129 3967.02 -14.5265 4111.89 +EDGE_SE3:QUAT 638 688 3.226 0.0664698 -5.19743 -0.26393 -0.0491625 0.177614 0.946772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3721.61 -52.5415 189.897 3990.08 35.339 3874.06 +EDGE_SE3:QUAT 637 688 2.18915 11.2166 -5.22966 0.100334 -0.0370469 0.0730062 0.99158 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.35 -17.2008 -379.908 3990.2 -10.1931 4014.3 +EDGE_SE3:QUAT 638 687 2.55231 -10.7583 -5.35938 -0.175146 -0.166551 -0.0741549 0.967515 1 7.70372e-19 7.70372e-19 7.79245e-10 5.38598e-08 8.84255e-09 1 7.70372e-19 7.79245e-10 5.38598e-08 8.84255e-09 1 7.79245e-10 5.38598e-08 8.84255e-09 4436.48 124.287 -1596.72 3881.95 -73.7132 4537.19 +EDGE_SE3:QUAT 639 689 3.11761 -0.0319039 -5.21419 0.0545957 -0.0554558 0.122558 0.989406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4054.29 -3.69647 -519.214 3983.05 -29.274 4006.13 +EDGE_SE3:QUAT 638 689 2.70014 10.5637 -5.85674 0.0834426 0.108005 0.164966 0.97681 1 1.92593e-19 1.92593e-19 2.74872e-08 5.17795e-09 2.04534e-09 1 1.92593e-19 2.74872e-08 5.17795e-09 2.04534e-09 1 2.74872e-08 5.17795e-09 2.04534e-09 4079.26 59.5606 668.679 3985.56 70.6802 3998.26 +EDGE_SE3:QUAT 639 688 2.22258 -11.1954 -5.2767 -0.143566 0.130044 -0.214618 0.957297 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.62 -72.9163 579.307 4003.81 -77.0254 3889.82 +EDGE_SE3:QUAT 640 690 3.02935 -0.0775561 -5.28472 0.00424425 -0.118593 0.0399873 0.992128 1 2.40788e-19 2.40788e-19 -1.36674e-10 -2.75951e-08 1.39667e-08 1 2.40788e-19 -1.36674e-10 -2.75951e-08 1.39667e-08 1 -1.36674e-10 -2.75951e-08 1.39667e-08 4234.7 12.0369 -997.105 3944.17 -21.3855 4228.38 +EDGE_SE3:QUAT 639 690 2.52059 11.1164 -5.62475 0.0593337 -0.0949093 0.0698573 0.991258 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4151 -10.2491 -829.27 3959.46 -17.7335 4145.56 +EDGE_SE3:QUAT 640 689 2.77701 -11.0276 -5.47015 0.0168704 0.0474245 -0.0297998 0.998288 1 1.50463e-20 1.50463e-20 3.8165e-09 -5.17423e-13 7.12768e-09 1 1.50463e-20 3.8165e-09 -5.17423e-13 7.12768e-09 1 3.8165e-09 -5.17423e-13 7.12768e-09 4036.14 1.70255 387.93 3990.7 -5.00425 4033.72 +EDGE_SE3:QUAT 641 691 3.2869 -0.332037 -5.10552 0.151926 -0.109371 0.0889253 0.978289 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4169.19 -61.3312 -1056.07 3937.32 2.72019 4229.88 +EDGE_SE3:QUAT 640 691 2.50181 10.6 -5.34987 0.0129902 -0.0804166 -0.106466 0.990974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4095.67 -20.2713 -628.353 3978.37 37.1023 4051 +EDGE_SE3:QUAT 641 690 2.6164 -10.9951 -5.2524 0.0465889 0.162477 0.0659138 0.983405 1 1.92593e-19 1.92593e-19 -4.48581e-09 -2.06982e-09 -2.87009e-08 1 1.92593e-19 -4.48581e-09 -2.06982e-09 -2.87009e-08 1 -4.48581e-09 -2.06982e-09 -2.87009e-08 4410.36 84.4878 1361 3911.1 88.0214 4401.66 +EDGE_SE3:QUAT 642 692 3.16984 -0.301653 -5.73512 0.00407289 0.110764 -0.0807465 0.990553 1 1.92593e-19 1.92593e-19 -3.12832e-09 3.99576e-10 -2.81819e-08 1 1.92593e-19 -3.12832e-09 3.99576e-10 -2.81819e-08 1 -3.12832e-09 3.99576e-10 -2.81819e-08 4201.43 -22.9998 920.124 3953.05 -40.6644 4175.42 +EDGE_SE3:QUAT 641 692 2.77107 10.9325 -5.77663 -0.105947 0.0937287 0.142015 0.979705 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4163.54 -15.4193 937.354 3947.92 46.0923 4127.77 +EDGE_SE3:QUAT 642 691 3.03493 -11.0528 -5.46973 0.0563327 0.190374 -0.0948321 0.975495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4677.34 -32.8924 1798.98 3848.86 -58.7941 4654.06 +EDGE_SE3:QUAT 643 693 3.18332 -0.0842548 -5.49381 0.131785 0.0464244 -0.013233 0.990102 1 4.89006e-20 4.89006e-20 -7.49386e-11 1.35132e-08 -3.54524e-09 1 4.89006e-20 -7.49386e-11 1.35132e-08 -3.54524e-09 1 -7.49386e-11 1.35132e-08 -3.54524e-09 3967.35 25.5248 385.531 3991.31 4.64289 4036.12 +EDGE_SE3:QUAT 642 693 2.59863 10.8157 -5.52255 -0.0730601 0.111568 0.0960823 0.986399 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4219.03 -8.41342 1009.74 3941.84 30.2986 4203.45 +EDGE_SE3:QUAT 643 692 2.54451 -10.4958 -4.83838 0.0856248 -0.012833 -0.0819781 0.992866 1 7.52316e-22 7.52316e-22 1.43919e-10 1.72221e-09 -1.50173e-10 1 7.52316e-22 1.43919e-10 1.72221e-09 -1.50173e-10 1 1.43919e-10 1.72221e-09 -1.50173e-10 3970.54 0.466115 -17.0473 4000 -0.443031 3972.98 +EDGE_SE3:QUAT 644 694 2.98331 -0.176173 -5.41835 -0.0274604 -0.0524895 -0.0280905 0.997849 1 1.20371e-20 1.20371e-20 -3.76018e-10 -1.71767e-10 6.96393e-09 1 1.20371e-20 -3.76018e-10 -1.71767e-10 6.96393e-09 1 -3.76018e-10 -1.71767e-10 6.96393e-09 4043.23 4.21093 -432.592 3988.44 4.39573 4043.09 +EDGE_SE3:QUAT 643 694 2.65645 11.3151 -5.16556 0.0584877 0.0316246 -0.0671461 0.995525 1 2.40741e-19 2.40741e-19 2.85847e-08 1.20618e-08 3.36989e-10 1 2.40741e-19 2.85847e-08 1.20618e-08 3.36989e-10 1 2.85847e-08 1.20618e-08 3.36989e-10 4008.42 7.17252 298.458 3994.06 -8.81562 4004.07 +EDGE_SE3:QUAT 644 693 2.17416 -11.5928 -5.09851 -0.0337315 0.0664095 -0.0317211 0.996717 1 4.81482e-20 4.81482e-20 -1.39488e-08 5.09836e-10 -8.95118e-10 1 4.81482e-20 -1.39488e-08 5.09836e-10 -8.95118e-10 1 -1.39488e-08 5.09836e-10 -8.95118e-10 4063 -12.4427 524.206 3983.83 -12.1051 4063.52 +EDGE_SE3:QUAT 645 695 3.29478 0.137669 -5.22804 -0.0982648 -0.0456371 -0.0968171 0.989388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.53 18.3163 -473.915 3984.91 17.8273 4017.66 +EDGE_SE3:QUAT 644 695 2.67241 10.6776 -5.48772 -0.216908 -0.0426014 0.0707464 0.972693 1 1.92593e-19 1.92593e-19 2.27068e-10 6.13961e-09 -2.70095e-08 1 1.92593e-19 2.27068e-10 6.13961e-09 -2.70095e-08 1 2.27068e-10 6.13961e-09 -2.70095e-08 3815.13 8.11094 -136.301 4000.34 -5.03768 3983.3 +EDGE_SE3:QUAT 645 694 2.50323 -10.7432 -5.08111 0.000511002 0.066311 0.00974793 0.997751 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4071.26 1.19453 538.612 3982.43 2.80169 4070.88 +EDGE_SE3:QUAT 646 696 3.30754 0.201594 -5.54336 0.0134643 0.0935467 -0.10672 0.989787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4144.81 -18.0276 776.741 3966.11 -42.4442 4099.98 +EDGE_SE3:QUAT 645 696 2.69056 11.0563 -5.66221 -0.0647925 0.139336 0.0955785 0.98349 1 4.81482e-20 4.81482e-20 1.42653e-08 1.16439e-09 2.15273e-09 1 4.81482e-20 1.42653e-08 1.16439e-09 2.15273e-09 1 1.42653e-08 1.16439e-09 2.15273e-09 4348.62 3.01916 1263.06 3914.5 38.3087 4328.87 +EDGE_SE3:QUAT 646 695 2.64827 -11.1014 -5.29966 0.0897312 -0.105661 -0.0215938 0.99011 1 1.92593e-19 1.92593e-19 2.80623e-08 -1.15971e-09 -2.8301e-09 1 1.92593e-19 2.80623e-08 -1.15971e-09 -2.8301e-09 1 2.80623e-08 -1.15971e-09 -2.8301e-09 4137.16 -47.2235 -840.473 3962.09 33.8087 4167.5 +EDGE_SE3:QUAT 647 697 3.16375 0.155169 -5.83103 -0.036355 0.0400353 0.0298882 0.998089 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.46 -5.0278 334.314 3992.98 3.64886 4024.17 +EDGE_SE3:QUAT 646 697 2.43368 10.531 -5.47785 -0.10812 -0.162542 -0.0431644 0.97981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4437.36 71.0219 -1473.39 3891.93 -40.8434 4476.67 +EDGE_SE3:QUAT 647 696 2.74899 -11.0391 -5.41723 -0.178203 -0.0258746 0.0158037 0.983526 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3879.63 13.5908 -164.24 3998.87 -3.23379 4005.66 +EDGE_SE3:QUAT 648 698 3.26881 0.166167 -5.71381 -0.00157761 -0.227182 0.0720325 0.971184 1 1.20371e-20 1.20371e-20 -7.5032e-09 -6.26524e-10 1.73284e-09 1 1.20371e-20 -7.5032e-09 -6.26524e-10 1.73284e-09 1 -7.5032e-09 -6.26524e-10 1.73284e-09 4952.77 117.322 -2172.35 3806.74 -125.026 4932.03 +EDGE_SE3:QUAT 647 698 2.13246 11.0243 -5.34291 0.126921 0.0608633 0.0178401 0.989883 1 4.81482e-20 4.81482e-20 -4.54911e-10 1.37321e-08 -1.80225e-09 1 4.81482e-20 -4.54911e-10 1.37321e-08 -1.80225e-09 1 -4.54911e-10 1.37321e-08 -1.80225e-09 3986.09 30.358 452.697 3989.19 14.2231 4049.25 +EDGE_SE3:QUAT 648 697 1.91169 -10.8093 -5.62383 0.0458615 0.00772468 -0.126911 0.990823 1 8.21529e-19 8.21529e-19 -1.31396e-08 6.64912e-10 5.49139e-08 1 8.21529e-19 -1.31396e-08 6.64912e-10 5.49139e-08 1 -1.31396e-08 6.64912e-10 5.49139e-08 3995.65 2.86404 129.253 3998.61 -9.43092 3939.63 +EDGE_SE3:QUAT 649 699 3.58983 0.132366 -5.53208 0.0212714 0.113548 -0.115439 0.986574 1 3.85186e-19 3.85186e-19 -1.37806e-10 2.754e-08 -2.79892e-08 1 3.85186e-19 -1.37806e-10 2.754e-08 -2.79892e-08 1 -1.37806e-10 2.754e-08 -2.79892e-08 4218.32 -27.3853 963.827 3949.59 -56.4903 4166.82 +EDGE_SE3:QUAT 648 699 2.67252 10.6042 -5.27836 0.13466 -0.0119635 0.0743524 0.988026 1 7.70372e-19 7.70372e-19 -5.49222e-08 -3.80825e-09 1.73407e-09 1 7.70372e-19 -5.49222e-08 -3.80825e-09 1.73407e-09 1 -5.49222e-08 -3.80825e-09 1.73407e-09 3938.26 -15.9342 -211.193 3996.27 -7.57869 3988.68 +EDGE_SE3:QUAT 649 698 2.44249 -10.9315 -5.09318 0.00756799 0.0140321 -0.0343843 0.999282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.09 0.271342 115.253 3999.16 -1.9651 3998.59 +EDGE_SE3:QUAT 650 700 3.35422 -0.0858594 -5.40806 0.024603 0.137207 0.0938364 0.985781 1 4.81482e-20 4.81482e-20 -1.41764e-08 -1.49901e-09 -1.86531e-09 1 4.81482e-20 -1.41764e-08 -1.49901e-09 -1.86531e-09 1 -1.41764e-08 -1.49901e-09 -1.86531e-09 4289.64 59.8728 1119.83 3936.95 73.4774 4256.84 +EDGE_SE3:QUAT 649 700 2.88802 10.9097 -5.47179 0.0287809 -0.0574231 -0.0162109 0.997803 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4048.48 -8.06312 -458.113 3987.37 6.08801 4050.74 +EDGE_SE3:QUAT 650 699 2.38494 -10.7915 -5.45116 0.026873 -0.054368 0.0422335 0.997265 1 4.81482e-20 4.81482e-20 -5.4819e-10 1.38414e-08 -3.09956e-10 1 4.81482e-20 -5.4819e-10 1.38414e-08 -3.09956e-10 1 -5.4819e-10 1.38414e-08 -3.09956e-10 4047.54 -3.14437 -451.946 3987.39 -7.91391 4043.29 +EDGE_SE3:QUAT 651 701 3.22924 -0.315518 -5.58151 0.0979083 -0.0724077 0.0639613 0.990495 1 1.92593e-19 1.92593e-19 2.78559e-08 1.38514e-09 -2.33479e-09 1 1.92593e-19 2.78559e-08 1.38514e-09 -2.33479e-09 1 2.78559e-08 1.38514e-09 -2.33479e-09 4066.99 -25.4519 -657.837 3973.42 -7.99126 4088.97 +EDGE_SE3:QUAT 650 701 2.6359 11.0654 -5.45661 -0.0803019 0.129877 0.0495287 0.987031 1 1.92593e-19 1.92593e-19 -2.84292e-08 -8.4454e-10 -3.91018e-09 1 1.92593e-19 -2.84292e-08 -8.4454e-10 -3.91018e-09 1 -2.84292e-08 -8.4454e-10 -3.91018e-09 4279.36 -32.0078 1146.21 3927.88 -3.54021 4295.34 +EDGE_SE3:QUAT 651 700 2.68037 -11.4087 -5.45255 -0.125068 0.0296333 -0.0385703 0.990955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3944.85 -10.1269 173.935 3998.73 -4.63177 4001.47 +EDGE_SE3:QUAT 652 702 3.66385 -0.0427272 -5.33521 0.103193 0.0642935 -0.0981099 0.987721 1 1.92593e-19 1.92593e-19 2.77538e-08 -2.35234e-09 2.30243e-09 1 1.92593e-19 2.77538e-08 -2.35234e-09 2.30243e-09 1 2.77538e-08 -2.35234e-09 2.30243e-09 4055.12 22.749 633.501 3974.41 -20.2542 4059.22 +EDGE_SE3:QUAT 651 702 2.67702 11.0745 -5.59065 0.121304 0.0899459 -0.0285778 0.988119 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4083.53 45.1617 768.015 3966.5 14.0348 4139.12 +EDGE_SE3:QUAT 652 701 2.38554 -11.0251 -5.05079 -0.0527087 0.00284904 -0.141831 0.988482 1 4.81482e-20 4.81482e-20 -1.37195e-08 1.96166e-09 1.67391e-10 1 4.81482e-20 -1.37195e-08 1.96166e-09 1.67391e-10 1 -1.37195e-08 1.96166e-09 1.67391e-10 3989.78 2.43095 -66.3392 3999.43 6.80222 3920.42 +EDGE_SE3:QUAT 653 703 3.04237 -0.117414 -5.10209 -0.11043 -0.0455074 0.111884 0.986517 1 1.92593e-19 1.92593e-19 2.74153e-08 3.31892e-09 -5.2102e-10 1 1.92593e-19 2.74153e-08 3.31892e-09 -5.2102e-10 1 2.74153e-08 3.31892e-09 -5.2102e-10 3960.87 10.877 -204.634 3999.08 -10.9566 3959.58 +EDGE_SE3:QUAT 652 703 2.60721 11.1814 -5.39412 -0.17868 -0.140188 -0.172067 0.958548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4407.79 51.6169 -1559.67 3875.54 39.3877 4417.07 +EDGE_SE3:QUAT 653 702 2.01805 -10.962 -5.21035 0.0451236 -0.0312015 -0.0793226 0.995338 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.18 -5.66655 -204.141 3997.9 8.3322 3985.16 +EDGE_SE3:QUAT 654 704 2.94335 -0.160548 -5.49945 0.106042 0.0340225 -0.0369935 0.993091 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.73 16.4152 315.59 3993.54 -2.4417 4019.24 +EDGE_SE3:QUAT 653 704 2.42463 11.3994 -5.88341 0.0552688 -0.0298743 -0.0525336 0.996641 1 6.01853e-20 6.01853e-20 -1.34632e-08 7.68694e-09 -7.40141e-11 1 6.01853e-20 -1.34632e-08 7.68694e-09 -7.40141e-11 1 -1.34632e-08 7.68694e-09 -7.40141e-11 3997.97 -6.17756 -202.577 3997.82 5.96084 3999.15 +EDGE_SE3:QUAT 654 703 1.81838 -11.0326 -5.48417 0.123306 -0.115612 -0.16545 0.971625 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.57 -67.4146 -633.074 3992.1 71.9694 3984.89 +EDGE_SE3:QUAT 655 705 2.94167 -0.293983 -5.45256 -0.0928164 -0.0956328 0.0758496 0.988173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4077.25 46.5201 -678.926 3977.96 -43.69 4088.7 +EDGE_SE3:QUAT 654 705 2.36949 11.2414 -5.57239 0.148163 -0.0542998 0.0612444 0.98557 1 7.70372e-19 7.70372e-19 5.51978e-08 2.40791e-09 -3.89545e-09 1 7.70372e-19 5.51978e-08 2.40791e-09 -3.89545e-09 1 5.51978e-08 2.40791e-09 -3.89545e-09 3982.07 -37.3611 -533.848 3982.01 -3.2797 4054.88 +EDGE_SE3:QUAT 655 704 2.40811 -11.2145 -5.32679 0.0103146 -0.194939 0.0320955 0.980236 1 7.52316e-22 7.52316e-22 1.84076e-09 5.72118e-11 -3.66542e-10 1 7.52316e-22 1.84076e-09 5.72118e-11 -3.66542e-10 1 1.84076e-09 5.72118e-11 -3.66542e-10 4686.27 22.4701 -1793.96 3848.23 -29.3125 4682.57 +EDGE_SE3:QUAT 656 706 3.23362 0.0779426 -5.74544 -0.0334905 0.237087 -0.0714082 0.968281 1 1.92593e-19 1.92593e-19 7.09494e-09 -2.30613e-09 3.00988e-08 1 1.92593e-19 7.09494e-09 -2.30613e-09 3.00988e-08 1 7.09494e-09 -2.30613e-09 3.00988e-08 5003.09 -182.702 2246.41 3808.13 -186.014 4987.18 +EDGE_SE3:QUAT 655 706 2.67021 11.3621 -5.7792 -0.123292 0.183301 0.0941407 0.970741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4627.68 -54.7757 1796.75 3848.43 -14.137 4653.03 +EDGE_SE3:QUAT 656 705 2.21536 -10.9454 -5.54743 -0.0342418 0.0499606 -0.13646 0.988792 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.86 -11.7349 334.157 3994.73 -23.3177 3953.07 +EDGE_SE3:QUAT 657 707 2.91071 0.163263 -5.51054 0.11619 0.0489808 0.130262 0.983429 1 7.70372e-19 7.70372e-19 -5.46502e-08 -7.69069e-09 -8.9165e-10 1 7.70372e-19 -5.46502e-08 -7.69069e-09 -8.9165e-10 1 -5.46502e-08 -7.69069e-09 -8.9165e-10 3954.36 10.4348 195.666 3999.58 11.056 3940.49 +EDGE_SE3:QUAT 656 707 2.40902 11.2008 -5.62634 -0.182073 -0.0159449 0.0960485 0.978453 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3867.98 -14.2679 84.4083 3998.46 7.48042 3963.68 +EDGE_SE3:QUAT 657 706 2.19815 -11.2145 -5.40163 0.104522 -0.119815 -0.0838863 0.983709 1 1.92593e-19 1.92593e-19 -2.76335e-09 3.57949e-09 2.79063e-08 1 1.92593e-19 -2.76335e-09 3.57949e-09 2.79063e-08 1 -2.76335e-09 3.57949e-09 2.79063e-08 4131.03 -72.8073 -855.844 3967.8 69.3046 4146.58 +EDGE_SE3:QUAT 658 708 3.1918 0.0296569 -5.20651 -0.0175251 0.1156 -0.162244 0.979799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4186.56 -57.9486 887.574 3963.85 -84.9859 4082.49 +EDGE_SE3:QUAT 657 708 2.50141 11.3264 -5.40704 -0.0129779 0.121001 -0.102306 0.987281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4227.52 -44.0156 982.401 3949.74 -61.9984 4186.33 +EDGE_SE3:QUAT 658 707 2.18948 -11.0373 -5.74679 -0.0500386 -0.0652994 0.0125145 0.996532 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4056.52 14.7788 -520.165 3983.99 -8.46055 4065.91 +EDGE_SE3:QUAT 659 709 3.26867 -0.191097 -5.48464 -0.0546331 0.0505658 -0.0874396 0.993384 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.12 -13.1858 342.951 3994.05 -17.015 3998.47 +EDGE_SE3:QUAT 658 709 2.63435 11.0153 -5.50276 0.14103 -0.13387 -0.0418723 0.980018 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4161.73 -97.9736 -1012.85 3955.02 80.284 4234.27 +EDGE_SE3:QUAT 659 708 2.36694 -10.8281 -5.15895 0.00186646 0.0930124 0.0466866 0.994568 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4140.7 10.8221 763.325 3966.18 19.8194 4132 +EDGE_SE3:QUAT 660 710 2.85275 0.28831 -5.35558 0.0125881 -0.080677 -0.0970605 0.991923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4097.6 -19.008 -634.581 3977.63 34.3733 4060.55 +EDGE_SE3:QUAT 659 710 2.66808 11.2123 -5.62407 0.0835428 0.19833 0.0475517 0.97541 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4609.61 150.75 1719.87 3875.92 145.627 4628.48 +EDGE_SE3:QUAT 660 709 2.67989 -11.1632 -5.29767 -0.104483 0.147297 0.0248441 0.983244 1 3.00927e-21 3.00927e-21 5.41897e-10 -3.69179e-10 3.57109e-09 1 3.00927e-21 5.41897e-10 -3.69179e-10 3.57109e-09 1 5.41897e-10 -3.69179e-10 3.57109e-09 4335.55 -68.8178 1288.68 3914.85 -42.1674 4376.75 +EDGE_SE3:QUAT 661 711 3.22816 -0.207342 -5.32503 0.0344095 -0.0543424 0.111798 0.991647 1 1.20371e-20 1.20371e-20 6.92979e-09 7.58297e-10 -4.23113e-10 1 1.20371e-20 6.92979e-09 7.58297e-10 -4.23113e-10 1 6.92979e-09 7.58297e-10 -4.23113e-10 4051.52 0.505927 -477.777 3985.99 -25.4941 4006.26 +EDGE_SE3:QUAT 660 711 2.60882 10.8515 -5.51074 0.0937932 0.167661 -0.0418853 0.980479 1 1.20371e-20 1.20371e-20 -1.2709e-09 -6.23657e-10 -7.23126e-09 1 1.20371e-20 -1.2709e-09 -6.23657e-10 -7.23126e-09 1 -1.2709e-09 -6.23657e-10 -7.23126e-09 4478.85 60.3536 1523.28 3884.74 33.9375 4507.02 +EDGE_SE3:QUAT 661 710 2.62967 -10.7958 -5.76639 0.0183065 -0.171429 -0.0899405 0.980912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4481.98 -87.6959 -1472.19 3898.07 100.456 4450.97 +EDGE_SE3:QUAT 662 712 3.01317 0.131612 -5.62634 -0.176352 0.0190446 -0.139152 0.974256 1 7.70372e-19 7.70372e-19 -5.41025e-08 7.60837e-09 1.70484e-09 1 7.70372e-19 -5.41025e-08 7.60837e-09 1.70484e-09 1 -5.41025e-08 7.60837e-09 1.70484e-09 3878.47 21.3862 -143.688 3996.26 16.7398 3925.41 +EDGE_SE3:QUAT 661 712 2.68351 11.0972 -5.94849 0.0830051 -0.0871143 0.0931976 0.98835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4126.67 -16.276 -800.709 3961.44 -23.1742 4119.48 +EDGE_SE3:QUAT 662 711 2.26683 -11.5985 -5.50864 -0.0203414 -0.18831 0.109942 0.975724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4578.2 127.472 -1629.94 3885.39 -141.5 4531.51 +EDGE_SE3:QUAT 663 713 2.69923 0.21262 -5.12425 -0.108265 0.0859697 -0.125908 0.982362 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.99 -39.3832 502.498 3991.45 -41.5098 3997.47 +EDGE_SE3:QUAT 662 713 2.75363 11.0207 -5.71824 -0.00702511 -0.0370946 0.08636 0.995548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.35 3.73393 -287.429 3995.17 -12.6528 3990.71 +EDGE_SE3:QUAT 663 712 2.23354 -10.7675 -5.58335 -0.11578 -0.109732 -0.210632 0.964463 1 9.62965e-19 9.62965e-19 3.82428e-08 4.84351e-08 -7.08924e-10 1 9.62965e-19 3.82428e-08 4.84351e-08 -7.08924e-10 1 3.82428e-08 4.84351e-08 -7.08924e-10 4263.8 -13.0685 -1171.6 3925.47 99.7144 4139.95 +EDGE_SE3:QUAT 664 714 3.16005 -0.151816 -5.52312 0.0206138 0.0959396 -0.263494 0.959657 1 3.00927e-21 3.00927e-21 3.39362e-09 -9.35817e-10 3.28903e-10 1 3.00927e-21 3.39362e-09 -9.35817e-10 3.28903e-10 1 3.39362e-09 -9.35817e-10 3.28903e-10 4142.96 -52.2583 775.018 3976.64 -107.04 3866.94 +EDGE_SE3:QUAT 663 714 2.5498 10.9169 -5.82517 -0.142767 -0.157017 0.0379739 0.976484 1 7.70372e-19 7.70372e-19 5.65781e-08 4.87924e-09 -8.01998e-09 1 7.70372e-19 5.65781e-08 4.87924e-09 -8.01998e-09 1 5.65781e-08 4.87924e-09 -8.01998e-09 4266.94 128.887 -1232.16 3936.49 -111.001 4342.7 +EDGE_SE3:QUAT 664 713 2.34188 -10.963 -5.10197 0.0472338 -0.130662 -0.214514 0.966789 1 3.85186e-19 3.85186e-19 -2.10399e-08 3.33384e-08 -1.24494e-11 1 3.85186e-19 -2.10399e-08 3.33384e-08 -1.24494e-11 1 -2.10399e-08 3.33384e-08 -1.24494e-11 4173.93 -91.7552 -879.449 3977.19 116.683 3998.79 +EDGE_SE3:QUAT 665 715 3.06719 0.0976525 -5.82769 0.0729022 0.0728213 0.0973168 0.989905 1 1.92593e-19 1.92593e-19 -1.57678e-09 -2.41535e-09 -2.76803e-08 1 1.92593e-19 -1.57678e-09 -2.41535e-09 -2.76803e-08 1 -1.57678e-09 -2.41535e-09 -2.76803e-08 4037.66 27.0962 490.417 3988.62 30.5497 4021.03 +EDGE_SE3:QUAT 664 715 2.57902 11.024 -5.50831 -0.0409679 0.0156948 0.136776 0.98963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.06 -2.73397 188.496 3997.4 13.9201 3933.94 +EDGE_SE3:QUAT 665 714 2.3803 -10.9248 -5.12769 -0.0412248 -0.143549 -0.149857 0.977362 1 1.20371e-20 1.20371e-20 -7.09929e-09 1.04579e-09 1.0837e-09 1 1.20371e-20 -7.09929e-09 1.04579e-09 1.0837e-09 1 -7.09929e-09 1.04579e-09 1.0837e-09 4367.69 -54.7637 -1279.91 3918.61 95.181 4284.66 +EDGE_SE3:QUAT 666 716 2.87772 0.0876577 -5.56409 0.18207 0.042603 -0.0693562 0.979911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3922.98 43.3861 476.052 3985.03 -4.73821 4036.34 +EDGE_SE3:QUAT 665 716 2.43561 10.7461 -5.39519 0.0678273 -0.0713566 -0.0459187 0.994082 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.97 -23.6599 -535.471 3984.23 20.0933 4061.94 +EDGE_SE3:QUAT 666 715 2.22597 -11.2153 -5.4373 0.138699 0.0428751 -0.215984 0.965544 1 7.70372e-19 7.70372e-19 -5.37848e-09 -6.11283e-09 -5.4366e-08 1 7.70372e-19 -5.37848e-09 -6.11283e-09 -5.4366e-08 1 -5.37848e-09 -6.11283e-09 -5.4366e-08 4031.39 26.6997 672.714 3967.47 -68.8307 3921.74 +EDGE_SE3:QUAT 667 717 2.96729 -0.0508796 -5.40848 0.0933685 -0.130571 0.01867 0.986856 1 7.52316e-22 7.52316e-22 2.36797e-10 -1.64749e-10 -1.77377e-09 1 7.52316e-22 2.36797e-10 -1.64749e-10 -1.77377e-09 1 2.36797e-10 -1.64749e-10 -1.77377e-09 4256.78 -53.568 -1118.79 3933.02 29.8506 4290.26 +EDGE_SE3:QUAT 666 717 2.47442 11.0271 -5.62973 -0.0347745 -0.116285 0.158962 0.979796 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4170.46 62.2291 -856.878 3967.93 -84.1944 4074.22 +EDGE_SE3:QUAT 667 716 2.34284 -11.0619 -5.83283 -0.203705 0.0101763 -0.163567 0.965218 1 7.82409e-19 7.82409e-19 -5.47953e-08 1.85903e-09 1.72802e-09 1 7.82409e-19 -5.47953e-08 1.85903e-09 1.72802e-09 1 -5.47953e-08 1.85903e-09 1.72802e-09 3854.27 42.4175 -309.937 3988.19 32.6807 3913.24 +EDGE_SE3:QUAT 668 718 3.36289 0.141274 -5.48598 -0.0947981 -0.188979 0.0621376 0.975418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4505.79 156.078 -1569.42 3899.24 -151.28 4526.29 +EDGE_SE3:QUAT 667 718 2.11467 10.8749 -5.5847 0.0955083 -0.05573 0.0774092 0.990848 1 3.85186e-19 3.85186e-19 -2.58156e-08 -4.2653e-09 -2.58156e-08 1 3.85186e-19 -2.58156e-08 -4.2653e-09 -2.58156e-08 1 -2.58156e-08 -4.2653e-09 -2.58156e-08 4033.05 -20.0465 -532.437 3981.77 -13.0024 4045.56 +EDGE_SE3:QUAT 668 717 1.94065 -11.0737 -5.13939 -0.200439 0.0908363 -0.130234 0.966753 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3867.01 -34.7431 360.827 4001.16 -31.2076 3959.87 +EDGE_SE3:QUAT 669 719 3.18633 0.474205 -5.32984 0.0135733 0.0769763 -0.0238773 0.996655 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4096.82 1.04273 632.258 3976.02 -6.03235 4095.28 +EDGE_SE3:QUAT 668 719 2.37974 11.0725 -5.73389 -0.00926633 -0.126324 0.125067 0.98403 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4246.57 54.4494 -1024.26 3947.56 -77.4901 4184.35 +EDGE_SE3:QUAT 669 718 2.35112 -11.0527 -5.11419 -0.245077 -0.203363 -0.000722268 0.947935 1 3.90001e-18 3.90001e-18 -1.21716e-07 3.60822e-08 5.00987e-08 1 3.90001e-18 -1.21716e-07 3.60822e-08 5.00987e-08 1 -1.21716e-07 3.60822e-08 5.00987e-08 4361.74 286.715 -1667.94 3932.5 -259.234 4601.99 +EDGE_SE3:QUAT 670 720 3.00044 0.234832 -5.38302 0.0759358 0.0793147 0.0655892 0.991787 1 3.85186e-19 3.85186e-19 -2.56525e-08 -2.96818e-08 5.05766e-10 1 3.85186e-19 -2.56525e-08 -2.96818e-08 5.05766e-10 1 -2.56525e-08 -2.96818e-08 5.05766e-10 4057.63 30.7441 574.48 3982.93 29.0644 4063.49 +EDGE_SE3:QUAT 669 720 2.72389 11.0507 -5.30311 0.109896 0.0340885 0.254198 0.960283 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3949.86 -11.0875 -76.3312 3997.55 -25.3589 3739.7 +EDGE_SE3:QUAT 670 719 2.46705 -10.9254 -5.93217 -0.103832 0.051983 -0.191081 0.974682 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.79 -6.71813 155.18 4000.54 -8.17556 3857.87 +EDGE_SE3:QUAT 671 721 3.18004 -0.071066 -5.50544 0.0118821 0.109074 0.0911593 0.989774 1 1.20371e-20 1.20371e-20 -7.02722e-09 -6.81296e-10 -7.45219e-10 1 1.20371e-20 -7.02722e-09 -6.81296e-10 -7.45219e-10 1 -7.02722e-09 -6.81296e-10 -7.45219e-10 4185.42 32.2926 882.435 3957.93 48.2628 4152.75 +EDGE_SE3:QUAT 670 721 2.68846 10.9053 -5.33609 0.310834 -0.055997 0.0687507 0.946319 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3712.43 -104.603 -637.292 3979.03 18.1042 4079.99 +EDGE_SE3:QUAT 671 720 2.10153 -10.9601 -5.02533 0.0315546 -0.0424864 -0.296001 0.95372 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.14 -7.86761 -190.104 4000.27 21.1511 3657.66 +EDGE_SE3:QUAT 672 722 3.27243 -0.0432936 -5.67398 0.00975838 -0.123089 -0.0123113 0.992271 1 3.00927e-21 3.00927e-21 -4.39231e-10 4.70838e-11 3.54982e-09 1 3.00927e-21 -4.39231e-10 4.70838e-11 3.54982e-09 1 -4.39231e-10 4.70838e-11 3.54982e-09 4252.5 -10.6802 -1037.06 3939.81 11.2192 4252.28 +EDGE_SE3:QUAT 671 722 2.49606 10.7664 -6.10206 0.103017 0.214981 0.0376576 0.970439 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4718.71 192.958 1904.22 3859.85 185.283 4755.48 +EDGE_SE3:QUAT 672 721 2.30918 -11.2632 -5.48936 0.062494 0.271175 -0.018068 0.960329 1 2.38038e-22 2.38038e-22 3.10539e-10 7.12555e-11 1.09951e-09 1 2.38038e-22 3.10539e-10 7.12555e-11 1.09951e-09 1 3.10539e-10 7.12555e-11 1.09951e-09 5485.03 117.785 2873.07 3712.01 115.685 5499.34 +EDGE_SE3:QUAT 673 723 2.95282 0.12044 -5.69726 0.0821399 -0.0451523 0.0541556 0.994123 1 1.92593e-19 1.92593e-19 2.77389e-08 1.29073e-09 -1.48378e-09 1 1.92593e-19 2.77389e-08 1.29073e-09 -1.48378e-09 1 2.77389e-08 1.29073e-09 -1.48378e-09 4015.19 -14.7733 -413.129 3989 -6.92582 4030.44 +EDGE_SE3:QUAT 672 723 2.22946 11.529 -6.23412 -0.0289612 0.0238603 0.0740003 0.996552 1 1.20371e-20 1.20371e-20 -5.03739e-10 6.91569e-09 1.74573e-10 1 1.20371e-20 -5.03739e-10 6.91569e-09 1.74573e-10 1 -5.03739e-10 6.91569e-09 1.74573e-10 4008.18 -2.02935 215.273 3996.96 7.83605 3989.63 +EDGE_SE3:QUAT 673 722 2.39735 -11.3302 -5.20487 -0.0942163 0.0657781 -0.216068 0.969593 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.02 -15.0727 246.342 4000.56 -20.1128 3825.78 +EDGE_SE3:QUAT 674 724 2.87251 0.264722 -5.58005 -0.0470669 -0.101545 -0.0489787 0.992509 1 1.92593e-19 1.92593e-19 -1.11402e-09 -2.75587e-08 -1.04861e-09 1 1.92593e-19 -1.11402e-09 -2.75587e-08 -1.04861e-09 1 -1.11402e-09 -2.75587e-08 -1.04861e-09 4171.34 9.55066 -867.938 3956.14 11.0034 4170.61 +EDGE_SE3:QUAT 673 724 2.51883 11.0461 -5.98967 0.154073 -0.0600715 -0.100787 0.981068 1 8.1852e-19 8.1852e-19 5.29918e-08 -1.99794e-08 8.64486e-10 1 8.1852e-19 5.29918e-08 -1.99794e-08 8.64486e-10 1 5.29918e-08 -1.99794e-08 8.64486e-10 3922.31 -20.0036 -273.826 3998.67 16.4976 3976.64 +EDGE_SE3:QUAT 674 723 2.68248 -11.2007 -5.70709 0.00751379 0.229815 0.0930305 0.968749 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4955.31 162.699 2176.18 3814.64 171.378 4920.92 +EDGE_SE3:QUAT 675 725 2.91313 -0.158549 -5.84826 -0.0631902 -0.0599388 0.100146 0.991153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.77 18.5305 -396.843 3992.48 -23.1508 3998.62 +EDGE_SE3:QUAT 674 725 2.19654 11.0269 -5.48203 0.0110922 -0.0750165 0.132463 0.988283 1 4.70198e-23 4.70198e-23 4.33594e-10 5.80467e-11 -3.30322e-11 1 4.70198e-23 4.33594e-10 5.80467e-11 -3.30322e-11 1 4.33594e-10 5.80467e-11 -3.30322e-11 4091.63 15.0264 -614 3978.97 -41.6153 4021.94 +EDGE_SE3:QUAT 675 724 2.29925 -11.0841 -5.59843 -0.118068 0.00512177 0.0187263 0.992816 1 7.70372e-19 7.70372e-19 5.51199e-08 9.4408e-10 5.19988e-10 1 7.70372e-19 5.51199e-08 9.4408e-10 5.19988e-10 1 5.51199e-08 9.4408e-10 5.19988e-10 3945.33 -4.40021 66.3967 3999.66 0.5376 3999.68 +EDGE_SE3:QUAT 676 726 2.50886 0.164925 -5.36524 -0.046925 -0.00545856 -0.0792457 0.995735 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.06 2.21988 -87.5283 3999.36 3.94629 3976.74 +EDGE_SE3:QUAT 675 726 2.14879 11.1514 -5.84133 -0.187706 0.0269675 0.158423 0.96899 1 1.54074e-18 1.54074e-18 -4.97301e-08 -1.72829e-08 4.97301e-08 1 1.54074e-18 -4.97301e-08 -1.72829e-08 4.97301e-08 1 -4.97301e-08 -1.72829e-08 4.97301e-08 3931.06 -49.8956 549.638 3975.67 37.4281 3971.6 +EDGE_SE3:QUAT 676 725 2.01906 -11.1742 -5.12623 0.0171404 -0.0512743 -0.194252 0.979461 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.03 -12.6776 -350.019 3994.77 33.5948 3879.27 +EDGE_SE3:QUAT 677 727 3.07431 0.0506531 -6.07437 0.20445 -0.00947664 0.0563822 0.977206 1 7.70372e-19 7.70372e-19 -5.43179e-08 -2.66259e-09 1.73226e-09 1 7.70372e-19 -5.43179e-08 -2.66259e-09 1.73226e-09 1 -5.43179e-08 -2.66259e-09 1.73226e-09 3842.96 -24.9464 -205.502 3996.41 -4.61736 3997.44 +EDGE_SE3:QUAT 676 727 2.65284 10.9355 -6.00017 0.177013 -0.0853528 0.0718489 0.977864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.6 -66.5271 -826.611 3960.62 8.29043 4143.29 +EDGE_SE3:QUAT 677 726 2.33412 -11.2584 -5.42732 -0.0670876 0.118418 0.073551 0.987961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4241.09 -12.4773 1050.55 3937.71 19.0038 4237.46 +EDGE_SE3:QUAT 678 728 2.98142 -0.153007 -5.35351 0.0195321 -0.112287 -0.0405034 0.992658 1 2.52778e-19 2.52778e-19 7.35332e-09 -2.82881e-08 -1.40957e-08 1 2.52778e-19 7.35332e-09 -2.82881e-08 -1.40957e-08 1 7.35332e-09 -2.82881e-08 -1.40957e-08 4202.04 -22.9405 -925.055 3952.07 27.2749 4197 +EDGE_SE3:QUAT 677 728 2.2576 11.5241 -6.00188 -0.04022 0.0856514 0.0732196 0.992817 1 4.81482e-20 4.81482e-20 1.40025e-08 9.47239e-10 1.27526e-09 1 4.81482e-20 1.40025e-08 9.47239e-10 1.27526e-09 1 1.40025e-08 9.47239e-10 1.27526e-09 4124.05 -1.83946 734.278 3967.94 21.5634 4109.07 +EDGE_SE3:QUAT 678 727 2.71908 -10.7957 -5.43324 -0.176553 -0.12987 -0.0858852 0.971898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4237.57 91.5908 -1257.31 3917.9 -29.1704 4332.75 +EDGE_SE3:QUAT 679 729 2.77395 -0.0991821 -5.48795 -0.0458703 -0.151934 -0.0403118 0.986502 1 8.1852e-19 8.1852e-19 1.28368e-08 -5.51894e-08 -4.21325e-09 1 8.1852e-19 1.28368e-08 -5.51894e-08 -4.21325e-09 1 1.28368e-08 -5.51894e-08 -4.21325e-09 4399.93 12.9744 -1341.69 3905.05 4.74601 4401.84 +EDGE_SE3:QUAT 678 729 2.65813 11.3556 -5.31118 0.0171748 0.128922 -0.105826 0.985842 1 9.64658e-19 9.64658e-19 4.75679e-09 5.47484e-08 -2.73928e-08 1 9.64658e-19 4.75679e-09 5.47484e-08 -2.73928e-08 1 4.75679e-09 5.47484e-08 -2.73928e-08 4281.23 -35.2844 1099.73 3935.94 -61.234 4237.61 +EDGE_SE3:QUAT 679 728 1.96345 -10.9112 -5.31958 -0.0767665 -0.00360632 -0.00431176 0.997033 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.69 1.2956 -32.5534 3999.93 0.0437925 4000.19 +EDGE_SE3:QUAT 680 730 3.2144 0.152685 -5.44917 0.0869979 0.0268376 0.0154654 0.995727 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.34 8.56976 196.509 3997.83 2.79859 4008.66 +EDGE_SE3:QUAT 679 730 2.42238 11.0308 -5.51093 0.0656367 -0.107585 0.102942 0.986671 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4205.19 -2.48654 -969.238 3946.21 -35.8555 4180.04 +EDGE_SE3:QUAT 680 729 2.2785 -11.1676 -5.76616 0.0738392 -0.0634759 0.0483297 0.994074 1 4.81482e-20 4.81482e-20 -9.75898e-10 9.52224e-10 1.39257e-08 1 4.81482e-20 -9.75898e-10 9.52224e-10 1.39257e-08 1 -9.75898e-10 9.52224e-10 1.39257e-08 4053.46 -16.5043 -553.945 3981.02 -6.12454 4065.93 +EDGE_SE3:QUAT 681 731 3.05629 -0.0470028 -5.78913 -0.057676 -0.0201858 -0.0886173 0.99419 1 6.01853e-20 6.01853e-20 -1.44136e-08 -5.70775e-09 4.60239e-11 1 6.01853e-20 -1.44136e-08 -5.70775e-09 4.60239e-11 1 -1.44136e-08 -5.70775e-09 4.60239e-11 3998.71 5.52466 -220.333 3996.52 9.75799 3980.6 +EDGE_SE3:QUAT 680 731 2.12742 11.1582 -5.54331 0.0190344 0.102666 0.120188 0.987245 1 4.81482e-20 4.81482e-20 1.39668e-08 1.79058e-09 1.34256e-09 1 4.81482e-20 1.39668e-08 1.79058e-09 1.34256e-09 1 1.39668e-08 1.79058e-09 1.34256e-09 4152.88 37.6495 801.013 3966.96 56.9769 4096.55 +EDGE_SE3:QUAT 681 730 2.16916 -10.9604 -5.62228 0.0245298 0.164358 -0.0250508 0.985777 1 1.20371e-20 1.20371e-20 -7.23468e-09 1.32477e-10 -1.21276e-09 1 1.20371e-20 -7.23468e-09 1.32477e-10 -1.21276e-09 1 -7.23468e-09 1.32477e-10 -1.21276e-09 4471.78 4.3834 1456.57 3891.04 -5.26384 4471.67 +EDGE_SE3:QUAT 682 732 2.97175 0.0330772 -5.59274 0.0878272 0.143111 -0.183729 0.96853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4407.54 -44.0706 1395.07 3903.4 -106.553 4303.37 +EDGE_SE3:QUAT 681 732 2.0913 11.3557 -5.36765 0.0689275 -0.116802 -0.100717 0.985628 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4157.46 -61.4077 -859.609 3965.41 67.0552 4135.89 +EDGE_SE3:QUAT 682 731 2.84333 -11.2848 -5.65396 0.0387313 0.03693 -0.142387 0.988363 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.98 1.08156 353.727 3992.01 -25.2794 3949.89 +EDGE_SE3:QUAT 683 733 3.3449 0.400071 -5.69993 0.0992077 0.0970596 0.0175 0.990167 1 1.01111e-18 1.01111e-18 -5.62099e-08 -3.10282e-08 -1.62583e-08 1 1.01111e-18 -5.62099e-08 -3.10282e-08 -1.62583e-08 1 -5.62099e-08 -3.10282e-08 -1.62583e-08 4102.35 44.9959 766.299 3968.35 29.2577 4140.5 +EDGE_SE3:QUAT 682 733 2.83707 11.4399 -5.84882 0.0289891 0.0972026 -0.0365283 0.994172 1 1.20371e-20 1.20371e-20 7.03525e-09 -2.22663e-10 7.00139e-10 1 1.20371e-20 7.03525e-09 -2.22663e-10 7.00139e-10 1 7.03525e-09 -2.22663e-10 7.00139e-10 4156.55 4.20118 815.609 3961.07 -9.43366 4154.57 +EDGE_SE3:QUAT 683 732 2.29597 -11.1775 -5.71172 0.0328716 0.0466905 -0.177702 0.982426 1 7.82409e-19 7.82409e-19 -3.77545e-09 2.03578e-09 5.44691e-08 1 7.82409e-19 -3.77545e-09 2.03578e-09 5.44691e-08 1 -3.77545e-09 2.03578e-09 5.44691e-08 4041.06 -4.19621 428.599 3989.14 -38.5001 3919.07 +EDGE_SE3:QUAT 684 734 3.07663 0.139813 -5.71765 -0.0409519 0.111181 0.0607412 0.991096 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4210.11 -2.35679 956.211 3947.74 19.7137 4202.07 +EDGE_SE3:QUAT 683 734 2.45306 11.2837 -5.81892 -0.18865 0.0754459 0.00145935 0.979141 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3941.39 -57.329 585.163 3983.43 -24.5094 4083.74 +EDGE_SE3:QUAT 684 733 2.32553 -11.0054 -4.8006 0.146191 0.00572073 0.0651096 0.987095 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3915.33 -7.7735 -68.2634 3999.29 -3.38586 3983.86 +EDGE_SE3:QUAT 685 735 2.88062 0.0843935 -5.66789 -0.0805218 0.0607892 -0.0394347 0.994116 1 1.92593e-19 1.92593e-19 2.77631e-08 -1.3684e-09 1.49198e-09 1 1.92593e-19 2.77631e-08 -1.3684e-09 1.49198e-09 1 2.77631e-08 -1.3684e-09 1.49198e-09 4023.32 -21.1141 446.919 3989.11 -15.1216 4043.04 +EDGE_SE3:QUAT 684 735 2.32285 11.6077 -5.67326 0.0960755 0.0298468 0.075277 0.992075 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.26 6.44694 147.538 3999.28 5.44399 3982.52 +EDGE_SE3:QUAT 685 734 2.11124 -11.5734 -5.36477 -0.0199926 -0.0940812 0.00342655 0.995358 1 1.20371e-20 1.20371e-20 -7.03076e-09 -5.15448e-11 6.63001e-10 1 1.20371e-20 -7.03076e-09 -5.15448e-11 6.63001e-10 1 -7.03076e-09 -5.15448e-11 6.63001e-10 4143.35 9.22691 -775.122 3964.83 -5.87455 4144.9 +EDGE_SE3:QUAT 686 736 3.2452 -0.13184 -6.07788 -0.0942303 0.168049 -0.0169629 0.981118 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4426.36 -99.8066 1435.73 3902.63 -85.8364 4460.73 +EDGE_SE3:QUAT 685 736 2.13589 11.5162 -5.93057 -0.128881 -0.017027 -0.0943973 0.98701 1 7.70372e-19 7.70372e-19 5.49197e-08 -4.84181e-09 -2.23706e-09 1 7.70372e-19 5.49197e-08 -4.84181e-09 -2.23706e-09 1 5.49197e-08 -4.84181e-09 -2.23706e-09 3952.04 18.8017 -275.902 3993.83 12.4147 3982.84 +EDGE_SE3:QUAT 686 735 2.23658 -10.7445 -5.54255 0.0625292 -0.0216703 -0.172594 0.982767 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.19 -0.0309354 -37.9938 4000.06 -0.597425 3880.68 +EDGE_SE3:QUAT 687 737 2.7364 -0.106556 -5.42217 0.0927127 0.0773743 0.0391581 0.991909 1 2.40741e-19 2.40741e-19 2.6852e-08 9.91677e-11 -1.19864e-08 1 2.40741e-19 2.6852e-08 9.91677e-11 -1.19864e-08 1 2.6852e-08 9.91677e-11 -1.19864e-08 4046.69 32.4433 575.587 3982.39 23.5233 4074.94 +EDGE_SE3:QUAT 686 737 1.88072 11.4594 -5.65369 0.0199193 0.00324093 0.177748 0.983869 1 7.70372e-19 7.70372e-19 -2.18355e-10 1.0988e-09 5.46159e-08 1 7.70372e-19 -2.18355e-10 1.0988e-09 5.46159e-08 1 -2.18355e-10 1.0988e-09 5.46159e-08 3998.43 -0.311097 -16.8883 3999.94 -2.79645 3873.64 +EDGE_SE3:QUAT 687 736 2.53714 -11.2331 -5.57425 -0.0123913 -0.0670878 0.122177 0.990161 1 1.20371e-20 1.20371e-20 -6.92694e-09 -8.73661e-10 4.33792e-10 1 1.20371e-20 -6.92694e-09 -8.73661e-10 4.33792e-10 1 -6.92694e-09 -8.73661e-10 4.33792e-10 4064.2 15.6604 -513.496 3985.75 -33.4192 4005.11 +EDGE_SE3:QUAT 688 738 3.26521 0.257378 -5.66258 -0.152871 0.131236 -0.0157201 0.979367 1 4.81482e-20 4.81482e-20 -1.71639e-09 2.32444e-09 -1.40244e-08 1 4.81482e-20 -1.71639e-09 2.32444e-09 -1.40244e-08 1 -1.71639e-09 2.32444e-09 -1.40244e-08 4158.74 -97.7721 1036.25 3950.7 -71.7595 4251.23 +EDGE_SE3:QUAT 687 738 2.43977 11.604 -5.59506 -0.105538 -0.054836 -0.0539014 0.991438 1 2.40741e-19 2.40741e-19 2.83115e-08 1.26063e-08 -4.24474e-10 1 2.40741e-19 2.83115e-08 1.26063e-08 -4.24474e-10 1 2.83115e-08 1.26063e-08 -4.24474e-10 4018.04 23.7965 -504.534 3983.93 5.11065 4050.97 +EDGE_SE3:QUAT 688 737 2.335 -11.1654 -5.31229 0.143878 0.0350274 -0.142833 0.978607 1 7.70372e-19 7.70372e-19 -5.47689e-08 7.13885e-09 -4.06139e-09 1 7.70372e-19 -5.47689e-08 7.13885e-09 -4.06139e-09 1 -5.47689e-08 7.13885e-09 -4.06139e-09 3980.52 31.8765 511.527 3980.45 -31.4773 3981.72 +EDGE_SE3:QUAT 689 739 2.91535 0.0531252 -5.62596 -0.0660852 0.071022 0.18424 0.978082 1 7.70372e-19 7.70372e-19 5.05762e-09 -2.05327e-09 5.51203e-08 1 7.70372e-19 5.05762e-09 -2.05327e-09 5.51203e-08 1 5.05762e-09 -2.05327e-09 5.51203e-08 4100.71 5.39004 698.085 3971.21 61.0264 3982.4 +EDGE_SE3:QUAT 688 739 2.13363 11.418 -5.50495 0.0493031 -0.00501679 0.0683277 0.996431 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.83 -2.17181 -79.9746 3999.46 -3.09598 3982.88 +EDGE_SE3:QUAT 689 738 2.40945 -11.4132 -5.32953 0.124438 -0.102257 -0.0191779 0.986758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4090.06 -58.2641 -794.763 3967.73 38.2685 4150.53 +EDGE_SE3:QUAT 690 740 3.32893 -0.285662 -5.61895 -0.003062 0.030352 -0.0513904 0.998213 1 7.52316e-22 7.52316e-22 -1.73475e-09 8.97946e-11 -5.19199e-11 1 7.52316e-22 -1.73475e-09 8.97946e-11 -5.19199e-11 1 -1.73475e-09 8.97946e-11 -5.19199e-11 4014.4 -1.49253 240.718 3996.47 -6.28689 4003.87 +EDGE_SE3:QUAT 689 740 1.95916 11.2741 -5.6461 0.00251596 -0.0173373 0.105892 0.994223 1 1.9264e-19 1.9264e-19 5.39761e-11 -1.28437e-11 -2.76046e-08 1 1.9264e-19 5.39761e-11 -1.28437e-11 -2.76046e-08 1 5.39761e-11 -1.28437e-11 -2.76046e-08 4004.85 0.600022 -139.694 3998.83 -7.41651 3960.02 +EDGE_SE3:QUAT 690 739 2.3201 -11.1358 -5.41008 -0.176397 -0.0346787 0.0813668 0.980337 1 7.70372e-19 7.70372e-19 -5.4428e-08 -4.90905e-09 2.13307e-10 1 7.70372e-19 -5.4428e-08 -4.90905e-09 2.13307e-10 1 -5.4428e-08 -4.90905e-09 2.13307e-10 3876.72 3.30005 -93.6695 4000.19 -2.44814 3974.7 +EDGE_SE3:QUAT 691 741 2.83475 -0.361877 -5.33977 -0.0746922 -0.0650731 0.166046 0.98113 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.07 20.7739 -350.107 3996.47 -29.3319 3919.1 +EDGE_SE3:QUAT 690 741 2.26915 11.217 -5.61624 -0.274128 0.0416181 -0.0694746 0.958277 1 3.28612e-18 3.28612e-18 1.05774e-07 -2.33426e-08 2.44844e-08 1 3.28612e-18 1.05774e-07 -2.33426e-08 2.44844e-08 1 1.05774e-07 -2.33426e-08 2.44844e-08 3698.88 1.33248 76.8721 4000.57 -1.30053 3980.15 +EDGE_SE3:QUAT 691 740 2.26325 -11.4939 -5.45554 0.129573 0.0162365 -0.176057 0.97568 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.94 23.8724 389.503 3986.89 -37.0527 3912.12 +EDGE_SE3:QUAT 692 742 2.9207 -0.211317 -5.54872 -0.0794215 -0.0443847 0.118306 0.9888 1 2.40741e-19 2.40741e-19 2.57686e-08 1.71647e-08 5.53894e-10 1 2.40741e-19 2.57686e-08 1.71647e-08 5.53894e-10 1 2.57686e-08 1.71647e-08 5.53894e-10 3987.85 10.7718 -233.262 3998.16 -13.5693 3957.1 +EDGE_SE3:QUAT 691 742 2.33938 11.2111 -6.06338 0.000816812 0.0609754 0.0550756 0.996618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4059.46 5.1749 491.335 3985.54 14.1068 4047.33 +EDGE_SE3:QUAT 692 741 1.85221 -11.034 -5.53429 -0.147213 0.0794804 -0.0270125 0.985536 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.57 -46.8371 576.665 3983.93 -27.3431 4078.34 +EDGE_SE3:QUAT 693 743 2.96236 -0.0462855 -5.62952 0.0441565 0.0197091 -0.0282702 0.99843 1 1.20371e-20 1.20371e-20 1.53467e-10 2.98711e-10 6.93442e-09 1 1.20371e-20 1.53467e-10 2.98711e-10 6.93442e-09 1 1.53467e-10 2.98711e-10 6.93442e-09 3999.6 3.62308 172.271 3998.06 -2.04017 4004.2 +EDGE_SE3:QUAT 692 743 2.27233 10.9858 -5.23081 0.026379 0.2639 0.0929521 0.959698 1 1.92593e-19 1.92593e-19 -8.06694e-09 -2.70764e-09 -3.06836e-08 1 1.92593e-19 -8.06694e-09 -2.70764e-09 -3.06836e-08 1 -8.06694e-09 -2.70764e-09 -3.06836e-08 5286.6 271.288 2611.85 3776.97 273.5 5254.83 +EDGE_SE3:QUAT 693 742 2.05986 -11.226 -4.9575 0.119441 -0.00456447 0.0153039 0.992713 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.75 -3.83742 -57.4596 3999.75 -0.368016 3999.88 +EDGE_SE3:QUAT 694 744 2.52568 -0.231898 -5.70033 -0.0403941 -0.0583922 -0.106776 0.991745 1 2.40741e-19 2.40741e-19 1.2044e-08 -2.19845e-09 2.6838e-08 1 2.40741e-19 1.2044e-08 -2.19845e-09 2.6838e-08 1 1.2044e-08 -2.19845e-09 2.6838e-08 4059.23 0.872017 -517.175 3983.53 25.5995 4020.15 +EDGE_SE3:QUAT 693 744 2.20917 11.0134 -5.61164 0.146258 -0.00538837 0.0506207 0.987936 1 4.81482e-20 4.81482e-20 2.74383e-10 -2.01316e-09 -1.37173e-08 1 4.81482e-20 2.74383e-10 -2.01316e-09 -1.37173e-08 1 2.74383e-10 -2.01316e-09 -1.37173e-08 3918.41 -11.3522 -129.13 3998.5 -3.33974 3993.73 +EDGE_SE3:QUAT 694 743 1.91441 -11.2202 -4.87957 0.010863 -0.163506 0.0289588 0.986057 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4465.84 11.1971 -1443.16 3892.94 -18.9478 4462.96 +EDGE_SE3:QUAT 695 745 3.23446 -0.449914 -5.39207 0.00721374 -0.0676835 0.0867725 0.9939 1 4.70198e-23 4.70198e-23 -4.35072e-10 -3.79057e-11 2.97268e-11 1 4.70198e-23 -4.35072e-10 -3.79057e-11 2.97268e-11 1 -4.35072e-10 -3.79057e-11 2.97268e-11 4074.49 7.74395 -551.719 3982.12 -24.3092 4044.58 +EDGE_SE3:QUAT 694 745 1.94834 11.3926 -5.7372 -0.0519657 -0.0870833 -0.0202848 0.994638 1 2.40741e-19 2.40741e-19 1.43376e-08 2.74507e-08 1.14553e-10 1 2.40741e-19 1.43376e-08 2.74507e-08 1.14553e-10 1 1.43376e-08 2.74507e-08 1.14553e-10 4116.88 16.565 -725.984 3968.86 -2.05223 4126.04 +EDGE_SE3:QUAT 695 744 1.85859 -11.5119 -5.25954 0.0272068 0.0769747 -0.122876 0.989058 1 2.0463e-19 2.0463e-19 1.02866e-08 2.66175e-08 3.55404e-10 1 2.0463e-19 1.02866e-08 2.66175e-08 3.55404e-10 1 1.02866e-08 2.66175e-08 3.55404e-10 4101.94 -9.72502 656.212 3975.08 -39.2493 4044.51 +EDGE_SE3:QUAT 696 746 2.57834 -0.183307 -5.3925 -0.00584534 -0.0233593 0.0243758 0.999413 1 7.52316e-22 7.52316e-22 1.73556e-09 4.28481e-11 -4.00189e-11 1 7.52316e-22 1.73556e-09 4.28481e-11 -4.00189e-11 1 1.73556e-09 4.28481e-11 -4.00189e-11 4008.43 0.85804 -185.333 3997.88 -2.33953 4006.19 +EDGE_SE3:QUAT 695 746 2.03082 11.4627 -5.58727 0.0672845 -0.207069 0.0982213 0.971055 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4824.94 32.3168 -2020.64 3819.46 -56.9506 4804.46 +EDGE_SE3:QUAT 696 745 1.97215 -11.3843 -5.54445 -0.0106365 -0.0980071 -0.2039 0.974016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4148.15 -43.3935 -785.563 3971.52 85.0227 3982.31 +EDGE_SE3:QUAT 697 747 2.89575 0.0985067 -5.82802 -0.0556041 -0.0734573 -0.0834232 0.992246 1 1.92593e-19 1.92593e-19 2.10158e-09 2.75575e-08 1.1988e-09 1 1.92593e-19 2.10158e-09 2.75575e-08 1.1988e-09 1 2.10158e-09 2.75575e-08 1.1988e-09 4090.32 6.99806 -649.216 3974.26 21.0284 4074.85 +EDGE_SE3:QUAT 696 747 2.02904 11.3022 -5.66437 0.00531765 0.118325 0.0450438 0.991938 1 1.95602e-19 1.95602e-19 2.21799e-09 2.76984e-08 -3.44163e-11 1 1.95602e-19 2.21799e-09 2.76984e-08 -3.44163e-11 1 2.21799e-09 2.76984e-08 -3.44163e-11 4230.61 19.0736 987.995 3945.54 27.4013 4222.61 +EDGE_SE3:QUAT 697 746 2.11961 -11.3763 -5.31108 -0.0648815 -0.134873 -0.0709927 0.986184 1 2.40741e-19 2.40741e-19 1.83512e-08 5.63803e-10 -3.05512e-08 1 2.40741e-19 1.83512e-08 5.63803e-10 -3.05512e-08 1 1.83512e-08 5.63803e-10 -3.05512e-08 4317.22 11.1053 -1203.3 3921.03 18.7121 4313.9 +EDGE_SE3:QUAT 698 748 2.85726 0.00161695 -5.60374 -0.0352381 -0.0987492 0.0168282 0.994346 1 2.40741e-19 2.40741e-19 -1.33969e-08 -2.79365e-08 2.85362e-10 1 2.40741e-19 -1.33969e-08 -2.79365e-08 2.85362e-10 1 -1.33969e-08 -2.79365e-08 2.85362e-10 4151.93 19.686 -807.612 3962.54 -15.9587 4155.77 +EDGE_SE3:QUAT 697 748 1.94831 11.1426 -5.78899 -0.0838432 0.0252892 0.0293133 0.995727 1 2.0463e-19 2.0463e-19 2.78543e-08 -6.22304e-09 2.56912e-10 1 2.0463e-19 2.78543e-08 -6.22304e-09 2.56912e-10 1 2.78543e-08 -6.22304e-09 2.56912e-10 3985.04 -9.54356 229.98 3996.54 1.94961 4009.73 +EDGE_SE3:QUAT 698 747 2.28696 -11.3834 -5.77339 -0.204169 0.117675 -0.0805737 0.968491 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3946.79 -86.4026 692.197 3989.25 -71.2447 4087.56 +EDGE_SE3:QUAT 699 749 3.12356 -0.0702803 -5.77611 0.00917703 0.0950057 -0.100006 0.990398 1 1.93345e-19 1.93345e-19 4.43344e-09 -4.59798e-10 2.81667e-08 1 1.93345e-19 4.43344e-09 -4.59798e-10 2.81667e-08 1 4.43344e-09 -4.59798e-10 2.81667e-08 4147.93 -18.7958 784.256 3965.48 -40.9103 4108.26 +EDGE_SE3:QUAT 698 749 1.71722 11.0531 -5.90528 -0.00548294 0.00219752 -0.0909007 0.995842 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.91 -0.0311989 11.4142 3999.99 -0.42519 3966.98 +EDGE_SE3:QUAT 699 748 2.2722 -11.2443 -5.27221 -0.158827 -0.194483 -0.204464 0.946121 1 7.70372e-19 7.70372e-19 -8.35661e-09 -5.30789e-08 -4.32943e-09 1 7.70372e-19 -8.35661e-09 -5.30789e-08 -4.32943e-09 1 -8.35661e-09 -5.30789e-08 -4.32943e-09 4871.93 -41.1915 -2199.99 3798.66 108.061 4805.61 +EDGE_SE3:QUAT 700 750 2.86629 -0.0769173 -5.79778 0.112672 -0.148169 -0.198463 0.96227 1 7.70372e-19 7.70372e-19 -4.90153e-09 9.44969e-09 5.45952e-08 1 7.70372e-19 -4.90153e-09 9.44969e-09 5.45952e-08 1 -4.90153e-09 9.44969e-09 5.45952e-08 4116.26 -114.566 -848.313 3990.57 123.265 4009.49 +EDGE_SE3:QUAT 699 750 2.07865 11.725 -5.96522 0.079915 0.065955 -0.0433123 0.993674 1 1.92593e-19 1.92593e-19 9.04722e-10 2.75913e-08 -2.07202e-09 1 1.92593e-19 9.04722e-10 2.75913e-08 -2.07202e-09 1 9.04722e-10 2.75913e-08 -2.07202e-09 4054.85 19.3577 572.82 3979.86 -3.78833 4072.89 +EDGE_SE3:QUAT 700 749 2.09036 -11.2919 -5.087 0.00906262 -0.053331 -0.0687058 0.996169 1 1.95602e-19 1.95602e-19 -4.91407e-09 7.0119e-10 2.79802e-08 1 1.95602e-19 -4.91407e-09 7.0119e-10 2.79802e-08 1 -4.91407e-09 7.0119e-10 2.79802e-08 4043.3 -6.52495 -420.027 3989.6 15.3342 4024.74 +EDGE_SE3:QUAT 701 751 2.81795 0.0546932 -5.65416 -0.0673412 -0.0483462 0.192913 0.977708 1 7.70372e-19 7.70372e-19 -1.04187e-09 -4.49345e-09 5.43451e-08 1 7.70372e-19 -1.04187e-09 -4.49345e-09 5.43451e-08 1 -1.04187e-09 -4.49345e-09 5.43451e-08 3991.94 9.72959 -210.953 3999.46 -16.3893 3861.21 +EDGE_SE3:QUAT 700 751 2.44828 11.3956 -5.68923 0.0669235 0.142229 0.0645768 0.985455 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4283.14 76.3968 1138.31 3936.79 75.9535 4284.37 +EDGE_SE3:QUAT 701 750 1.86239 -11.2376 -5.59904 0.0180512 -0.00971587 -0.145004 0.989219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.15 -0.443561 -44.2864 3999.95 2.41065 3916.35 +EDGE_SE3:QUAT 702 752 2.66787 0.396294 -5.46306 -0.187595 0.0518361 0.0297139 0.980428 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3912.23 -43.9833 463.53 3987.79 -7.31197 4049.47 +EDGE_SE3:QUAT 701 752 2.0896 11.3301 -5.79713 0.0958303 -0.0965952 0.0175584 0.990544 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4120.75 -38.6306 -809.158 3962.85 15.1741 4156.25 +EDGE_SE3:QUAT 702 751 2.33412 -11.1454 -5.46689 -0.000627235 0.000851828 -0.204328 0.978902 1 1.17549e-23 1.17549e-23 2.12266e-10 -4.43069e-11 1.14879e-13 1 1.17549e-23 2.12266e-10 -4.43069e-11 1.14879e-13 1 2.12266e-10 -4.43069e-11 1.14879e-13 4000 -0.0035341 4.89721 4000 -0.433009 3833.01 +EDGE_SE3:QUAT 703 753 3.1149 -0.274747 -5.7336 0.0922618 0.0410657 -0.0734917 0.99217 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.69 16.1391 406.348 3988.98 -10.9342 4019.14 +EDGE_SE3:QUAT 702 753 1.9142 11.5871 -5.46786 0.0816662 -0.0110088 -0.0276993 0.996214 1 1.95602e-19 1.95602e-19 -2.75525e-08 4.26469e-09 -1.09159e-10 1 1.95602e-19 -2.75525e-08 4.26469e-09 -1.09159e-10 1 -2.75525e-08 4.26469e-09 -1.09159e-10 3974.2 -2.1182 -60.0835 3999.85 0.837677 3997.81 +EDGE_SE3:QUAT 703 752 1.66579 -11.2944 -5.3373 0.0435831 0.0630302 -0.134232 0.987982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4071.73 -2.16735 569.018 3980.44 -36.2254 4007.26 +EDGE_SE3:QUAT 704 754 2.63626 -0.108502 -5.62774 -0.0896297 0.126977 0.0743454 0.985046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4274.93 -27.4085 1150.11 3926.86 9.6905 4284.95 +EDGE_SE3:QUAT 703 754 2.38882 11.036 -5.74433 -0.138378 0.126197 0.0337065 0.981728 1 3.85186e-18 3.85186e-18 1.12744e-07 -5.47514e-08 7.55375e-09 1 3.85186e-18 1.12744e-07 -5.47514e-08 7.55375e-09 1 1.12744e-07 -5.47514e-08 7.55375e-09 4205.98 -75.6251 1100.06 3936.87 -38.4159 4278.03 +EDGE_SE3:QUAT 704 753 2.21683 -11.3083 -5.31424 0.0918326 -0.10884 -0.0402626 0.988989 1 1.92593e-19 1.92593e-19 -2.80335e-08 1.72181e-09 2.80692e-09 1 1.92593e-19 -2.80335e-08 1.72181e-09 2.80692e-09 1 -2.80335e-08 1.72181e-09 2.80692e-09 4136.14 -53.1963 -842.006 3963.42 43.3801 4163.39 +EDGE_SE3:QUAT 705 755 2.80501 -0.14112 -5.77428 -0.0310108 0.0281338 0.0282969 0.998722 1 1.20371e-20 1.20371e-20 2.07078e-10 -2.04489e-10 6.94203e-09 1 1.20371e-20 2.07078e-10 -2.04489e-10 6.94203e-09 1 2.07078e-10 -2.04489e-10 6.94203e-09 4010 -3.16056 235.729 3996.47 2.77796 4010.64 +EDGE_SE3:QUAT 704 755 2.23514 11.2626 -5.37319 -0.0262262 -0.089486 0.0577437 0.993967 1 4.81482e-20 4.81482e-20 1.20712e-09 5.19989e-10 -1.40051e-08 1 4.81482e-20 1.20712e-09 5.19989e-10 -1.40051e-08 1 1.20712e-09 5.19989e-10 -1.40051e-08 4120.05 20.9727 -711.584 3971.34 -26.9952 4109.46 +EDGE_SE3:QUAT 705 754 1.82133 -11.3493 -5.2626 -0.104694 -0.103917 -0.160683 0.975921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4212.33 5.52079 -1044.88 3937.56 61.4653 4152.89 +EDGE_SE3:QUAT 706 756 2.68277 0.220999 -5.83621 0.0454399 -0.0524826 -0.0181434 0.997422 1 1.20371e-20 1.20371e-20 -3.52755e-10 3.31799e-10 6.95736e-09 1 1.20371e-20 -3.52755e-10 3.31799e-10 6.95736e-09 1 -3.52755e-10 3.31799e-10 6.95736e-09 4033.76 -10.7061 -412.147 3989.89 6.7278 4040.7 +EDGE_SE3:QUAT 705 756 2.02078 11.4174 -5.54862 -0.0867504 -0.0976117 0.0982598 0.986555 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4079.44 47.9104 -672.72 3979.53 -49.7572 4070.92 +EDGE_SE3:QUAT 706 755 1.93913 -11.9276 -5.49472 -0.199424 -0.238401 -0.0295417 0.950012 1 7.82409e-19 7.82409e-19 6.12178e-08 6.11412e-09 -2.18091e-08 1 7.82409e-19 6.12178e-08 6.11412e-09 -2.18091e-08 1 6.12178e-08 6.11412e-09 -2.18091e-08 4871.99 319.931 -2278.37 3843.58 -302.503 5027.58 +EDGE_SE3:QUAT 707 757 2.80361 -0.0592652 -5.69786 -0.0604224 0.0233488 0.0383249 0.997164 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.76 -6.14224 213.627 3996.97 3.31088 4005.48 +EDGE_SE3:QUAT 706 757 2.19152 11.3313 -5.58932 -0.0645012 -0.0770794 0.0536522 0.993489 1 4.81482e-20 4.81482e-20 9.67178e-10 1.02596e-09 -1.39289e-08 1 4.81482e-20 9.67178e-10 1.02596e-09 -1.39289e-08 1 9.67178e-10 1.02596e-09 -1.39289e-08 4065.19 26.1432 -578.247 3981.81 -24.3172 4070.32 +EDGE_SE3:QUAT 707 756 2.22731 -11.5523 -5.90558 0.0255375 -0.0558662 0.0859152 0.994407 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4052.7 0.708219 -473.623 3986.29 -19.2618 4025.78 +EDGE_SE3:QUAT 708 758 2.25965 -0.0222709 -5.69138 -0.117215 0.0718124 0.0521661 0.989132 1 4.81482e-20 4.81482e-20 1.14873e-09 -1.55193e-09 1.39042e-08 1 4.81482e-20 1.14873e-09 -1.55193e-09 1.39042e-08 1 1.14873e-09 -1.55193e-09 1.39042e-08 4047.41 -33.6954 648.212 3974.55 0.88999 4091.48 +EDGE_SE3:QUAT 707 758 2.00151 11.5505 -5.97745 -0.11065 0.0650245 0.246659 0.960566 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4107.29 -0.829528 808.295 3960.01 95.3642 3912.9 +EDGE_SE3:QUAT 708 757 1.8109 -11.382 -5.33254 0.0505356 0.0519206 0.107486 0.991563 1 2.40741e-19 2.40741e-19 1.49145e-08 3.26135e-09 2.81745e-08 1 2.40741e-19 1.49145e-08 3.26135e-09 2.81745e-08 1 1.49145e-08 3.26135e-09 2.81745e-08 4018.93 13.5084 343.748 3994.3 20.037 3982.93 +EDGE_SE3:QUAT 709 759 3.05049 0.0801649 -5.5713 0.120594 -0.0101284 -0.0270942 0.99228 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3942.19 -1.63399 -40.3637 3999.97 0.471485 3997.42 +EDGE_SE3:QUAT 708 759 2.07357 11.5072 -5.62805 -0.0473038 0.155176 -0.0867858 0.98293 1 7.70372e-19 7.70372e-19 -5.86124e-09 -5.44613e-08 -4.2474e-09 1 7.70372e-19 -5.86124e-09 -5.44613e-08 -4.2474e-09 1 -5.86124e-09 -5.44613e-08 -4.2474e-09 4356.53 -88.0512 1263.55 3924.72 -95.2691 4335.36 +EDGE_SE3:QUAT 709 758 2.23276 -11.3891 -5.58008 0.00873699 -0.128388 -0.337584 0.932457 1 4.81482e-20 4.81482e-20 -1.32468e-08 4.98512e-09 1.31184e-09 1 4.81482e-20 -1.32468e-08 4.98512e-09 1.31184e-09 1 -1.32468e-08 4.98512e-09 1.31184e-09 4168.27 -109.824 -847.673 3996.23 155.112 3712.72 +EDGE_SE3:QUAT 710 760 2.93047 -0.470033 -5.22878 0.149465 0.127295 -0.184749 0.962977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4345.53 17.1609 1389.98 3897.03 -71.58 4298.36 +EDGE_SE3:QUAT 709 760 1.96442 11.7275 -5.95742 -0.092173 -0.131377 0.0941847 0.982534 1 1.92593e-19 1.92593e-19 -2.80173e-08 -3.42903e-09 3.10019e-09 1 1.92593e-19 -2.80173e-08 -3.42903e-09 3.10019e-09 1 -2.80173e-08 -3.42903e-09 3.10019e-09 4183.22 83.3984 -958.753 3959.98 -83.7432 4181.72 +EDGE_SE3:QUAT 710 759 2.13276 -11.5702 -5.36063 0.193773 -0.0891703 -0.0096318 0.976938 1 1.92593e-19 1.92593e-19 -1.2019e-09 -2.70901e-08 5.50445e-09 1 1.92593e-19 -1.2019e-09 -2.70901e-08 5.50445e-09 1 -1.2019e-09 -2.70901e-08 5.50445e-09 3957.5 -69.2328 -665.989 3980.26 37.1922 4107.32 +EDGE_SE3:QUAT 711 761 2.73203 -0.232767 -5.76803 -0.0876001 -0.0439297 0.0308092 0.99471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.1 14.7777 -316.231 3994.56 -8.23168 4021 +EDGE_SE3:QUAT 710 761 2.16738 11.3251 -5.63236 -0.117391 -0.0168254 -0.0649082 0.990819 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3956.98 13.8189 -222.031 3996.23 6.37719 3995.25 +EDGE_SE3:QUAT 711 760 2.05151 -11.2782 -5.26674 0.08222 0.0342254 -0.0490885 0.994816 1 4.81482e-20 4.81482e-20 5.79956e-10 1.0955e-09 1.385e-08 1 4.81482e-20 5.79956e-10 1.0955e-09 1.385e-08 1 5.79956e-10 1.0955e-09 1.385e-08 3998.37 12.1979 320.131 3993.24 -5.37239 4015.77 +EDGE_SE3:QUAT 712 762 2.81903 -0.0755593 -5.55445 0.116442 0.102661 -0.050913 0.986565 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4143.69 45.4373 911.599 3952.68 8.15121 4187.56 +EDGE_SE3:QUAT 711 762 2.20555 11.1711 -5.76153 -0.0934287 -0.089832 -0.115019 0.984872 1 1.92593e-19 1.92593e-19 3.05125e-09 2.04e-09 -2.79412e-08 1 1.92593e-19 3.05125e-09 2.04e-09 -2.79412e-08 1 3.05125e-09 2.04e-09 -2.79412e-08 4140.77 16.3945 -856.979 3956 32.5098 4122.77 +EDGE_SE3:QUAT 712 761 1.56707 -11.2608 -5.42538 -0.0213753 -0.108486 0.00487534 0.993856 1 1.20371e-20 1.20371e-20 -7.06183e-09 -6.8984e-11 7.68563e-10 1 1.20371e-20 -7.06183e-09 -6.8984e-11 7.68563e-10 1 -7.06183e-09 -6.8984e-11 7.68563e-10 4192.45 12.2974 -902.684 3953.33 -8.84771 4194.18 +EDGE_SE3:QUAT 713 763 2.86125 -0.0958996 -5.99444 -0.0710264 -0.00491929 0.0555363 0.995915 1 2.40741e-19 2.40741e-19 -2.76002e-08 -2.53238e-09 1.37373e-08 1 2.40741e-19 -2.76002e-08 -2.53238e-09 1.37373e-08 1 -2.76002e-08 -2.53238e-09 1.37373e-08 3979.78 -0.857847 8.20322 3999.96 0.670994 3987.62 +EDGE_SE3:QUAT 712 763 1.96285 11.318 -6.17261 0.153585 0.0246207 -0.110084 0.981676 1 1.92593e-19 1.92593e-19 -1.56564e-09 -4.03908e-09 -2.73756e-08 1 1.92593e-19 -1.56564e-09 -4.03908e-09 -2.73756e-08 1 -1.56564e-09 -4.03908e-09 -2.73756e-08 3942.21 30.2219 388.353 3988.19 -18.2662 3988.09 +EDGE_SE3:QUAT 713 762 2.03238 -11.4801 -5.75659 -0.135711 -0.241785 -0.107565 0.954753 1 1.92593e-19 1.92593e-19 -8.29665e-09 -3.03173e-09 3.05724e-08 1 1.92593e-19 -8.29665e-09 -3.03173e-09 3.05724e-08 1 -8.29665e-09 -3.03173e-09 3.05724e-08 5219.34 73.3291 -2616.15 3743.02 -51.4666 5246.73 +EDGE_SE3:QUAT 714 764 2.56514 0.0392221 -5.4724 0.0356611 0.102718 0.0490828 0.992859 1 1.92593e-19 1.92593e-19 1.59308e-09 -2.7545e-08 1.28906e-09 1 1.92593e-19 1.59308e-09 -2.7545e-08 1.28906e-09 1 1.59308e-09 -2.7545e-08 1.28906e-09 4157.94 28.5687 823.888 3962.25 31.236 4153.39 +EDGE_SE3:QUAT 713 764 2.2859 11.2581 -5.84866 0.0856739 0.0234655 -0.0809719 0.99275 1 1.92593e-19 1.92593e-19 1.0185e-09 2.25027e-09 2.76159e-08 1 1.92593e-19 1.0185e-09 2.25027e-09 2.76159e-08 1 1.0185e-09 2.25027e-09 2.76159e-08 3988.3 10.7934 267.508 3994.81 -9.98597 3991.44 +EDGE_SE3:QUAT 714 763 1.83856 -11.4049 -5.25588 -0.00490066 0.0188378 -0.0151123 0.999696 1 1.27894e-20 1.27894e-20 1.6292e-09 -6.96334e-09 -5.53851e-12 1 1.27894e-20 1.6292e-09 -6.96334e-09 -5.53851e-12 1 1.6292e-09 -6.96334e-09 -5.53851e-12 4005.52 -0.495674 149.94 3998.61 -1.17618 4004.7 +EDGE_SE3:QUAT 715 765 2.84349 -0.0562 -5.35808 -0.0542431 -0.0630694 -0.0912289 0.992349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4066.51 6.09666 -565.187 3980.15 21.5883 4044.99 +EDGE_SE3:QUAT 714 765 2.25417 11.3658 -5.63277 -0.14982 0.0406135 0.154612 0.975705 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.68 -35.5259 584.65 3975.04 37.6917 3986.84 +EDGE_SE3:QUAT 715 764 2.04112 -11.5569 -5.38336 0.0351851 -0.0618925 -0.13932 0.987685 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4039.56 -17.5528 -425.315 3991.4 31.4995 3966.87 +EDGE_SE3:QUAT 716 766 2.51262 -0.249547 -5.74173 -0.0974978 0.0395927 0.0647749 0.992336 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.33 -17.0988 388.889 3989.93 8.5091 4020.57 +EDGE_SE3:QUAT 715 766 2.06639 11.7849 -5.89073 0.138279 0.0010969 0.198713 0.970253 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3945.1 -24.8239 -310.556 3989.6 -38.9155 3863.64 +EDGE_SE3:QUAT 716 765 2.06119 -11.4662 -5.09514 -0.0997204 0.0740039 -0.181492 0.97552 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.26 -24.3318 342.79 3998.43 -30.3678 3895.28 +EDGE_SE3:QUAT 717 767 2.67852 0.522561 -5.79536 0.0621981 0.0278023 -0.00860206 0.997639 1 7.52316e-22 7.52316e-22 4.97854e-11 1.07396e-10 1.73344e-09 1 7.52316e-22 4.97854e-11 1.07396e-10 1.73344e-09 1 4.97854e-11 1.07396e-10 1.73344e-09 3997.5 7.04188 228.166 3996.77 0.205517 4012.68 +EDGE_SE3:QUAT 716 767 1.88552 11.6639 -5.74679 0.0222941 0.0693039 -0.0339297 0.996769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.23 2.63792 572.102 3980.16 -7.55808 4075.61 +EDGE_SE3:QUAT 717 766 1.81633 -11.8514 -5.41678 0.151442 0.12851 -0.0476996 0.978915 1 7.82409e-19 7.82409e-19 -5.58526e-10 5.33674e-08 -1.50449e-08 1 7.82409e-19 -5.58526e-10 5.33674e-08 -1.50449e-08 1 -5.58526e-10 5.33674e-08 -1.50449e-08 4215.49 82.5059 1150.35 3931.41 38.4541 4298.13 +EDGE_SE3:QUAT 718 768 2.60677 -0.423689 -5.88545 -0.0309127 -0.0863365 -0.0749595 0.992961 1 2.0463e-19 2.0463e-19 8.96176e-09 2.70712e-08 -1.34422e-10 1 2.0463e-19 8.96176e-09 2.70712e-08 -1.34422e-10 1 8.96176e-09 2.70712e-08 -1.34422e-10 4126.03 -2.29945 -732.317 3968.34 23.9258 4107.37 +EDGE_SE3:QUAT 717 768 1.69658 11.371 -5.80353 0.0404392 -0.0187357 0.0367936 0.998329 1 9.62965e-20 9.62965e-20 1.35667e-08 1.03022e-09 1.35667e-08 1 9.62965e-20 1.35667e-08 1.03022e-09 1.35667e-08 1 1.35667e-08 1.03022e-09 1.35667e-08 4000.44 -3.1441 -167.308 3998.15 -2.79084 4001.56 +EDGE_SE3:QUAT 718 767 1.66292 -11.4159 -5.67199 -0.0501271 0.0142534 -0.030043 0.998189 1 5.11575e-20 5.11575e-20 1.37479e-08 -3.89794e-09 -2.1872e-11 1 5.11575e-20 1.37479e-08 -3.89794e-09 -2.1872e-11 1 1.37479e-08 -3.89794e-09 -2.1872e-11 3992.22 -2.35245 95.4508 3999.51 -1.52949 3998.66 +EDGE_SE3:QUAT 719 769 2.76933 -0.184215 -5.9711 0.0169002 0.0761647 0.0299386 0.996502 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4091.04 9.69259 614.191 3977.67 12.09 4088.6 +EDGE_SE3:QUAT 718 769 1.94716 11.7497 -5.70672 0.00193734 -0.0481064 0.146812 0.987992 1 7.70372e-19 7.70372e-19 -2.5979e-09 -6.77981e-10 5.5093e-08 1 7.70372e-19 -2.5979e-09 -6.77981e-10 5.5093e-08 1 -2.5979e-09 -6.77981e-10 5.5093e-08 4035.52 7.6583 -378.74 3992.13 -28.1449 3949.32 +EDGE_SE3:QUAT 719 768 2.09785 -11.4919 -5.49286 0.00419199 0.0291475 -0.0649364 0.997455 1 1.88079e-22 1.88079e-22 -8.66656e-10 5.63039e-11 -2.55835e-11 1 1.88079e-22 -8.66656e-10 5.63039e-11 -2.55835e-11 1 -8.66656e-10 5.63039e-11 -2.55835e-11 4013.77 -0.848609 235.675 3996.59 -7.65349 3996.97 +EDGE_SE3:QUAT 720 770 2.59098 -0.0290508 -5.73678 0.180702 -0.0965591 -0.076162 0.975819 1 9.62965e-19 9.62965e-19 -5.64465e-08 1.14954e-08 3.08079e-08 1 9.62965e-19 -5.64465e-08 1.14954e-08 3.08079e-08 1 -5.64465e-08 1.14954e-08 3.08079e-08 3948.17 -60.2219 -572.984 3990.26 47.0562 4055.58 +EDGE_SE3:QUAT 719 770 1.85415 11.6505 -5.75564 -0.128925 -0.0545119 0.199178 0.969915 1 7.82409e-19 7.82409e-19 5.24029e-08 1.81993e-08 1.06931e-09 1 7.82409e-19 5.24029e-08 1.81993e-08 1.06931e-09 1 5.24029e-08 1.81993e-08 1.06931e-09 3932.77 1.38189 -101.895 4000.73 -0.146303 3840.57 +EDGE_SE3:QUAT 720 769 1.83206 -11.1018 -5.4151 0.00018508 -0.0194322 0.0552831 0.998282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006 0.485337 -155.071 3998.52 -4.29626 3993.78 +EDGE_SE3:QUAT 721 771 3.09246 0.0139175 -5.42906 -0.0283336 0.114457 -0.120467 0.98569 1 1.01111e-18 1.01111e-18 1.63006e-08 -3.23604e-08 5.59278e-08 1 1.01111e-18 1.63006e-08 -3.23604e-08 5.59278e-08 1 1.63006e-08 -3.23604e-08 5.59278e-08 4184.56 -50.1344 887.226 3960.98 -67.6739 4129.72 +EDGE_SE3:QUAT 720 771 1.88239 11.2153 -5.91077 0.00601712 0.129559 0.0354782 0.990919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4279.86 19.2936 1094.73 3934.17 25.4701 4274.97 +EDGE_SE3:QUAT 721 770 1.87877 -11.3912 -5.61314 -0.0709624 0.125293 -0.10199 0.984309 1 1.92593e-19 1.92593e-19 2.80233e-08 -3.47544e-09 3.02884e-09 1 1.92593e-19 2.80233e-08 -3.47544e-09 3.02884e-09 1 2.80233e-08 -3.47544e-09 3.02884e-09 4184.51 -70.9259 928.827 3960.47 -76.4353 4163.04 +EDGE_SE3:QUAT 722 772 2.38209 0.0187994 -5.53655 0.127343 0.116369 -0.0743968 0.982195 1 1.92593e-19 1.92593e-19 -2.81892e-08 1.26767e-09 -3.74813e-09 1 1.92593e-19 -2.81892e-08 1.26767e-09 -3.74813e-09 1 -2.81892e-08 1.26767e-09 -3.74813e-09 4206.74 51.3089 1077.3 3935.34 4.21524 4249.46 +EDGE_SE3:QUAT 721 772 2.19406 11.3191 -6.02794 -0.1325 -0.0445466 0.0124527 0.990103 1 8.1852e-19 8.1852e-19 5.48193e-08 1.50629e-08 -3.49787e-10 1 8.1852e-19 5.48193e-08 1.50629e-08 -3.49787e-10 1 5.48193e-08 1.50629e-08 -3.49787e-10 3956.64 22.107 -329.172 3994.24 -7.65655 4026.25 +EDGE_SE3:QUAT 722 771 2.04926 -11.5038 -5.5975 0.104974 -0.0324575 0.0857752 0.990237 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.23 -17.3737 -362.234 3990.75 -12.6796 4002.88 +EDGE_SE3:QUAT 723 773 2.85215 0.0337405 -5.8633 0.0972658 0.104626 -0.117891 0.982698 1 3.85186e-19 3.85186e-19 3.08057e-08 2.45338e-08 1.50896e-09 1 3.85186e-19 3.08057e-08 2.45338e-08 1.50896e-09 1 3.08057e-08 2.45338e-08 1.50896e-09 4196.34 16.2355 996.178 3942.52 -35.4262 4178.59 +EDGE_SE3:QUAT 722 773 1.89709 11.1384 -6.06409 0.0225797 -0.0531135 -0.0939821 0.9939 1 9.62965e-20 9.62965e-20 -1.25178e-08 1.51393e-08 2.19651e-10 1 9.62965e-20 -1.25178e-08 1.51393e-08 2.19651e-10 1 -1.25178e-08 1.51393e-08 2.19651e-10 4036.9 -10.2308 -396.795 3991.27 20.0441 4003.61 +EDGE_SE3:QUAT 723 772 1.94084 -11.818 -5.64427 -0.0240973 -0.050178 0.11806 0.991445 1 1.92593e-19 1.92593e-19 -1.19924e-09 -9.84894e-10 2.76306e-08 1 1.92593e-19 -1.19924e-09 -9.84894e-10 2.76306e-08 1 -1.19924e-09 -9.84894e-10 2.76306e-08 4029.96 10.3864 -361.18 3993.16 -22.223 3976.53 +EDGE_SE3:QUAT 724 774 2.71475 -0.329936 -5.70685 -0.113572 -0.00390096 0.0813541 0.990186 1 1.93345e-19 1.93345e-19 -2.76265e-08 -5.06519e-10 -2.08358e-10 1 1.93345e-19 -2.76265e-08 -5.06519e-10 -2.08358e-10 1 -2.76265e-08 -5.06519e-10 -2.08358e-10 3949.65 -6.52344 79.1557 3999.16 4.61292 3974.77 +EDGE_SE3:QUAT 723 774 2.07096 11.2914 -5.50221 -0.218682 -0.0530481 0.0473078 0.973204 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3826.42 26.3937 -273.117 3998.49 -13.1974 4008.76 +EDGE_SE3:QUAT 724 773 1.88167 -11.816 -5.32447 0.0456277 -0.02952 0.0555682 0.996975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.23 -4.9428 -265.75 3995.37 -6.57578 4005.21 +EDGE_SE3:QUAT 725 775 2.86768 -0.062821 -5.66745 0.0304388 -0.100695 0.093884 0.99001 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4173.69 10.5873 -860.848 3957.69 -37.1126 4142.14 +EDGE_SE3:QUAT 724 775 2.13308 11.5421 -5.71184 -0.131696 0.0554173 0.0901522 0.985625 1 9.62965e-19 9.62965e-19 -5.31441e-08 -7.48719e-09 2.33654e-08 1 9.62965e-19 -5.31441e-08 -7.48719e-09 2.33654e-08 1 -5.31441e-08 -7.48719e-09 2.33654e-08 4012.23 -32.3339 578.207 3978.13 14.1961 4049.09 +EDGE_SE3:QUAT 725 774 1.59149 -11.7252 -5.52521 0.0899893 0.0938671 0.0661417 0.989301 1 3.85186e-19 3.85186e-19 2.55421e-08 2.97639e-08 -6.25254e-10 1 3.85186e-19 2.55421e-08 2.97639e-08 -6.25254e-10 1 2.55421e-08 2.97639e-08 -6.25254e-10 4079.96 43.9339 680.581 3977.03 39.8532 4094.85 +EDGE_SE3:QUAT 726 776 2.76389 -0.227043 -5.53331 -0.0701907 0.14764 0.11383 0.979958 1 1.01111e-18 1.01111e-18 -1.50545e-08 5.20001e-08 2.83617e-08 1 1.01111e-18 -1.50545e-08 5.20001e-08 2.83617e-08 1 -1.50545e-08 5.20001e-08 2.83617e-08 4401.3 13.0495 1364.36 3903.08 53.111 4369.18 +EDGE_SE3:QUAT 725 776 1.99822 11.6445 -5.66342 -0.0604122 0.101993 0.0575034 0.991283 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4172.36 -13.9675 884.81 3954.42 11.6939 4173.74 +EDGE_SE3:QUAT 726 775 1.84032 -11.4425 -5.77351 0.0100668 0.10683 -0.184127 0.977028 1 1.95602e-19 1.95602e-19 -1.70168e-09 -2.77681e-08 -4.59144e-10 1 1.95602e-19 -1.70168e-09 -2.77681e-08 -4.59144e-10 1 -1.70168e-09 -2.77681e-08 -4.59144e-10 4178.83 -47.2339 865.764 3964.21 -85.9279 4043.62 +EDGE_SE3:QUAT 727 777 2.71778 0.0543509 -5.20447 0.0509998 0.0272462 0.0556693 0.996774 1 6.01853e-20 6.01853e-20 -1.42514e-08 6.10659e-09 -6.68508e-10 1 6.01853e-20 -1.42514e-08 6.10659e-09 -6.68508e-10 1 -1.42514e-08 6.10659e-09 -6.68508e-10 3997.86 5.13396 182.433 3998.25 5.47106 3995.87 +EDGE_SE3:QUAT 726 777 1.95526 11.7504 -5.75541 0.0720863 0.0261246 -0.0337467 0.996485 1 2.0463e-19 2.0463e-19 -2.79126e-08 -6.08997e-09 -3.64594e-10 1 2.0463e-19 -2.79126e-08 -6.08997e-09 -3.64594e-10 1 -2.79126e-08 -6.08997e-09 -3.64594e-10 3993.17 8.261 236.865 3996.32 -2.74164 4009.4 +EDGE_SE3:QUAT 727 776 1.87111 -11.4654 -5.41689 0.14459 -0.0885156 -0.0118642 0.985453 1 9.62965e-19 9.62965e-19 -5.65171e-08 -2.52419e-08 8.70629e-09 1 9.62965e-19 -5.65171e-08 -2.52419e-08 8.70629e-09 1 -5.65171e-08 -2.52419e-08 8.70629e-09 4029.11 -54.2098 -681.273 3976.45 30.0924 4112.17 +EDGE_SE3:QUAT 728 778 2.66655 0.346351 -5.51783 0.00411076 -0.0510954 -0.060846 0.99683 1 7.52316e-22 7.52316e-22 -1.7381e-09 1.07377e-10 8.75488e-11 1 7.52316e-22 -1.7381e-09 1.07377e-10 8.75488e-11 1 -1.7381e-09 1.07377e-10 8.75488e-11 4040.94 -4.64554 -407.078 3990.08 12.9234 4026.2 +EDGE_SE3:QUAT 727 778 2.08866 11.8764 -6.04134 -0.0707142 -0.0973777 0.0247061 0.992425 1 1.92593e-19 1.92593e-19 -2.80424e-08 -1.09777e-09 2.61928e-09 1 1.92593e-19 -2.80424e-08 -1.09777e-09 2.61928e-09 1 -2.80424e-08 -1.09777e-09 2.61928e-09 4124.76 35.2837 -774.688 3966.77 -26.3158 4142.32 +EDGE_SE3:QUAT 728 777 1.67317 -11.6781 -5.51233 -0.00554938 -0.0621843 0.0778078 0.995012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4060 8.56983 -494.11 3985.73 -20.3769 4035.91 +EDGE_SE3:QUAT 729 779 2.70832 0.213518 -5.57621 0.0203952 -0.0657373 -0.0498672 0.996381 1 4.81482e-20 4.81482e-20 8.85712e-10 -3.78586e-10 -1.39418e-08 1 4.81482e-20 8.85712e-10 -3.78586e-10 -1.39418e-08 1 8.85712e-10 -3.78586e-10 -1.39418e-08 4064.49 -10.5323 -518.662 3984.22 15.452 4056.2 +EDGE_SE3:QUAT 728 779 2.40159 11.9992 -5.86064 -0.129389 0.0503827 -0.00636659 0.990293 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3969.95 -25.5545 386.171 3991.83 -8.67097 4036.75 +EDGE_SE3:QUAT 729 778 1.96612 -11.7297 -5.5821 -0.0212044 -0.0703812 -0.0193773 0.997107 1 2.40741e-20 2.40741e-20 7.48751e-09 1.47624e-11 -7.48751e-09 1 2.40741e-20 7.48751e-09 1.47624e-11 -7.48751e-09 1 7.48751e-09 1.47624e-11 -7.48751e-09 4079.9 4.07112 -577.476 3979.83 3.28911 4080.2 +EDGE_SE3:QUAT 730 780 2.37911 -0.0515977 -5.66949 -0.187171 -0.15349 -0.0654495 0.968052 1 7.70372e-19 7.70372e-19 5.68827e-08 -3.2456e-10 -9.77724e-09 1 7.70372e-19 5.68827e-08 -3.2456e-10 -9.77724e-09 1 5.68827e-08 -3.2456e-10 -9.77724e-09 4324.32 128.061 -1439.98 3902.98 -74.4661 4447.32 +EDGE_SE3:QUAT 729 780 1.95801 11.8556 -6.09859 -0.0585519 -0.0719265 0.166142 0.981731 1 2.40741e-19 2.40741e-19 -2.49892e-08 -1.84856e-08 2.40027e-10 1 2.40741e-19 -2.49892e-08 -1.84856e-08 2.40027e-10 1 -2.49892e-08 -1.84856e-08 2.40027e-10 4032.79 25.7634 -437.314 3993.01 -38.6885 3936.09 +EDGE_SE3:QUAT 730 779 2.01788 -11.2614 -5.54043 -0.0586795 -0.037383 -0.00329431 0.997571 1 4.70198e-23 4.70198e-23 -1.63139e-11 -2.54843e-11 4.33851e-10 1 4.70198e-23 -1.63139e-11 -2.54843e-11 4.33851e-10 1 -1.63139e-11 -2.54843e-11 4.33851e-10 4008.8 8.86699 -301.316 3994.45 -1.48886 4022.53 +EDGE_SE3:QUAT 731 781 2.66325 -0.291034 -5.80572 0.00470518 -0.105262 -0.0899508 0.990357 1 1.92593e-19 1.92593e-19 2.91175e-09 -6.78262e-10 -2.80925e-08 1 1.92593e-19 2.91175e-09 -6.78262e-10 -2.80925e-08 1 2.91175e-09 -6.78262e-10 -2.80925e-08 4176.3 -26.8424 -858.33 3959.54 44.1409 4144.02 +EDGE_SE3:QUAT 730 781 2.07677 11.6428 -5.89935 -0.0759456 0.0671416 0.208684 0.972715 1 4.81482e-20 4.81482e-20 -1.37091e-08 -2.79873e-09 -1.29344e-09 1 4.81482e-20 -1.37091e-08 -2.79873e-09 -1.29344e-09 1 -1.37091e-08 -2.79873e-09 -1.29344e-09 4096.48 4.88549 702.612 3970.65 70.6854 3945.36 +EDGE_SE3:QUAT 731 780 1.44089 -11.8218 -5.4624 0.0779753 -0.00874418 -0.0903933 0.99281 1 4.70198e-23 4.70198e-23 3.93125e-11 4.30553e-10 -3.39446e-11 1 4.70198e-23 3.93125e-11 4.30553e-10 -3.39446e-11 1 3.93125e-11 4.30553e-10 -3.39446e-11 3975.54 1.71875 15.318 3999.88 -1.99168 3967.17 +EDGE_SE3:QUAT 732 782 2.52763 -0.249046 -5.51341 -0.0482438 0.180667 0.0752627 0.979473 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4595.42 17.2048 1668.73 3864.78 39.6761 4582.08 +EDGE_SE3:QUAT 731 782 2.15829 11.6402 -6.08504 -0.0835356 -0.0987477 0.0586276 0.989865 1 1.92593e-19 1.92593e-19 -2.79284e-08 -2.1313e-09 2.44547e-09 1 1.92593e-19 -2.79284e-08 -2.1313e-09 2.44547e-09 1 -2.79284e-08 -2.1313e-09 2.44547e-09 4103.79 45.1237 -738.251 3972.15 -40.6359 4117.96 +EDGE_SE3:QUAT 732 781 1.90034 -11.2615 -5.50961 -0.043161 0.0431558 0.132146 0.989349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.45 -1.69774 406.849 3989.48 26.3001 3971.05 +EDGE_SE3:QUAT 733 783 2.7639 0.140466 -5.50615 0.0933457 -0.0570408 -0.15789 0.981378 1 8.1852e-19 8.1852e-19 -5.22818e-08 2.28554e-08 -1.45191e-10 1 8.1852e-19 -5.22818e-08 2.28554e-08 -1.45191e-10 1 -5.22818e-08 2.28554e-08 -1.45191e-10 3980.76 -14.7717 -260.274 3998.77 18.9163 3915.9 +EDGE_SE3:QUAT 732 783 1.49574 11.4801 -5.81915 0.0333096 -0.128153 0.0200999 0.990991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4275.3 -12.7914 -1094.17 3933.54 1.43006 4278.12 +EDGE_SE3:QUAT 733 782 2.08626 -11.6005 -5.76553 0.147978 -0.0881775 -0.056061 0.983455 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.9 -51.4995 -589.672 3985.29 37.7428 4071.92 +EDGE_SE3:QUAT 734 784 2.55632 0.0119262 -5.60673 0.134787 -0.105549 0.00865493 0.985199 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4107.61 -62.8532 -868.18 3960.26 33.5629 4179.98 +EDGE_SE3:QUAT 733 784 2.19417 11.4953 -5.85215 0.120708 0.134673 0.132658 0.974523 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4116.16 96.5587 859.482 3977.37 98.1917 4104.05 +EDGE_SE3:QUAT 734 783 1.955 -11.5242 -5.50643 0.0892326 0.0525249 0.0533598 0.993193 1 1.92593e-19 1.92593e-19 2.76772e-08 1.73142e-09 1.16627e-09 1 1.92593e-19 2.76772e-08 1.73142e-09 1.16627e-09 1 2.76772e-08 1.73142e-09 1.16627e-09 3999.93 18.2287 358.732 3993.47 13.8963 4020.39 +EDGE_SE3:QUAT 735 785 2.64579 -0.107375 -5.95171 0.134219 0.130225 -0.0441241 0.981366 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4238.58 72.5264 1157.18 3929.67 33.4069 4302.85 +EDGE_SE3:QUAT 734 785 2.16685 11.505 -5.77801 0.102674 -0.1251 0.0612828 0.984912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4252.64 -41.6745 -1125.31 3930.23 4.76572 4279.79 +EDGE_SE3:QUAT 735 784 1.73657 -11.7097 -5.46387 0.0276946 -0.0986111 0.0186465 0.994566 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4159.29 -7.97548 -822.065 3960.56 -1.62378 4160.97 +EDGE_SE3:QUAT 736 786 2.51877 -0.010323 -5.70608 -0.161509 0.0362488 0.133362 0.977147 1 1.58889e-18 1.58889e-18 -4.88958e-08 -2.82864e-08 4.84578e-08 1 1.58889e-18 -4.88958e-08 -2.82864e-08 4.84578e-08 1 -4.88958e-08 -2.82864e-08 4.84578e-08 3963.99 -39.1365 531.629 3979.01 27.8474 3997.19 +EDGE_SE3:QUAT 735 786 1.52854 11.8641 -6.02776 0.0634526 -0.00447105 0.0500669 0.996718 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.2 -2.65005 -73.4004 3999.54 -2.05302 3991.28 +EDGE_SE3:QUAT 736 785 1.6847 -11.5374 -5.37382 0.0230721 -0.116981 -0.0347343 0.992258 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4219.85 -24.6696 -968.107 3947.82 27.0908 4217.16 +EDGE_SE3:QUAT 737 787 2.45936 -0.51385 -5.50208 0.230268 0.0175076 0.0125421 0.972889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3790.11 9.3132 95.6284 3999.77 1.48369 4001.58 +EDGE_SE3:QUAT 736 787 1.69371 11.5938 -6.41972 -0.0783727 0.0713241 0.0763991 0.99143 1 1.92593e-19 1.92593e-19 -2.78699e-08 -1.82987e-09 -2.29562e-09 1 1.92593e-19 -2.78699e-08 -1.82987e-09 -2.29562e-09 1 -2.78699e-08 -1.82987e-09 -2.29562e-09 4077.35 -16.3513 646.815 3974.13 15.3597 4078.57 +EDGE_SE3:QUAT 737 786 2.13669 -11.5793 -6.05131 0.0323674 0.0920613 -0.00258958 0.995224 1 1.17549e-23 1.17549e-23 -2.03012e-11 -7.15632e-12 -2.19528e-10 1 1.17549e-23 -2.03012e-11 -7.15632e-12 -2.19528e-10 1 -2.03012e-11 -7.15632e-12 -2.19528e-10 4134.88 12.831 758.709 3966.27 5.79286 4139.05 +EDGE_SE3:QUAT 738 788 2.19016 0.268409 -5.98154 -0.178938 -0.075895 0.0130565 0.980842 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3948.42 52.7177 -559.165 3985.41 -25.8422 4075.82 +EDGE_SE3:QUAT 737 788 1.68059 11.5242 -6.15294 -0.167706 -0.125312 0.0533215 0.976385 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4071.32 96.6665 -879.707 3970.32 -78.037 4172.45 +EDGE_SE3:QUAT 738 787 1.74905 -11.4447 -6.13272 0.0851753 -0.119814 -0.13726 0.979566 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4125.16 -72.6527 -803.753 3975.42 80.6806 4078.82 +EDGE_SE3:QUAT 739 789 2.37248 0.330438 -6.12419 -0.0502385 0.100166 -0.0182189 0.993535 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4149.17 -26.9356 813.931 3962.45 -20.4914 4157.94 +EDGE_SE3:QUAT 738 789 1.88346 11.4705 -5.93987 -0.118975 0.0979761 0.0807816 0.984744 1 1.92593e-19 1.92593e-19 -2.80165e-08 -1.61413e-09 -3.22528e-09 1 1.92593e-19 -2.80165e-08 -1.61413e-09 -3.22528e-09 1 -2.80165e-08 -1.61413e-09 -3.22528e-09 4142.49 -38.9938 914.675 3951.08 7.64694 4173 +EDGE_SE3:QUAT 739 788 1.59027 -11.496 -5.84745 -0.00777685 0.00825118 -0.0108873 0.999876 1 3.00927e-21 3.00927e-21 3.46948e-09 -3.82239e-11 2.80329e-11 1 3.00927e-21 3.46948e-09 -3.82239e-11 2.80329e-11 1 3.46948e-09 -3.82239e-11 2.80329e-11 4000.81 -0.268914 64.9906 3999.74 -0.364564 4000.58 +EDGE_SE3:QUAT 740 790 2.59711 -0.207083 -5.88417 0.102856 -0.0024195 -0.0982624 0.989828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3959.84 7.08177 100.927 3998.77 -6.74722 3963.54 +EDGE_SE3:QUAT 739 790 1.62901 11.7326 -5.89726 -0.0418755 0.236574 -0.0463528 0.969603 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5012.79 -156.06 2262.66 3799.95 -156.465 5011.21 +EDGE_SE3:QUAT 740 789 1.94635 -11.6024 -5.64923 0.0571937 0.0968982 -0.186203 0.976047 1 7.70372e-19 7.70372e-19 -6.30293e-09 -1.04589e-09 -5.5508e-08 1 7.70372e-19 -6.30293e-09 -1.04589e-09 -5.5508e-08 1 -6.30293e-09 -1.04589e-09 -5.5508e-08 4178.07 -23.7268 895.17 3956.66 -79.4298 4052.47 +EDGE_SE3:QUAT 741 791 2.58773 0.109546 -5.675 0.258751 0.0871618 -0.0469448 0.960857 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3883.84 104.981 793.481 3970.72 38.5189 4142.84 +EDGE_SE3:QUAT 740 791 1.97365 11.6091 -5.53156 0.0232047 -0.0587117 -0.08783 0.994133 1 2.0463e-19 2.0463e-19 -8.43836e-09 1.56615e-09 2.8136e-08 1 2.0463e-19 -8.43836e-09 1.56615e-09 2.8136e-08 1 -8.43836e-09 1.56615e-09 2.8136e-08 4046.5 -11.8891 -443.986 3988.98 21.4787 4017.8 +EDGE_SE3:QUAT 741 790 1.78627 -11.426 -5.95928 0.00929576 0.0613029 -0.236427 0.969669 1 3.00927e-21 3.00927e-21 -3.38951e-09 8.28894e-10 -2.0518e-10 1 3.00927e-21 -3.38951e-09 8.28894e-10 -2.0518e-10 1 -3.38951e-09 8.28894e-10 -2.0518e-10 4056.64 -18.9584 481.184 3989.72 -57.7136 3833.39 +EDGE_SE3:QUAT 742 792 2.51863 -0.0180986 -5.68401 -0.0555652 0.0859584 0.266546 0.958372 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4146.33 37.6853 812.362 3968.83 110.279 3874.5 +EDGE_SE3:QUAT 741 792 2.17958 11.9942 -5.71428 -0.00665076 -0.0164241 -0.00429294 0.999834 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.16 0.412118 -131.848 3998.91 0.240765 4004.27 +EDGE_SE3:QUAT 742 791 1.96886 -11.437 -5.7667 -0.104682 0.115858 -0.0370544 0.987039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4148.2 -63.5054 897.687 3959.58 -50.6257 4186.54 +EDGE_SE3:QUAT 743 793 2.14659 -0.0558013 -5.7093 -0.107243 -0.0289596 -0.0853917 0.990136 1 1.92593e-19 1.92593e-19 -2.75789e-08 2.15723e-09 1.28291e-09 1 1.92593e-19 -2.75789e-08 2.15723e-09 1.28291e-09 1 -2.75789e-08 2.15723e-09 1.28291e-09 3981.8 16.9721 -336.088 3991.88 12.0635 3998.63 +EDGE_SE3:QUAT 742 793 1.59421 11.7676 -5.93446 -0.0718468 -0.091201 -0.149747 0.981884 1 4.81482e-20 4.81482e-20 1.39332e-08 -1.95689e-09 -1.52955e-09 1 4.81482e-20 1.39332e-08 -1.95689e-09 -1.52955e-09 1 1.39332e-08 -1.95689e-09 -1.52955e-09 4156.95 -3.5879 -861.669 3956.87 55.1253 4087.9 +EDGE_SE3:QUAT 743 792 1.4099 -11.6976 -5.42029 -0.0358335 -0.0993534 -0.161754 0.981163 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4173.81 -26.519 -864.749 3959.84 69.1647 4074.28 +EDGE_SE3:QUAT 744 794 2.09753 -0.140857 -5.72167 0.00635979 -0.0115748 -0.11181 0.993642 1 7.52316e-22 7.52316e-22 1.72406e-09 -1.94288e-10 -1.71266e-11 1 7.52316e-22 1.72406e-09 -1.94288e-10 -1.71266e-11 1 1.72406e-09 -1.94288e-10 -1.71266e-11 4001.53 -0.553959 -82.4273 3999.63 4.43926 3951.69 +EDGE_SE3:QUAT 743 794 1.8954 11.7153 -6.39087 -0.18607 -0.0808371 0.0526177 0.977791 1 7.70372e-19 7.70372e-19 5.47062e-08 4.43657e-09 -3.08957e-09 1 7.70372e-19 5.47062e-08 4.43657e-09 -3.08957e-09 1 5.47062e-08 4.43657e-09 -3.08957e-09 3922.29 49.9323 -500.612 3991.32 -32.7003 4049.7 +EDGE_SE3:QUAT 744 793 1.98379 -11.4005 -5.5896 0.192861 -0.00473871 -0.0540949 0.979722 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3852.68 12.3438 86.2219 3998.99 -3.23644 3989.76 +EDGE_SE3:QUAT 745 795 2.60235 -0.208327 -5.77532 -0.19706 0.0524833 0.0251867 0.978662 1 5.11575e-20 5.11575e-20 -2.44715e-10 1.42686e-08 -7.0564e-10 1 5.11575e-20 -2.44715e-10 1.42686e-08 -7.0564e-10 1 -2.44715e-10 1.42686e-08 -7.0564e-10 3896.62 -45.8877 458.817 3988.45 -9.13068 4049.41 +EDGE_SE3:QUAT 744 795 2.07762 11.432 -5.91377 -0.14506 0.0443307 0.167096 0.974203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.15 -33.4757 625.773 3971.91 44.3355 3982.63 +EDGE_SE3:QUAT 745 794 1.73348 -11.7128 -5.65995 -0.0313192 -0.116364 -0.143732 0.982252 1 3.00927e-21 3.00927e-21 -3.51011e-09 5.01144e-10 4.30286e-10 1 3.00927e-21 -3.51011e-09 5.01144e-10 4.30286e-10 1 -3.51011e-09 5.01144e-10 4.30286e-10 4234.58 -34.489 -1005.44 3946.66 72.3426 4155.87 +EDGE_SE3:QUAT 746 796 2.27331 0.174067 -5.14548 0.144953 -0.0296853 -0.105676 0.983331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3915.43 1.09123 -46.0244 4000.08 -0.607915 3954.81 +EDGE_SE3:QUAT 745 796 2.29014 11.4203 -6.00945 -0.0776993 0.138084 -0.0454476 0.986321 1 4.81482e-20 4.81482e-20 1.84542e-09 -1.33997e-09 1.41776e-08 1 4.81482e-20 1.84542e-09 -1.33997e-09 1.41776e-08 1 1.84542e-09 -1.33997e-09 1.41776e-08 4264.21 -71.8028 1112.31 3938.3 -65.5778 4280.1 +EDGE_SE3:QUAT 746 795 1.81766 -11.2139 -5.7554 0.0719472 -0.0960004 0.0278991 0.992386 1 3.85186e-19 3.85186e-19 2.84824e-08 -2.71513e-08 -9.18021e-10 1 3.85186e-19 2.84824e-08 -2.71513e-08 -9.18021e-10 1 2.84824e-08 -2.71513e-08 -9.18021e-10 4138.21 -25.6868 -812.975 3961.58 4.76242 4155.8 +EDGE_SE3:QUAT 747 797 2.74455 0.148913 -5.55591 0.0602141 0.0949396 -0.025348 0.993337 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4139.31 20.6454 799.321 3962.68 2.8673 4151.24 +EDGE_SE3:QUAT 746 797 2.01996 11.4396 -5.88769 0.0331662 -0.0958384 0.166485 0.980815 1 9.62965e-19 9.62965e-19 1.21633e-09 2.7237e-08 -5.55904e-08 1 9.62965e-19 1.21633e-09 2.7237e-08 -5.55904e-08 1 1.21633e-09 2.7237e-08 -5.55904e-08 4160.62 26.4073 -829.035 3963.25 -68.9081 4054.15 +EDGE_SE3:QUAT 747 796 1.81635 -11.5545 -5.63792 -0.0910917 0.0790464 0.0118539 0.99263 1 3.85186e-19 3.85186e-19 2.78341e-08 -2.7628e-08 -2.62027e-10 1 3.85186e-19 2.78341e-08 -2.7628e-08 -2.62027e-10 1 2.78341e-08 -2.7628e-08 -2.62027e-10 4070.36 -29.8979 651.856 3975.32 -10.1921 4102.99 +EDGE_SE3:QUAT 748 798 2.59829 -0.357666 -5.85358 0.182653 -0.152733 0.102507 0.965817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4384.52 -105.112 -1530.01 3885.82 40.4107 4475.93 +EDGE_SE3:QUAT 747 798 1.54449 11.9331 -5.83732 -0.0507854 -0.0315065 -0.150176 0.986851 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.41 3.62466 -334.942 3992.44 25.6552 3937.51 +EDGE_SE3:QUAT 748 797 1.53106 -11.7781 -5.52724 0.00451961 0.0929102 -0.0167018 0.995524 1 1.88079e-22 1.88079e-22 -8.78678e-10 1.42492e-11 -8.20914e-11 1 1.88079e-22 -8.78678e-10 1.42492e-11 -8.20914e-11 1 -8.78678e-10 1.42492e-11 -8.20914e-11 4141.93 -1.72222 766.944 3965.43 -6.01407 4140.89 +EDGE_SE3:QUAT 749 799 2.06241 -0.122672 -5.50177 -0.118555 0.0476091 -0.0520013 0.990441 1 4.81482e-20 4.81482e-20 -4.69244e-10 1.71597e-09 -1.37836e-08 1 4.81482e-20 -4.69244e-10 1.71597e-09 -1.37836e-08 1 -4.69244e-10 1.71597e-09 -1.37836e-08 3965.8 -18.3826 299.191 3995.97 -11.7055 4011.21 +EDGE_SE3:QUAT 748 799 1.75148 11.5568 -5.81746 0.00416649 0.109686 0.196458 0.974349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4171.54 56.5293 846.942 3968.71 92.5379 4017.22 +EDGE_SE3:QUAT 749 798 1.88985 -11.523 -5.93972 0.0444032 0.0950442 -0.0653655 0.992332 1 4.81482e-20 4.81482e-20 -1.40459e-08 8.18248e-10 -1.41202e-09 1 4.81482e-20 -1.40459e-08 8.18248e-10 -1.41202e-09 1 -1.40459e-08 8.18248e-10 -1.41202e-09 4152.3 4.38167 816.362 3960.85 -18.955 4143.09 +EDGE_SE3:QUAT 750 800 2.5685 0.165275 -5.87034 0.0443 -0.0368283 -0.0463952 0.997261 1 4.81482e-20 4.81482e-20 1.3871e-08 -6.89811e-10 -4.50781e-10 1 4.81482e-20 1.3871e-08 -6.89811e-10 -4.50781e-10 1 1.3871e-08 -6.89811e-10 -4.50781e-10 4010.16 -7.15929 -269.179 3995.89 7.3762 4009.4 +EDGE_SE3:QUAT 749 800 1.67266 11.7019 -5.80112 0.0529732 0.168772 -0.102772 0.97885 1 8.1852e-19 8.1852e-19 -1.94721e-08 -5.30761e-08 -1.53947e-09 1 8.1852e-19 -1.94721e-08 -5.30761e-08 -1.53947e-09 1 -1.94721e-08 -5.30761e-08 -1.53947e-09 4521.43 -31.4092 1553.82 3880.76 -61.8968 4490.4 +EDGE_SE3:QUAT 750 799 1.94479 -11.7381 -5.61135 -0.0815502 0.11785 -0.233365 0.96177 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4070.29 -70.0888 643.24 3995.12 -86.0536 3879.06 +EDGE_SE3:QUAT 751 801 2.55305 -0.0708289 -5.50653 -0.000124925 -0.0790435 -0.0339869 0.996292 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4101.53 -5.19991 -645.3 3975.24 11.6637 4096.91 +EDGE_SE3:QUAT 750 801 1.73219 11.7594 -6.0365 0.057485 0.002448 0.191182 0.979867 1 4.81482e-20 4.81482e-20 1.3603e-08 2.64025e-09 -2.6771e-10 1 4.81482e-20 1.3603e-08 2.64025e-09 -2.6771e-10 1 1.3603e-08 2.64025e-09 -2.6771e-10 3989.38 -3.96318 -110.022 3998.56 -14.6173 3856.4 +EDGE_SE3:QUAT 751 800 1.35299 -11.5826 -5.56736 -0.0645269 -0.0526007 -0.156419 0.984176 1 4.81482e-20 4.81482e-20 -1.37788e-08 2.09199e-09 9.74774e-10 1 4.81482e-20 -1.37788e-08 2.09199e-09 9.74774e-10 1 -1.37788e-08 2.09199e-09 9.74774e-10 4052.37 3.72531 -530.672 3982.09 39.5639 3971.16 +EDGE_SE3:QUAT 752 802 2.38945 -0.130865 -5.97142 0.0730419 0.196697 -0.0305198 0.977263 1 1.20371e-20 1.20371e-20 1.49912e-09 5.00111e-10 7.36415e-09 1 1.20371e-20 1.49912e-09 5.00111e-10 7.36415e-09 1 1.49912e-09 5.00111e-10 7.36415e-09 4692.03 60.6862 1833.68 3844.68 44.1253 4709.65 +EDGE_SE3:QUAT 751 802 1.75063 11.3832 -5.7898 -0.0910136 0.0892759 0.147086 0.980873 1 7.70372e-19 7.70372e-19 -6.29471e-09 3.54835e-09 -5.57204e-08 1 7.70372e-19 -6.29471e-09 3.54835e-09 -5.57204e-08 1 -6.29471e-09 3.54835e-09 -5.57204e-08 4150.72 -7.0303 877.673 3954.27 50.3983 4097.32 +EDGE_SE3:QUAT 752 801 1.50133 -11.7329 -5.63268 0.00496824 -0.0252188 -0.0156062 0.999548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.99 -0.739345 -201.18 3997.49 1.65311 4009.12 +EDGE_SE3:QUAT 753 803 2.58329 0.0600163 -5.54663 -0.0163316 0.0672452 0.179435 0.981333 1 3.00927e-21 3.00927e-21 3.43784e-09 6.26636e-10 2.40571e-10 1 3.00927e-21 3.43784e-09 6.26636e-10 2.40571e-10 1 3.43784e-09 6.26636e-10 2.40571e-10 4074.7 15.9773 555.737 3983.62 50.7405 3946.98 +EDGE_SE3:QUAT 752 803 1.62183 11.6271 -6.17907 0.0974233 0.0399689 -0.101571 0.989239 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008 17.0039 432.47 3987.13 -18.2582 4004.7 +EDGE_SE3:QUAT 753 802 1.43815 -11.9758 -5.61976 0.0267171 0.102668 -0.192496 0.975546 1 7.73381e-19 7.73381e-19 9.43357e-09 -1.48135e-09 5.57842e-08 1 7.73381e-19 9.43357e-09 -1.48135e-09 5.57842e-08 1 9.43357e-09 -1.48135e-09 5.57842e-08 4178.02 -40.8513 869.683 3962.6 -86.6861 4032.66 +EDGE_SE3:QUAT 754 804 2.25405 0.160099 -5.82355 -0.00191704 -0.115079 0.00457678 0.993344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4220.53 2.60684 -964.789 3947.06 -3.16848 4220.46 +EDGE_SE3:QUAT 753 804 1.79049 11.6856 -5.79673 -0.150012 0.0206401 0.0680284 0.986125 1 1.92593e-19 1.92593e-19 -1.10406e-09 4.06345e-09 -2.74379e-08 1 1.92593e-19 -1.10406e-09 4.06345e-09 -2.74379e-08 1 -1.10406e-09 4.06345e-09 -2.74379e-08 3929.21 -22.4216 280.114 3994.07 7.23804 4000.72 +EDGE_SE3:QUAT 754 803 1.77134 -11.5524 -5.61189 -0.00661948 0.238225 -0.135109 0.961744 1 8.1852e-19 8.1852e-19 -6.33525e-09 5.56399e-08 7.4136e-10 1 8.1852e-19 -6.33525e-09 5.56399e-08 7.4136e-10 1 -6.33525e-09 5.56399e-08 7.4136e-10 4997.49 -244.157 2233.44 3827.95 -254.427 4924.65 +EDGE_SE3:QUAT 755 805 2.40832 0.126633 -5.69928 0.00129311 -0.0703428 -0.217395 0.973545 1 7.82409e-19 7.82409e-19 1.0348e-08 -3.28875e-09 -5.4966e-08 1 7.82409e-19 1.0348e-08 -3.28875e-09 -5.4966e-08 1 1.0348e-08 -3.28875e-09 -5.4966e-08 4068.2 -24.2319 -527.466 3987.84 58.7348 3879.16 +EDGE_SE3:QUAT 754 805 1.81421 11.6623 -6.20333 0.071871 0.0738701 -0.177086 0.978784 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4108.4 -3.14332 730.546 3968.24 -59.795 4003.62 +EDGE_SE3:QUAT 755 804 1.4964 -11.5818 -5.63898 -0.0709103 -0.260983 0.0875557 0.958746 1 1.92593e-19 1.92593e-19 3.02891e-08 4.4506e-09 -7.53783e-09 1 1.92593e-19 3.02891e-08 4.4506e-09 -7.53783e-09 1 3.02891e-08 4.4506e-09 -7.53783e-09 5136.95 328.738 -2443.84 3820.93 -329.26 5126.4 +EDGE_SE3:QUAT 756 806 2.41008 0.167395 -5.80101 -0.1871 -0.0514833 0.00876632 0.980952 1 7.70372e-19 7.70372e-19 -5.46968e-08 -1.51609e-09 2.48734e-09 1 7.70372e-19 -5.46968e-08 -1.51609e-09 2.48734e-09 1 -5.46968e-08 -1.51609e-09 2.48734e-09 3894.49 35.0407 -373.739 3993.45 -12.038 4034.21 +EDGE_SE3:QUAT 755 806 1.29337 12.0272 -5.31169 -0.0367008 0.205753 0.10819 0.971912 1 1.20371e-20 1.20371e-20 7.39139e-09 7.7594e-10 1.58717e-09 1 1.20371e-20 7.39139e-09 7.7594e-10 1.58717e-09 1 7.39139e-09 7.7594e-10 1.58717e-09 4789.67 87.4249 1952.53 3833.91 108.63 4748.24 +EDGE_SE3:QUAT 756 805 1.39994 -11.6596 -5.68964 -0.0713983 0.0851866 0.0297557 0.993358 1 1.20371e-20 1.20371e-20 6.23503e-10 -4.73867e-10 7.00098e-09 1 1.20371e-20 6.23503e-10 -4.73867e-10 7.00098e-09 1 6.23503e-10 -4.73867e-10 7.00098e-09 4105.44 -22.3703 720.538 3969.28 -1.85908 4122.29 +EDGE_SE3:QUAT 757 807 2.44129 0.00481663 -5.71069 0.0261282 0.0287132 -0.00775131 0.999216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.75 2.91807 232.568 3996.63 -0.385099 4013.24 +EDGE_SE3:QUAT 756 807 1.31969 11.5155 -5.73584 0.125179 -0.149456 0.0909692 0.976585 1 9.62965e-19 9.62965e-19 3.16524e-08 -5.27735e-08 7.83423e-10 1 9.62965e-19 3.16524e-08 -5.27735e-08 7.83423e-10 1 3.16524e-08 -5.27735e-08 7.83423e-10 4392.42 -51.7121 -1424.07 3895.21 3.67494 4422 +EDGE_SE3:QUAT 757 806 1.95431 -11.6984 -6.04675 -0.0446585 -0.0689347 -0.00895979 0.996581 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4070.04 12.199 -564.069 3980.85 -2.60555 4077.7 +EDGE_SE3:QUAT 758 808 2.44909 0.180557 -5.76924 -0.0435093 -0.0348338 -0.0340125 0.997866 1 9.62965e-20 9.62965e-20 1.44091e-08 1.42093e-10 -1.44091e-08 1 9.62965e-20 1.44091e-08 1.42093e-10 -1.44091e-08 1 1.44091e-08 1.42093e-10 -1.44091e-08 4014.29 5.56794 -296.592 3994.4 3.80913 4017.24 +EDGE_SE3:QUAT 757 808 1.17139 11.2512 -5.90095 0.0483422 0.0140353 0.0978724 0.993925 1 4.81482e-20 4.81482e-20 -1.37946e-08 -1.37109e-09 -5.95566e-11 1 4.81482e-20 -1.37946e-08 -1.37109e-09 -5.95566e-11 1 -1.37946e-08 -1.37109e-09 -5.95566e-11 3991.28 0.994645 53.9436 3999.94 1.76376 3962.31 +EDGE_SE3:QUAT 758 807 1.52265 -11.5385 -5.87227 -0.0163557 0.0596516 -0.0181866 0.99792 1 1.20371e-20 1.20371e-20 6.97328e-09 -1.41626e-10 4.1214e-10 1 1.20371e-20 6.97328e-09 -1.41626e-10 4.1214e-10 1 6.97328e-09 -1.41626e-10 4.1214e-10 4055.5 -5.6116 479.03 3986.13 -5.90817 4055.24 +EDGE_SE3:QUAT 759 809 2.57903 -0.172527 -5.81956 0.142397 0.0880733 0.0466261 0.98478 1 7.70372e-19 7.70372e-19 -5.53022e-08 -3.956e-09 -3.96963e-09 1 7.70372e-19 -5.53022e-08 -3.956e-09 -3.96963e-09 1 -5.53022e-08 -3.956e-09 -3.96963e-09 4010.19 51.284 612.651 3983.02 36.1126 4082.6 +EDGE_SE3:QUAT 758 809 1.89875 11.7056 -6.24572 0.140846 -0.0944024 0.185906 0.967827 1 7.70372e-19 7.70372e-19 -7.8227e-09 5.70779e-09 5.55643e-08 1 7.70372e-19 -7.8227e-09 5.70779e-09 5.55643e-08 1 -7.8227e-09 5.70779e-09 5.55643e-08 4185.95 -22.1685 -1065.61 3933.08 -68.412 4127.05 +EDGE_SE3:QUAT 759 808 1.57117 -11.7847 -5.69801 -0.00506498 -0.00205694 -0.0931431 0.995638 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.02 0.0450061 -21.8702 3999.97 1.10231 3965.42 +EDGE_SE3:QUAT 760 810 2.25479 -0.0459942 -5.77745 -0.185059 0.0800941 0.0975795 0.974585 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.6 -67.4468 844.552 3957.24 3.25901 4132.5 +EDGE_SE3:QUAT 759 810 1.77348 11.7699 -5.93487 0.106755 0.0942576 0.103566 0.984374 1 1.92593e-19 1.92593e-19 -1.90057e-09 -3.52714e-09 -2.76325e-08 1 1.92593e-19 -1.90057e-09 -3.52714e-09 -2.76325e-08 1 -1.90057e-09 -3.52714e-09 -2.76325e-08 4043.56 48.0363 606.886 3985.12 47.5772 4046.24 +EDGE_SE3:QUAT 760 809 1.60393 -11.4391 -5.58621 0.0612648 -0.127907 -0.0833778 0.986374 1 9.62965e-19 9.62965e-19 5.30682e-08 -3.38976e-09 2.16292e-08 1 9.62965e-19 5.30682e-08 -3.38976e-09 2.16292e-08 1 5.30682e-08 -3.38976e-09 2.16292e-08 4216.58 -65.6001 -990.528 3952.04 69.7532 4203.78 +EDGE_SE3:QUAT 761 811 2.39719 0.0260259 -5.99646 -0.0357093 -0.0329762 -0.0222019 0.998571 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.55 4.3846 -273.754 3995.28 2.12036 4016.67 +EDGE_SE3:QUAT 760 811 1.70979 11.6433 -5.86348 0.222578 -0.0817031 0.159798 0.958253 1 7.70372e-19 7.70372e-19 5.50137e-08 6.38826e-09 -7.99226e-09 1 7.70372e-19 5.50137e-08 6.38826e-09 -7.99226e-09 1 5.50137e-08 6.38826e-09 -7.99226e-09 4061.77 -89.4344 -1055.78 3932.13 -25.908 4157.8 +EDGE_SE3:QUAT 761 810 1.54001 -11.7572 -5.66693 0.00130195 0.0387008 0.0345799 0.998651 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.89 1.45067 310.12 3994.1 5.48674 4019.12 +EDGE_SE3:QUAT 762 812 2.44749 -0.104984 -5.48373 0.0329229 -0.0142306 -0.130797 0.99076 1 5.11575e-20 5.11575e-20 -1.32949e-08 5.2619e-09 -5.13013e-11 1 5.11575e-20 -1.32949e-08 5.2619e-09 -5.13013e-11 1 -1.32949e-08 5.2619e-09 -5.13013e-11 3996.47 -0.934903 -59.695 3999.92 2.77649 3932.37 +EDGE_SE3:QUAT 761 812 1.38703 11.6807 -5.84009 -0.204434 0.0626477 0.151449 0.965062 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.74 -70.5488 845.863 3952.74 31.4572 4078.17 +EDGE_SE3:QUAT 762 811 1.18845 -12.0666 -5.1901 -0.0554159 0.0788911 -0.0962931 0.990673 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.58 -28.008 564.277 3983.92 -34.5142 4040.78 +EDGE_SE3:QUAT 763 813 2.49868 -0.0165975 -6.07284 -0.117736 0.129018 0.0777681 0.981552 1 3.85186e-19 3.85186e-19 3.24851e-08 -1.52295e-09 3.24851e-08 1 3.85186e-19 3.24851e-08 -1.52295e-09 3.24851e-08 1 3.24851e-08 -1.52295e-09 3.24851e-08 4274.29 -47.0596 1195.01 3922.21 -2.07921 4305.55 +EDGE_SE3:QUAT 762 813 1.90256 11.7355 -5.92229 0.0790653 0.143396 0.00909841 0.98646 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4312.36 62.793 1209.72 3924.55 48.7259 4337.04 +EDGE_SE3:QUAT 763 812 1.78445 -11.9693 -5.64561 0.19563 -0.0390951 -0.178692 0.963467 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3845.5 26.62 119.694 3995.42 -24.3353 3870.86 +EDGE_SE3:QUAT 764 814 2.34598 -0.176466 -5.6545 -0.0529063 0.0479201 -0.008197 0.997415 1 3.00927e-21 3.00927e-21 1.63001e-10 -1.87936e-10 3.47592e-09 1 3.00927e-21 1.63001e-10 -1.87936e-10 3.47592e-09 1 1.63001e-10 -1.87936e-10 3.47592e-09 4024.47 -10.659 379.417 3991.36 -4.45254 4035.4 +EDGE_SE3:QUAT 763 814 1.5426 11.4844 -5.62282 -0.0212678 0.0572688 0.178744 0.981997 1 3.00927e-21 3.00927e-21 -3.43262e-09 -6.20224e-10 -2.13493e-10 1 3.00927e-21 -3.43262e-09 -6.20224e-10 -2.13493e-10 1 -3.43262e-09 -6.20224e-10 -2.13493e-10 4056.68 10.2499 487.197 3986.92 44.0134 3930.69 +EDGE_SE3:QUAT 764 813 1.70015 -11.7223 -5.53829 -0.0602967 -0.0934375 0.0231639 0.993528 1 2.0463e-19 2.0463e-19 2.74058e-08 5.18531e-10 4.47564e-09 1 2.0463e-19 2.74058e-08 5.18531e-10 4.47564e-09 1 2.74058e-08 5.18531e-10 4.47564e-09 4120.4 29.1642 -747.034 3968.53 -21.9415 4132.8 +EDGE_SE3:QUAT 765 815 2.47864 0.0737237 -5.8809 0.0137002 -0.16856 -0.0784014 0.982473 1 1.20371e-20 1.20371e-20 -7.21349e-09 6.45161e-10 1.20408e-09 1 1.20371e-20 -7.21349e-09 6.45161e-10 1.20408e-09 1 -7.21349e-09 6.45161e-10 1.20408e-09 4474.14 -72.611 -1457.83 3897.19 84.4811 4450.3 +EDGE_SE3:QUAT 764 815 1.0804 11.8655 -6.09029 0.188386 0.0507072 0.122679 0.973082 1 1.55278e-18 1.55278e-18 -5.31159e-08 -2.49666e-08 -5.26833e-08 1 1.55278e-18 -5.31159e-08 -2.49666e-08 -5.26833e-08 1 -5.31159e-08 -2.49666e-08 -5.26833e-08 3858.18 1.69303 106.269 4000.61 2.27592 3939.94 +EDGE_SE3:QUAT 765 814 1.53321 -11.6295 -5.87862 0.158692 -0.0421119 -0.141265 0.976262 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3897.63 2.88541 -52.8145 4000.15 -2.41621 3918.54 +EDGE_SE3:QUAT 766 816 2.40032 -0.19557 -5.96365 0.107113 -0.00286406 -0.119577 0.987026 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3957.67 9.27624 129.136 3998 -10.4448 3946.37 +EDGE_SE3:QUAT 765 816 1.51243 11.649 -5.79673 0.0555557 -0.0582788 -0.0662707 0.994548 1 1.92593e-19 1.92593e-19 -1.39557e-09 1.76243e-09 2.77557e-08 1 1.92593e-19 -1.39557e-09 1.76243e-09 2.77557e-08 1 -1.39557e-09 1.76243e-09 2.77557e-08 4031.32 -16.2199 -420.611 3990.45 17.7082 4026.1 +EDGE_SE3:QUAT 766 815 1.96844 -11.9448 -5.95719 0.0521184 -0.0888274 0.0781406 0.991608 1 4.81482e-20 4.81482e-20 1.401e-08 9.84556e-10 -1.34945e-09 1 4.81482e-20 1.401e-08 9.84556e-10 -1.34945e-09 1 1.401e-08 9.84556e-10 -1.34945e-09 4133.88 -5.45397 -774.617 3964.35 -22.2385 4120.32 +EDGE_SE3:QUAT 767 817 2.17937 -0.070737 -6.07539 -0.00289905 -0.0536309 0.0573229 0.99691 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.49 4.59731 -429.144 3988.95 -12.8303 4032.38 +EDGE_SE3:QUAT 766 817 1.90142 11.7344 -5.92335 0.0137913 -0.0191295 0.0440193 0.998752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.63 -0.708797 -160.054 3998.37 -3.45689 3998.64 +EDGE_SE3:QUAT 767 816 1.52612 -11.5717 -5.33568 0.127608 -0.0763388 -0.193192 0.969827 1 7.70372e-19 7.70372e-19 1.09012e-09 -8.22309e-09 -5.39439e-08 1 7.70372e-19 1.09012e-09 -8.22309e-09 -5.39439e-08 1 1.09012e-09 -8.22309e-09 -5.39439e-08 3949.94 -19.516 -274.608 4001.01 21.9414 3865.78 +EDGE_SE3:QUAT 768 818 2.20766 0.0251924 -6.22985 -0.0583384 -0.00790181 0.047143 0.997152 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.58 0.567692 -29.8003 3999.98 -0.46918 3991.3 +EDGE_SE3:QUAT 767 818 1.74375 11.8117 -6.04436 -0.0664439 -0.159859 0.0321327 0.984377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4396.72 77.8468 -1352.61 3910.04 -71.3967 4410.25 +EDGE_SE3:QUAT 768 817 1.80197 -11.5443 -5.79446 -0.0305651 -0.0696062 -0.156046 0.98482 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4085.59 -10.8688 -604.412 3979.19 46.6943 3991.93 +EDGE_SE3:QUAT 769 819 2.08082 0.105768 -5.63476 0.194338 0.119828 -0.00402681 0.97358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.57 104.056 956.363 3959.51 65.502 4216.57 +EDGE_SE3:QUAT 768 819 1.91644 11.8503 -6.04171 -0.133474 0.013516 0.0772903 0.987941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3941.23 -16.7129 226.88 3995.76 8.32816 3988.59 +EDGE_SE3:QUAT 769 818 1.81251 -11.6044 -5.80306 -0.11219 -0.0811725 -0.0794598 0.987173 1 3.85186e-19 3.85186e-19 2.95604e-08 2.5732e-08 5.26506e-11 1 3.85186e-19 2.95604e-08 2.5732e-08 5.26506e-11 1 2.95604e-08 2.5732e-08 5.26506e-11 4089.54 31.7539 -761.369 3964.78 11.1105 4114.63 +EDGE_SE3:QUAT 770 820 2.49229 -0.314481 -5.9673 0.163018 -0.253039 0.0156726 0.953494 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5075.11 -313.48 -2474.68 3810.48 304.319 5180.43 +EDGE_SE3:QUAT 769 820 1.65128 11.9106 -6.15594 0.139874 0.0505627 0.110267 0.98271 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3930.84 12.2163 203.73 3999.55 10.8595 3960.46 +EDGE_SE3:QUAT 770 819 1.60719 -11.6476 -5.31744 -0.198712 -0.00727466 -0.0244799 0.979725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3845.11 12.8265 -111.638 3999.04 0.833672 4000.66 +EDGE_SE3:QUAT 771 821 2.3121 -0.328605 -6.03869 0.0184711 -0.0149825 0.0624147 0.997767 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.05 -0.87525 -133.032 3998.84 -4.18125 3988.83 +EDGE_SE3:QUAT 770 821 1.79262 11.7301 -6.20805 0.132078 0.0163416 -0.0182388 0.990937 1 7.82409e-19 7.82409e-19 5.49079e-08 -1.65374e-09 -5.7403e-09 1 7.82409e-19 5.49079e-08 -1.65374e-09 -5.7403e-09 1 5.49079e-08 -1.65374e-09 -5.7403e-09 3936.29 10.7452 156.059 3998.41 -0.374563 4004.74 +EDGE_SE3:QUAT 771 820 1.68294 -11.6779 -5.80139 0.0739516 -0.0257859 -0.198814 0.976903 1 1.92593e-19 1.92593e-19 2.71114e-08 -5.5637e-09 1.47029e-10 1 1.92593e-19 2.71114e-08 -5.5637e-09 1.47029e-10 1 2.71114e-08 -5.5637e-09 1.47029e-10 3977.26 1.31147 -21.2445 3999.97 -4.11308 3841.02 +EDGE_SE3:QUAT 772 822 2.54802 -0.0622281 -5.49389 -0.262871 0.0804683 0.117427 0.954272 1 3.27408e-18 3.27408e-18 1.0735e-07 3.37116e-08 2.13051e-08 1 3.27408e-18 1.0735e-07 3.37116e-08 2.13051e-08 1 1.0735e-07 3.37116e-08 2.13051e-08 3945.42 -119.002 969.635 3946.73 -11.9486 4166.67 +EDGE_SE3:QUAT 771 822 1.91708 11.4913 -5.55592 0.00792208 0.112046 -0.0207347 0.993455 1 2.0463e-19 2.0463e-19 2.59103e-10 -2.75505e-08 7.16559e-09 1 2.0463e-19 2.59103e-10 -2.75505e-08 7.16559e-09 1 2.59103e-10 -2.75505e-08 7.16559e-09 4209.11 -2.44533 938.754 3949.66 -8.49222 4207.64 +EDGE_SE3:QUAT 772 821 1.5849 -11.8201 -5.88436 -0.134217 0.129448 -0.0640533 0.98037 1 3.85186e-19 3.85186e-19 -2.77447e-10 3.15229e-08 -2.36569e-08 1 3.85186e-19 -2.77447e-10 3.15229e-08 -2.36569e-08 1 -2.77447e-10 3.15229e-08 -2.36569e-08 4134.78 -91.6099 934.782 3963.37 -79.7449 4190.43 +EDGE_SE3:QUAT 773 823 2.50374 -0.348136 -5.97522 -0.0940819 -0.00234073 -0.231384 0.9683 1 7.70372e-19 7.70372e-19 2.45964e-09 4.61582e-09 -5.38697e-08 1 7.70372e-19 2.45964e-09 4.61582e-09 -5.38697e-08 1 2.45964e-09 4.61582e-09 -5.38697e-08 3981.13 12.6977 -268.535 3992.71 39.5553 3802.38 +EDGE_SE3:QUAT 772 823 1.67532 11.6295 -5.71719 0.140027 0.0976121 -0.105855 0.979622 1 7.70372e-19 7.70372e-19 -5.59111e-08 4.37249e-09 -6.9317e-09 1 7.70372e-19 -5.59111e-08 4.37249e-09 -6.9317e-09 1 -5.59111e-08 4.37249e-09 -6.9317e-09 4143.82 45.7662 969.409 3944.82 -15.2372 4177.43 +EDGE_SE3:QUAT 773 822 1.24275 -11.5245 -5.84488 0.0907592 -0.136197 0.0113174 0.986451 1 9.63012e-19 9.63012e-19 -2.77378e-08 5.51954e-08 -6.9217e-10 1 9.63012e-19 -2.77378e-08 5.51954e-08 -6.9217e-10 1 -2.77378e-08 5.51954e-08 -6.9217e-10 4280.55 -57.7642 -1162.89 3928.73 36.517 4312.99 +EDGE_SE3:QUAT 774 824 2.3674 0.0229818 -5.97558 -0.0567282 -0.119476 0.0424428 0.990306 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4206.63 45.5874 -962.526 3950.57 -42.7261 4212.3 +EDGE_SE3:QUAT 773 824 1.50477 11.737 -5.91779 0.00238194 -0.0975065 0.165955 0.981298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4145.24 36.9542 -776.257 3970.06 -69.5119 4035.1 +EDGE_SE3:QUAT 774 823 1.58839 -11.5748 -5.89363 -0.0671946 0.0231394 0.0766183 0.994525 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.75 -7.3974 244.499 3995.78 8.84098 3991.32 +EDGE_SE3:QUAT 775 825 2.14893 0.121643 -5.92225 0.0882282 0.0107652 0.202594 0.975221 1 1.92593e-19 1.92593e-19 -2.70781e-08 -5.5882e-09 6.98251e-10 1 1.92593e-19 -2.70781e-08 -5.5882e-09 6.98251e-10 1 -2.70781e-08 -5.5882e-09 6.98251e-10 3971.76 -8.40842 -127.698 3997.51 -20.1878 3838.72 +EDGE_SE3:QUAT 774 825 1.65336 11.9725 -5.92099 0.0173138 0.117267 0.129115 0.984519 1 7.70372e-19 7.70372e-19 6.1823e-09 2.72367e-09 5.60517e-08 1 7.70372e-19 6.1823e-09 2.72367e-09 5.60517e-08 1 6.1823e-09 2.72367e-09 5.60517e-08 4202.51 50.8961 925.749 3957.46 72.6283 4137.03 +EDGE_SE3:QUAT 775 824 1.59062 -11.464 -5.74139 -0.00207419 0.0342079 -0.0322508 0.998892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.6 -1.19168 273.538 3995.4 -4.51652 4014.46 +EDGE_SE3:QUAT 776 826 2.48393 0.129155 -5.72089 0.00597973 -0.0989608 0.0271783 0.994702 1 1.92781e-19 1.92781e-19 1.61614e-09 -2.75856e-08 -7.01522e-11 1 1.92781e-19 1.61614e-09 -2.75856e-08 -7.01522e-11 1 1.61614e-09 -2.75856e-08 -7.01522e-11 4161.73 4.00832 -820.78 3960.8 -10.8403 4158.91 +EDGE_SE3:QUAT 775 826 1.58865 11.8222 -6.24752 -0.26907 -0.00715669 0.0561773 0.961454 1 3.0845e-18 3.0845e-18 -1.06964e-07 -2.40992e-09 -1.62281e-09 1 3.0845e-18 -1.06964e-07 -2.40992e-09 -1.62281e-09 1 -1.06964e-07 -2.40992e-09 -1.62281e-09 3713.32 -24.6195 121.443 3997.97 4.48151 3990.29 +EDGE_SE3:QUAT 776 825 1.37535 -11.9555 -5.47574 -0.0117965 0.116892 -0.174331 0.977653 1 2.40741e-19 2.40741e-19 8.86326e-09 -2.96849e-08 4.80613e-11 1 2.40741e-19 8.86326e-09 -2.96849e-08 4.80613e-11 1 8.86326e-09 -2.96849e-08 4.80613e-11 4193.69 -60.7865 903.422 3963.29 -91.3207 4072.68 +EDGE_SE3:QUAT 777 827 2.37021 0.0116916 -5.70271 -0.0493136 0.05356 -0.168665 0.982981 1 8.66668e-19 8.66668e-19 1.31519e-08 -1.96456e-08 5.43075e-08 1 8.66668e-19 1.31519e-08 -1.96456e-08 5.43075e-08 1 1.31519e-08 -1.96456e-08 5.43075e-08 4013.95 -14.1803 311.911 3996.54 -25.6296 3909.89 +EDGE_SE3:QUAT 776 827 1.90629 11.6566 -5.84531 0.0290039 -0.161346 -0.0354047 0.985836 1 4.81482e-20 4.81482e-20 1.44134e-08 -6.87211e-10 -2.31648e-09 1 4.81482e-20 1.44134e-08 -6.87211e-10 -2.31648e-09 1 1.44134e-08 -6.87211e-10 -2.31648e-09 4434.99 -50.3665 -1394.86 3901.46 51.5954 4433.34 +EDGE_SE3:QUAT 777 826 1.60285 -11.4303 -6.1612 -0.00871663 0.020636 -0.0510056 0.998447 1 7.22224e-20 7.22224e-20 6.84969e-09 -7.43467e-09 1.39288e-08 1 7.22224e-20 6.84969e-09 -7.43467e-09 1.39288e-08 1 6.84969e-09 -7.43467e-09 1.39288e-08 4006.03 -1.18246 159.313 3998.48 -4.11377 3995.93 +EDGE_SE3:QUAT 778 828 2.42264 0.207051 -6.18501 0.0143086 0.114288 0.0730863 0.990652 1 1.92593e-19 1.92593e-19 3.15537e-09 8.97411e-10 2.8204e-08 1 1.92593e-19 3.15537e-09 8.97411e-10 2.8204e-08 1 3.15537e-09 8.97411e-10 2.8204e-08 4206.52 31.1388 934.036 3952.42 43.1482 4185.97 +EDGE_SE3:QUAT 777 828 1.44736 11.7415 -6.04197 -0.0211722 0.166424 -0.0215231 0.985592 1 2.40741e-20 2.40741e-20 8.44771e-09 -4.40297e-10 8.44771e-09 1 2.40741e-20 8.44771e-09 -4.40297e-10 8.44771e-09 1 8.44771e-09 -4.40297e-10 8.44771e-09 4474.96 -36.2995 1460.93 3891.85 -36.3662 4474.9 +EDGE_SE3:QUAT 778 827 1.79735 -11.4332 -5.61401 0.0185734 0.0531369 0.0143604 0.998311 1 1.20371e-20 1.20371e-20 -6.96588e-09 -1.14526e-10 -3.66613e-10 1 1.20371e-20 -6.96588e-09 -1.14526e-10 -3.66613e-10 1 -6.96588e-09 -1.14526e-10 -3.66613e-10 4043.41 5.03199 425.646 3988.99 4.39716 4043.97 +EDGE_SE3:QUAT 779 829 2.42243 -0.162708 -5.80949 -0.216402 -0.083188 -0.0709727 0.970161 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.87 85.7831 -824.625 3962.44 -17.7157 4143.04 +EDGE_SE3:QUAT 778 829 1.50781 11.7376 -6.19924 -0.127043 -0.130219 0.00790582 0.98328 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4199.43 81.8253 -1061.2 3944.22 -58.155 4263.74 +EDGE_SE3:QUAT 779 828 1.53938 -12.1376 -5.69669 -0.0368458 0.119859 -0.0878905 0.988206 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4207.53 -49.3957 947.482 3953.85 -59.3566 4182.06 +EDGE_SE3:QUAT 780 830 2.36081 0.238478 -5.71976 -0.0901864 -0.0068943 0.0501152 0.994639 1 1.88079e-22 1.88079e-22 -4.38342e-11 8.62694e-10 7.84283e-11 1 1.88079e-22 -4.38342e-11 8.62694e-10 7.84283e-11 1 -4.38342e-11 8.62694e-10 7.84283e-11 3967.38 -0.807294 -0.421938 3999.98 0.445796 3989.87 +EDGE_SE3:QUAT 779 830 1.53313 12.5 -6.15921 -0.150137 -0.0110797 0.148429 0.977397 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3915.84 -19.3693 176.926 3995.61 19.1315 3917.88 +EDGE_SE3:QUAT 780 829 1.67537 -12.0277 -5.74247 0.0108684 0.0373968 -0.0769027 0.996278 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.12 -0.994609 308.078 3994.17 -11.7378 3999.93 +EDGE_SE3:QUAT 781 831 2.4228 -0.0932454 -5.92796 -0.186898 0.064003 -0.117413 0.973235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3869.47 -14.9467 218.753 4000.63 -12.8173 3954.06 +EDGE_SE3:QUAT 780 831 1.67011 11.9151 -5.79339 -0.0754088 0.101688 0.0689646 0.989554 1 4.81482e-20 4.81482e-20 -1.56552e-09 8.83519e-10 -1.40642e-08 1 4.81482e-20 -1.56552e-09 8.83519e-10 -1.40642e-08 1 -1.56552e-09 8.83519e-10 -1.40642e-08 4170.83 -18.6505 901.08 3952.66 13.4776 4174.55 +EDGE_SE3:QUAT 781 830 1.39228 -11.6033 -5.52574 0.145552 0.126704 -0.0646503 0.979071 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4230.31 72.0419 1166.05 3927.59 23.9609 4298.33 +EDGE_SE3:QUAT 782 832 2.60261 -0.237062 -5.82975 -0.195376 0.0617446 -0.268976 0.941099 1 3.08149e-18 3.08149e-18 5.69462e-09 2.20256e-08 -1.0442e-07 1 3.08149e-18 5.69462e-09 2.20256e-08 -1.0442e-07 1 5.69462e-09 2.20256e-08 -1.0442e-07 3843.02 40.5776 -170.767 3989.53 55.5461 3706.32 +EDGE_SE3:QUAT 781 832 1.42714 11.4816 -5.97775 -0.0360984 -0.0429195 -0.13182 0.989686 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.14 0.270203 -393.761 3990.3 25.6011 3968.85 +EDGE_SE3:QUAT 782 831 1.603 -11.8957 -5.46003 -0.0338219 0.17944 -0.174732 0.967536 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4443.87 -164.557 1414.54 3929.8 -185.009 4326.32 +EDGE_SE3:QUAT 783 833 2.35919 0.0918784 -5.89001 -0.131692 0.013807 0.191635 0.972493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.97 -24.7806 397.537 3985.96 42.3495 3890.44 +EDGE_SE3:QUAT 782 833 1.7013 12.0628 -5.89695 -0.0764338 -0.0573721 0.0674129 0.993137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4014.75 18.8033 -393.145 3992.16 -17.6478 4019.94 +EDGE_SE3:QUAT 783 832 1.47784 -11.9471 -5.80021 0.0356921 -0.130196 -0.188739 0.972704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4204.48 -85.677 -941.72 3966.69 111.309 4067.09 +EDGE_SE3:QUAT 784 834 2.3683 0.134163 -6.02275 -0.00118309 -0.00993369 -0.0909717 0.995803 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.59 -0.170407 -79.7973 3999.61 3.63516 3968.49 +EDGE_SE3:QUAT 783 834 1.71879 11.6144 -5.81653 -0.0664918 -0.0861574 -0.095176 0.989493 1 4.81482e-20 4.81482e-20 -1.3982e-08 1.1918e-09 1.36529e-09 1 4.81482e-20 -1.3982e-08 1.1918e-09 1.36529e-09 1 -1.3982e-08 1.1918e-09 1.36529e-09 4127.55 8.36514 -776.099 3963.92 26.9317 4109 +EDGE_SE3:QUAT 784 833 1.54655 -12.3998 -5.48204 0.00780303 0.120865 -0.153993 0.980621 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4233.51 -52.2743 994.998 3951.1 -85.1647 4138.9 +EDGE_SE3:QUAT 785 835 2.03179 0.209122 -6.04242 -0.0873624 -0.0328582 0.00478164 0.995623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.75 11.2968 -255.754 3996.16 -2.78839 4016.19 +EDGE_SE3:QUAT 784 835 1.52045 11.9397 -5.89851 0.0594863 -0.00997272 0.125312 0.990282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.55 -4.79632 -166.092 3997.71 -11.7709 3943.89 +EDGE_SE3:QUAT 785 834 1.34824 -12.2285 -5.8881 -0.0688587 0.141095 0.0833535 0.984075 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4353.87 -6.74983 1276.91 3912.55 26.5414 4345.05 +EDGE_SE3:QUAT 786 836 1.64362 -0.332636 -5.8636 -0.0538846 -0.0770256 0.0426644 0.994657 1 9.62965e-20 9.62965e-20 1.29481e-08 -1.35563e-10 1.29481e-08 1 9.62965e-20 1.29481e-08 -1.35563e-10 1.29481e-08 1 1.29481e-08 -1.35563e-10 1.29481e-08 4074.95 22.4416 -594.904 3980.06 -20.4801 4079.28 +EDGE_SE3:QUAT 785 836 1.29736 12.0309 -5.86238 0.0475552 -0.0128815 0.163319 0.985342 1 7.70372e-19 7.70372e-19 -1.52564e-09 2.27268e-09 5.47599e-08 1 7.70372e-19 -1.52564e-09 2.27268e-09 5.47599e-08 1 -1.52564e-09 2.27268e-09 5.47599e-08 3999.83 -3.43286 -190.465 3997.17 -17.4997 3902.18 +EDGE_SE3:QUAT 786 835 1.41531 -11.477 -5.6236 0.128122 -0.277212 0.0110315 0.952164 1 1.20371e-20 1.20371e-20 -2.20369e-09 1.18108e-09 7.77653e-09 1 1.20371e-20 -2.20369e-09 1.18108e-09 7.77653e-09 1 -2.20369e-09 1.18108e-09 7.77653e-09 5445.53 -316.364 -2886.16 3749.93 315.67 5510.7 +EDGE_SE3:QUAT 787 837 2.46422 0.00637625 -6.04773 -0.0160745 -0.143783 0.101679 0.984241 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4326.17 64.5144 -1190.09 3929.76 -81.2599 4285.85 +EDGE_SE3:QUAT 786 837 1.27687 12.2369 -6.10165 0.048382 0.0291159 0.127361 0.990248 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.32 4.49071 153.494 3999.16 8.65438 3940.8 +EDGE_SE3:QUAT 787 836 1.52885 -11.537 -5.9884 -0.0380769 0.12975 -0.181793 0.973995 1 3.85186e-19 3.85186e-19 -2.23015e-08 3.25729e-08 -7.0047e-10 1 3.85186e-19 -2.23015e-08 3.25729e-08 -7.0047e-10 1 -2.23015e-08 3.25729e-08 -7.0047e-10 4202.88 -83.9732 939.483 3966.11 -108.146 4076.49 +EDGE_SE3:QUAT 788 838 2.07789 -0.154475 -5.8487 -0.116614 -0.0701747 -0.071281 0.988127 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.79 31.6581 -660.725 3972.98 8.15127 4085.86 +EDGE_SE3:QUAT 787 838 1.55483 11.6564 -6.15823 0.0533491 0.00891973 0.0440586 0.997564 1 4.81482e-20 4.81482e-20 1.38447e-08 6.21237e-10 5.7511e-11 1 4.81482e-20 1.38447e-08 6.21237e-10 5.7511e-11 1 1.38447e-08 6.21237e-10 5.7511e-11 3989.05 0.924685 42.7298 3999.93 0.778948 3992.67 +EDGE_SE3:QUAT 788 837 1.60681 -12.0078 -5.90475 0.0678743 -0.123837 -0.20213 0.969124 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4126.12 -80.4564 -780.516 3983.44 98.8143 3981.12 +EDGE_SE3:QUAT 789 839 2.15298 0.539293 -5.52386 -0.0877614 0.0327699 -0.109695 0.989541 1 1.92593e-19 1.92593e-19 -3.4359e-10 2.58007e-09 -2.74809e-08 1 1.92593e-19 -3.4359e-10 2.58007e-09 -2.74809e-08 1 -3.4359e-10 2.58007e-09 -2.74809e-08 3973.66 -5.54117 140.329 3999.57 -6.40714 3956.34 +EDGE_SE3:QUAT 788 839 1.39882 11.9371 -5.81408 0.171527 0.0973616 0.0277928 0.979963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.12 68.592 703.863 3978.2 44.1009 4116.72 +EDGE_SE3:QUAT 789 838 1.23967 -11.7925 -5.83225 0.0123076 -0.216617 0.00823539 0.976144 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4871.72 -7.43807 -2061.62 3812.17 4.76167 4872.06 +EDGE_SE3:QUAT 790 840 2.32912 0.527668 -6.03383 -0.0590974 -0.0263625 0.0470349 0.996795 1 9.62965e-20 9.62965e-20 -1.35618e-08 1.59887e-10 -1.35618e-08 1 9.62965e-20 -1.35618e-08 1.59887e-10 -1.35618e-08 1 -1.35618e-08 1.59887e-10 -1.35618e-08 3993.73 5.48556 -176.106 3998.37 -4.64106 3998.85 +EDGE_SE3:QUAT 789 840 1.48922 11.8972 -6.06552 0.010292 0.0733218 0.273541 0.959006 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4059.28 30.738 495.173 3993.04 67.4479 3760.41 +EDGE_SE3:QUAT 790 839 1.32456 -12.1635 -5.80748 0.00836888 -0.119845 0.0696742 0.990309 1 1.94251e-19 1.94251e-19 6.05081e-09 4.27604e-10 -2.86213e-08 1 1.94251e-19 6.05081e-09 4.27604e-10 -2.86213e-08 1 6.05081e-09 4.27604e-10 -2.86213e-08 4239.85 20.9731 -1009.05 3943.75 -37.4512 4220.71 +EDGE_SE3:QUAT 791 841 2.34888 -0.310621 -5.69424 -0.0077169 -0.0892312 -0.0950383 0.991436 1 3.85198e-19 3.85198e-19 8.89879e-11 -2.78033e-08 -2.77252e-08 1 3.85198e-19 8.89879e-11 -2.78033e-08 -2.77252e-08 1 8.89879e-11 -2.78033e-08 -2.77252e-08 4129.94 -15.8642 -733.252 3969.47 36.2529 4094.05 +EDGE_SE3:QUAT 790 841 1.57641 11.8203 -5.8448 0.120973 0.0577042 0.211452 0.968155 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3941.9 3.62703 124.814 4000.97 2.73672 3821.6 +EDGE_SE3:QUAT 791 840 1.34437 -12.0743 -5.55303 0.0233468 0.0294835 0.00926034 0.99925 1 1.50463e-20 1.50463e-20 -2.6972e-11 -7.01676e-09 -3.3067e-09 1 1.50463e-20 -2.6972e-11 -7.01676e-09 -3.3067e-09 1 -2.6972e-11 -7.01676e-09 -3.3067e-09 4011.43 2.9326 233.739 3996.64 1.56783 4013.27 +EDGE_SE3:QUAT 792 842 2.2098 -0.146512 -5.95476 0.0978511 0.0273696 0.00422116 0.994816 1 7.52316e-22 7.52316e-22 -4.52011e-11 -1.70628e-10 -1.72815e-09 1 7.52316e-22 -4.52011e-11 -1.70628e-10 -1.72815e-09 1 -4.52011e-11 -1.70628e-10 -1.72815e-09 3972.84 10.3606 211.389 3997.4 2.11705 4011.07 +EDGE_SE3:QUAT 791 842 1.63075 11.714 -6.30528 -0.168668 -0.0384396 0.159167 0.971977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3883.26 -12.1139 27.9397 3998.8 11.4278 3895.72 +EDGE_SE3:QUAT 792 841 1.55811 -11.9718 -5.74498 0.0498667 0.0660276 -0.0291014 0.996146 1 6.01853e-20 6.01853e-20 -1.34735e-08 6.41282e-10 6.01698e-09 1 6.01853e-20 -1.34735e-08 6.41282e-10 6.01698e-09 1 -1.34735e-08 6.41282e-10 6.01698e-09 4064.84 11.2872 552.042 3981.41 -2.90697 4071.4 +EDGE_SE3:QUAT 793 843 2.56501 -0.0345732 -5.48591 0.151815 0.110831 -0.199783 0.961642 1 7.70372e-19 7.70372e-19 -9.15073e-09 -5.82767e-09 -5.58875e-08 1 7.70372e-19 -9.15073e-09 -5.82767e-09 -5.58875e-08 1 -9.15073e-09 -5.82767e-09 -5.58875e-08 4271.36 17.5799 1261.26 3911.53 -81.0797 4203.9 +EDGE_SE3:QUAT 792 843 1.3616 11.8909 -5.84828 0.179342 -0.0205669 0.0784006 0.980442 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3896.53 -31.4715 -321.759 3991.95 -9.20481 4000.6 +EDGE_SE3:QUAT 793 842 1.36567 -11.7213 -6.07679 -0.133834 -0.057118 -0.0502579 0.988079 1 7.70372e-19 7.70372e-19 5.53319e-08 -1.88138e-09 -3.8192e-09 1 7.70372e-19 5.53319e-08 -1.88138e-09 -3.8192e-09 1 5.53319e-08 -1.88138e-09 -3.8192e-09 3997.66 33.4968 -531.344 3982.51 1.08401 4059.2 +EDGE_SE3:QUAT 794 844 2.17973 0.0938333 -5.85486 -0.16027 0.0107023 -0.0456224 0.98596 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3897.03 2.76262 -4.05051 3999.93 0.77848 3991.45 +EDGE_SE3:QUAT 793 844 1.47737 11.8594 -6.07804 0.101186 0.0440967 0.125476 0.985937 1 2.0463e-19 2.0463e-19 2.64781e-08 1.05049e-08 -2.94718e-10 1 2.0463e-19 2.64781e-08 1.05049e-08 -2.94718e-10 1 2.64781e-08 1.05049e-08 -2.94718e-10 3967.14 9.26384 189.145 3999.34 10.4464 3945.12 +EDGE_SE3:QUAT 794 843 1.33187 -12.0261 -5.59918 0.0132961 0.00401653 -0.117818 0.992938 1 1.96355e-19 1.96355e-19 3.45464e-09 9.81447e-10 -2.75582e-08 1 1.96355e-19 3.45464e-09 9.81447e-10 -2.75582e-08 1 3.45464e-09 9.81447e-10 -2.75582e-08 3999.91 0.278721 50.0872 3999.81 -3.29649 3945.09 +EDGE_SE3:QUAT 795 845 1.84578 0.281965 -5.9549 0.0124272 -0.114469 0.0256181 0.993019 1 3.00927e-21 3.00927e-21 -3.5386e-09 -8.3385e-11 4.09573e-10 1 3.00927e-21 -3.5386e-09 -8.3385e-11 4.09573e-10 1 -3.5386e-09 -8.3385e-11 4.09573e-10 4218.98 1.81524 -962.602 3947.28 -9.87581 4216.97 +EDGE_SE3:QUAT 794 845 1.49891 11.9836 -5.86849 0.0726272 0.024129 0.102604 0.991774 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.14 3.06044 99.946 3999.78 3.92977 3960.13 +EDGE_SE3:QUAT 795 844 1.43527 -12.0252 -5.44732 0.13517 -0.0312307 -0.0433152 0.989382 1 4.81482e-20 4.81482e-20 -2.54962e-10 1.91076e-09 1.37432e-08 1 4.81482e-20 -2.54962e-10 1.91076e-09 1.37432e-08 1 -2.54962e-10 1.91076e-09 1.37432e-08 3934.21 -10.6171 -173.134 3998.87 5.05826 3999.79 +EDGE_SE3:QUAT 796 846 2.21174 -0.238025 -5.86286 0.0523709 0.0135045 -0.15482 0.986461 1 6.01853e-20 6.01853e-20 1.47667e-08 4.72592e-09 8.24189e-11 1 6.01853e-20 1.47667e-08 4.72592e-09 8.24189e-11 1 1.47667e-08 4.72592e-09 8.24189e-11 3998.79 4.17416 199.82 3996.87 -17.2934 3913.89 +EDGE_SE3:QUAT 795 846 1.14292 11.8564 -6.21854 0.123359 0.0259438 -0.0595192 0.990236 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3959.94 18.1296 290.283 3994.04 -6.10362 4006.64 +EDGE_SE3:QUAT 796 845 1.62518 -11.9307 -5.54701 0.128517 -0.0927387 0.0295591 0.986919 1 7.82409e-19 7.82409e-19 5.51458e-08 1.17616e-09 1.48267e-09 1 7.82409e-19 5.51458e-08 1.17616e-09 1.48267e-09 1 5.51458e-08 1.17616e-09 1.48267e-09 4085.83 -49.7367 -794.133 3964.58 16.5681 4148.4 +EDGE_SE3:QUAT 797 847 2.33205 0.202569 -5.55038 0.099152 -0.100124 -0.0250889 0.989704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4108.11 -47.8103 -782.207 3967.58 33.6578 4144.92 +EDGE_SE3:QUAT 796 847 0.978012 12.2032 -5.9221 -0.0330522 0.0324568 0.0931521 0.994574 1 1.20371e-20 1.20371e-20 6.91992e-09 6.33321e-10 2.64157e-10 1 1.20371e-20 6.91992e-09 6.33321e-10 2.64157e-10 1 6.91992e-09 6.33321e-10 2.64157e-10 4017.11 -2.2293 294.058 3994.41 13.3678 3986.77 +EDGE_SE3:QUAT 797 846 1.19591 -11.6747 -5.5739 0.000768353 -0.048276 -0.178814 0.982697 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.68 -9.59711 -368.844 3993.12 33.1913 3905.79 +EDGE_SE3:QUAT 798 848 2.02234 0.241322 -5.97983 -0.065987 0.026014 0.141008 0.987464 1 4.81482e-20 4.81482e-20 1.89745e-09 -1.37122e-08 -7.80715e-10 1 4.81482e-20 1.89745e-09 -1.37122e-08 -7.80715e-10 1 1.89745e-09 -1.37122e-08 -7.80715e-10 4006.6 -7.10917 312.388 3992.97 22.648 3944.48 +EDGE_SE3:QUAT 797 848 1.24732 12.0234 -5.89007 0.0542129 -0.0950887 0.0903652 0.989875 1 4.81482e-20 4.81482e-20 1.40261e-08 1.15018e-09 -1.45824e-09 1 4.81482e-20 1.40261e-08 1.15018e-09 -1.45824e-09 1 1.40261e-08 1.15018e-09 -1.45824e-09 4156.51 -2.74489 -837.564 3958.87 -28.8412 4135.6 +EDGE_SE3:QUAT 798 847 1.00762 -12.1205 -5.54527 -0.0538439 0.0698936 -0.0875076 0.992249 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4049.81 -22.1607 500.019 3987.04 -27.2481 4030.78 +EDGE_SE3:QUAT 799 849 2.27211 -0.0690279 -6.16746 -0.0709917 0.0755134 0.146541 0.98376 1 4.81482e-20 4.81482e-20 -1.38729e-08 -1.92192e-09 -1.30184e-09 1 4.81482e-20 -1.38729e-08 -1.92192e-09 -1.30184e-09 1 -1.38729e-08 -1.92192e-09 -1.30184e-09 4106.91 -1.94903 724.621 3968.27 46.5123 4041.17 +EDGE_SE3:QUAT 798 849 1.14729 12.0304 -6.0062 0.0774594 -0.0156544 0.276768 0.957682 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.5 -6.97043 -356.13 3989.87 -58.1478 3724.1 +EDGE_SE3:QUAT 799 848 1.41643 -12.289 -5.77488 0.0385258 -0.0465648 -0.0887788 0.994216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.74 -9.96831 -328.169 3994.28 15.8262 3995.15 +EDGE_SE3:QUAT 800 850 2.00454 0.167117 -5.82902 0.040794 0.0123771 -0.00742623 0.999063 1 1.95602e-19 1.95602e-19 2.77609e-08 3.28868e-09 2.18354e-10 1 1.95602e-19 2.77609e-08 3.28868e-09 2.18354e-10 1 2.77609e-08 3.28868e-09 2.18354e-10 3995.97 2.0874 102.453 3999.33 -0.226935 4002.4 +EDGE_SE3:QUAT 799 850 1.32496 12.1366 -6.06756 0.150822 -0.122921 0.0555483 0.979315 1 8.1852e-19 8.1852e-19 5.44206e-08 3.02257e-09 6.40019e-09 1 8.1852e-19 5.44206e-08 3.02257e-09 6.40019e-09 1 5.44206e-08 3.02257e-09 6.40019e-09 4198.49 -76.1528 -1114.37 3934.17 29.4534 4277.14 +EDGE_SE3:QUAT 800 849 1.56842 -12.2778 -5.73135 0.0392573 -0.0343262 -0.197869 0.97884 1 4.81482e-20 4.81482e-20 -1.35958e-08 2.78155e-09 2.26045e-10 1 4.81482e-20 -1.35958e-08 2.78155e-09 2.26045e-10 1 -1.35958e-08 2.78155e-09 2.26045e-10 4000.43 -5.32888 -167.328 3999.4 13.5777 3849.99 +EDGE_SE3:QUAT 801 851 2.06333 0.0367148 -6.096 -0.0633097 0.0732518 0.0227838 0.995041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4075.36 -17.5 611.512 3977.54 -1.27489 4089.32 +EDGE_SE3:QUAT 800 851 1.29185 12.0528 -5.92395 -0.0514166 0.0350151 0.00661224 0.998041 1 4.81482e-20 4.81482e-20 -1.38855e-08 -4.16132e-11 -4.94008e-10 1 4.81482e-20 -1.38855e-08 -4.16132e-11 -4.94008e-10 1 -1.38855e-08 -4.16132e-11 -4.94008e-10 4009.53 -7.2312 284.323 3995.01 -0.593725 4019.93 +EDGE_SE3:QUAT 801 850 1.31828 -12.0845 -5.59925 0.0306695 0.0473599 -0.266456 0.962194 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4043.46 -11.4468 437.169 3990.56 -60.3059 3763.23 +EDGE_SE3:QUAT 802 852 2.1435 0.0180108 -5.86809 -0.159213 -0.0342311 0.148659 0.975387 1 7.73381e-19 7.73381e-19 5.4655e-08 5.04487e-09 2.85438e-10 1 7.73381e-19 5.4655e-08 5.04487e-09 2.85438e-10 1 5.4655e-08 5.04487e-09 2.85438e-10 3896.29 -9.68472 20.722 3999.14 9.0369 3909.29 +EDGE_SE3:QUAT 801 852 1.74091 12.1224 -6.00259 -0.221851 -0.142818 0.15901 0.951368 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3881.5 86.6297 -605.04 4008.78 -84.1777 3977.24 +EDGE_SE3:QUAT 802 851 1.2143 -12.024 -5.85727 0.0607971 0.104991 -0.0263671 0.992263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4174.02 22.8302 889.32 3954.52 4.29772 4186.03 +EDGE_SE3:QUAT 803 853 2.20796 0.369187 -5.75664 -0.0635337 0.0309712 -0.0538482 0.996044 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.24 -7.02259 204.696 3997.85 -6.26096 3998.79 +EDGE_SE3:QUAT 802 853 1.24814 12.2791 -6.05029 -0.130344 -0.0174373 0.0439852 0.990339 1 4.81482e-20 4.81482e-20 -7.51336e-11 -1.82394e-09 1.37455e-08 1 4.81482e-20 -7.51336e-11 -1.82394e-09 1.37455e-08 1 -7.51336e-11 -1.82394e-09 1.37455e-08 3933.03 2.94535 -67.6032 3999.92 -1.29536 3993.25 +EDGE_SE3:QUAT 803 852 1.1992 -12.2407 -5.99954 0.00590368 0.0911444 -0.23661 0.967302 1 2.0463e-19 2.0463e-19 -1.72074e-10 2.85175e-08 4.40409e-10 1 2.0463e-19 -1.72074e-10 2.85175e-08 4.40409e-10 1 -1.72074e-10 2.85175e-08 4.40409e-10 4119.31 -43.4762 702.375 3979.91 -87.342 3895.51 +EDGE_SE3:QUAT 804 854 2.1329 -0.0738914 -5.97006 -0.0557013 0.00942862 -0.0648471 0.996295 1 4.89006e-20 4.89006e-20 -1.37131e-08 2.63722e-09 6.89005e-11 1 4.89006e-20 -1.37131e-08 2.63722e-09 6.89005e-11 1 -1.37131e-08 2.63722e-09 6.89005e-11 3987.78 -0.507362 31.465 3999.99 -0.578203 3983.37 +EDGE_SE3:QUAT 803 854 1.15625 11.8617 -5.81599 0.0084418 -0.180359 -0.227123 0.956982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4458.13 -187.46 -1432.42 3939.07 218.446 4252.08 +EDGE_SE3:QUAT 804 853 1.18106 -12.3775 -5.77249 0.0114259 -0.0950896 0.0135141 0.995311 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4148.79 -1.85558 -787.112 3963.67 -3.23209 4148.58 +EDGE_SE3:QUAT 805 855 1.71401 0.446181 -5.86788 0.0983598 -0.0394348 0.0215642 0.994135 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.68 -16.366 -338.168 3992.91 0.32289 4026.52 +EDGE_SE3:QUAT 804 855 1.62638 12.0892 -6.13384 -0.0311824 -0.00739805 -0.0512597 0.998171 1 1.50463e-20 1.50463e-20 7.10344e-09 3.11129e-09 3.18833e-11 1 1.50463e-20 7.10344e-09 3.11129e-09 3.18833e-11 1 7.10344e-09 3.11129e-09 3.18833e-11 3997.62 1.21066 -78.0294 3999.56 2.09882 3991 +EDGE_SE3:QUAT 805 854 1.47343 -11.634 -5.60651 0.195162 -0.0434563 0.0194036 0.979616 1 3.00927e-21 3.00927e-21 -1.65767e-10 6.76679e-10 3.41409e-09 1 3.00927e-21 -1.65767e-10 6.76679e-10 3.41409e-09 1 -1.65767e-10 6.76679e-10 3.41409e-09 3882.52 -37.2306 -375.113 3992.26 6.34687 4033.37 +EDGE_SE3:QUAT 806 856 2.23994 -0.22829 -5.82492 -0.0912002 -0.02014 -0.0849496 0.991998 1 2.0463e-19 2.0463e-19 -2.81425e-08 -4.66192e-09 3.69723e-10 1 2.0463e-19 -2.81425e-08 -4.66192e-09 3.69723e-10 1 -2.81425e-08 -4.66192e-09 3.69723e-10 3982.15 11.158 -250.39 3995.29 10.1512 3986.56 +EDGE_SE3:QUAT 805 856 1.62024 12.095 -6.01461 0.0919225 0.0149972 -0.0946254 0.991146 1 2.0463e-19 2.0463e-19 2.81786e-08 4.36847e-09 2.74538e-10 1 2.0463e-19 2.81786e-08 4.36847e-09 2.74538e-10 1 2.81786e-08 4.36847e-09 2.74538e-10 3978.09 10.3456 220.721 3996.11 -10.7312 3976.08 +EDGE_SE3:QUAT 806 855 1.67612 -11.7135 -5.91274 0.171797 0.0842289 -0.0100385 0.981474 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.63 60.9172 680.886 3976.24 26.4078 4112.28 +EDGE_SE3:QUAT 807 857 2.22778 0.359149 -6.03729 0.00681055 -0.0756589 -0.116753 0.990252 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4086.18 -17.7729 -594.198 3980.62 37.2079 4031.84 +EDGE_SE3:QUAT 806 857 1.28982 12.3956 -5.76608 -0.0368374 0.0565999 -0.0411167 0.99687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.72 -11.1717 436.88 3988.87 -11.8106 4040.38 +EDGE_SE3:QUAT 807 856 1.59854 -11.47 -5.78368 0.145772 -0.0603902 0.0511077 0.98615 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.02 -39.0491 -564.352 3980.54 0.723002 4067.57 +EDGE_SE3:QUAT 808 858 1.98922 -0.020912 -6.30046 -0.0287213 0.00659378 0.190939 0.98116 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.87 -1.20409 114.098 3998.95 12.7933 3857.34 +EDGE_SE3:QUAT 807 858 1.17448 11.9385 -5.83215 0.0782866 0.0587039 0.015703 0.995077 1 4.81482e-20 4.81482e-20 -3.44441e-10 1.38069e-08 -1.11871e-09 1 4.81482e-20 -3.44441e-10 1.38069e-08 -1.11871e-09 1 -3.44441e-10 1.38069e-08 -1.11871e-09 4026.65 19.4317 455.333 3988.07 9.8317 4050.18 +EDGE_SE3:QUAT 808 857 1.13797 -12.0216 -5.8006 0.151673 0.00747581 -0.0659059 0.986203 1 1.20371e-20 1.20371e-20 -4.21009e-10 -6.84549e-09 1.03718e-09 1 1.20371e-20 -4.21009e-10 -6.84549e-09 1.03718e-09 1 -4.21009e-10 -6.84549e-09 1.03718e-09 3915.34 15.7529 175.483 3997.25 -5.79914 3989.98 +EDGE_SE3:QUAT 809 859 1.61692 0.0956338 -6.10958 -0.0915901 0.0754397 0.0446739 0.99193 1 4.33334e-19 4.33334e-19 -2.99001e-08 2.78895e-08 -1.38812e-08 1 4.33334e-19 -2.99001e-08 2.78895e-08 -1.38812e-08 1 -2.99001e-08 2.78895e-08 -1.38812e-08 4072.04 -25.7509 658.528 3973.84 1.62953 4097.62 +EDGE_SE3:QUAT 808 859 1.11101 11.9391 -5.74135 0.0715503 -0.025059 0.163994 0.983544 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.38 -7.87203 -331.066 3991.92 -28.5999 3919.28 +EDGE_SE3:QUAT 809 858 1.24131 -11.9188 -5.78102 0.109573 -0.131029 0.00320113 0.985299 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4232.86 -69.3777 -1096.61 3937.84 46.2189 4280.84 +EDGE_SE3:QUAT 810 860 2.03812 -0.720531 -6.17486 0.130645 -0.149621 -0.0191854 0.979886 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4272.86 -107.072 -1217.4 3931.68 86.3205 4339.66 +EDGE_SE3:QUAT 809 860 1.76651 12.057 -6.40334 0.0387686 -0.0983965 0.0726055 0.991738 1 4.81482e-20 4.81482e-20 -1.40556e-08 -9.37365e-10 1.4568e-09 1 4.81482e-20 -1.40556e-08 -9.37365e-10 1.4568e-09 1 -1.40556e-08 -9.37365e-10 1.4568e-09 4164.78 0.449133 -844.015 3958.54 -24.2442 4149.7 +EDGE_SE3:QUAT 810 859 1.37504 -12.3473 -5.6973 -0.208647 0.15565 -0.0639142 0.963408 1 7.70372e-19 7.70372e-19 -5.52434e-08 7.25426e-09 -6.4543e-09 1 7.70372e-19 -5.52434e-08 7.25426e-09 -6.4543e-09 1 -5.52434e-08 7.25426e-09 -6.4543e-09 4078.8 -152.483 1043.87 3972.89 -133.399 4236.59 +EDGE_SE3:QUAT 811 861 1.97991 -0.175036 -5.78845 0.0234278 0.113539 0.0202506 0.993051 1 1.20371e-20 1.20371e-20 -7.99801e-10 -2.04424e-10 -7.07027e-09 1 1.20371e-20 -7.99801e-10 -2.04424e-10 -7.07027e-09 1 -7.99801e-10 -2.04424e-10 -7.07027e-09 4208.78 19.1041 942.573 3949.86 18.4411 4209.34 +EDGE_SE3:QUAT 810 861 1.2824 12.1733 -6.1422 -0.150182 0.276427 -0.133991 0.939723 1 7.70372e-19 7.70372e-19 1.2537e-08 -1.5451e-08 5.81739e-08 1 7.70372e-19 1.2537e-08 -1.5451e-08 5.81739e-08 1 1.2537e-08 -1.5451e-08 5.81739e-08 4817.28 -508.933 2122.77 3979.72 -509.584 4835.68 +EDGE_SE3:QUAT 811 860 1.40591 -11.8703 -6.03762 -0.0128977 -0.0643218 -0.0363836 0.997182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4067.56 -0.183326 -526.853 3983.15 8.70874 4062.93 +EDGE_SE3:QUAT 812 862 2.04622 0.0410481 -6.00411 0.245951 -0.108645 -0.07389 0.960336 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3836.41 -76.2883 -578.813 3996.83 58.813 4056.54 +EDGE_SE3:QUAT 811 862 1.29719 11.9085 -6.00152 -0.0246674 -0.141096 0.106707 0.983919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4302.64 68.9595 -1146.33 3935.86 -84.772 4259.53 +EDGE_SE3:QUAT 812 861 0.92962 -12.1819 -6.02694 0.127721 0.056336 -0.181602 0.973414 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4055.68 23.9542 709.006 3966.23 -55.1221 3989.01 +EDGE_SE3:QUAT 813 863 1.77286 -0.247918 -5.73115 0.0440873 -0.154284 -0.0568797 0.985402 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4372.73 -69.775 -1291.18 3917.14 72.2148 4367.56 +EDGE_SE3:QUAT 812 863 1.2366 11.6444 -6.03279 -0.0302158 0.0404014 0.00668329 0.998704 1 1.27894e-20 1.27894e-20 7.02379e-09 -2.22518e-11 2.02178e-09 1 1.27894e-20 7.02379e-09 -2.22518e-11 2.02178e-09 1 7.02379e-09 -2.22518e-11 2.02178e-09 4022.91 -4.77018 327.068 3993.39 -0.091028 4026.39 +EDGE_SE3:QUAT 813 862 0.923489 -11.681 -5.71403 0.120374 0.135998 -0.0768273 0.980363 1 4.81482e-20 4.81482e-20 -2.16853e-09 -1.48745e-09 -1.42236e-08 1 4.81482e-20 -2.16853e-09 -1.48745e-09 -1.42236e-08 1 -2.16853e-09 -1.48745e-09 -1.42236e-08 4307.38 51.5705 1263 3914.71 6.81226 4341.73 +EDGE_SE3:QUAT 814 864 1.89645 0.350223 -5.90976 0.0162774 -0.0679172 0.126436 0.989513 1 7.71124e-19 7.71124e-19 -2.18057e-09 1.4961e-10 5.53489e-08 1 7.71124e-19 -2.18057e-09 1.4961e-10 5.53489e-08 1 -2.18057e-09 1.4961e-10 5.53489e-08 4077.02 10.0672 -564.294 3981.73 -35.8057 4014.14 +EDGE_SE3:QUAT 813 864 1.06179 12.1774 -6.06386 -0.0833659 -0.0971525 0.0976758 0.98695 1 1.92593e-19 1.92593e-19 2.17763e-09 2.87825e-09 -2.77755e-08 1 1.92593e-19 2.17763e-09 2.87825e-09 -2.77755e-08 1 2.17763e-09 2.87825e-09 -2.77755e-08 4082.42 46.8273 -674.693 3979.11 -49.1471 4072.06 +EDGE_SE3:QUAT 814 863 1.16072 -11.945 -5.92064 0.243015 -0.0222954 -0.265134 0.932818 1 7.70372e-19 7.70372e-19 5.2288e-08 -1.36446e-08 5.80073e-09 1 7.70372e-19 5.2288e-08 -1.36446e-08 5.80073e-09 1 5.2288e-08 -1.36446e-08 5.80073e-09 3832.49 85.5581 571.252 3959.99 -96.3829 3787.53 +EDGE_SE3:QUAT 815 865 1.81607 0.164931 -5.84135 -0.0050572 -0.0270962 0.12148 0.992211 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.38 2.49138 -205.131 3997.65 -12.3857 3951.45 +EDGE_SE3:QUAT 814 865 1.28598 12.2404 -5.73253 -0.0987218 -0.00895526 0.00410641 0.995066 1 1.92593e-19 1.92593e-19 -2.76224e-08 -1.60635e-10 2.21337e-10 1 1.92593e-19 -2.76224e-08 -1.60635e-10 2.21337e-10 1 -2.76224e-08 -1.60635e-10 2.21337e-10 3962.1 3.15883 -65.7769 3999.76 -0.298449 4001.01 +EDGE_SE3:QUAT 815 864 1.10673 -11.822 -5.78561 -0.0405822 -0.0254206 -0.0945742 0.994365 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.54 3.33805 -246.785 3995.9 11.5869 3979.35 +EDGE_SE3:QUAT 816 866 1.73742 -0.190588 -6.28837 0.0103316 0.0709633 -0.00430895 0.997416 1 3.19734e-21 3.19734e-21 3.55799e-09 -1.46989e-12 1.1229e-09 1 3.19734e-21 3.55799e-09 -1.46989e-12 1.1229e-09 1 3.55799e-09 -1.46989e-12 1.1229e-09 4081.51 2.61269 578.315 3979.82 -0.0312669 4081.86 +EDGE_SE3:QUAT 815 866 1.06048 12.198 -6.12282 -0.0884925 -0.0704346 0.125111 0.985675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.51 26.3177 -415.093 3993.56 -30.4783 3979.23 +EDGE_SE3:QUAT 816 865 1.48129 -11.8468 -6.1001 0.0319341 -0.0781465 0.052554 0.995043 1 4.81482e-20 4.81482e-20 -1.13813e-09 3.35777e-10 1.39898e-08 1 4.81482e-20 -1.13813e-09 3.35777e-10 1.39898e-08 1 -1.13813e-09 3.35777e-10 1.39898e-08 4101 -2.97943 -656.789 3974.07 -13.5164 4094.03 +EDGE_SE3:QUAT 817 867 2.03893 -0.390963 -5.93129 0.0903146 -0.0632249 -0.0388455 0.993145 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.82 -24.1236 -461.401 3988.6 16.5309 4046.41 +EDGE_SE3:QUAT 816 867 1.48797 12.314 -6.1648 0.139147 -0.240019 0.0759945 0.957734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5131.95 -141.196 -2510.03 3763.5 121.725 5186.29 +EDGE_SE3:QUAT 817 866 1.08674 -12.1185 -6.0794 -0.0800024 -0.0666794 -0.164375 0.980884 1 1.92593e-19 1.92593e-19 2.76159e-08 -4.32009e-09 -2.48802e-09 1 1.92593e-19 2.76159e-08 -4.32009e-09 -2.48802e-09 1 2.76159e-08 -4.32009e-09 -2.48802e-09 4086.5 4.62707 -679.784 3971.35 50.3523 4004.02 +EDGE_SE3:QUAT 818 868 2.05238 0.165674 -5.74265 0.0584193 0.022688 0.0110538 0.997973 1 3.00927e-21 3.00927e-21 -7.37482e-11 -2.04766e-10 -3.46566e-09 1 3.00927e-21 -7.37482e-11 -2.04766e-10 -3.46566e-09 1 -7.37482e-11 -2.04766e-10 -3.46566e-09 3993.82 5.12377 173.082 3998.22 1.61702 4006.98 +EDGE_SE3:QUAT 817 868 1.2502 11.82 -6.04478 -0.105751 -0.0137803 0.100975 0.989157 1 1.92593e-19 1.92593e-19 -2.2036e-10 2.95184e-09 -2.74533e-08 1 1.92593e-19 -2.2036e-10 2.95184e-09 -2.74533e-08 1 -2.2036e-10 2.95184e-09 -2.74533e-08 3954.9 -3.36341 19.6018 3999.75 3.21196 3958.85 +EDGE_SE3:QUAT 818 867 1.11099 -11.9402 -5.62582 0.117057 -0.182193 -0.0981374 0.971325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4368.88 -173.969 -1372.13 3935.57 171.448 4385.17 +EDGE_SE3:QUAT 819 869 1.65822 -0.0409382 -5.65098 0.0762488 0.112324 -0.0464287 0.989653 1 1.92593e-19 1.92593e-19 -8.25168e-10 -2.74862e-08 1.87059e-09 1 1.92593e-19 -8.25168e-10 -2.74862e-08 1.87059e-09 1 -8.25168e-10 -2.74862e-08 1.87059e-09 4202.82 26.9929 977.493 3945.65 0.0367083 4217.46 +EDGE_SE3:QUAT 818 869 1.01337 12.2331 -6.15272 -0.0971864 0.0783181 0.201943 0.971411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4132.05 0.539746 842.708 3957.76 76.2019 4006.71 +EDGE_SE3:QUAT 819 868 0.902116 -11.809 -5.6885 -0.0671059 -0.114886 -0.0304697 0.990641 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4210.79 27.3026 -983.65 3945.35 -6.24077 4225.09 +EDGE_SE3:QUAT 820 870 1.71804 -0.148434 -6.09363 -0.0829436 -0.109112 0.0240977 0.99027 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4154.08 46.9317 -871.552 3959.21 -35.2561 4179.27 +EDGE_SE3:QUAT 819 870 0.921887 12.1016 -6.02389 -0.103837 -0.0878339 0.15873 0.97791 1 9.62965e-19 9.62965e-19 -3.00432e-08 -1.20248e-08 5.60177e-08 1 9.62965e-19 -3.00432e-08 -1.20248e-08 5.60177e-08 1 -3.00432e-08 -1.20248e-08 5.60177e-08 4010.31 38.4875 -473.821 3994.31 -44.2499 3952.66 +EDGE_SE3:QUAT 820 869 1.21149 -12.1538 -5.73089 -0.03794 0.000868411 -0.00158289 0.999278 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.25 -0.11322 6.21231 4000 -0.00530128 4000 +EDGE_SE3:QUAT 821 871 2.25906 0.0119154 -5.68836 -0.00901169 0.00914073 -0.00105169 0.999917 1 3.00927e-21 3.00927e-21 -3.46974e-09 4.22113e-12 -3.16475e-11 1 3.00927e-21 -3.46974e-09 4.22113e-12 -3.16475e-11 1 -3.46974e-09 4.22113e-12 -3.16475e-11 4001.01 -0.331244 73.0243 3999.67 -0.0564432 4001.33 +EDGE_SE3:QUAT 820 871 1.11828 12.0901 -6.17162 -0.0322989 0.0974786 0.108417 0.988787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4163.98 12.4975 837.212 3960.11 42.486 4121.14 +EDGE_SE3:QUAT 821 870 1.1076 -11.9097 -5.94213 0.00815014 -0.0191146 -0.160716 0.986782 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.04 -1.64314 -131.675 3999.16 10.0905 3900.99 +EDGE_SE3:QUAT 822 872 2.0605 0.116108 -6.11033 0.140972 0.226967 -0.0957015 0.958882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5025.14 99.2978 2374.65 3776.28 71.4642 5067.99 +EDGE_SE3:QUAT 821 872 1.27522 12.3507 -6.00407 -0.245662 -0.0231797 0.0699271 0.966552 1 7.70372e-19 7.70372e-19 5.36468e-08 4.0247e-09 7.26018e-10 1 7.70372e-19 5.36468e-08 4.0247e-09 7.26018e-10 1 5.36468e-08 4.0247e-09 7.26018e-10 3757.54 -12.8609 29.6599 3999.34 3.68892 3979.38 +EDGE_SE3:QUAT 822 871 1.17095 -11.6731 -5.97992 -0.0562837 0.228162 0.0421335 0.971081 1 1.92593e-19 1.92593e-19 -3.0168e-08 -5.8766e-10 -7.17861e-09 1 1.92593e-19 -3.0168e-08 -5.8766e-10 -7.17861e-09 1 -3.0168e-08 -5.8766e-10 -7.17861e-09 4994.56 -29.9533 2245.76 3788.22 -18.9107 5000.13 +EDGE_SE3:QUAT 823 873 1.72521 -0.0173914 -5.6189 -0.0346948 0.141204 0.154293 0.977267 1 1.20371e-20 1.20371e-20 7.08238e-09 1.0913e-09 1.05068e-09 1 1.20371e-20 7.08238e-09 1.0913e-09 1.05068e-09 1 7.08238e-09 1.0913e-09 1.05068e-09 4349.65 59.0725 1242.4 3923.99 98.7447 4259.24 +EDGE_SE3:QUAT 822 873 1.02368 11.9483 -5.97149 0.118578 0.0500666 -0.00156958 0.99168 1 2.40741e-19 2.40741e-19 -2.7518e-08 -1.40489e-08 2.84253e-10 1 2.40741e-19 -2.7518e-08 -1.40489e-08 2.84253e-10 1 -2.7518e-08 -1.40489e-08 2.84253e-10 3982.91 23.9808 397.688 3990.96 6.77695 4039.14 +EDGE_SE3:QUAT 823 872 0.769162 -11.9242 -6.0831 0.077056 -0.0664759 -0.0662191 0.992602 1 2.40741e-19 2.40741e-19 -4.75191e-10 1.61633e-08 2.65467e-08 1 2.40741e-19 -4.75191e-10 1.61633e-08 2.65467e-08 1 -4.75191e-10 1.61633e-08 2.65467e-08 4029.99 -23.6268 -467.468 3988.78 22.066 4036.2 +EDGE_SE3:QUAT 824 874 1.78178 -0.0943419 -5.52074 -0.18155 -0.0453808 -0.0727554 0.979636 1 7.70372e-19 7.70372e-19 -5.48194e-08 2.9152e-09 3.80322e-09 1 7.70372e-19 -5.48194e-08 2.9152e-09 3.80322e-09 1 -5.48194e-08 2.9152e-09 3.80322e-09 3930.58 45.3347 -504.897 3983.26 5.17126 4041.25 +EDGE_SE3:QUAT 823 874 1.52242 12.1079 -6.25335 0.0251924 -0.18848 0.158981 0.968796 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4624.17 132.971 -1702.99 3878.48 -162.852 4525.61 +EDGE_SE3:QUAT 824 873 0.880964 -12.1958 -5.70441 -0.0880766 -0.116187 0.0151029 0.989199 1 1.92593e-19 1.92593e-19 1.00079e-09 -2.74407e-08 -2.60807e-09 1 1.92593e-19 1.00079e-09 -2.74407e-08 -2.60807e-09 1 1.00079e-09 -2.74407e-08 -2.60807e-09 4180.2 51.9428 -943.258 3952.5 -37.1804 4210.32 +EDGE_SE3:QUAT 825 875 2.2078 0.0522525 -6.05941 0.0790541 0.211554 0.0525326 0.972746 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4712.92 172.839 1870.25 3859.91 169.553 4726.88 +EDGE_SE3:QUAT 824 875 1.00077 12.0058 -6.04586 -0.0770874 -0.0566923 0.125125 0.987516 1 1.92593e-19 1.92593e-19 2.74994e-08 3.70302e-09 -9.75063e-10 1 1.92593e-19 2.74994e-08 3.70302e-09 -9.75063e-10 1 2.74994e-08 3.70302e-09 -9.75063e-10 4002.04 17.1113 -325.776 3995.99 -21.7926 3963.18 +EDGE_SE3:QUAT 825 874 1.18071 -12.3258 -5.84481 0.00367903 0.100534 -0.0731246 0.992236 1 1.88079e-22 1.88079e-22 -8.78333e-10 6.54045e-11 -8.85068e-11 1 1.88079e-22 -8.78333e-10 6.54045e-11 -8.85068e-11 1 -8.78333e-10 6.54045e-11 -8.85068e-11 4165.31 -16.8785 829.959 3960.95 -32.6271 4143.98 +EDGE_SE3:QUAT 826 876 1.83775 -0.097001 -6.08775 0.140374 -0.132023 0.0250883 0.980936 1 3.0845e-18 3.0845e-18 -1.12524e-07 9.65497e-10 1.18768e-08 1 3.0845e-18 -1.12524e-07 9.65497e-10 1.18768e-08 1 -1.12524e-07 9.65497e-10 1.18768e-08 4221.85 -83.6775 -1137.16 3934.32 48.791 4298.15 +EDGE_SE3:QUAT 825 876 0.829528 11.6636 -6.32545 -0.00680736 0.12056 -0.0461674 0.991609 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4239.17 -21.0539 1007.34 3943.69 -29.2966 4230.83 +EDGE_SE3:QUAT 826 875 1.05948 -12.0053 -5.73863 -0.0898907 0.167782 -0.00536023 0.981703 1 2.0463e-19 2.0463e-19 3.00313e-08 -1.79824e-09 1.20192e-08 1 2.0463e-19 3.00313e-08 -1.79824e-09 1.20192e-08 1 3.00313e-08 -1.79824e-09 1.20192e-08 4440.86 -88.7739 1454.93 3897.95 -73.1674 4473.06 +EDGE_SE3:QUAT 827 877 1.89917 0.0666691 -5.76085 0.109271 0.0116648 0.0020545 0.993941 1 1.88079e-22 1.88079e-22 9.49097e-12 9.4867e-11 8.62323e-10 1 1.88079e-22 9.49097e-12 9.4867e-11 8.62323e-10 1 9.49097e-12 9.4867e-11 8.62323e-10 3954.22 4.79658 89.0161 3999.55 0.423686 4001.96 +EDGE_SE3:QUAT 826 877 1.13905 12.3363 -6.0768 0.138365 -0.103045 0.155375 0.972674 1 7.70372e-19 7.70372e-19 7.89286e-09 -5.9326e-09 -5.59158e-08 1 7.70372e-19 7.89286e-09 -5.9326e-09 -5.59158e-08 1 7.89286e-09 -5.9326e-09 -5.59158e-08 4202.37 -29.891 -1093.75 3930.6 -48.0478 4182.38 +EDGE_SE3:QUAT 827 876 1.25145 -11.9003 -6.07001 -0.0440499 0.0503311 -0.0347799 0.997154 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.01 -10.5282 385.342 3991.34 -9.25546 4031.93 +EDGE_SE3:QUAT 828 878 1.71462 0.0912589 -5.91108 0.0146737 -0.105146 0.013364 0.994259 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4182.94 -3.43733 -876.917 3955.55 -2.4268 4183.09 +EDGE_SE3:QUAT 827 878 1.34146 12.2535 -6.48118 0.232037 0.0874191 0.0414068 0.967886 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3853.91 64.4741 536.119 3992.24 39.8602 4062.42 +EDGE_SE3:QUAT 828 877 1.15041 -11.9358 -5.69897 0.143235 -0.175065 -0.0702803 0.971543 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4313.21 -165.85 -1320.87 3938.57 155.483 4375.52 +EDGE_SE3:QUAT 829 879 1.89092 -0.069656 -5.96345 0.112038 0.0469947 -0.129985 0.984044 1 1.92593e-19 1.92593e-19 -2.04759e-09 -2.711e-09 -2.75617e-08 1 1.92593e-19 -2.04759e-09 -2.711e-09 -2.75617e-08 1 -2.04759e-09 -2.711e-09 -2.75617e-08 4021.06 21.8839 540.594 3979.94 -29.1137 4003.69 +EDGE_SE3:QUAT 828 879 0.98025 11.8711 -5.70106 0.00316104 0.0446854 0.222875 0.973817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4026.05 9.93528 324.72 3995.46 35.6923 3827.4 +EDGE_SE3:QUAT 829 878 0.995321 -12.3123 -5.74434 0.0897461 -0.085998 -0.0377278 0.991527 1 4.81482e-20 4.81482e-20 1.08922e-09 -1.36791e-09 -1.39386e-08 1 4.81482e-20 1.08922e-09 -1.36791e-09 -1.39386e-08 1 1.08922e-09 -1.36791e-09 -1.39386e-08 4071.06 -36.7495 -651.312 3977.37 27.5328 4097.58 +EDGE_SE3:QUAT 830 880 2.18034 -0.261688 -6.0792 -0.0827597 -0.00493539 0.1036 0.991158 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.32 -3.99109 63.2443 3999.4 5.02315 3957.78 +EDGE_SE3:QUAT 829 880 1.04797 11.9576 -5.97172 0.118216 -0.086165 0.180668 0.972605 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4152.26 -12.7819 -937.385 3947.28 -65.9448 4077.59 +EDGE_SE3:QUAT 830 879 1.31296 -11.8158 -6.16468 -0.109087 -0.09984 -0.0987396 0.984064 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4164.68 29.1719 -946.008 3947.51 20.2541 4173.28 +EDGE_SE3:QUAT 831 881 1.7828 0.124146 -6.10687 -0.156075 -0.0154947 -0.01309 0.987537 1 3.00927e-21 3.00927e-21 6.51729e-11 5.4057e-10 -3.42847e-09 1 3.00927e-21 6.51729e-11 5.4057e-10 -3.42847e-09 1 6.51729e-11 5.4057e-10 -3.42847e-09 3907.71 11.6708 -143.72 3998.71 -0.163655 4004.47 +EDGE_SE3:QUAT 830 881 1.06721 12.0115 -6.47485 -0.0260457 0.122021 0.0687499 0.989801 1 3.85186e-19 3.85186e-19 -1.77625e-09 -2.72093e-08 -2.86088e-08 1 3.85186e-19 -1.77625e-09 -2.72093e-08 -2.86088e-08 1 -1.77625e-09 -2.72093e-08 -2.86088e-08 4254.29 11.2674 1045.98 3939.17 31.6576 4238.1 +EDGE_SE3:QUAT 831 880 0.984846 -12.1573 -5.97086 -0.233276 -0.0367276 -0.239712 0.941686 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.87 82.7009 -914.152 3936.56 88.0422 3963.69 +EDGE_SE3:QUAT 832 882 1.72225 -0.371339 -6.04668 -0.00515658 0.00627951 -0.0557963 0.998409 1 7.52316e-22 7.52316e-22 1.73208e-09 -9.6912e-11 9.82873e-12 1 7.52316e-22 1.73208e-09 -9.6912e-11 9.82873e-12 1 1.73208e-09 -9.6912e-11 9.82873e-12 4000.44 -0.163949 46.5595 3999.87 -1.26945 3988.09 +EDGE_SE3:QUAT 831 882 1.31642 12.1757 -6.22941 -0.152667 -0.0308084 0.286967 0.945195 1 3.85487e-18 3.85487e-18 -4.70358e-08 -2.84377e-08 1.02375e-07 1 3.85487e-18 -4.70358e-08 -2.84377e-08 1.02375e-07 1 -4.70358e-08 -2.84377e-08 1.02375e-07 3919.82 -32.9306 281.023 3986.61 65.8323 3683.65 +EDGE_SE3:QUAT 832 881 1.18303 -12.1775 -6.23315 0.0133996 0.118552 -0.113625 0.986334 1 1.05794e-22 1.05794e-22 -6.60428e-10 7.61228e-11 -7.93407e-11 1 1.05794e-22 -6.60428e-10 7.61228e-11 -7.93407e-11 1 -6.60428e-10 7.61228e-11 -7.93407e-11 4233.96 -33.6587 996.905 3946.96 -60.3529 4183.03 +EDGE_SE3:QUAT 833 883 2.1995 0.09925 -5.76891 0.0362478 -0.0522957 0.0219549 0.997732 1 1.20371e-20 1.20371e-20 3.74812e-10 -2.38051e-10 -6.96287e-09 1 1.20371e-20 3.74812e-10 -2.38051e-10 -6.96287e-09 1 3.74812e-10 -2.38051e-10 -6.96287e-09 4040.68 -6.5871 -431.136 3988.53 -2.41272 4044.01 +EDGE_SE3:QUAT 832 883 1.08282 11.5832 -6.04013 0.168345 0.0165442 0.173005 0.970286 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3895.16 -27.0533 -215.357 3993.12 -27.8688 3888.8 +EDGE_SE3:QUAT 833 882 0.901427 -11.7963 -5.79899 0.142083 -0.09619 -0.111317 0.978861 1 1.54074e-18 1.54074e-18 -5.81015e-08 1.66799e-08 5.81015e-08 1 1.54074e-18 -5.81015e-08 1.66799e-08 5.81015e-08 1 -5.81015e-08 1.66799e-08 5.81015e-08 3991.85 -51.6312 -550.716 3991.06 47.9752 4023.03 +EDGE_SE3:QUAT 834 884 2.05308 -0.157346 -6.07551 -0.190561 0.0544944 0.10743 0.974256 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.31 -57.9437 660.764 3971.06 14.2026 4059.4 +EDGE_SE3:QUAT 833 884 1.62788 11.7799 -5.88943 -0.0757329 0.265953 -0.0423811 0.960072 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5284.15 -274.078 2634.13 3773.83 -273.109 5299.91 +EDGE_SE3:QUAT 834 883 0.979131 -12.1214 -6.13353 -0.0781718 0.0560832 -0.179775 0.978992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.99 -13.9075 258.461 3998.87 -20.4885 3886.15 +EDGE_SE3:QUAT 835 885 2.07069 0.18773 -6.34965 0.145784 0.112703 0.0322306 0.982347 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4085.36 75.9052 843.88 3967.11 55.3063 4166.21 +EDGE_SE3:QUAT 834 885 1.27303 12.0575 -6.20933 0.165415 0.06453 -0.032895 0.983561 1 1.20371e-20 1.20371e-20 5.02379e-10 1.13796e-09 6.89406e-09 1 1.20371e-20 5.02379e-10 1.13796e-09 6.89406e-09 1 5.02379e-10 1.13796e-09 6.89406e-09 3969.86 46.7168 568.838 3981.48 9.39889 4074.98 +EDGE_SE3:QUAT 835 884 0.869831 -12.0502 -5.64176 -0.0688413 -0.0572028 0.0877122 0.992117 1 2.40741e-19 2.40741e-19 -2.63393e-08 -1.64144e-08 1.33391e-10 1 2.40741e-19 -2.63393e-08 -1.64144e-08 1.33391e-10 1 -2.63393e-08 -1.64144e-08 1.33391e-10 4016.52 17.7088 -379.556 3993.01 -20.0132 4004.71 +EDGE_SE3:QUAT 836 886 1.77774 0.35437 -6.19555 0.150199 0.0493505 -0.107431 0.981562 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.44 37.738 575.851 3977.43 -19.0216 4034.51 +EDGE_SE3:QUAT 835 886 0.994823 12.0578 -6.04783 -0.0130203 0.0129196 0.133447 0.990886 1 7.70372e-19 7.70372e-19 8.83047e-10 -5.07794e-10 5.50309e-08 1 7.70372e-19 8.83047e-10 -5.07794e-10 5.50309e-08 1 8.83047e-10 -5.07794e-10 5.50309e-08 4002.99 -0.135504 121.291 3999.05 8.44368 3932.44 +EDGE_SE3:QUAT 836 885 0.893661 -12.2632 -5.76072 0.100429 0.00688767 0.00773906 0.99489 1 1.93345e-19 1.93345e-19 2.76e-08 1.97455e-09 -3.00216e-11 1 1.93345e-19 2.76e-08 1.97455e-09 -3.00216e-11 1 2.76e-08 1.97455e-09 -3.00216e-11 3960.16 2.09706 45.0051 3999.9 0.245508 4000.26 +EDGE_SE3:QUAT 837 887 2.10954 -0.379206 -5.91079 0.0318842 -0.0856809 -0.148177 0.984726 1 2.40741e-19 2.40741e-19 -9.51855e-09 2.94837e-08 -5.46463e-10 1 2.40741e-19 -9.51855e-09 2.94837e-08 -5.46463e-10 1 -9.51855e-09 2.94837e-08 -5.46463e-10 4088.67 -32.5347 -617.053 3982.04 51.6954 4004.91 +EDGE_SE3:QUAT 836 887 1.09467 11.9591 -6.38528 0.102553 0.032731 0.0933483 0.989797 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3962.44 6.15292 140.826 3999.55 5.78625 3969.66 +EDGE_SE3:QUAT 837 886 0.747124 -12.6443 -5.83049 0.0176329 0.159856 -0.0649825 0.984841 1 6.77085e-21 6.77085e-21 -5.40513e-09 3.43643e-10 -8.82356e-10 1 6.77085e-21 -5.40513e-09 3.43643e-10 -8.82356e-10 1 -5.40513e-09 3.43643e-10 -8.82356e-10 4445.55 -29.8389 1409.55 3898.34 -46.1656 4429.91 +EDGE_SE3:QUAT 838 888 1.92336 0.0872411 -6.10628 -0.00534318 0.155253 -0.0797882 0.984633 1 7.82409e-19 7.82409e-19 -2.42482e-09 5.52544e-08 6.20485e-10 1 7.82409e-19 -2.42482e-09 5.52544e-08 6.20485e-10 1 -2.42482e-09 5.52544e-08 6.20485e-10 4402.64 -55.3951 1331.67 3910.75 -69.9418 4377.29 +EDGE_SE3:QUAT 837 888 1.22217 12.1416 -6.29505 0.0499364 -0.0210696 -0.0916592 0.994314 1 2.52778e-19 2.52778e-19 1.34756e-08 -9.66536e-09 -2.74003e-08 1 2.52778e-19 1.34756e-08 -9.66536e-09 -2.74003e-08 1 1.34756e-08 -9.66536e-09 -2.74003e-08 3993.02 -2.8366 -111.303 3999.52 4.52295 3969.39 +EDGE_SE3:QUAT 838 887 1.26755 -12.0228 -5.66002 0.0647561 0.0573526 -0.0545975 0.994754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.55 12.3421 503.284 3984.13 -8.69642 4050.4 +EDGE_SE3:QUAT 839 889 2.16474 0.267699 -5.51263 0.0999691 -0.167374 0.0688273 0.978394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4496.6 -46.1768 -1560.24 3878.66 12.4314 4517.63 +EDGE_SE3:QUAT 838 889 1.15449 12.3603 -6.53622 0.184798 0.162344 0.110512 0.962954 1 7.70372e-19 7.70372e-19 -5.95811e-09 -1.28773e-08 -5.50742e-08 1 7.70372e-19 -5.95811e-09 -1.28773e-08 -5.50742e-08 1 -5.95811e-09 -1.28773e-08 -5.50742e-08 4094.96 150.485 1001.05 3982.13 142.534 4182.71 +EDGE_SE3:QUAT 839 888 1.05799 -12.1035 -5.80127 0.0329715 -0.119766 -0.187278 0.974421 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4172.87 -71.2983 -862.545 3970.91 97.5059 4036.93 +EDGE_SE3:QUAT 840 890 1.80188 -0.0238955 -6.08398 0.0826091 0.0601581 -0.0276993 0.994379 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4036.8 19.6025 510.436 3984.11 0.415442 4061.03 +EDGE_SE3:QUAT 839 890 1.36393 12.2206 -6.29858 0.0332112 0.064699 0.0805743 0.994092 1 9.62965e-20 9.62965e-20 1.27123e-08 1.49834e-08 2.11927e-10 1 9.62965e-20 1.27123e-08 1.49834e-08 2.11927e-10 1 1.27123e-08 1.49834e-08 2.11927e-10 4053.6 15.5286 485.441 3986.97 22.8701 4032.05 +EDGE_SE3:QUAT 840 889 0.885044 -12.1231 -5.32106 -0.0842347 0.0459122 0.0444058 0.994397 1 1.92593e-19 1.92593e-19 -2.77449e-08 -1.01141e-09 -1.46663e-09 1 1.92593e-19 -2.77449e-08 -1.01141e-09 -1.46663e-09 1 -2.77449e-08 -1.01141e-09 -1.46663e-09 4013.36 -15.6212 410.926 3989.25 4.55538 4033.86 +EDGE_SE3:QUAT 841 891 1.82107 0.172706 -6.01177 -0.0044747 -0.0379996 0.0433964 0.998325 1 7.52316e-22 7.52316e-22 1.73674e-09 7.63014e-11 -6.51763e-11 1 7.52316e-22 1.73674e-09 7.63014e-11 -6.51763e-11 1 1.73674e-09 7.63014e-11 -6.51763e-11 4022.63 2.17508 -302.285 3994.43 -6.78817 4015.18 +EDGE_SE3:QUAT 840 891 1.25104 11.9487 -6.19051 0.0572907 -0.00416437 0.144385 0.987853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.85 -4.02122 -129.92 3998.41 -11.4962 3920.59 +EDGE_SE3:QUAT 841 890 1.00531 -12.3351 -5.76755 -0.0179821 -0.0429344 -0.0994004 0.993958 1 4.81482e-20 4.81482e-20 -1.36266e-09 -1.37956e-08 -1.27389e-10 1 4.81482e-20 -1.36266e-09 -1.37956e-08 -1.27389e-10 1 -1.36266e-09 -1.37956e-08 -1.27389e-10 4031.24 -1.42311 -362.197 3991.98 17.7752 3993.01 +EDGE_SE3:QUAT 842 892 1.93747 0.104643 -5.80155 -0.0238514 0.0533698 0.133393 0.989338 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4049.58 4.51117 458.386 3987.54 30.3305 3980.68 +EDGE_SE3:QUAT 841 892 1.39315 12.3325 -6.09929 0.0656755 0.0133249 0.0580778 0.99606 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.58 1.55919 59.831 3999.89 1.40521 3987.34 +EDGE_SE3:QUAT 842 891 1.24215 -12.4264 -5.85544 0.109009 0.114178 -0.0476597 0.986311 1 3.85186e-19 3.85186e-19 2.88218e-08 2.67546e-08 6.81505e-10 1 3.85186e-19 2.88218e-08 2.67546e-08 6.81505e-10 1 2.88218e-08 2.67546e-08 6.81505e-10 4192.13 46.5838 1008.05 3943.31 11.7046 4230.58 +EDGE_SE3:QUAT 843 893 1.86344 0.0703709 -6.18487 -0.0293333 0.139062 0.0180808 0.989684 1 3.00927e-21 3.00927e-21 -5.04851e-10 9.14166e-11 -3.57315e-09 1 3.00927e-21 -5.04851e-10 9.14166e-11 -3.57315e-09 1 -5.04851e-10 9.14166e-11 -3.57315e-09 4327.84 -11.9396 1197.85 3922.02 -2.00133 4329.97 +EDGE_SE3:QUAT 842 893 1.05619 11.9348 -6.24256 0.170027 -0.014618 0.0482631 0.984148 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3895.02 -19.7959 -208.521 3996.67 -3.51159 4001.34 +EDGE_SE3:QUAT 843 892 0.92231 -12.0551 -5.95241 -0.149023 -0.0518216 -0.0425455 0.986558 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.17 35.0977 -481.124 3985.8 -1.24086 4049.76 +EDGE_SE3:QUAT 844 894 1.6352 0.137666 -5.94336 0.103773 -0.0733438 0.0154898 0.991772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4047.37 -31.4578 -608.256 3978.48 9.18668 4089.49 +EDGE_SE3:QUAT 843 894 1.2217 12.0961 -6.42464 0.0667045 0.183269 0.0139516 0.980698 1 1.20371e-20 1.20371e-20 -1.33213e-09 -5.70419e-10 -7.28133e-09 1 1.20371e-20 -1.33213e-09 -5.70419e-10 -7.28133e-09 1 -1.33213e-09 -5.70419e-10 -7.28133e-09 4558.53 86.3958 1624.07 3875.84 77.4135 4575.55 +EDGE_SE3:QUAT 844 893 0.627423 -12.3697 -5.86691 -0.00950772 0.0386256 -0.140706 0.989252 1 3.00927e-21 3.00927e-21 3.44099e-09 -4.93287e-10 1.19747e-10 1 3.00927e-21 3.44099e-09 -4.93287e-10 1.19747e-10 1 3.44099e-09 -4.93287e-10 1.19747e-10 4019.83 -5.82774 285.162 3995.71 -20.0606 3941 +EDGE_SE3:QUAT 845 895 1.71731 -0.240843 -6.0859 0.101809 0.10113 0.00507196 0.989637 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4119.2 47.0086 817.662 3963.59 27.6897 4160.56 +EDGE_SE3:QUAT 844 895 1.16408 11.8745 -5.99525 -0.0459206 -0.136017 0.0713745 0.987064 1 1.92593e-19 1.92593e-19 2.83533e-08 2.48548e-09 -3.6522e-09 1 1.92593e-19 2.83533e-08 2.48548e-09 -3.6522e-09 1 2.83533e-08 2.48548e-09 -3.6522e-09 4273.26 61.6266 -1098.49 3939.02 -66.5871 4261.32 +EDGE_SE3:QUAT 845 894 1.13908 -12.4939 -6.05284 -0.0952304 -0.0479588 0.0792599 0.991135 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.75 15.1047 -285.964 3996.52 -13.617 3994.9 +EDGE_SE3:QUAT 846 896 1.57762 -0.0225093 -5.89329 -0.025852 0.0907236 0.212029 0.9727 1 7.52316e-22 7.52316e-22 1.71824e-09 3.72495e-10 1.64715e-10 1 7.52316e-22 1.71824e-09 3.72495e-10 1.64715e-10 1 1.71824e-09 3.72495e-10 1.64715e-10 4138.37 35.3647 764.331 3971.71 83.5603 3961.22 +EDGE_SE3:QUAT 845 896 1.17465 11.8457 -6.04913 0.0833042 0.133611 0.0412545 0.986664 1 9.62965e-19 9.62965e-19 2.4701e-08 5.6562e-08 -1.83485e-09 1 9.62965e-19 2.4701e-08 5.6562e-08 -1.83485e-09 1 2.4701e-08 5.6562e-08 -1.83485e-09 4240.77 69.5874 1070.91 3942.44 61.4272 4261.72 +EDGE_SE3:QUAT 846 895 1.20498 -11.9117 -5.45359 -0.0449341 -0.0943861 -0.0497369 0.993277 1 4.81482e-20 4.81482e-20 -1.40508e-08 5.92357e-10 1.38751e-09 1 4.81482e-20 -1.40508e-08 5.92357e-10 1.38751e-09 1 -1.40508e-08 5.92357e-10 1.38751e-09 4147.39 8.32246 -803.778 3961.96 11.5867 4145.57 +EDGE_SE3:QUAT 847 897 1.94709 -0.192506 -5.77883 -0.00259266 0.0837125 -0.09882 0.991575 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4109.99 -17.6803 672.482 3974.6 -35.8852 4070.96 +EDGE_SE3:QUAT 846 897 1.09485 12.4858 -6.0286 -0.0970759 -0.0563192 0.0439192 0.992711 1 4.81482e-20 4.81482e-20 -6.48326e-10 -1.42536e-09 1.38436e-08 1 4.81482e-20 -6.48326e-10 -1.42536e-09 1.38436e-08 1 -6.48326e-10 -1.42536e-09 1.38436e-08 4000.81 21.5141 -394.976 3991.94 -14.5618 4030.79 +EDGE_SE3:QUAT 847 896 0.746166 -11.8266 -6.55438 0.107755 -0.0107946 -0.303415 0.946685 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3971.8 17.8706 293.253 3989.39 -63.2487 3650 +EDGE_SE3:QUAT 848 898 1.78454 0.0989325 -6.02676 0.093148 -0.0758463 0.00508139 0.992746 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4058.25 -29.7271 -616.825 3978.05 11.5462 4092.85 +EDGE_SE3:QUAT 847 898 1.23182 12.1895 -6.22569 0.0317455 0.140101 0.0635002 0.987589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4308.3 53.376 1160.64 3930.5 59.6953 4296.2 +EDGE_SE3:QUAT 848 897 0.856836 -12.3821 -5.64039 0.105686 -0.0760507 -0.0468556 0.990379 1 1.92593e-19 1.92593e-19 -2.77409e-08 1.74795e-09 1.79327e-09 1 1.92593e-19 -2.77409e-08 1.74795e-09 1.79327e-09 1 -2.77409e-08 1.74795e-09 1.79327e-09 4028.03 -34.5902 -544.885 3984.99 25.3457 4063.92 +EDGE_SE3:QUAT 849 899 1.40197 -0.0887625 -5.6094 -0.00794934 0.210407 -0.0738951 0.974785 1 7.70372e-19 7.70372e-19 -4.69304e-09 -5.40634e-08 -2.32226e-09 1 7.70372e-19 -4.69304e-09 -5.40634e-08 -2.32226e-09 1 -4.69304e-09 -5.40634e-08 -2.32226e-09 4789.52 -107.642 1945.01 3836.81 -116.549 4767.93 +EDGE_SE3:QUAT 848 899 0.762177 12.1127 -6.1626 0.0434451 0.129746 -0.0331527 0.99004 1 9.62965e-19 9.62965e-19 -2.97216e-08 -5.43239e-08 -1.79127e-09 1 9.62965e-19 -2.97216e-08 -5.43239e-08 -1.79127e-09 1 -2.97216e-08 -5.43239e-08 -1.79127e-09 4283.77 13.9298 1118.1 3930.84 -2.4783 4286.92 +EDGE_SE3:QUAT 849 898 0.810544 -12.2706 -5.92718 -0.110785 0.0438199 -0.213001 0.969761 1 7.82409e-19 7.82409e-19 -5.23094e-08 1.8796e-08 1.22364e-09 1 7.82409e-19 -5.23094e-08 1.8796e-08 1.22364e-09 1 -5.23094e-08 1.8796e-08 1.22364e-09 3948.8 2.21208 47.7139 4000.15 5.58567 3816.42 +EDGE_SE3:QUAT 850 900 1.8982 -0.220503 -6.21254 0.00977419 0.136336 -0.0458242 0.989554 1 7.7056e-19 7.7056e-19 -3.38148e-09 -5.48933e-08 -2.74862e-10 1 7.7056e-19 -3.38148e-09 -5.48933e-08 -2.74862e-10 1 -3.38148e-09 -5.48933e-08 -2.74862e-10 4315.67 -15.6535 1167.95 3925.94 -27.3129 4307.65 +EDGE_SE3:QUAT 849 900 0.591293 11.8432 -6.10162 0.0997549 0.0118228 0.145907 0.984185 1 1.88079e-22 1.88079e-22 -1.26051e-10 8.53719e-10 -8.57862e-11 1 1.88079e-22 -1.26051e-10 8.53719e-10 -8.57862e-11 1 -1.26051e-10 8.53719e-10 -8.57862e-11 3961 -6.93132 -80.851 3998.77 -10.2 3915.65 +EDGE_SE3:QUAT 850 899 1.0617 -12.1773 -5.89125 -0.108248 0.124019 -0.0941015 0.981859 1 1.92593e-19 1.92593e-19 3.36726e-09 2.71691e-08 3.68018e-09 1 1.92593e-19 3.36726e-09 2.71691e-08 3.68018e-09 1 3.36726e-09 2.71691e-08 3.68018e-09 4132.56 -79.3514 868.362 3968.7 -77.035 4144.01 +EDGE_SE3:QUAT 851 901 1.88202 -0.273103 -5.87117 -0.177955 0.0838679 -0.212846 0.957076 1 1.58889e-18 1.58889e-18 -4.97885e-08 3.69345e-08 -5.02332e-08 1 1.58889e-18 -4.97885e-08 3.69345e-08 -5.02332e-08 1 -4.97885e-08 3.69345e-08 -5.02332e-08 3871.55 -4.14851 158.983 4002.61 -2.91048 3817 +EDGE_SE3:QUAT 850 901 1.04787 12.0642 -5.9628 -0.0836832 -0.0915174 0.156139 0.97992 1 3.85186e-19 3.85186e-19 -2.27079e-08 -3.19318e-08 -1.3559e-09 1 3.85186e-19 -2.27079e-08 -3.19318e-08 -1.3559e-09 1 -2.27079e-08 -3.19318e-08 -1.3559e-09 4044.79 42.5381 -549.588 3989.87 -51.7913 3975.28 +EDGE_SE3:QUAT 851 900 0.968098 -11.9592 -6.19479 -0.0334876 0.133989 -0.175638 0.974719 1 7.70372e-19 7.70372e-19 -6.46072e-09 4.57563e-09 -5.57193e-08 1 7.70372e-19 -6.46072e-09 4.57563e-09 -5.57193e-08 1 -6.46072e-09 4.57563e-09 -5.57193e-08 4228.63 -87.3863 995.242 3960.46 -111.93 4109.73 +EDGE_SE3:QUAT 852 902 1.73299 -0.0401312 -6.26331 0.0693732 -0.0067869 -0.027077 0.9972 1 7.52316e-22 7.52316e-22 4.81502e-11 1.72983e-09 -1.20808e-10 1 7.52316e-22 4.81502e-11 1.72983e-09 -1.20808e-10 1 4.81502e-11 1.72983e-09 -1.20808e-10 3980.98 -0.836565 -31.3861 3999.97 0.355773 3997.3 +EDGE_SE3:QUAT 851 902 1.40569 12.0675 -5.68181 0.0566746 -0.0476974 0.00443399 0.997243 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.03 -10.962 -385.841 3990.94 2.2722 4036.8 +EDGE_SE3:QUAT 852 901 1.05509 -12.164 -5.7122 0.041762 -0.0146661 -0.0978395 0.994217 1 2.43751e-19 2.43751e-19 -1.3629e-08 6.03631e-09 2.75328e-08 1 2.43751e-19 -1.3629e-08 6.03631e-09 2.75328e-08 1 -1.3629e-08 6.03631e-09 2.75328e-08 3994.06 -1.26122 -66.6755 3999.87 2.52839 3962.75 +EDGE_SE3:QUAT 853 903 1.5496 -0.0895167 -6.03413 -0.149713 0.0500994 -0.0637137 0.985402 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3928.33 -19.7153 272.935 3997.52 -12.6068 4001.75 +EDGE_SE3:QUAT 852 903 1.2468 11.7556 -6.09912 -0.0731143 0.0282592 0.0157733 0.996798 1 1.92593e-19 1.92593e-19 2.7716e-08 3.19888e-10 8.41028e-10 1 1.92593e-19 2.7716e-08 3.19888e-10 8.41028e-10 1 2.7716e-08 3.19888e-10 8.41028e-10 3992.81 -8.62158 238.737 3996.41 0.401829 4013.2 +EDGE_SE3:QUAT 853 902 0.677557 -12.0952 -5.93134 0.079803 -0.0691058 0.104931 0.988861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.55 -13.1229 -653.825 3973.3 -25.9664 4059.98 +EDGE_SE3:QUAT 854 904 1.75016 -0.355306 -6.04697 0.0854902 -0.0870914 0.206463 0.970814 1 1.92593e-19 1.92593e-19 5.35863e-09 -2.70219e-08 1.22743e-09 1 1.92593e-19 5.35863e-09 -2.70219e-08 1.22743e-09 1 5.35863e-09 -2.70219e-08 1.22743e-09 4159.74 11.7837 -890.379 3955.09 -84.1615 4018.47 +EDGE_SE3:QUAT 853 904 1.18725 12.0397 -6.35921 0.0134123 0.0707623 0.133555 0.988421 1 4.81482e-20 4.81482e-20 1.38404e-08 1.91438e-09 9.04466e-10 1 4.81482e-20 1.38404e-08 1.91438e-09 9.04466e-10 1 1.38404e-08 1.91438e-09 9.04466e-10 4070.16 18.6219 537.429 3984.82 38.3492 3999.53 +EDGE_SE3:QUAT 854 903 1.09838 -11.8788 -5.62203 0.0658617 -0.0850409 0.0266927 0.99384 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4106.77 -20.6024 -715.489 3969.7 1.95777 4121.28 +EDGE_SE3:QUAT 855 905 1.74537 0.130224 -6.3479 0.131452 0.00303373 0.109579 0.985243 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3935.48 -12.9617 -146.43 3997.45 -10.6289 3956.57 +EDGE_SE3:QUAT 854 905 0.970907 12.1898 -6.72971 0.188608 -0.0837629 0.0769965 0.97544 1 4.81482e-20 4.81482e-20 -1.49831e-09 2.50459e-09 1.38253e-08 1 4.81482e-20 -1.49831e-09 2.50459e-09 1.38253e-08 1 -1.49831e-09 2.50459e-09 1.38253e-08 4023.31 -71.7017 -831.073 3960.19 8.38564 4141.89 +EDGE_SE3:QUAT 855 904 0.673228 -12.0114 -5.60218 0.0253715 -0.0718614 -0.0923753 0.992804 1 1.92593e-19 1.92593e-19 -1.84329e-09 1.07857e-09 2.78102e-08 1 1.92593e-19 -1.84329e-09 1.07857e-09 2.78102e-08 1 -1.84329e-09 1.07857e-09 2.78102e-08 4070.89 -17.7829 -547.24 3983.54 28.9297 4039.33 +EDGE_SE3:QUAT 856 906 2.17183 0.216576 -6.16383 0.0583968 -0.182256 -0.210733 0.958626 1 9.62965e-19 9.62965e-19 -3.59219e-08 1.49995e-08 5.98239e-08 1 9.62965e-19 -3.59219e-08 1.49995e-08 5.98239e-08 1 -3.59219e-08 1.49995e-08 5.98239e-08 4363.54 -190.855 -1291.49 3961.76 208.455 4199.55 +EDGE_SE3:QUAT 855 906 1.14399 12.0687 -6.24647 0.103665 -0.0529065 0.142772 0.982889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.8 -18.1924 -590.155 3976.72 -35.8087 4003.25 +EDGE_SE3:QUAT 856 905 0.543792 -12.0423 -6.11913 0.199333 -0.0840736 -0.0603428 0.974452 1 7.70372e-19 7.70372e-19 -5.45057e-08 4.99415e-09 2.95258e-09 1 7.70372e-19 -5.45057e-08 4.99415e-09 2.95258e-09 1 -5.45057e-08 4.99415e-09 2.95258e-09 3899.47 -51.9905 -492.574 3993.05 35.406 4043.84 +EDGE_SE3:QUAT 857 907 1.87532 0.169566 -6.11503 -0.0345848 -0.109599 0.00172096 0.993373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4193.46 18.295 -912.291 3952.57 -11.4197 4198.23 +EDGE_SE3:QUAT 856 907 1.27428 12.2938 -6.61027 0.00974849 0.0861735 0.0868725 0.992438 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4114.62 19.0182 687.957 3973.41 33.6448 4084.81 +EDGE_SE3:QUAT 857 906 0.755693 -12.3363 -6.22547 -0.00786689 0.0556717 -0.207921 0.976528 1 1.20371e-20 1.20371e-20 6.81104e-09 -1.46479e-09 3.31982e-10 1 1.20371e-20 6.81104e-09 -1.46479e-09 3.31982e-10 1 6.81104e-09 -1.46479e-09 3.31982e-10 4039.37 -14.9838 400.855 3992.97 -41.7146 3866.7 +EDGE_SE3:QUAT 858 908 1.89769 -0.0807283 -5.79995 -0.0729959 0.00854552 0.139318 0.987517 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987 -6.92296 186.281 3996.94 15.0833 3930.68 +EDGE_SE3:QUAT 857 908 0.907004 12.2282 -6.52531 0.00911807 0.165098 0.112228 0.979829 1 1.20371e-20 1.20371e-20 -7.17188e-09 -8.91191e-10 -1.16008e-09 1 1.20371e-20 -7.17188e-09 -8.91191e-10 -1.16008e-09 1 -7.17188e-09 -8.91191e-10 -1.16008e-09 4444.09 88.59 1405.61 3907.62 107.429 4394.04 +EDGE_SE3:QUAT 858 907 1.11568 -12.4888 -6.09599 0.221242 -0.077823 -0.0892811 0.968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3830.25 -33.7652 -340.921 3999.77 25.1433 3994.16 +EDGE_SE3:QUAT 859 909 1.99492 0.267606 -6.16202 0.140338 0.162048 -0.0395107 0.975953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4398.74 103.868 1462.23 3897.66 68.327 4471.28 +EDGE_SE3:QUAT 858 909 0.893161 12.2391 -6.39333 0.114621 0.0738391 0.11385 0.984098 1 4.81482e-20 4.81482e-20 -1.78236e-09 1.36322e-08 -1.79185e-09 1 4.81482e-20 -1.78236e-09 1.36322e-08 -1.79185e-09 1 -1.78236e-09 1.36322e-08 -1.79185e-09 3989.09 30.2289 415.556 3994.24 30.1461 3989.79 +EDGE_SE3:QUAT 859 908 1.01385 -12.4116 -5.70033 0.0713205 -0.0508445 -0.127412 0.987975 1 1.92593e-19 1.92593e-19 2.74919e-08 -3.72451e-09 -8.51142e-10 1 1.92593e-19 2.74919e-08 -3.72451e-09 -8.51142e-10 1 2.74919e-08 -3.72451e-09 -8.51142e-10 3999.65 -13.7033 -286.904 3996.94 18.6699 3955.06 +EDGE_SE3:QUAT 860 910 1.75116 -0.0509133 -6.06451 -0.0823686 0.0929666 0.170763 0.977452 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4170.28 5.49899 910.803 3952.31 66.7624 4080.78 +EDGE_SE3:QUAT 859 910 0.712276 12.5096 -5.99555 0.0764544 -0.0266351 -0.0815143 0.993378 1 1.92593e-19 1.92593e-19 -3.76712e-10 2.21719e-09 2.7587e-08 1 1.92593e-19 -3.76712e-10 2.21719e-09 2.7587e-08 1 -3.76712e-10 2.21719e-09 2.7587e-08 3980.98 -4.88819 -134.955 3999.35 5.12057 3977.79 +EDGE_SE3:QUAT 860 909 1.14279 -11.7347 -6.1014 0.0149656 0.0883663 0.0600111 0.994166 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4121.5 17.0159 710.345 3971.12 25.7088 4107.99 +EDGE_SE3:QUAT 861 911 1.71919 0.148791 -5.84981 -0.0436555 0.0852458 0.0178242 0.995244 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4113.82 -13.4189 707.475 3970.32 -1.21443 4120.17 +EDGE_SE3:QUAT 860 911 1.07596 12.0076 -6.19226 -0.108826 0.110502 0.229128 0.960961 1 7.70372e-19 7.70372e-19 1.15387e-08 -5.36118e-08 -2.80366e-09 1 7.70372e-19 1.15387e-08 -5.36118e-08 -2.80366e-09 1 1.15387e-08 -5.36118e-08 -2.80366e-09 4271.69 27.4909 1174.65 3927.51 116.518 4109.06 +EDGE_SE3:QUAT 861 910 0.635197 -11.8493 -6.02617 0.0371611 -0.077534 -0.168841 0.981886 1 2.40741e-19 2.40741e-19 8.86613e-09 -2.96824e-08 8.5862e-10 1 2.40741e-19 8.86613e-09 -2.96824e-08 8.5862e-10 1 8.86613e-09 -2.96824e-08 8.5862e-10 4061.81 -28.8018 -525.118 3988.25 47.9819 3953.31 +EDGE_SE3:QUAT 862 912 1.81797 -0.220294 -6.19059 0.205658 0.0426471 -0.156949 0.965014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3947.4 64.646 699.205 3964.32 -36.6924 4018.05 +EDGE_SE3:QUAT 861 912 1.03074 12.3787 -6.2521 -0.0231896 0.145423 -0.0344373 0.988498 1 4.81482e-20 4.81482e-20 1.4311e-08 -6.20656e-10 2.07341e-09 1 4.81482e-20 1.4311e-08 -6.20656e-10 2.07341e-09 1 1.4311e-08 -6.20656e-10 2.07341e-09 4350.24 -36.5793 1238.46 3919.09 -38.8575 4347.65 +EDGE_SE3:QUAT 862 911 0.583642 -12.2835 -5.88829 -0.0233509 0.084151 -0.110254 0.990059 1 4.81482e-20 4.81482e-20 1.39141e-08 -1.62478e-09 1.07901e-09 1 4.81482e-20 1.39141e-08 -1.62478e-09 1.07901e-09 1 1.39141e-08 -1.62478e-09 1.07901e-09 4098.52 -25.3854 642.908 3978.07 -40.8307 4052.08 +EDGE_SE3:QUAT 863 913 1.30108 0.0172345 -5.93383 -0.0056757 0.0144563 -0.249439 0.968266 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.8 -1.08697 88.7631 3999.77 -9.93409 3753.05 +EDGE_SE3:QUAT 862 913 1.01904 12.0422 -6.10407 0.170092 0.00411035 0.0353878 0.984784 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3884.52 -5.43179 -39.3731 3999.75 -1.09961 3995.24 +EDGE_SE3:QUAT 863 912 1.17408 -12.21 -5.9114 -0.00590511 0.178944 -0.159667 0.970799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4507.04 -139.846 1512.6 3907.13 -164.752 4405.2 +EDGE_SE3:QUAT 864 914 1.64668 0.00352729 -6.27634 -0.17774 -0.222484 -0.0211385 0.958365 1 7.70372e-19 7.70372e-19 -5.89398e-08 -3.82936e-09 1.32269e-08 1 7.70372e-19 -5.89398e-08 -3.82936e-09 1.32269e-08 1 -5.89398e-08 -3.82936e-09 1.32269e-08 4751.93 253.108 -2070.45 3851.74 -231.846 4876.51 +EDGE_SE3:QUAT 863 914 1.01856 12.4288 -6.18789 -0.00448715 -0.0129545 0.0701463 0.997443 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.38 0.483892 -99.1552 3999.42 -3.44727 3982.77 +EDGE_SE3:QUAT 864 913 0.674439 -12.3517 -5.85833 0.158892 -0.0661394 -0.130384 0.976411 1 8.1852e-19 8.1852e-19 -5.63081e-08 -5.44839e-09 3.4647e-09 1 8.1852e-19 -5.63081e-08 -5.44839e-09 3.4647e-09 1 -5.63081e-08 -5.44839e-09 3.4647e-09 3912.51 -17.8828 -252.99 4000.02 16.6101 3945.5 +EDGE_SE3:QUAT 865 915 1.65404 0.0298398 -5.98808 -0.0129298 -0.116525 -0.0270085 0.992736 1 3.00927e-21 3.00927e-21 3.54112e-09 -8.80353e-11 -4.17459e-10 1 3.00927e-21 3.54112e-09 -8.80353e-11 -4.17459e-10 1 3.54112e-09 -8.80353e-11 -4.17459e-10 4227.32 -2.18947 -981.803 3945.36 10.6646 4225.07 +EDGE_SE3:QUAT 864 915 1.00693 12.3446 -6.31918 -0.0592881 -0.044125 0.0186881 0.99709 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4014.58 10.9396 -339.732 3993.22 -5.80232 4027.24 +EDGE_SE3:QUAT 865 914 0.744236 -12.4222 -5.95222 0.0116085 0.0752828 0.0412575 0.996241 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4089.38 9.37353 606.446 3978.28 14.7905 4083.11 +EDGE_SE3:QUAT 866 916 1.60171 -0.10895 -6.05515 0.0243257 0.0468605 0.154738 0.986544 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.65 10.1255 318.179 3995.27 24.5776 3929.24 +EDGE_SE3:QUAT 865 916 0.522196 12.6177 -6.30343 0.0330334 -0.0564313 0.0357335 0.99722 1 4.81482e-20 4.81482e-20 4.4618e-10 -1.38409e-08 4.04124e-10 1 4.81482e-20 4.4618e-10 -1.38409e-08 4.04124e-10 1 4.4618e-10 -1.38409e-08 4.04124e-10 4050.03 -5.19457 -469.634 3986.39 -6.07553 4049.29 +EDGE_SE3:QUAT 866 915 0.706469 -12.5891 -5.78003 -0.0436319 -0.131537 -0.0271143 0.989979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4290.53 16.9085 -1132.02 3929.41 -1.82821 4295.2 +EDGE_SE3:QUAT 867 917 1.75633 -0.259329 -6.06455 -0.0449489 0.119677 0.122499 0.984201 1 3.85186e-19 3.85186e-19 4.4436e-10 2.69066e-08 2.86357e-08 1 3.85186e-19 4.4436e-10 2.69066e-08 2.86357e-08 1 4.4436e-10 2.69066e-08 2.86357e-08 4254.55 21.1046 1058.09 3939.04 58.2691 4202.61 +EDGE_SE3:QUAT 866 917 0.567143 12.2378 -6.24282 0.0734144 -0.0478934 -0.0294126 0.995717 1 4.81482e-20 4.81482e-20 5.03044e-10 1.38152e-08 -1.0604e-09 1 4.81482e-20 5.03044e-10 1.38152e-08 -1.0604e-09 1 5.03044e-10 1.38152e-08 -1.0604e-09 4009.85 -14.4447 -356.012 3992.86 8.8238 4027.95 +EDGE_SE3:QUAT 867 916 0.838537 -12.3268 -6.041 0.0237493 -0.0313893 -0.00805468 0.999193 1 1.20371e-20 1.20371e-20 -6.94671e-09 6.64229e-11 2.15288e-10 1 1.20371e-20 -6.94671e-09 6.64229e-11 2.15288e-10 1 -6.94671e-09 6.64229e-11 2.15288e-10 4013.24 -3.17048 -249.418 3996.18 1.56695 4015.23 +EDGE_SE3:QUAT 868 918 1.43707 -0.0156078 -6.06578 0.132899 -0.231414 -0.0558771 0.962114 1 1.54074e-18 1.54074e-18 6.57215e-08 4.53392e-08 -2.21021e-08 1 1.54074e-18 6.57215e-08 4.53392e-08 -2.21021e-08 1 6.57215e-08 4.53392e-08 -2.21021e-08 4746.94 -281.719 -1986.55 3877.87 275.661 4805.1 +EDGE_SE3:QUAT 867 918 0.58315 12.2397 -6.1537 0.169706 0.0908144 0.146528 0.9703 1 7.70372e-19 7.70372e-19 -5.40903e-08 -9.4773e-09 -1.80128e-09 1 7.70372e-19 -5.40903e-08 -9.4773e-09 -1.80128e-09 1 -5.40903e-08 -9.4773e-09 -1.80128e-09 3916.8 35.479 381.5 4000.06 34.0917 3946.12 +EDGE_SE3:QUAT 868 917 0.703029 -12.3174 -6.37691 0.0136632 -0.0220093 0.00812658 0.999631 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.13 -1.12695 -177.647 3998.03 -0.566223 4007.61 +EDGE_SE3:QUAT 869 919 1.10686 0.370703 -6.00656 -0.110404 0.0355742 -0.086167 0.989505 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3957.47 -8.01006 163.525 3999.3 -6.84003 3976.53 +EDGE_SE3:QUAT 868 919 1.08741 11.9863 -6.35538 -0.0435256 -0.0490265 0.0699172 0.995396 1 1.92593e-19 1.92593e-19 -1.17747e-09 -1.39738e-09 2.77355e-08 1 1.92593e-19 -1.17747e-09 -1.39738e-09 2.77355e-08 1 -1.17747e-09 -1.39738e-09 2.77355e-08 4023.46 11.038 -354.019 3993.13 -14.3315 4011.48 +EDGE_SE3:QUAT 869 918 1.13786 -12.1366 -6.04729 -0.0803652 0.0223708 -0.104633 0.991006 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.24 -1.95623 74.5116 3999.96 -2.34886 3957.28 +EDGE_SE3:QUAT 870 920 1.4466 0.266285 -6.0431 -0.189764 -0.0706957 0.0500096 0.978003 1 1.01111e-18 1.01111e-18 -5.48782e-08 -2.31544e-08 2.7153e-08 1 1.01111e-18 -5.48782e-08 -2.31544e-08 2.7153e-08 1 -5.48782e-08 -2.31544e-08 2.7153e-08 3899.75 41.1735 -424.729 3993.97 -24.8688 4033.78 +EDGE_SE3:QUAT 869 920 0.942117 12.4088 -6.10334 0.120153 -0.12348 0.181617 0.968159 1 9.62965e-19 9.62965e-19 -3.6698e-08 4.95553e-08 5.51026e-10 1 9.62965e-19 -3.6698e-08 4.95553e-08 5.51026e-10 1 -3.6698e-08 4.95553e-08 5.51026e-10 4316.95 3.19866 -1281.06 3911.87 -80.5739 4242.76 +EDGE_SE3:QUAT 870 919 0.920701 -12.2851 -6.12385 0.0536974 0.0914842 0.0131482 0.994271 1 2.40741e-19 2.40741e-19 1.33816e-08 2.79191e-08 -3.20038e-10 1 2.40741e-19 1.33816e-08 2.79191e-08 -3.20038e-10 1 1.33816e-08 2.79191e-08 -3.20038e-10 4121.21 24.1964 740.699 3968.5 16.2245 4132.05 +EDGE_SE3:QUAT 871 921 1.48079 0.382881 -5.88896 -0.0741017 0.0726084 -0.0635476 0.992572 1 3.85186e-19 3.85186e-19 2.57225e-08 -2.96075e-08 -5.8794e-10 1 3.85186e-19 2.57225e-08 -2.96075e-08 -5.8794e-10 1 2.57225e-08 -2.96075e-08 -5.8794e-10 4045.18 -26.4024 523.164 3985.71 -24.7627 4050.99 +EDGE_SE3:QUAT 870 921 0.778755 12.4578 -6.27808 0.0429993 0.0728616 -0.0394683 0.995633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4084.3 8.64097 612.565 3977.24 -7.00114 4085.47 +EDGE_SE3:QUAT 871 920 0.852296 -12.2194 -5.8673 -0.0873701 0.146249 -0.117126 0.978396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4232.41 -105.512 1061.15 3955.37 -110.306 4208.07 +EDGE_SE3:QUAT 872 922 1.90026 -0.253183 -5.98468 0.00242214 -0.0916516 0.0997394 0.990781 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4134.73 19.703 -746.456 3968.84 -39.8926 4094.96 +EDGE_SE3:QUAT 871 922 0.874146 11.8417 -6.18752 0.109878 -0.0693915 -0.0531057 0.990097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.86 -30.8093 -478.313 3988.84 22.6956 4044.88 +EDGE_SE3:QUAT 872 921 0.908983 -12.4784 -5.90566 -0.0795241 0.201691 -0.12693 0.967928 1 7.70372e-19 7.70372e-19 5.7463e-08 -1.00596e-08 1.008e-08 1 7.70372e-19 5.7463e-08 -1.00596e-08 1.008e-08 1 5.7463e-08 -1.00596e-08 1.008e-08 4531.48 -209.364 1595.47 3915.99 -214.854 4492.33 +EDGE_SE3:QUAT 873 923 1.48423 -0.0912037 -6.30387 0.142154 0.133091 0.205558 0.959075 1 9.62965e-19 9.62965e-19 4.72611e-08 3.98959e-08 -1.95323e-09 1 9.62965e-19 4.72611e-08 3.98959e-08 -1.95323e-09 1 4.72611e-08 3.98959e-08 -1.95323e-09 4007.72 80.5779 627.345 4001.83 84.888 3919.54 +EDGE_SE3:QUAT 872 923 0.964915 12.0483 -5.788 0.0523431 0.091257 0.0660671 0.992254 1 4.81482e-20 4.81482e-20 -1.39737e-08 -1.07604e-09 -1.16754e-09 1 4.81482e-20 -1.39737e-08 -1.07604e-09 -1.16754e-09 1 -1.39737e-08 -1.07604e-09 -1.16754e-09 4107.08 31.6344 697.494 3973.8 34.1394 4100.58 +EDGE_SE3:QUAT 873 922 0.206081 -12.1189 -6.04491 0.0182424 -0.0517718 -0.114922 0.991857 1 1.92593e-19 1.92593e-19 -1.2874e-09 8.28579e-10 2.76564e-08 1 1.92593e-19 -1.2874e-09 8.28579e-10 2.76564e-08 1 -1.2874e-09 8.28579e-10 2.76564e-08 4035.09 -10.0972 -383.68 3992.05 23.0221 3983.59 +EDGE_SE3:QUAT 874 924 1.53707 -0.0676393 -5.71003 -0.166771 -0.169323 -0.150158 0.959672 1 3.08149e-18 3.08149e-18 1.15782e-07 -1.13186e-08 -2.46282e-08 1 3.08149e-18 1.15782e-07 -1.13186e-08 -2.46282e-08 1 1.15782e-07 -1.13186e-08 -2.46282e-08 4582.91 54.2222 -1805.69 3846 15.0326 4603.97 +EDGE_SE3:QUAT 873 924 0.874211 12.2302 -5.8462 -0.0986242 0.0345698 0.0896652 0.990474 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.18 -16.323 377.425 3990.06 14.0272 4002.92 +EDGE_SE3:QUAT 874 923 0.725013 -12.3895 -6.04114 -0.0773125 -0.151545 0.117906 0.978343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4271.73 109.991 -1128.88 3948.3 -116.63 4240.03 +EDGE_SE3:QUAT 875 925 1.74535 0.311198 -6.14817 0.0607738 -0.0321575 0.195304 0.97833 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.36 -3.71661 -383.355 3990 -39.3057 3883.56 +EDGE_SE3:QUAT 874 925 0.965313 12.4691 -6.30667 -0.0606443 0.12543 0.259578 0.95562 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4296.87 82.8909 1159.11 3943.07 154.625 4042.06 +EDGE_SE3:QUAT 875 924 0.706836 -12.2013 -5.8603 0.123978 -0.153743 -0.0753483 0.977402 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4241.09 -122.078 -1143.1 3948.07 114.241 4279.86 +EDGE_SE3:QUAT 876 926 1.36482 0.528865 -6.27459 0.093449 -0.0449176 -0.0351672 0.993988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.86 -15.7573 -316.293 3994.7 9.13813 4019.84 +EDGE_SE3:QUAT 875 926 0.469888 12.3619 -6.01477 0.16577 0.0988983 -0.0372157 0.980487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4068.7 70.7567 863.943 3960.02 26.8179 4173.08 +EDGE_SE3:QUAT 876 925 0.919986 -12.3226 -5.8857 -0.146011 -0.194071 -0.0065963 0.970038 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4554.55 169.359 -1723.29 3878.15 -146.295 4639.65 +EDGE_SE3:QUAT 877 927 1.59495 -0.203532 -6.20326 -0.0130806 0.0472033 -0.0959174 0.994183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.4 -7.13772 359.767 3992.66 -17.9618 3995.28 +EDGE_SE3:QUAT 876 927 0.331026 12.1616 -6.15474 -0.228703 0.0508309 0.070334 0.969621 1 2.40741e-19 2.40741e-19 -2.20417e-09 3.00586e-08 -7.45107e-09 1 2.40741e-19 -2.20417e-09 3.00586e-08 -7.45107e-09 1 -2.20417e-09 3.00586e-08 -7.45107e-09 3869.95 -66.2629 569.448 3980.06 -2.24765 4059.39 +EDGE_SE3:QUAT 877 926 0.314761 -12.2886 -5.65397 -0.056794 -0.0523589 -0.0383868 0.996273 1 4.81482e-20 4.81482e-20 -1.39114e-08 4.52403e-10 7.85377e-10 1 4.81482e-20 -1.39114e-08 4.52403e-10 7.85377e-10 1 -1.39114e-08 4.52403e-10 7.85377e-10 4036.42 10.5102 -446.974 3987.52 4.85712 4043.43 +EDGE_SE3:QUAT 878 928 1.52061 0.102355 -6.05305 0.081861 0.0189106 0.202864 0.975596 1 7.70372e-19 7.70372e-19 8.502e-10 -4.58576e-09 -5.41533e-08 1 7.70372e-19 8.502e-10 -4.58576e-09 -5.41533e-08 1 8.502e-10 -4.58576e-09 -5.41533e-08 3972.75 -5.05018 -52.3958 3999.06 -12.4424 3834.94 +EDGE_SE3:QUAT 877 928 0.844835 12.1865 -6.51934 0.0823034 0.012869 -0.0124236 0.996447 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.16 4.80349 114.184 3999.15 -0.347599 4002.64 +EDGE_SE3:QUAT 878 927 0.513774 -12.1368 -5.75185 0.0877131 0.0804595 -0.0981171 0.988031 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4106.14 17.4462 752.977 3965.36 -23.9045 4098.41 +EDGE_SE3:QUAT 879 929 1.77525 0.112964 -5.83474 -0.0736708 -0.137003 0.129722 0.979273 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4207.59 91.1227 -987.051 3960.5 -100.374 4161.99 +EDGE_SE3:QUAT 878 929 1.00201 12.3013 -6.44918 0.127411 -0.0620354 0.0376096 0.989193 1 7.82409e-19 7.82409e-19 -5.49397e-08 -2.03716e-09 -3.03828e-09 1 7.82409e-19 -5.49397e-08 -2.03716e-09 -3.03828e-09 1 -5.49397e-08 -2.03716e-09 -3.03828e-09 4009.13 -33.4533 -549.399 3981.82 2.7929 4068.4 +EDGE_SE3:QUAT 879 928 0.734783 -12.1247 -5.97222 0.0430165 -0.130265 -0.0338501 0.989967 1 9.62965e-20 9.62965e-20 1.60145e-08 -1.43187e-09 -1.60145e-08 1 9.62965e-20 1.60145e-08 -1.43187e-09 -1.60145e-08 1 1.60145e-08 -1.43187e-09 -1.60145e-08 4265.4 -41.6341 -1079.68 3937.53 39.7603 4268.21 +EDGE_SE3:QUAT 880 930 1.46162 -0.401473 -5.76793 0.0372373 -0.0990896 -0.0703691 0.991889 1 4.81482e-20 4.81482e-20 -1.40152e-08 1.11631e-09 1.30639e-09 1 4.81482e-20 -1.40152e-08 1.11631e-09 1.30639e-09 1 -1.40152e-08 1.11631e-09 1.30639e-09 4139.97 -31.7117 -776.852 3967.2 38.071 4125.71 +EDGE_SE3:QUAT 879 930 0.906425 12.3911 -6.53998 -0.280534 0.0889719 -0.0015954 0.95571 1 1.92593e-19 1.92593e-19 -1.38139e-09 -2.64903e-08 -7.90784e-09 1 1.92593e-19 -1.38139e-09 -2.64903e-08 -7.90784e-09 1 -1.38139e-09 -2.64903e-08 -7.90784e-09 3783.29 -92.1416 636.544 3988.09 -47.1622 4098.08 +EDGE_SE3:QUAT 880 929 0.928011 -12.5291 -5.86942 0.0403007 -0.0351881 -0.124565 0.990768 1 4.81482e-20 4.81482e-20 -1.37696e-08 1.76837e-09 3.33523e-10 1 4.81482e-20 -1.37696e-08 1.76837e-09 3.33523e-10 1 -1.37696e-08 1.76837e-09 3.33523e-10 4004.89 -6.40692 -215.094 3997.96 12.9269 3949.32 +EDGE_SE3:QUAT 881 931 1.74791 -0.325305 -6.33927 -0.0324605 -0.0812709 0.342468 0.935445 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.7 35.1462 -415.951 4002.23 -62.5841 3570.78 +EDGE_SE3:QUAT 880 931 1.1104 11.9763 -6.29798 0.156288 -0.0126852 0.11975 0.980343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3926.11 -27.3476 -316.442 3991.13 -19.1805 3966.45 +EDGE_SE3:QUAT 881 930 0.946601 -12.4677 -6.27119 -0.11332 -0.105285 0.0918889 0.983682 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4068.89 59.9007 -706.561 3979.24 -56.5679 4086.48 +EDGE_SE3:QUAT 882 932 1.6352 0.377161 -6.39701 0.0462558 0.0591384 -0.191499 0.978617 1 4.81482e-20 4.81482e-20 1.37158e-08 -2.61855e-09 1.00985e-09 1 4.81482e-20 1.37158e-08 -2.61855e-09 1.00985e-09 1 1.37158e-08 -2.61855e-09 1.00985e-09 4068.23 -7.15331 559.724 3981.77 -53.437 3930.1 +EDGE_SE3:QUAT 881 932 0.629383 12.1695 -6.09074 -0.135179 0.200932 -0.0619335 0.968255 1 1.92593e-19 1.92593e-19 -5.14319e-09 5.09908e-09 -2.87896e-08 1 1.92593e-19 -5.14319e-09 5.09908e-09 -2.87896e-08 1 -5.14319e-09 5.09908e-09 -2.87896e-08 4499.47 -211.154 1620.15 3909.84 -202.298 4557.22 +EDGE_SE3:QUAT 882 931 0.308156 -11.7653 -6.27818 -0.0226544 0.0241461 -0.0987362 0.994563 1 2.40741e-20 2.40741e-20 -6.21435e-09 7.5937e-09 5.39221e-11 1 2.40741e-20 -6.21435e-09 7.5937e-09 5.39221e-11 1 -6.21435e-09 7.5937e-09 5.39221e-11 4004.61 -2.8298 163.742 3998.61 -7.88108 3967.67 +EDGE_SE3:QUAT 883 933 1.35177 0.383885 -6.32006 0.0712617 0.150247 0.0997338 0.98102 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4290.06 100.172 1157.8 3941.13 105.104 4270.59 +EDGE_SE3:QUAT 882 933 0.492463 12.1783 -6.18797 -0.06151 0.197345 -0.0361343 0.977735 1 1.92593e-19 1.92593e-19 -2.93136e-08 1.93585e-09 -5.70444e-09 1 1.92593e-19 -2.93136e-08 1.93585e-09 -5.70444e-09 1 -2.93136e-08 1.93585e-09 -5.70444e-09 4647.26 -115.313 1757.49 3862.98 -111.503 4657.17 +EDGE_SE3:QUAT 883 932 0.416818 -12.2287 -5.4071 0.0670735 -0.0334461 0.0746776 0.994387 1 1.92593e-19 1.92593e-19 -2.76909e-08 -1.94161e-09 1.191e-09 1 1.92593e-19 -2.76909e-08 -1.94161e-09 1.191e-09 1 -2.76909e-08 -1.94161e-09 1.191e-09 4008.22 -8.95839 -325.313 3992.88 -10.5642 4003.9 +EDGE_SE3:QUAT 884 934 1.32869 0.556665 -6.08146 -0.129771 0.0345554 0.0114205 0.990876 1 4.81482e-20 4.81482e-20 2.99014e-11 -1.3752e-08 -1.7942e-09 1 4.81482e-20 2.99014e-11 -1.3752e-08 -1.7942e-09 1 2.99014e-11 -1.3752e-08 -1.7942e-09 3953.32 -18.8403 288.369 3995.06 -2.31443 4020.16 +EDGE_SE3:QUAT 883 934 0.629508 12.3289 -6.15704 0.0278693 -0.042413 0.0743291 0.995942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.66 -1.68974 -363.568 3991.7 -12.7151 4010.67 +EDGE_SE3:QUAT 884 933 0.558254 -12.4149 -6.10922 -0.0404164 -0.109617 -0.0987002 0.988235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4209.29 -10.2369 -953.9 3948.68 40.7436 4176.86 +EDGE_SE3:QUAT 885 935 1.17006 0.0205099 -6.18983 -0.0277275 0.0417571 -0.0774679 0.995734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.24 -7.03026 306.438 3994.75 -12.7081 3999.31 +EDGE_SE3:QUAT 884 935 1.13913 12.0179 -5.97646 -0.0401658 -0.0620961 -0.00866908 0.997224 1 4.81482e-20 4.81482e-20 -1.39483e-08 5.16871e-11 8.75417e-10 1 4.81482e-20 -1.39483e-08 5.16871e-11 8.75417e-10 1 -1.39483e-08 5.16871e-11 8.75417e-10 4056.72 9.7854 -506.625 3984.43 -1.53605 4062.87 +EDGE_SE3:QUAT 885 934 0.516717 -12.1357 -6.00634 -0.070926 0.0510466 0.0760843 0.993265 1 1.92593e-19 1.92593e-19 -2.77591e-08 -1.915e-09 -1.6977e-09 1 1.92593e-19 -2.77591e-08 -1.915e-09 -1.6977e-09 1 -2.77591e-08 -1.915e-09 -1.6977e-09 4034.79 -11.9845 472.172 3985.66 13.6986 4031.75 +EDGE_SE3:QUAT 886 936 1.59778 0.115626 -5.94762 -0.034895 -0.196615 0.0370198 0.97916 1 8.1852e-19 8.1852e-19 -1.3459e-10 5.51063e-08 -1.17473e-08 1 8.1852e-19 -1.3459e-10 5.51063e-08 -1.17473e-08 1 -1.3459e-10 5.51063e-08 -1.17473e-08 4670.08 84.4301 -1776.36 3855.74 -84.7588 4669.46 +EDGE_SE3:QUAT 885 936 1.01831 11.6848 -6.13643 0.0942159 0.153862 0.189431 0.965176 1 7.70372e-19 7.70372e-19 5.51093e-08 1.27531e-08 5.85974e-09 1 7.70372e-19 5.51093e-08 1.27531e-08 5.85974e-09 1 5.51093e-08 1.27531e-08 5.85974e-09 4183.57 127.427 970.433 3979.39 138.831 4075.54 +EDGE_SE3:QUAT 886 935 0.567356 -12.0548 -6.2665 -0.0386904 0.0198818 -0.122076 0.991567 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.36 -2.11107 99.1031 3999.67 -5.01411 3942.73 +EDGE_SE3:QUAT 887 937 1.60231 0.0547597 -5.88636 -0.109334 -0.0917401 0.0744539 0.986958 1 1.92593e-19 1.92593e-19 -2.0233e-09 -3.46943e-09 2.7727e-08 1 1.92593e-19 -2.0233e-09 -3.46943e-09 2.7727e-08 1 -2.0233e-09 -3.46943e-09 2.7727e-08 4048.2 46.765 -628.814 3982 -41.2835 4073.84 +EDGE_SE3:QUAT 886 937 0.538016 12.3163 -6.2366 -0.122216 -0.14691 0.0660903 0.979343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4223.56 109.897 -1103.23 3948.91 -100.409 4265.84 +EDGE_SE3:QUAT 887 936 0.895016 -12.1126 -5.80179 0.0882885 0.0180905 -0.100244 0.990873 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.74 10.5756 246.777 3995.28 -12.4915 3974.72 +EDGE_SE3:QUAT 888 938 1.68718 0.295238 -5.72181 0.0854151 -0.0492006 -0.178651 0.978962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3978.71 -9.11237 -191.832 3999.83 12.9785 3880.23 +EDGE_SE3:QUAT 887 938 0.600071 12.4133 -6.47623 0.0938998 0.102318 0.0500613 0.989044 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4107.72 50.2019 770.228 3969.89 42.193 4132.96 +EDGE_SE3:QUAT 888 937 0.472598 -12.272 -5.91941 -0.0168213 -0.124157 -0.0428329 0.991195 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4260.57 -6.91139 -1056.09 3937.8 19.6185 4254.37 +EDGE_SE3:QUAT 889 939 1.33089 -0.0551289 -6.25562 -0.101574 0.0041608 -0.085365 0.99115 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3959.68 5.28487 -70.4325 3999.31 4.41743 3971.8 +EDGE_SE3:QUAT 888 939 0.897933 12.495 -6.50837 0.170494 0.153041 -0.159375 0.960265 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4477.34 51.0651 1652.14 3864.82 -28.4343 4492.01 +EDGE_SE3:QUAT 889 938 0.522771 -12.0376 -6.04979 0.0988163 -0.079166 0.0221648 0.991704 1 3.00927e-21 3.00927e-21 -2.88164e-10 3.39264e-10 3.48717e-09 1 3.00927e-21 -2.88164e-10 3.39264e-10 3.48717e-09 1 -2.88164e-10 3.39264e-10 3.48717e-09 4068.73 -31.8191 -665.424 3974.13 8.12086 4105.83 +EDGE_SE3:QUAT 890 940 1.04198 -0.0799357 -5.89562 -0.0694775 0.0149027 0.0415154 0.996608 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.49 -5.38056 152.734 3998.36 2.86061 3998.9 +EDGE_SE3:QUAT 889 940 1.10825 11.9229 -6.21618 0.000108112 -0.0572511 -0.0326727 0.997825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4052.78 -2.63164 -462.505 3987.01 7.82065 4048.51 +EDGE_SE3:QUAT 890 939 0.810086 -12.2672 -5.88791 0.0918415 -0.0796711 0.148423 0.981422 1 1.92593e-19 1.92593e-19 -3.71462e-09 2.72981e-08 -1.82359e-09 1 1.92593e-19 -3.71462e-09 2.72981e-08 -1.82359e-09 1 -3.71462e-09 2.72981e-08 -1.82359e-09 4119.24 -9.44747 -797.845 3961.24 -47.6555 4064.86 +EDGE_SE3:QUAT 891 941 1.21947 -0.0533005 -6.31527 -0.132084 -0.135251 -0.0123116 0.981891 1 7.52316e-22 7.52316e-22 2.40722e-10 2.40793e-10 -1.76803e-09 1 7.52316e-22 2.40722e-10 2.40793e-10 -1.76803e-09 1 2.40722e-10 2.40793e-10 -1.76803e-09 4234.41 84.4169 -1144.33 3934.29 -54.7855 4303.59 +EDGE_SE3:QUAT 890 941 0.928615 12.1909 -6.35804 0.181238 -0.0289063 0.0859725 0.979248 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3908.35 -38.1111 -403.648 3987.98 -10.9276 4010.17 +EDGE_SE3:QUAT 891 940 0.398266 -12.1889 -6.19912 0.0193856 0.0881104 -0.167549 0.981727 1 3.00927e-21 3.00927e-21 3.46275e-09 -5.88181e-10 3.15858e-10 1 3.00927e-21 3.46275e-09 -5.88181e-10 3.15858e-10 1 3.46275e-09 -5.88181e-10 3.15858e-10 4128.98 -25.8285 734.16 3971.63 -63.1571 4018.19 +EDGE_SE3:QUAT 892 942 1.26212 0.181631 -6.18526 0.0678877 -0.0126386 -0.0168756 0.99747 1 1.20371e-20 1.20371e-20 -7.09898e-11 4.73999e-10 6.92297e-09 1 1.20371e-20 -7.09898e-11 4.73999e-10 6.92297e-09 1 -7.09898e-11 4.73999e-10 6.92297e-09 3983.44 -2.83413 -86.6941 3999.59 0.897912 4000.73 +EDGE_SE3:QUAT 891 942 0.675192 12.3557 -6.11495 -0.0482146 0.305465 0.197235 0.930304 1 1.08334e-19 1.08334e-19 -2.38641e-08 -5.36837e-09 -7.65826e-09 1 1.08334e-19 -2.38641e-08 -5.36837e-09 -7.65826e-09 1 -2.38641e-08 -5.36837e-09 -7.65826e-09 5972.47 559.942 3443.74 3751.9 542.86 5826.16 +EDGE_SE3:QUAT 892 941 0.51889 -12.3248 -5.82925 -0.0826759 -0.108599 -0.224282 0.964919 1 8.1852e-19 8.1852e-19 2.15118e-08 -1.39605e-09 -5.73628e-08 1 8.1852e-19 2.15118e-08 -1.39605e-09 -5.73628e-08 1 2.15118e-08 -1.39605e-09 -5.73628e-08 4244.28 -36.7247 -1077.41 3940.35 112.58 4070.41 +EDGE_SE3:QUAT 893 943 1.61331 -0.294393 -6.34634 -0.082399 0.014082 0.153133 0.984664 1 1.55278e-18 1.55278e-18 -5.36864e-08 -5.58004e-09 5.31688e-08 1 1.55278e-18 -5.36864e-08 -5.58004e-09 5.31688e-08 1 -5.36864e-08 -5.58004e-09 5.31688e-08 3988.81 -9.72546 257.049 3994.5 21.9594 3922.17 +EDGE_SE3:QUAT 892 943 0.848671 12.255 -6.25183 0.193346 0.0185914 0.0183017 0.980784 1 3.00927e-21 3.00927e-21 -8.32484e-11 3.40235e-09 -6.72961e-10 1 3.00927e-21 -8.32484e-11 3.40235e-09 -6.72961e-10 1 -8.32484e-11 3.40235e-09 -6.72961e-10 3852.83 8.0327 99.0173 3999.71 1.64145 4001.02 +EDGE_SE3:QUAT 893 942 0.679563 -12.7316 -6.1514 0.00629709 -0.0260937 -0.0686661 0.997279 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.07 -1.70794 -202.531 3997.56 7.02351 3991.37 +EDGE_SE3:QUAT 894 944 1.44929 -0.00496118 -6.27458 -0.0409345 -0.0447455 0.018875 0.997981 1 1.20371e-20 1.20371e-20 -2.99586e-10 -2.97829e-10 6.95118e-09 1 1.20371e-20 -2.99586e-10 -2.97829e-10 6.95118e-09 1 -2.99586e-10 -2.97829e-10 6.95118e-09 4023.67 8.11141 -349.868 3992.67 -5.23505 4028.94 +EDGE_SE3:QUAT 893 944 0.821721 12.0667 -6.13922 0.0125441 0.169659 0.0167399 0.985281 1 7.82409e-19 7.82409e-19 -6.01974e-09 -5.48515e-08 -1.7639e-10 1 7.82409e-19 -6.01974e-09 -5.48515e-08 -1.7639e-10 1 -6.01974e-09 -5.48515e-08 -1.7639e-10 4500.01 25.618 1501.07 3886.15 26.4081 4499.52 +EDGE_SE3:QUAT 894 943 0.961766 -12.1679 -5.97654 -0.108327 -0.0504919 -0.243859 0.962418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.67 7.72264 -683.8 3969.29 83.009 3874.74 +EDGE_SE3:QUAT 895 945 1.40361 -0.256881 -6.28009 -0.168463 0.00386832 0.146826 0.974704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3909.61 -31.5735 317.52 3989.86 26.5214 3936.9 +EDGE_SE3:QUAT 894 945 0.906216 12.0065 -6.01019 0.0270595 -0.157768 0.0262219 0.986757 1 1.20371e-20 1.20371e-20 -7.20994e-09 -1.36585e-10 1.16036e-09 1 1.20371e-20 -7.20994e-09 -1.36585e-10 1.16036e-09 1 -7.20994e-09 -1.36585e-10 1.16036e-09 4431.85 -5.97847 -1388.58 3899.41 -4.66755 4432.03 +EDGE_SE3:QUAT 895 944 0.232185 -12.0141 -6.09174 0.136851 0.0812731 -0.122815 0.979583 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4097.74 37.6438 849.999 3955.42 -27.2778 4112.32 +EDGE_SE3:QUAT 896 946 1.46171 0.414146 -5.8411 0.043512 0.108796 -0.13403 0.984026 1 7.82409e-19 7.82409e-19 3.83466e-10 -1.68323e-09 -5.52927e-08 1 7.82409e-19 3.83466e-10 -1.68323e-09 -5.52927e-08 1 3.83466e-10 -1.68323e-09 -5.52927e-08 4210.59 -20.3078 959.31 3949.35 -59.6636 4146.3 +EDGE_SE3:QUAT 895 946 0.268092 12.538 -6.36546 0.139322 -0.307968 0.17619 0.924501 1 1.92593e-19 1.92593e-19 3.29968e-08 4.04654e-09 -1.18616e-08 1 1.92593e-19 3.29968e-08 4.04654e-09 -1.18616e-08 1 3.29968e-08 4.04654e-09 -1.18616e-08 6436.35 181.225 -4046.78 3585.17 -159.812 6389.82 +EDGE_SE3:QUAT 896 945 0.604794 -12.4825 -6.06359 0.0319549 0.140341 0.0339109 0.989006 1 4.81482e-20 4.81482e-20 1.42714e-08 6.41409e-10 1.98314e-09 1 4.81482e-20 1.42714e-08 6.41409e-10 1.98314e-09 1 1.42714e-08 6.41409e-10 1.98314e-09 4319.72 39.9645 1183.27 3925.77 40.3625 4319.2 +EDGE_SE3:QUAT 897 947 1.17349 0.13968 -6.26941 -0.0540893 -0.0835908 0.021899 0.99479 1 4.81482e-20 4.81482e-20 -1.39913e-08 -4.38763e-10 1.13371e-09 1 4.81482e-20 -1.39913e-08 -4.38763e-10 1.13371e-09 1 -1.39913e-08 -4.38763e-10 1.13371e-09 4096.32 22.7952 -666.181 3974.51 -16.7556 4106.1 +EDGE_SE3:QUAT 896 947 0.296331 11.8805 -6.35605 0.0784138 -0.155223 0.0839808 0.981175 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4434.3 -12.5759 -1430.51 3894.01 -21.6766 4430.68 +EDGE_SE3:QUAT 897 946 0.816554 -12.0127 -6.02928 -0.0438524 -0.0019399 -0.118332 0.992003 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.68 1.9596 -76.7861 3999.42 5.70003 3945.37 +EDGE_SE3:QUAT 898 948 1.4876 -0.232049 -5.91477 -0.232788 0.223038 0.0228272 0.946331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4613.97 -326.857 2005.08 3892.05 -302.846 4828.65 +EDGE_SE3:QUAT 897 948 0.296854 12.227 -6.35387 0.174185 -0.0504372 0.11424 0.976762 1 7.70372e-19 7.70372e-19 5.48841e-08 5.10168e-09 -4.79218e-09 1 7.70372e-19 5.48841e-08 5.10168e-09 -4.79218e-09 1 5.48841e-08 5.10168e-09 -4.79218e-09 3973.09 -48.8038 -624.601 3973.4 -19.5163 4042.25 +EDGE_SE3:QUAT 898 947 0.709396 -12.2945 -6.12491 -0.0259132 0.0905683 0.0243643 0.995255 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4134.29 -5.57021 752.773 3966.53 4.6123 4134.6 +EDGE_SE3:QUAT 899 949 1.25632 -0.272475 -6.21219 0.00822879 -0.0291209 -0.218543 0.975358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.22 -4.24831 -195.902 3998.47 20.2853 3818.45 +EDGE_SE3:QUAT 898 949 0.710905 12.664 -6.17183 0.191594 -0.168264 0.119883 0.959483 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4511.66 -114.4 -1751.78 3858.08 47.4586 4601.01 +EDGE_SE3:QUAT 899 948 0.502545 -12.2815 -5.92052 -0.149308 -0.167173 -0.122455 0.966832 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4533.22 57.8046 -1696.49 3860.74 0.347454 4562.41 +EDGE_SE3:QUAT 900 950 1.42807 0.191939 -6.4366 -0.0235547 0.0250951 0.191082 0.98097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.5 0.934956 243.267 3996.38 24.3079 3868.67 +EDGE_SE3:QUAT 899 950 0.572531 12.4559 -6.23557 0.0507918 -0.0655953 0.167097 0.982444 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4081.77 5.22993 -614.122 3977.65 -49.5328 3980.41 +EDGE_SE3:QUAT 900 949 0.514168 -12.2336 -6.24115 -0.0974998 -0.0679582 -0.0264194 0.992561 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4043.4 26.7137 -576.518 3980.13 -3.75301 4078.64 +EDGE_SE3:QUAT 901 951 1.08585 -0.121204 -6.02577 -0.0541675 0.0450668 -0.134772 0.988368 1 8.66668e-19 8.66668e-19 1.34081e-08 -1.9229e-08 5.44891e-08 1 8.66668e-19 1.34081e-08 -1.9229e-08 5.44891e-08 1 1.34081e-08 -1.9229e-08 5.44891e-08 4005.21 -10.4829 263.353 3997.25 -17.4491 3944.29 +EDGE_SE3:QUAT 900 951 0.632449 12.2639 -6.26144 -0.0213242 -0.00802252 -0.0364319 0.999076 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.52 0.745633 -73.3436 3999.64 1.35197 3996.03 +EDGE_SE3:QUAT 901 950 0.430897 -12.1916 -6.15198 0.0624972 -0.0778158 0.0200616 0.994805 1 2.40741e-19 2.40741e-19 -1.42694e-08 2.74699e-08 -5.47947e-10 1 2.40741e-19 -1.42694e-08 2.74699e-08 -5.47947e-10 1 -1.42694e-08 2.74699e-08 -5.47947e-10 4086.7 -18.5939 -647.911 3974.98 2.6843 4100.72 +EDGE_SE3:QUAT 902 952 1.26991 0.324365 -5.74588 -0.0659986 -0.0906602 -0.15208 0.981986 1 1.15556e-18 1.15556e-18 2.57832e-08 2.121e-08 5.37146e-08 1 1.15556e-18 2.57832e-08 2.121e-08 5.37146e-08 1 2.57832e-08 2.121e-08 5.37146e-08 4154.57 -6.64629 -847.348 3958.56 56.7046 4079.48 +EDGE_SE3:QUAT 901 952 0.594611 12.434 -5.98001 0.0358172 -0.151475 0.109823 0.981688 1 1.20371e-20 1.20371e-20 7.15802e-09 7.56696e-10 -1.13406e-09 1 1.20371e-20 7.15802e-09 7.56696e-10 -1.13406e-09 1 7.15802e-09 7.56696e-10 -1.13406e-09 4406.61 40.2816 -1347.77 3907.55 -70.3196 4363.5 +EDGE_SE3:QUAT 902 951 0.377448 -12.0745 -5.87959 -0.0442364 0.031565 -0.182935 0.981622 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997 -4.35389 144.354 3999.59 -10.3739 3870.96 +EDGE_SE3:QUAT 903 953 1.54623 0.0602836 -6.245 0.0346685 0.0557663 0.0292682 0.997412 1 4.81482e-20 4.81482e-20 -1.39234e-08 -4.64262e-10 -7.4673e-10 1 4.81482e-20 -1.39234e-08 -4.64262e-10 -7.4673e-10 1 -1.39234e-08 -4.64262e-10 -7.4673e-10 4042.36 9.84944 436.943 3988.68 9.03464 4043.74 +EDGE_SE3:QUAT 902 953 0.786815 12.2414 -6.29771 -0.122879 -0.100119 0.103315 0.981938 1 1.92593e-19 1.92593e-19 -1.94494e-09 -4.01946e-09 2.75873e-08 1 1.92593e-19 -1.94494e-09 -4.01946e-09 2.75873e-08 1 -1.94494e-09 -4.01946e-09 2.75873e-08 4035.01 55.5252 -629.226 3985.32 -52.7903 4052.71 +EDGE_SE3:QUAT 903 952 0.622746 -12.1015 -5.65119 -0.049173 0.210315 -0.2378 0.946996 1 3.08149e-18 3.08149e-18 1.87005e-08 -1.78708e-08 1.12149e-07 1 3.08149e-18 1.87005e-08 -1.78708e-08 1.12149e-07 1 1.87005e-08 -1.78708e-08 1.12149e-07 4500.71 -277.819 1526.18 3967.03 -292.321 4284.18 +EDGE_SE3:QUAT 904 954 1.23637 0.324018 -6.12389 0.0242771 0.0305243 -0.0772612 0.996248 1 6.01853e-20 6.01853e-20 7.98072e-09 1.32998e-08 -3.26917e-11 1 6.01853e-20 7.98072e-09 1.32998e-08 -3.26917e-11 1 7.98072e-09 1.32998e-08 -3.26917e-11 4015.15 1.3643 265.279 3995.51 -9.99844 3993.63 +EDGE_SE3:QUAT 903 954 0.771697 12.2255 -6.30234 -0.131472 -0.163178 -0.0339453 0.977208 1 7.73381e-19 7.73381e-19 -1.14909e-09 5.38082e-08 1.06619e-08 1 7.73381e-19 -1.14909e-09 5.38082e-08 1.06619e-08 1 -1.14909e-09 5.38082e-08 1.06619e-08 4408.93 99.5553 -1463.16 3897.12 -67.2225 4473.46 +EDGE_SE3:QUAT 904 953 0.475119 -12.0902 -6.28102 -0.0427159 -0.0444509 -0.011995 0.998026 1 9.62965e-20 9.62965e-20 -1.37933e-08 1.39651e-08 1.2115e-09 1 9.62965e-20 -1.37933e-08 1.39651e-08 1.2115e-09 1 -1.37933e-08 1.39651e-08 1.2115e-09 4025.43 7.37246 -363.312 3991.85 0.141642 4032.16 +EDGE_SE3:QUAT 905 955 1.72066 0.21213 -6.4512 0.0893193 -0.190876 -0.0149757 0.977427 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4586.22 -119.429 -1689.69 3872.42 107.663 4617.23 +EDGE_SE3:QUAT 904 955 0.280604 11.7591 -5.82855 0.201623 -0.0864818 0.101968 0.970294 1 7.70372e-19 7.70372e-19 -5.52721e-08 -3.47345e-09 6.74808e-09 1 7.70372e-19 -5.52721e-08 -3.47345e-09 6.74808e-09 1 -5.52721e-08 -3.47345e-09 6.74808e-09 4039.72 -80.8022 -923.182 3950.36 2.35894 4160.73 +EDGE_SE3:QUAT 905 954 0.48398 -12.4202 -6.25344 -0.199084 -0.136241 0.0724797 0.967756 1 9.62965e-19 9.62965e-19 -5.83816e-08 1.97148e-08 1.15184e-08 1 9.62965e-19 -5.83816e-08 1.97148e-08 1.15184e-08 1 -5.83816e-08 1.97148e-08 1.15184e-08 4020.71 115.704 -872.356 3979.98 -98.595 4158.23 +EDGE_SE3:QUAT 906 956 1.12604 -0.288757 -6.17678 -0.0440022 0.0227123 0.0981696 0.993937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.47 -3.68345 230.746 3996.33 11.4048 3974.66 +EDGE_SE3:QUAT 905 956 0.41792 12.6579 -6.03767 0.184335 -0.151755 0.18774 0.952756 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4507.31 -42.9939 -1729.43 3854.12 -50.4239 4502.24 +EDGE_SE3:QUAT 906 955 0.970712 -12.4339 -6.09239 -0.0108919 -0.0980279 -0.11794 0.98811 1 1.17549e-23 1.17549e-23 -2.18509e-10 2.61169e-11 2.16356e-11 1 1.17549e-23 -2.18509e-10 2.61169e-11 2.16356e-11 1 -2.18509e-10 2.61169e-11 2.16356e-11 4157.42 -23.7949 -810.263 3963.97 50.0499 4102.25 +EDGE_SE3:QUAT 907 957 1.25642 -0.0312295 -6.23863 -0.0141999 -0.150991 0.0586026 0.986694 1 1.20371e-20 1.20371e-20 -7.16519e-09 -4.77778e-10 1.07533e-09 1 1.20371e-20 -7.16519e-09 -4.77778e-10 1.07533e-09 1 -7.16519e-09 -4.77778e-10 1.07533e-09 4378.52 46.4177 -1288.9 3914.45 -55.2298 4365.59 +EDGE_SE3:QUAT 906 957 0.732313 12.3818 -6.42 0.175999 -0.0676672 0.109395 0.97595 1 1.92593e-19 1.92593e-19 -2.82492e-09 4.49788e-09 2.75699e-08 1 1.92593e-19 -2.82492e-09 4.49788e-09 2.75699e-08 1 -2.82492e-09 4.49788e-09 2.75699e-08 4014.06 -56.522 -757.332 3963.61 -14.5454 4090.1 +EDGE_SE3:QUAT 907 956 0.584551 -12.3228 -5.94397 0.0879393 0.179285 -0.02444 0.979554 1 3.00927e-21 3.00927e-21 6.71109e-10 3.14739e-10 3.63711e-09 1 3.00927e-21 6.71109e-10 3.14739e-10 3.63711e-09 1 6.71109e-10 3.14739e-10 3.63711e-09 4545.84 74.3327 1624.73 3873.44 54.131 4574.38 +EDGE_SE3:QUAT 908 958 1.27062 -0.224048 -6.18355 -0.154484 -0.0903693 0.108617 0.97784 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3961.71 45.9655 -490.104 3993.87 -41.0741 4009.98 +EDGE_SE3:QUAT 907 958 1.05194 12.3495 -6.71558 -0.147494 0.0288135 0.0428023 0.987716 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3935.06 -22.6499 298.621 3994.04 2.45903 4014.75 +EDGE_SE3:QUAT 908 957 0.64721 -12.1488 -5.86336 0.0708556 -0.0348122 -0.116729 0.990021 1 1.92593e-19 1.92593e-19 -4.74614e-10 2.14225e-09 2.75035e-08 1 1.92593e-19 -4.74614e-10 2.14225e-09 2.75035e-08 1 -4.74614e-10 2.14225e-09 2.75035e-08 3987.02 -6.59301 -172.739 3999.06 9.10034 3952.6 +EDGE_SE3:QUAT 909 959 1.14019 0.140639 -5.99342 -0.0283699 0.0141561 0.057278 0.997855 1 1.20371e-20 1.20371e-20 3.91439e-10 -6.92435e-09 -1.84427e-10 1 1.20371e-20 3.91439e-10 -6.92435e-09 -1.84427e-10 1 3.91439e-10 -6.92435e-09 -1.84427e-10 4001.13 -1.61594 132.14 3998.82 3.79913 3991.23 +EDGE_SE3:QUAT 908 959 0.684179 12.4042 -6.28976 -0.151947 -0.0758609 0.0405916 0.984637 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.21 43.337 -517.77 3988 -27.0529 4058.97 +EDGE_SE3:QUAT 909 958 0.429258 -11.995 -5.70113 0.144798 0.0572253 -0.132228 0.978915 1 1.92593e-19 1.92593e-19 2.55391e-09 3.54739e-09 2.75543e-08 1 1.92593e-19 2.55391e-09 3.54739e-09 2.75543e-08 1 2.55391e-09 3.54739e-09 2.75543e-08 4025.99 36.8987 674.306 3969.53 -30.1264 4039.92 +EDGE_SE3:QUAT 910 960 1.41575 -0.100197 -5.75137 0.177157 -0.237166 -0.114039 0.948347 1 7.70372e-19 7.70372e-19 5.67699e-08 -1.24425e-08 -1.00777e-08 1 7.70372e-19 5.67699e-08 -1.24425e-08 -1.00777e-08 1 5.67699e-08 -1.24425e-08 -1.00777e-08 4482.58 -348.991 -1685.99 3972.45 347.179 4556.1 +EDGE_SE3:QUAT 909 960 0.490214 12.0442 -6.14597 -0.0255141 -0.0929508 -0.000492334 0.995344 1 1.20371e-20 1.20371e-20 7.02791e-09 3.03875e-11 -6.55617e-10 1 1.20371e-20 7.02791e-09 3.03875e-11 -6.55617e-10 1 7.02791e-09 3.03875e-11 -6.55617e-10 4139.07 10.5566 -766.018 3965.61 -5.30757 4141.68 +EDGE_SE3:QUAT 910 959 0.670556 -12.7156 -5.6985 0.231287 -0.120444 0.06497 0.963213 1 7.70372e-19 7.70372e-19 -5.5531e-08 -2.59535e-10 7.86757e-09 1 7.70372e-19 -5.5531e-08 -2.59535e-10 7.86757e-09 1 -5.5531e-08 -2.59535e-10 7.86757e-09 4083.29 -129.141 -1130.23 3939.72 60.5801 4280.38 +EDGE_SE3:QUAT 911 961 1.49606 0.185548 -6.35364 -0.0570149 -0.126683 0.00765076 0.990274 1 3.00927e-21 3.00927e-21 -4.47479e-10 -2.1808e-10 3.54759e-09 1 3.00927e-21 -4.47479e-10 -2.1808e-10 3.54759e-09 1 -4.47479e-10 -2.1808e-10 3.54759e-09 4250.79 38.4033 -1060.56 3938.74 -28.1271 4263.56 +EDGE_SE3:QUAT 910 961 0.568167 12.4376 -6.43528 -0.0871498 -0.0960111 0.0281392 0.991158 1 8.1852e-19 8.1852e-19 5.72173e-08 3.8741e-09 -1.90346e-08 1 8.1852e-19 5.72173e-08 3.8741e-09 -1.90346e-08 1 5.72173e-08 3.8741e-09 -1.90346e-08 4105.53 41.1378 -749.93 3969.64 -29.9395 4132.74 +EDGE_SE3:QUAT 911 960 0.753066 -12.2619 -6.17806 -0.0549246 -0.0058819 -0.0564884 0.996874 1 5.11575e-20 5.11575e-20 -1.403e-08 -2.68828e-09 -2.05661e-11 1 5.11575e-20 -1.403e-08 -2.68828e-09 -2.05661e-11 1 -1.403e-08 -2.68828e-09 -2.05661e-11 3989.65 2.51698 -83.7327 3999.43 2.59545 3988.95 +EDGE_SE3:QUAT 912 962 1.16196 -0.278554 -6.42122 -0.0369604 -0.118421 -0.0295188 0.991836 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4234.1 10.6568 -1007.8 3942.58 3.59138 4236.08 +EDGE_SE3:QUAT 911 962 0.381776 12.0737 -6.33745 -0.0955024 0.0820297 0.134029 0.982948 1 7.70372e-19 7.70372e-19 5.84664e-09 -4.05268e-09 5.56571e-08 1 7.70372e-19 5.84664e-09 -4.05268e-09 5.56571e-08 1 5.84664e-09 -4.05268e-09 5.56571e-08 4121.38 -13.8986 810.875 3959.95 40.4948 4086.01 +EDGE_SE3:QUAT 912 961 0.234939 -12.3052 -6.17913 -0.00248853 0.128764 0.119972 0.984388 1 7.70372e-19 7.70372e-19 -6.84951e-09 5.46211e-08 -1.60688e-09 1 7.70372e-19 -6.84951e-09 5.46211e-08 -1.60688e-09 1 -6.84951e-09 5.46211e-08 -1.60688e-09 4268.32 49.0555 1070.31 3941.44 74.0774 4210.77 +EDGE_SE3:QUAT 913 963 1.17614 0.391263 -6.24461 -0.0187428 -0.0161908 0.0827029 0.996266 1 1.92593e-19 1.92593e-19 3.57265e-10 5.87655e-10 -2.76624e-08 1 1.92593e-19 3.57265e-10 5.87655e-10 -2.76624e-08 1 3.57265e-10 5.87655e-10 -2.76624e-08 4001.59 1.37256 -109.679 3999.36 -4.36171 3975.63 +EDGE_SE3:QUAT 912 963 0.295246 12.5499 -6.51854 -0.00881595 -0.117314 -0.0254616 0.992729 1 7.52316e-22 7.52316e-22 1.77107e-09 -4.29384e-11 -2.09809e-10 1 7.52316e-22 1.77107e-09 -4.29384e-11 -2.09809e-10 1 1.77107e-09 -4.29384e-11 -2.09809e-10 4230.22 -4.03471 -987.565 3944.81 11.2988 4227.94 +EDGE_SE3:QUAT 913 962 0.599931 -12.5947 -6.09826 0.125784 0.0262162 0.0414988 0.990842 1 7.70372e-19 7.70372e-19 -5.50372e-08 -2.59798e-09 -8.2944e-10 1 7.70372e-19 -5.50372e-08 -2.59798e-09 -8.2944e-10 1 -5.50372e-08 -2.59798e-09 -8.2944e-10 3941.63 7.95378 142.384 3999.24 3.6701 3998.03 +EDGE_SE3:QUAT 914 964 1.39332 0.134101 -6.17223 -0.0113953 0.20826 -0.0864714 0.974177 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4759.28 -124.426 1901.82 3845.96 -134.645 4729.89 +EDGE_SE3:QUAT 913 964 0.303168 12.302 -5.84048 0.0136563 -0.196151 -0.071727 0.977851 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4668.03 -95.2703 -1767.08 3859.3 104.228 4648.19 +EDGE_SE3:QUAT 914 963 0.44768 -12.4412 -5.54315 0.0108803 0.00120533 -0.221814 0.975028 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.85 0.170685 36.9499 3999.88 -5.13645 3803.52 +EDGE_SE3:QUAT 915 965 1.15985 0.164149 -6.09838 -0.0476729 -0.128366 -0.0912911 0.986365 1 8.1852e-19 8.1852e-19 -9.66318e-09 5.59753e-08 3.30367e-09 1 8.1852e-19 -9.66318e-09 5.59753e-08 3.30367e-09 1 -9.66318e-09 5.59753e-08 3.30367e-09 4290.09 -9.50996 -1134.15 3929.57 40.0753 4265.85 +EDGE_SE3:QUAT 914 965 0.541448 12.2588 -6.30453 -0.182651 0.04125 0.129449 0.973745 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3951.39 -50.091 593.014 3974.59 25.5918 4017.8 +EDGE_SE3:QUAT 915 964 0.257448 -12.6102 -5.80039 -0.0552678 -0.016306 -0.0649404 0.996224 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.14 4.51319 -172.206 3997.88 5.51302 3990.49 +EDGE_SE3:QUAT 916 966 1.45657 -0.146484 -5.9177 -0.12943 -0.0532211 0.0342468 0.989567 1 7.70372e-19 7.70372e-19 -5.51603e-08 -2.61854e-09 2.36676e-09 1 7.70372e-19 -5.51603e-08 -2.61854e-09 2.36676e-09 1 -5.51603e-08 -2.61854e-09 2.36676e-09 3965.69 24.5942 -363.975 3993.55 -13.0004 4028 +EDGE_SE3:QUAT 915 966 0.512063 12.244 -6.1439 0.120219 0.0864532 -0.165734 0.97499 1 7.70372e-19 7.70372e-19 6.77611e-09 4.97189e-09 5.55352e-08 1 7.70372e-19 6.77611e-09 4.97189e-09 5.55352e-08 1 6.77611e-09 4.97189e-09 5.55352e-08 4145.82 18.1652 926.564 3948.14 -56.2368 4093.76 +EDGE_SE3:QUAT 916 965 0.3254 -11.9642 -6.43722 -0.129121 -0.0070085 -0.112634 0.985186 1 9.75002e-19 9.75002e-19 5.45365e-08 -2.5717e-09 2.62892e-08 1 9.75002e-19 5.45365e-08 -2.5717e-09 2.62892e-08 1 5.45365e-08 -2.5717e-09 2.62892e-08 3945.27 16.8114 -225.439 3995.22 14.2527 3961.21 +EDGE_SE3:QUAT 917 967 1.50418 0.28541 -6.29473 -0.116037 0.166918 -0.0452336 0.978073 1 7.70372e-19 7.70372e-19 5.70648e-08 -5.051e-09 8.76774e-09 1 7.70372e-19 5.70648e-08 -5.051e-09 8.76774e-09 1 5.70648e-08 -5.051e-09 8.76774e-09 4356.63 -128.843 1346.36 3921.86 -116.946 4402.3 +EDGE_SE3:QUAT 916 967 0.612872 12.4523 -6.25141 -0.10799 0.0434241 -0.0341813 0.992615 1 4.81482e-20 4.81482e-20 -4.86218e-10 1.54566e-09 -1.38136e-08 1 4.81482e-20 -4.86218e-10 1.54566e-09 -1.38136e-08 1 -4.86218e-10 1.54566e-09 -1.38136e-08 3975.34 -16.6714 298.01 3995.47 -8.77586 4017.32 +EDGE_SE3:QUAT 917 966 0.426932 -12.0041 -5.84336 -0.0244474 -0.0101071 -0.136512 0.990285 1 3.00927e-21 3.00927e-21 4.71524e-10 3.43603e-09 7.22026e-11 1 3.00927e-21 4.71524e-10 3.43603e-09 7.22026e-11 1 4.71524e-10 3.43603e-09 7.22026e-11 4001.07 0.976629 -118.176 3998.99 8.82608 3928.91 +EDGE_SE3:QUAT 918 968 1.29034 -0.0730129 -6.3358 -0.098519 0.0479184 -0.00491183 0.993969 1 2.40741e-19 2.40741e-19 2.75112e-08 -1.41905e-08 -9.7085e-11 1 2.40741e-19 2.75112e-08 -1.41905e-08 -9.7085e-11 1 2.75112e-08 -1.41905e-08 -9.7085e-11 3995.98 -18.9706 374.772 3991.89 -6.19453 4034.71 +EDGE_SE3:QUAT 917 968 0.631731 12.3274 -6.22299 0.0317263 0.142579 -0.0278942 0.988882 1 1.20371e-20 1.20371e-20 -1.0416e-09 -1.79691e-10 -7.1573e-09 1 1.20371e-20 -1.0416e-09 -1.79691e-10 -7.1573e-09 1 -1.0416e-09 -1.79691e-10 -7.1573e-09 4347.46 8.72354 1236.72 3917.48 -3.73362 4348.37 +EDGE_SE3:QUAT 918 967 0.571904 -12.2673 -5.83755 -0.049349 -0.0772417 -0.0824943 0.992367 1 1.92593e-19 1.92593e-19 -2.36458e-09 -1.02681e-09 2.79255e-08 1 1.92593e-19 -2.36458e-09 -1.02681e-09 2.79255e-08 1 -2.36458e-09 -1.02681e-09 2.79255e-08 4100.96 4.57986 -674.687 3972.48 22.1957 4083.48 +EDGE_SE3:QUAT 919 969 1.25376 0.0557851 -6.32863 -0.0227222 0.0826157 -0.00587446 0.996305 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4108.67 -9.19771 674.679 3973.01 -5.95069 4110.59 +EDGE_SE3:QUAT 918 969 0.70173 12.1158 -5.96909 -0.000561297 -0.024404 0.219227 0.975368 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.08 2.8831 -180.201 3998.53 -19.2915 3815.84 +EDGE_SE3:QUAT 919 968 0.00918247 -12.6811 -5.79188 -0.15563 0.0294112 -0.209492 0.964898 1 7.70372e-19 7.70372e-19 -5.35802e-08 1.1557e-08 2.08533e-09 1 7.70372e-19 -5.35802e-08 1.1557e-08 2.08533e-09 1 -5.35802e-08 1.1557e-08 2.08533e-09 3905.57 23.0639 -161.945 3994.37 31.2414 3826.9 +EDGE_SE3:QUAT 920 970 1.0647 -0.263506 -6.1251 0.0321642 -0.0390094 -0.00244786 0.998718 1 1.88079e-22 1.88079e-22 3.37294e-11 -2.82339e-11 -8.68873e-10 1 1.88079e-22 3.37294e-11 -2.82339e-11 -8.68873e-10 1 3.37294e-11 -2.82339e-11 -8.68873e-10 4020.1 -5.184 -312.285 3994.01 1.5632 4024.21 +EDGE_SE3:QUAT 919 970 0.500997 12.5527 -6.38994 0.0550399 -0.0103567 0.116462 0.991615 1 6.01853e-20 6.01853e-20 1.45678e-08 -5.28962e-09 3.94528e-11 1 6.01853e-20 1.45678e-08 -5.28962e-09 3.94528e-11 1 1.45678e-08 -5.28962e-09 3.94528e-11 3993.91 -4.15308 -157.121 3998 -10.2158 3951.77 +EDGE_SE3:QUAT 920 969 0.554358 -12.1444 -5.9547 0.128957 0.0842578 -0.249342 0.956086 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4179.7 -4.17178 1024.73 3939.53 -112.992 3997.54 +EDGE_SE3:QUAT 921 971 1.15714 0.480595 -5.68231 0.0180518 0.0229887 0.0958489 0.994967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.14 2.38274 160.856 3998.61 7.55911 3969.69 +EDGE_SE3:QUAT 920 971 0.345044 12.5645 -6.37001 0.0856978 0.180801 0.0894293 0.975689 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4437.61 150.462 1445.63 3916.4 151.02 4434.99 +EDGE_SE3:QUAT 921 970 0.38905 -12.2331 -5.95808 -0.136054 0.0630431 0.106894 0.982898 1 9.62965e-19 9.62965e-19 5.29041e-08 3.22278e-08 8.32737e-09 1 9.62965e-19 5.29041e-08 3.22278e-08 8.32737e-09 1 5.29041e-08 3.22278e-08 8.32737e-09 4035.08 -35.6283 670.964 3970.88 20.0966 4063.42 +EDGE_SE3:QUAT 922 972 1.24388 0.0710835 -6.02347 -0.0596461 -0.141587 0.0369772 0.987435 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4303.94 60.5128 -1172.24 3929.42 -56.0257 4312.7 +EDGE_SE3:QUAT 921 972 0.378058 12.4685 -6.41501 0.213511 0.120609 0.182157 0.9522 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3846.23 43.674 400.043 4007.71 43.3971 3895.85 +EDGE_SE3:QUAT 922 971 0.144876 -12.211 -6.00891 -0.0354855 -0.07733 -0.215273 0.97284 1 7.70372e-19 7.70372e-19 -4.78929e-09 1.10406e-11 5.47973e-08 1 7.70372e-19 -4.78929e-09 1.10406e-11 5.47973e-08 1 -4.78929e-09 1.10406e-11 5.47973e-08 4107.89 -23.4214 -681.5 3976.14 74.3248 3927.55 +EDGE_SE3:QUAT 923 973 1.04216 0.00197679 -6.54447 -0.00318376 -0.0198454 0.0383964 0.99906 1 7.52316e-22 7.52316e-22 1.73443e-09 6.69287e-11 -3.3926e-11 1 7.52316e-22 1.73443e-09 6.69287e-11 -3.3926e-11 1 1.73443e-09 6.69287e-11 -3.3926e-11 4006.12 0.607644 -157.154 3998.48 -3.04739 4000.27 +EDGE_SE3:QUAT 922 973 0.573761 12.3706 -6.40219 0.128035 -0.162883 -0.0792501 0.975088 1 3.08149e-18 3.08149e-18 -1.12858e-07 1.42888e-08 1.54754e-08 1 3.08149e-18 -1.12858e-07 1.42888e-08 1.54754e-08 1 -1.12858e-07 1.42888e-08 1.54754e-08 4271.5 -138.998 -1211.61 3944.79 131.551 4311.95 +EDGE_SE3:QUAT 923 972 0.457432 -12.819 -5.64463 0.00482886 -0.0579294 -0.0395062 0.997527 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.34 -4.35948 -465.395 3986.93 9.88431 4047.19 +EDGE_SE3:QUAT 924 974 1.16722 -0.167269 -6.63189 0.0727426 -0.0393541 -0.00384829 0.996567 1 2.40741e-19 2.40741e-19 -2.76111e-08 1.40953e-08 5.15595e-11 1 2.40741e-19 -2.76111e-08 1.40953e-08 5.15595e-11 1 -2.76111e-08 1.40953e-08 5.15595e-11 4002.8 -11.5463 -310.583 3994.24 3.25565 4023.91 +EDGE_SE3:QUAT 923 974 0.85755 12.348 -6.36051 -0.131398 0.0459943 -0.00227325 0.99026 1 7.70372e-19 7.70372e-19 5.51914e-08 -7.92757e-10 2.44136e-09 1 7.70372e-19 5.51914e-08 -7.92757e-10 2.44136e-09 1 5.51914e-08 -7.92757e-10 2.44136e-09 3962.59 -23.8077 357.328 3992.91 -6.83384 4031.64 +EDGE_SE3:QUAT 924 973 0.198648 -12.435 -5.99738 -0.0538732 0.0161781 -0.00558564 0.998401 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.31 -3.38152 125.357 3999.05 -0.66962 4003.8 +EDGE_SE3:QUAT 925 975 1.16983 -0.132988 -6.16264 -0.0284351 -0.0605006 0.0531613 0.996346 1 9.62965e-20 9.62965e-20 -1.47173e-08 -1.2832e-09 1.47173e-08 1 9.62965e-20 -1.47173e-08 -1.2832e-09 1.47173e-08 1 -1.47173e-08 -1.2832e-09 1.47173e-08 4050.9 11.2505 -468.557 3987.25 -15.104 4042.83 +EDGE_SE3:QUAT 924 975 0.794755 12.4364 -6.49721 -0.0500983 0.0810754 -0.106664 0.989717 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.32 -29.0631 580.653 3983.17 -38.1709 4036.85 +EDGE_SE3:QUAT 925 974 0.465905 -12.4049 -6.07643 0.117402 0.0965218 -0.068818 0.985984 1 2.40741e-19 2.40741e-19 -2.64554e-08 2.78816e-09 1.08993e-08 1 2.40741e-19 -2.64554e-08 2.78816e-09 1.08993e-08 1 -2.64554e-08 2.78816e-09 1.08993e-08 4131.32 40.2103 883.706 3954.44 -2.27965 4167.51 +EDGE_SE3:QUAT 926 976 1.34817 -0.00310424 -5.80989 -0.0315893 -0.114067 -0.0440625 0.991993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4219.18 2.52297 -970.834 3946.34 13.7167 4215.41 +EDGE_SE3:QUAT 925 976 0.349689 12.4677 -6.41172 0.188895 0.0544229 0.185928 0.962698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3851.64 -15.6923 -12.5561 3998.57 -15.4361 3856.09 +EDGE_SE3:QUAT 926 975 0.460647 -11.8897 -6.0696 -0.0465313 -0.141176 -0.196466 0.969178 1 1.20371e-20 1.20371e-20 -7.03893e-09 1.38722e-09 1.07529e-09 1 1.20371e-20 -7.03893e-09 1.38722e-09 1.07529e-09 1 -7.03893e-09 1.38722e-09 1.07529e-09 4358.47 -76.4693 -1266.25 3925.8 128.015 4212.74 +EDGE_SE3:QUAT 927 977 1.20399 0.00042534 -6.11955 0.0280544 0.16643 -0.127709 0.977346 1 7.70372e-19 7.70372e-19 6.96789e-09 5.42693e-08 8.47984e-10 1 7.70372e-19 6.96789e-09 5.42693e-08 8.47984e-10 1 6.96789e-09 5.42693e-08 8.47984e-10 4488.26 -72.5535 1485.65 3894.94 -102.307 4426.17 +EDGE_SE3:QUAT 926 977 0.396852 12.3911 -6.43274 -0.142037 -0.143326 0.0399986 0.978613 1 8.1852e-19 8.1852e-19 5.80547e-08 6.96796e-09 -2.12507e-08 1 8.1852e-19 5.80547e-08 6.96796e-09 -2.12507e-08 1 5.80547e-08 6.96796e-09 -2.12507e-08 4201.81 110.074 -1101.13 3947.75 -92.0537 4276.1 +EDGE_SE3:QUAT 927 976 0.0374724 -12.6595 -6.20606 0.0642464 0.017849 -0.173483 0.982577 1 1.20371e-20 1.20371e-20 1.18015e-09 6.82213e-09 -3.77363e-10 1 1.20371e-20 1.18015e-09 6.82213e-09 -3.77363e-10 1 1.18015e-09 6.82213e-09 -3.77363e-10 4000.96 6.21223 267.469 3994.47 -25.6284 3897.08 +EDGE_SE3:QUAT 928 978 1.36012 0.0145094 -6.17507 0.109075 0.106537 -0.060001 0.986485 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4169.04 40.6322 955.86 3947.85 2.38415 4202.23 +EDGE_SE3:QUAT 927 978 0.451842 12.1089 -6.62977 0.0338775 -0.0173161 -0.00201135 0.999274 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.14 -2.34665 -137.614 3998.83 0.379866 4004.71 +EDGE_SE3:QUAT 928 977 0.522722 -12.1971 -5.93518 -0.0580623 -0.170497 -0.203132 0.962443 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4542.43 -118.023 -1591.49 3892.69 167.762 4390.87 +EDGE_SE3:QUAT 929 979 1.27333 -0.283157 -6.21712 0.110873 0.211763 -0.169778 0.956054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4948.7 -79.3932 2233.32 3797.01 -120.476 4882.58 +EDGE_SE3:QUAT 928 979 0.652604 12.4668 -6.49173 -0.0212614 -0.230636 0.0701832 0.970273 1 8.1852e-19 8.1852e-19 1.00735e-08 5.51531e-08 -2.20523e-10 1 8.1852e-19 1.00735e-08 5.51531e-08 -2.20523e-10 1 1.00735e-08 5.51531e-08 -2.20523e-10 4960.45 150.293 -2185.27 3810.31 -155.226 4942.55 +EDGE_SE3:QUAT 929 978 0.0435234 -12.2413 -5.86713 -0.126419 0.0710213 -0.0480377 0.988264 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.91 -34.8137 485.695 3988.86 -23.6242 4048.61 +EDGE_SE3:QUAT 930 980 1.43428 0.132531 -6.30524 0.013211 -0.00605304 -0.0436562 0.998941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.73 -0.287949 -41.3652 3999.91 0.860892 3992.8 +EDGE_SE3:QUAT 929 980 0.215195 12.0909 -6.50442 0.0909929 0.0694911 0.16301 0.979959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.48 23.2794 353.564 3997 29.5643 3923.31 +EDGE_SE3:QUAT 930 979 0.47609 -12.4139 -6.22101 0.0667564 0.191246 0.00980996 0.97922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4619.72 89.9609 1719.53 3863.56 80.7551 4637.16 +EDGE_SE3:QUAT 931 981 1.15415 0.19798 -6.03949 -0.111977 -0.103777 -0.0421589 0.987377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4146.05 45.2703 -907.401 3953.4 -11.4576 4189.1 +EDGE_SE3:QUAT 930 981 0.402437 12.2278 -6.60795 0.156821 0.171885 0.344622 0.909449 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3923.67 74.0511 465.245 4034.45 59.448 3546.99 +EDGE_SE3:QUAT 931 980 0.329531 -12.6325 -5.91793 0.0922523 -0.136788 -0.118793 0.979115 1 7.70372e-19 7.70372e-19 6.14607e-09 -7.17701e-09 -5.58634e-08 1 7.70372e-19 6.14607e-09 -7.17701e-09 -5.58634e-08 1 6.14607e-09 -7.17701e-09 -5.58634e-08 4185.18 -93.9263 -964.531 3963.46 98.1734 4162.78 +EDGE_SE3:QUAT 932 982 0.97293 -0.0241997 -5.94977 -0.0407544 0.0255285 0.122577 0.991293 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.06 -2.87996 259.496 3995.44 16.2321 3956.6 +EDGE_SE3:QUAT 931 982 0.349574 12.4911 -6.06727 0.0749005 0.0840973 0.0734267 0.990922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4067.29 33.9155 606.529 3981.32 33.6726 4068.16 +EDGE_SE3:QUAT 932 981 0.115601 -12.4792 -6.00165 -0.186633 -0.00097089 -0.120863 0.974966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3877.19 31.6435 -270.116 3992.33 18.6361 3958.09 +EDGE_SE3:QUAT 933 983 1.32463 0.020016 -5.84 -0.0611012 -0.0413791 -0.123485 0.989599 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.62 6.49076 -415.396 3988.58 24.3081 3981.56 +EDGE_SE3:QUAT 932 983 0.20117 12.4834 -6.35662 0.0865584 0.175454 -0.0779537 0.977572 1 7.70372e-19 7.70372e-19 -2.79805e-09 -5.43664e-08 3.49158e-09 1 7.70372e-19 -2.79805e-09 -5.43664e-08 3.49158e-09 1 -2.79805e-09 -5.43664e-08 3.49158e-09 4562.9 24.6414 1650.19 3866.5 -6.90755 4568.56 +EDGE_SE3:QUAT 933 982 0.380639 -12.3239 -6.01524 0.0260944 0.112871 -0.19689 0.973557 1 7.72065e-19 7.72065e-19 -9.11506e-09 1.64982e-09 -5.58465e-08 1 7.72065e-19 -9.11506e-09 1.64982e-09 -5.58465e-08 1 -9.11506e-09 1.64982e-09 -5.58465e-08 4213.27 -52.2018 954.403 3956.56 -98.8644 4060.93 +EDGE_SE3:QUAT 934 984 1.01439 -0.0635657 -6.46755 -0.0614558 0.0182058 0.156978 0.98552 1 2.0463e-19 2.0463e-19 -2.84766e-08 2.56595e-09 -6.40206e-10 1 2.0463e-19 -2.84766e-08 2.56595e-09 -6.40206e-10 1 -2.84766e-08 2.56595e-09 -6.40206e-10 4000.71 -5.83299 254.121 3995.07 21.7225 3917.25 +EDGE_SE3:QUAT 933 984 0.259293 12.5981 -6.34299 0.119199 0.0505553 0.0600094 0.989765 1 4.33334e-19 4.33334e-19 2.75356e-08 1.91668e-08 2.67819e-08 1 4.33334e-19 2.75356e-08 1.91668e-08 2.67819e-08 1 2.75356e-08 1.91668e-08 2.67819e-08 3966.73 19.3993 309.908 3995.86 13.449 4009.16 +EDGE_SE3:QUAT 934 983 0.425384 -12.4304 -6.19894 0.208353 -0.190533 0.0915925 0.954933 1 1.92593e-19 1.92593e-19 -6.40321e-09 5.67884e-09 2.90792e-08 1 1.92593e-19 -6.40321e-09 5.67884e-09 2.90792e-08 1 -6.40321e-09 5.67884e-09 2.90792e-08 4603.78 -182.486 -1927.21 3848.65 129.996 4743.87 +EDGE_SE3:QUAT 935 985 0.964891 -0.0220229 -6.09027 -0.0957148 -0.00359923 0.100011 0.990365 1 3.85938e-19 3.85938e-19 2.72346e-08 3.64978e-09 -2.7227e-08 1 3.85938e-19 2.72346e-08 3.64978e-09 -2.7227e-08 1 2.72346e-08 3.64978e-09 -2.7227e-08 3964.83 -5.80474 85.4619 3999.05 6.07687 3961.47 +EDGE_SE3:QUAT 934 985 0.435131 12.6668 -6.09246 0.0834014 0.0029218 0.00590188 0.996494 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3972.25 0.634654 17.2507 3999.99 0.0557073 3999.93 +EDGE_SE3:QUAT 935 984 0.395549 -12.4139 -6.14268 0.104889 0.0459554 -0.0961487 0.988758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.19 20.4609 482.783 3984.3 -17.4356 4020.21 +EDGE_SE3:QUAT 936 986 1.12803 -0.152026 -6.52955 0.104883 0.00737545 -0.059369 0.992683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.2 7.9117 131.869 3998.52 -4.1193 3990.11 +EDGE_SE3:QUAT 935 986 0.372189 11.9541 -6.218 0.0998625 -0.0384693 0.157703 0.981671 1 7.70372e-19 7.70372e-19 3.73958e-09 -4.65993e-09 -5.48939e-08 1 7.70372e-19 3.73958e-09 -4.65993e-09 -5.48939e-08 1 3.73958e-09 -4.65993e-09 -5.48939e-08 4017.15 -15.8822 -483.572 3983.39 -36.271 3957.56 +EDGE_SE3:QUAT 936 985 0.410199 -12.0721 -6.18075 -0.0448791 -0.106764 -0.232848 0.965593 1 1.20371e-20 1.20371e-20 -6.88705e-09 1.62899e-09 8.23098e-10 1 1.20371e-20 -6.88705e-09 1.62899e-09 8.23098e-10 1 -6.88705e-09 1.62899e-09 8.23098e-10 4205.83 -52.0619 -949.386 3958 113.117 3997.01 +EDGE_SE3:QUAT 937 987 1.20674 0.0428654 -6.64729 0.068007 0.00479036 -0.00194218 0.997671 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.89 1.36207 39.6407 3999.9 0.00064548 4000.38 +EDGE_SE3:QUAT 936 987 0.204615 12.8066 -6.50552 -0.175353 0.10105 0.178317 0.962935 1 7.70372e-19 7.70372e-19 7.65285e-09 -5.3821e-08 -7.4388e-09 1 7.70372e-19 7.65285e-09 -5.3821e-08 -7.4388e-09 1 7.65285e-09 -5.3821e-08 -7.4388e-09 4200.92 -49.195 1185.77 3918.46 52.7587 4196.73 +EDGE_SE3:QUAT 937 986 0.0380168 -11.9462 -6.07628 -0.074295 0.195814 0.0177128 0.977662 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4673.03 -75.5058 1806.56 3849.77 -60.84 4693.86 +EDGE_SE3:QUAT 938 988 1.09619 0.0299313 -6.27176 0.0247418 0.0440068 -0.221299 0.973898 1 5.11575e-20 5.11575e-20 6.44811e-09 1.27532e-08 1.28887e-10 1 5.11575e-20 6.44811e-09 1.27532e-08 1.28887e-10 1 6.44811e-09 1.27532e-08 1.28887e-10 4035.86 -7.39989 393.332 3991.68 -44.6099 3842.41 +EDGE_SE3:QUAT 937 988 0.45454 12.4191 -6.39067 0.0990433 -0.0141509 0.201128 0.974442 1 2.40741e-19 2.40741e-19 2.98478e-08 -8.11895e-09 -2.48172e-10 1 2.40741e-19 2.98478e-08 -8.11895e-09 -2.48172e-10 1 2.98478e-08 -8.11895e-09 -2.48172e-10 3988.07 -14.3132 -338.311 3990.15 -38.932 3865.5 +EDGE_SE3:QUAT 938 987 0.360091 -12.5125 -6.2622 0.00683729 -0.0422599 -0.0276459 0.998701 1 3.00927e-21 3.00927e-21 -3.47717e-09 9.86056e-11 1.45575e-10 1 3.00927e-21 -3.47717e-09 9.86056e-11 1.45575e-10 1 -3.47717e-09 9.86056e-11 1.45575e-10 4028.08 -2.35295 -337.462 3993.03 5.03127 4025.21 +EDGE_SE3:QUAT 939 989 0.871898 0.200612 -6.0719 0.0631414 0.15066 0.0232948 0.986292 1 1.92593e-19 1.92593e-19 -2.86229e-08 -1.2724e-09 -4.24056e-09 1 1.92593e-19 -2.86229e-08 -1.2724e-09 -4.24056e-09 1 -2.86229e-08 -1.2724e-09 -4.24056e-09 4354.94 63.204 1273.29 3917.48 55.3846 4368.71 +EDGE_SE3:QUAT 938 989 0.0534191 12.5893 -6.5325 -0.0528015 -0.138232 0.232274 0.961329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4178.01 105.654 -897.356 3981.59 -130.019 3973.36 +EDGE_SE3:QUAT 939 988 0.174287 -12.5548 -5.78506 -0.10444 0.012815 -0.00188162 0.994447 1 1.88079e-22 1.88079e-22 -1.05367e-11 9.0685e-11 -8.6281e-10 1 1.88079e-22 -1.05367e-11 9.0685e-11 -8.6281e-10 1 -1.05367e-11 9.0685e-11 -8.6281e-10 3958.8 -5.09169 98.5565 3999.44 -0.480905 4002.41 +EDGE_SE3:QUAT 940 990 1.00409 0.147853 -6.34751 -0.0139815 0.136159 0.123524 0.982857 1 7.52316e-22 7.52316e-22 -1.77112e-09 -2.24181e-10 -2.43959e-10 1 7.52316e-22 -1.77112e-09 -2.24181e-10 -2.43959e-10 1 -1.77112e-09 -2.24181e-10 -2.43959e-10 4310.63 50.633 1158.75 3931.74 79.0162 4250.38 +EDGE_SE3:QUAT 939 990 0.427109 12.419 -6.29891 -0.0224014 -0.0782342 0.216748 0.97283 1 4.81482e-20 4.81482e-20 -1.36227e-08 -3.11556e-09 8.55595e-10 1 4.81482e-20 -1.36227e-08 -3.11556e-09 8.55595e-10 1 -1.36227e-08 -3.11556e-09 8.55595e-10 4066.99 31.3153 -532.003 3989.44 -59.7009 3881.07 +EDGE_SE3:QUAT 940 989 0.770513 -12.2919 -5.87212 -0.058972 0.0762369 -0.22848 0.968766 1 1.92593e-19 1.92593e-19 2.70273e-08 -6.63603e-09 1.14791e-09 1 1.92593e-19 2.70273e-08 -6.63603e-09 1.14791e-09 1 2.70273e-08 -6.63603e-09 1.14791e-09 4025 -28.1137 404.967 3997.04 -44.5427 3830.1 +EDGE_SE3:QUAT 941 991 0.867845 -0.0766861 -6.27011 0.12903 0.164137 0.0711335 0.975372 1 7.70372e-19 7.70372e-19 -5.65453e-08 -6.72312e-09 -7.95581e-09 1 7.70372e-19 -5.65453e-08 -6.72312e-09 -7.95581e-09 1 -5.65453e-08 -6.72312e-09 -7.95581e-09 4285.92 139.884 1240.82 3940.66 130.897 4332.28 +EDGE_SE3:QUAT 940 991 0.226511 12.2079 -6.61281 0.180303 -0.0332042 -0.0588017 0.98129 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3873.4 -7.8035 -127.088 3999.9 4.05271 3989.61 +EDGE_SE3:QUAT 941 990 0.491938 -12.9939 -6.15507 -0.231256 -0.00917961 -0.104838 0.967184 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3814.45 48.1542 -347.534 3988.93 15.9893 3984.4 +EDGE_SE3:QUAT 942 992 1.13 -0.238805 -6.10462 0.143578 -0.171914 0.147633 0.963346 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4600.05 -26.0825 -1788.11 3848.23 -35.5189 4595.32 +EDGE_SE3:QUAT 941 992 0.281715 12.1241 -6.05585 -0.0343064 -0.00135085 0.0185172 0.999239 1 4.81482e-20 4.81482e-20 -1.38672e-08 -2.57658e-10 1.07124e-12 1 4.81482e-20 -1.38672e-08 -2.57658e-10 1.07124e-12 1 -1.38672e-08 -2.57658e-10 1.07124e-12 3995.29 0.0107523 -3.16679 4000 -0.00601284 3998.63 +EDGE_SE3:QUAT 942 991 0.251133 -12.3947 -5.86776 0.0422284 0.0448667 0.0863688 0.994356 1 1.92593e-19 1.92593e-19 1.02281e-09 1.37773e-09 2.76827e-08 1 1.92593e-19 1.02281e-09 1.37773e-09 2.76827e-08 1 1.02281e-09 1.37773e-09 2.76827e-08 4016.96 9.73878 311.868 3994.89 14.6599 3994.25 +EDGE_SE3:QUAT 943 993 0.763208 -0.0126086 -6.4732 0.0350603 0.0572682 0.0524881 0.996361 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.39 11.6282 437.657 3988.97 14.2144 4036.28 +EDGE_SE3:QUAT 942 993 0.0658335 12.0133 -6.36784 -0.0327983 0.140988 0.155369 0.977193 1 3.00927e-21 3.00927e-21 3.53954e-09 5.51563e-10 5.22228e-10 1 3.00927e-21 3.53954e-09 5.51563e-10 5.22228e-10 1 3.53954e-09 5.51563e-10 5.22228e-10 4346.73 60.5711 1235.88 3925.08 99.9255 4254.47 +EDGE_SE3:QUAT 943 992 0.546106 -12.6408 -6.07494 0.0452234 0.0618393 -0.0957545 0.992452 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.29 2.94818 547.211 3981.51 -23.2108 4036.8 +EDGE_SE3:QUAT 944 994 0.756042 0.0666397 -6.15948 -0.182729 0.150959 -0.0865266 0.967644 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4091.66 -134.487 982.634 3974.89 -121.999 4195.27 +EDGE_SE3:QUAT 943 994 0.194663 12.4284 -6.26299 -0.114972 -0.0212944 0.087504 0.989278 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3947.21 0.397745 -45.927 4000.04 -0.397557 3969.46 +EDGE_SE3:QUAT 944 993 0.263785 -12.096 -6.22275 -0.234151 0.0307569 -0.122698 0.963936 1 7.70372e-19 7.70372e-19 5.35062e-08 -6.83498e-09 -1.60913e-09 1 7.70372e-19 5.35062e-08 -6.83498e-09 -1.60913e-09 1 5.35062e-08 -6.83498e-09 -1.60913e-09 3780.28 27.1745 -108.091 3996.64 14.2737 3939.37 +EDGE_SE3:QUAT 945 995 1.31391 -0.126112 -6.1045 0.041001 0.0639786 -0.0332389 0.996554 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.4 8.05442 534.264 3982.52 -5.05573 4065.71 +EDGE_SE3:QUAT 944 995 0.175026 12.3799 -6.50735 -0.0101183 0.15611 -0.0704198 0.985174 1 1.20371e-20 1.20371e-20 -7.17714e-09 5.62896e-10 -1.11417e-09 1 1.20371e-20 -7.17714e-09 5.62896e-10 -1.11417e-09 1 -7.17714e-09 5.62896e-10 -1.11417e-09 4406.38 -53.912 1338.93 3909.46 -65.6591 4386.95 +EDGE_SE3:QUAT 945 994 0.425181 -12.584 -5.98362 -0.0104903 0.0300637 0.122277 0.991985 1 7.52316e-22 7.52316e-22 1.72425e-09 2.11804e-10 5.51149e-11 1 7.52316e-22 1.72425e-09 2.11804e-10 5.51149e-11 1 1.72425e-09 2.11804e-10 5.51149e-11 4015.28 1.51089 251.23 3996.21 15.4723 3955.91 +EDGE_SE3:QUAT 946 996 1.1657 0.0452132 -6.1321 -0.202239 -0.0208469 0.0733574 0.976362 1 7.52316e-22 7.52316e-22 -1.31135e-10 1.69342e-09 3.52254e-10 1 7.52316e-22 -1.31135e-10 1.69342e-09 3.52254e-10 1 -1.31135e-10 1.69342e-09 3.52254e-10 3835.53 -8.14557 17.2628 3999.62 2.94917 3977.61 +EDGE_SE3:QUAT 945 996 0.431891 12.2812 -6.13972 -0.144412 0.13097 0.127413 0.972501 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4313.63 -45.8115 1321.91 3905.89 21.4809 4332.11 +EDGE_SE3:QUAT 946 995 0.148193 -12.7385 -6.20154 -0.0878832 -0.0253731 -0.0545288 0.994314 1 1.92593e-19 1.92593e-19 -2.76552e-08 1.37197e-09 9.56225e-10 1 1.92593e-19 -2.76552e-08 1.37197e-09 9.56225e-10 1 -2.76552e-08 1.37197e-09 9.56225e-10 3985.59 10.9917 -257.887 3995.41 5.59176 4004.59 +EDGE_SE3:QUAT 947 997 0.858472 -0.00647696 -6.4896 0.0407651 0.0962451 0.0552129 0.992989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4132.58 28.6975 759.245 3968.09 31.4789 4127.03 +EDGE_SE3:QUAT 946 997 0.0272706 12.2332 -6.44967 -0.0831083 -0.108897 0.277343 0.950955 1 3.08149e-18 3.08149e-18 5.03999e-09 1.45622e-08 -1.06389e-07 1 3.08149e-18 5.03999e-09 1.45622e-08 -1.06389e-07 1 5.03999e-09 1.45622e-08 -1.06389e-07 4028.41 53.4765 -500.543 4002.99 -67.2304 3748.36 +EDGE_SE3:QUAT 947 996 0.625333 -12.2014 -6.23878 0.0354388 -0.0457593 -0.0403236 0.997509 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4025.29 -8.1002 -349.577 3992.84 8.72773 4023.81 +EDGE_SE3:QUAT 948 998 1.10679 0.0233952 -6.07456 0.0893008 0.0135386 -0.0162321 0.99578 1 1.92593e-19 1.92593e-19 2.76519e-08 -3.76851e-10 4.49969e-10 1 1.92593e-19 2.76519e-08 -3.76851e-10 4.49969e-10 1 2.76519e-08 -3.76851e-10 4.49969e-10 3971.96 5.71638 124.387 3998.98 -0.564565 4002.8 +EDGE_SE3:QUAT 947 998 0.257171 12.5661 -6.18572 -0.10443 -0.0869051 0.182613 0.973753 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.97 35.1165 -427.451 3997.15 -41.9297 3909.2 +EDGE_SE3:QUAT 948 997 0.122783 -12.3971 -6.28306 0.139482 0.0208493 -0.170682 0.975181 1 7.70372e-19 7.70372e-19 5.44556e-08 -8.86028e-09 3.64985e-09 1 7.70372e-19 5.44556e-08 -8.86028e-09 3.64985e-09 1 5.44556e-08 -8.86028e-09 3.64985e-09 3967.73 28.0971 436.565 3984.13 -38.1437 3929.02 +EDGE_SE3:QUAT 949 999 1.2822 0.275579 -5.95831 -0.114771 0.00253963 -0.210944 0.970734 1 7.70372e-19 7.70372e-19 2.48921e-09 5.87294e-09 -5.39948e-08 1 7.70372e-19 2.48921e-09 5.87294e-09 -5.39948e-08 1 2.48921e-09 5.87294e-09 -5.39948e-08 3962.49 17.4581 -261.777 3992.38 36.2324 3837.19 +EDGE_SE3:QUAT 948 999 0.0951897 12.5354 -6.1831 0.00413322 -0.0166681 -0.0514916 0.998526 1 7.52316e-22 7.52316e-22 1.73309e-09 -8.96562e-11 -2.80372e-11 1 7.52316e-22 1.73309e-09 -8.96562e-11 -2.80372e-11 1 1.73309e-09 -8.96562e-11 -2.80372e-11 4004.18 -0.600046 -130.381 3998.97 3.36646 3993.64 +EDGE_SE3:QUAT 949 998 0.607543 -12.4392 -6.10064 -0.0406672 0.0508748 -0.0760556 0.994974 1 4.81482e-20 4.81482e-20 -1.38662e-08 1.11924e-09 -6.11985e-10 1 4.81482e-20 -1.38662e-08 1.11924e-09 -6.11985e-10 1 -1.38662e-08 1.11924e-09 -6.11985e-10 4026.89 -11.4378 367.942 3992.61 -15.9713 4010.37 +EDGE_SE3:QUAT 950 1000 0.948239 -0.061321 -6.07581 -0.123081 -0.0233861 -0.0323022 0.991595 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3952.61 14.5824 -230.508 3996.45 1.71524 4009.03 +EDGE_SE3:QUAT 949 1000 0.394601 12.5829 -6.45077 0.0324637 -0.0457883 0.0880783 0.994531 1 2.0463e-19 2.0463e-19 5.52091e-09 1.26564e-09 2.73871e-08 1 2.0463e-19 5.52091e-09 1.26564e-09 2.73871e-08 1 5.52091e-09 1.26564e-09 2.73871e-08 4035.22 -1.71366 -399.205 3990.01 -16.57 4008.4 +EDGE_SE3:QUAT 950 999 0.271378 -12.2943 -6.1335 0.108273 0.0232055 -0.131238 0.985147 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.5 17.1673 347.577 3990.56 -22.6783 3960.5 +EDGE_SE3:QUAT 951 1001 0.983503 0.153614 -6.62361 -0.0851637 0.118284 0.00784514 0.98929 1 1.88079e-22 1.88079e-22 -1.05198e-10 7.65045e-11 -8.82833e-10 1 1.88079e-22 -1.05198e-10 7.65045e-11 -8.82833e-10 1 -1.05198e-10 7.65045e-11 -8.82833e-10 4203.44 -45.7042 991.89 3946.18 -26.1601 4232.2 +EDGE_SE3:QUAT 950 1001 0.0684248 12.2443 -6.20623 -0.110557 -0.0661752 -0.0623621 0.989701 1 3.85186e-19 3.85186e-19 2.90866e-08 2.61793e-08 6.61915e-10 1 3.85186e-19 2.90866e-08 2.61793e-08 6.61915e-10 1 2.90866e-08 2.61793e-08 6.61915e-10 4042.43 28.6965 -611.556 3976.8 6.21287 4075.77 +EDGE_SE3:QUAT 951 1000 -0.0368012 -12.2898 -5.60008 0.0553398 -0.000947949 -0.0801402 0.995246 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.19 1.71525 45.4116 3999.75 -2.50911 3974.75 +EDGE_SE3:QUAT 952 1002 1.38125 -0.140923 -6.16094 0.189671 -0.084126 -0.0208097 0.978016 1 8.1852e-19 8.1852e-19 -5.39238e-08 1.30352e-10 -9.79497e-09 1 8.1852e-19 -5.39238e-08 1.30352e-10 -9.79497e-09 1 -5.39238e-08 1.30352e-10 -9.79497e-09 3943.9 -61.0635 -600.42 3984.53 33.8786 4086.07 +EDGE_SE3:QUAT 951 1002 -0.0689094 12.3227 -6.19468 0.139087 0.128706 0.0860292 0.978105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4103.76 92.288 873.839 3971.62 84.103 4151.54 +EDGE_SE3:QUAT 952 1001 0.162291 -12.1578 -6.37159 0.00538571 -0.0717858 0.00250684 0.997402 1 7.52316e-22 7.52316e-22 -1.74824e-09 -3.0736e-12 1.25865e-10 1 7.52316e-22 -1.74824e-09 -3.0736e-12 1.25865e-10 1 -1.74824e-09 -3.0736e-12 1.25865e-10 4083.67 -1.3429 -584.939 3979.38 -0.089843 4083.76 +EDGE_SE3:QUAT 953 1003 0.774036 0.307631 -6.18442 -0.0124896 -0.145345 -0.117919 0.982249 1 1.92593e-19 1.92593e-19 -4.17826e-09 6.51738e-10 2.84682e-08 1 1.92593e-19 -4.17826e-09 6.51738e-10 2.84682e-08 1 -4.17826e-09 6.51738e-10 2.84682e-08 4355.71 -56.7121 -1245.96 3922.26 83.101 4300.71 +EDGE_SE3:QUAT 952 1003 0.193823 12.3264 -6.23849 -0.00994595 -0.120803 -0.0209193 0.992406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4244.69 -2.03307 -1020 3941.43 8.58121 4243.33 +EDGE_SE3:QUAT 953 1002 -0.0509947 -12.2335 -6.00607 0.0185216 0.191807 -0.123439 0.973463 1 7.52316e-22 7.52316e-22 1.82347e-09 -2.3566e-10 3.5655e-10 1 7.52316e-22 1.82347e-09 -2.3566e-10 3.5655e-10 1 1.82347e-09 -2.3566e-10 3.5655e-10 4651.98 -108.609 1743.71 3866.33 -131.412 4592.4 +EDGE_SE3:QUAT 954 1004 0.850376 -0.0136064 -6.26343 0.0207945 -0.115111 -0.0166115 0.992996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4216.38 -16.9376 -959.173 3948.06 16.061 4217.01 +EDGE_SE3:QUAT 953 1004 0.224207 12.5366 -6.43855 -0.056316 -0.0203769 0.0438044 0.997243 1 4.81482e-20 4.81482e-20 2.11661e-10 8.04273e-10 -1.38471e-08 1 4.81482e-20 2.11661e-10 8.04273e-10 -1.38471e-08 1 2.11661e-10 8.04273e-10 -1.38471e-08 3991.66 3.76905 -132.365 3999.1 -3.09354 3996.67 +EDGE_SE3:QUAT 954 1003 0.195266 -12.2279 -5.84819 0.0413999 -0.0949713 -0.0836365 0.991096 1 4.81482e-20 4.81482e-20 -1.39747e-08 1.30787e-09 1.21599e-09 1 4.81482e-20 -1.39747e-08 1.30787e-09 1.21599e-09 1 -1.39747e-08 1.30787e-09 1.21599e-09 4121.14 -32.9804 -727.19 3971.92 40.7764 4100.01 +EDGE_SE3:QUAT 955 1005 0.887496 -0.0406138 -6.32825 -0.00643622 0.214671 -0.0773879 0.973594 1 7.82409e-19 7.82409e-19 -2.53544e-09 5.46674e-08 7.57013e-10 1 7.82409e-19 -2.53544e-09 5.46674e-08 7.57013e-10 1 -2.53544e-09 5.46674e-08 7.57013e-10 4826.69 -115.56 1997.84 3830.82 -124.673 4802.9 +EDGE_SE3:QUAT 954 1005 0.249169 12.2916 -6.06246 0.167368 -0.118945 0.103384 0.973217 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4213.13 -72.567 -1186.46 3923.12 5.02628 4282.42 +EDGE_SE3:QUAT 955 1004 0.326816 -12.256 -6.05556 0.0926959 -0.0459654 -0.11346 0.98814 1 1.92593e-19 1.92593e-19 -6.41857e-10 2.80633e-09 2.74712e-08 1 1.92593e-19 -6.41857e-10 2.80633e-09 2.74712e-08 1 -6.41857e-10 2.80633e-09 2.74712e-08 3978.41 -11.6777 -231.612 3998.35 13.0987 3961.29 +EDGE_SE3:QUAT 956 1006 0.89418 0.0477376 -6.2809 -0.105819 -0.0683399 0.241786 0.962118 1 4.81482e-20 4.81482e-20 3.48468e-09 -1.33189e-08 -1.74371e-09 1 4.81482e-20 3.48468e-09 -1.33189e-08 -1.74371e-09 1 3.48468e-09 -1.33189e-08 -1.74371e-09 3960.78 10.8021 -195.573 4001.73 -12.2082 3771.73 +EDGE_SE3:QUAT 955 1006 0.340279 12.4944 -6.1271 0.0385117 -0.12528 0.198703 0.971256 1 7.70372e-19 7.70372e-19 -7.49284e-09 -7.66576e-10 5.58537e-08 1 7.70372e-19 -7.49284e-09 -7.66576e-10 5.58537e-08 1 -7.49284e-09 -7.66576e-10 5.58537e-08 4275.1 61.9241 -1096.92 3943 -112.93 4123.1 +EDGE_SE3:QUAT 956 1005 0.0825526 -12.6885 -6.2396 -0.13893 -0.164413 -0.156011 0.964016 1 2.31112e-18 2.31112e-18 -5.23524e-08 -4.18064e-08 -5.09696e-08 1 2.31112e-18 -5.23524e-08 -4.18064e-08 -5.09696e-08 1 -5.23524e-08 -4.18064e-08 -5.09696e-08 4553.05 14.1906 -1708.77 3858.51 51.0727 4532.9 +EDGE_SE3:QUAT 957 1007 0.969048 0.322056 -6.36991 0.211307 -0.0110327 -0.00139514 0.977356 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3822.95 -8.02117 -79.0084 3999.72 0.584664 4001.55 +EDGE_SE3:QUAT 956 1007 0.307705 12.5825 -6.6662 0.0351923 0.0455718 -0.00586838 0.998324 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.81 6.34972 369.073 3991.62 0.67817 4033.63 +EDGE_SE3:QUAT 957 1006 0.291846 -12.4271 -5.65724 0.0253487 0.175521 0.0838743 0.980569 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4502.84 93.8194 1509.17 3894.09 103.974 4477.27 +EDGE_SE3:QUAT 958 1008 0.590446 -0.0385952 -6.32717 0.0261535 -0.212689 0.0944485 0.972193 1 7.52316e-22 7.52316e-22 1.85737e-09 1.75611e-10 -4.08333e-10 1 7.52316e-22 1.85737e-09 1.75611e-10 -4.08333e-10 1 1.85737e-09 1.75611e-10 -4.08333e-10 4841.04 91.195 -2021.66 3824.55 -107.476 4808.09 +EDGE_SE3:QUAT 957 1008 0.55365 12.1936 -5.9786 0.071334 -0.214005 0.0880061 0.970241 1 8.1852e-19 8.1852e-19 -1.84569e-08 5.29884e-08 1.34734e-09 1 8.1852e-19 -1.84569e-08 5.29884e-08 1.34734e-09 1 -1.84569e-08 5.29884e-08 1.34734e-09 4885.76 14.8183 -2108.46 3806.88 -36.8161 4875.14 +EDGE_SE3:QUAT 958 1007 -0.306013 -12.4201 -5.89552 0.00521551 0.0507589 0.110249 0.992593 1 3.00927e-21 3.00927e-21 -3.46055e-09 -3.88158e-10 -1.6862e-10 1 3.00927e-21 -3.46055e-09 -3.88158e-10 -1.6862e-10 1 -3.46055e-09 -3.88158e-10 -1.6862e-10 4038.52 7.61 395.063 3991.15 22.3976 3990.01 +EDGE_SE3:QUAT 959 1009 0.78917 -0.171273 -6.21362 0.00464937 0.176517 0.10957 0.978169 1 1.92593e-19 1.92593e-19 5.04679e-09 1.33432e-09 2.88873e-08 1 1.92593e-19 5.04679e-09 1.33432e-09 2.88873e-08 1 5.04679e-09 1.33432e-09 2.88873e-08 4521.18 97.2096 1535.33 3892.07 115.457 4473.24 +EDGE_SE3:QUAT 958 1009 0.256441 12.1571 -6.43108 0.143358 0.0393642 -0.0802035 0.98563 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3965.99 30.3494 443.182 3986.49 -10.568 4022.47 +EDGE_SE3:QUAT 959 1008 0.0469284 -12.6721 -6.20514 0.0553099 -0.135689 -0.122291 0.981618 1 1.92593e-19 1.92593e-19 2.8089e-08 -4.04082e-09 -3.33651e-09 1 1.92593e-19 2.8089e-08 -4.04082e-09 -3.33651e-09 1 2.8089e-08 -4.04082e-09 -3.33651e-09 4233.86 -81.978 -1023.45 3953.48 93.8475 4186.27 +EDGE_SE3:QUAT 960 1010 0.960481 0.00976786 -5.80872 0.0417036 -0.0119987 0.0287543 0.998644 1 4.81482e-20 4.81482e-20 -1.38642e-08 -3.84055e-10 1.98989e-10 1 4.81482e-20 -1.38642e-08 -3.84055e-10 1.98989e-10 1 -1.38642e-08 -3.84055e-10 1.98989e-10 3996.06 -2.2732 -110.065 3999.18 -1.47344 3999.71 +EDGE_SE3:QUAT 959 1010 0.505586 12.1824 -6.03187 -0.0881668 0.0188478 0.158751 0.983194 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.16 -11.6009 309.578 3992.33 26.5428 3922.44 +EDGE_SE3:QUAT 960 1009 0.50935 -12.787 -5.47432 -0.0173444 -0.183208 -0.0922568 0.978582 1 9.65699e-19 9.65699e-19 3.80629e-09 -5.51615e-08 -2.88299e-08 1 9.65699e-19 3.80629e-09 -5.51615e-08 -2.88299e-08 1 3.80629e-09 -5.51615e-08 -2.88299e-08 4595.86 -68.8641 -1656.73 3871.02 87.9084 4563.01 +EDGE_SE3:QUAT 961 1011 0.940809 0.122531 -6.12041 -0.115569 0.0520277 0.102933 0.986581 1 3.85186e-19 3.85186e-19 -3.01137e-08 2.49295e-08 8.18088e-10 1 3.85186e-19 -3.01137e-08 2.49295e-08 8.18088e-10 1 -3.01137e-08 2.49295e-08 8.18088e-10 4021.04 -25.0932 552.036 3979.71 19.8955 4032.08 +EDGE_SE3:QUAT 960 1011 -0.459651 12.7475 -5.98289 0.0316543 0.171572 0.0639691 0.982583 1 4.81482e-20 4.81482e-20 -1.44459e-08 -1.16316e-09 -2.43116e-09 1 4.81482e-20 -1.44459e-08 -1.16316e-09 -2.43116e-09 1 -1.44459e-08 -1.16316e-09 -2.43116e-09 4481.96 80.4719 1476.6 3895.56 86.2577 4469.6 +EDGE_SE3:QUAT 961 1010 -0.159804 -12.1122 -6.03388 -0.0712714 0.0966552 -0.140815 0.982725 1 7.70372e-19 7.70372e-19 4.01893e-09 -5.4415e-09 5.5235e-08 1 7.70372e-19 4.01893e-09 -5.4415e-09 5.5235e-08 1 4.01893e-09 -5.4415e-09 5.5235e-08 4077.6 -46.479 636.269 3983.61 -56.8642 4018.6 +EDGE_SE3:QUAT 962 1012 0.84543 0.151728 -6.39675 -0.0310228 -0.135849 -0.0540127 0.98877 1 1.20371e-20 1.20371e-20 -7.13223e-09 3.41503e-10 9.97313e-10 1 1.20371e-20 -7.13223e-09 3.41503e-10 9.97313e-10 1 -7.13223e-09 3.41503e-10 9.97313e-10 4317.61 -4.83104 -1178.65 3924.29 22.9301 4309.79 +EDGE_SE3:QUAT 961 1012 -0.011622 12.5963 -6.83178 -0.0363892 0.240251 0.0648781 0.967856 1 7.70372e-19 7.70372e-19 -3.0047e-09 5.37635e-08 3.71686e-10 1 7.70372e-19 -3.0047e-09 5.37635e-08 3.71686e-10 1 -3.0047e-09 5.37635e-08 3.71686e-10 5129.21 51.0357 2413.53 3767.37 60.1377 5117.67 +EDGE_SE3:QUAT 962 1011 0.0419733 -12.4954 -6.17194 0.132163 -0.0889079 0.0474177 0.986093 1 7.70372e-19 7.70372e-19 5.57809e-08 1.29973e-09 -5.54455e-09 1 7.70372e-19 5.57809e-08 1.29973e-09 -5.54455e-09 1 5.57809e-08 1.29973e-09 -5.54455e-09 4080.98 -47.7234 -791.392 3963.89 8.77235 4141.86 +EDGE_SE3:QUAT 963 1013 0.886663 -0.217332 -6.44949 0.0336186 0.0243577 0.0767592 0.996185 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.01 3.38344 162.175 3998.63 6.196 3982.96 +EDGE_SE3:QUAT 962 1013 0.346768 12.8423 -6.38981 0.0885535 0.0727332 0.204949 0.972041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.03 22.5863 327.564 3999.12 30.5854 3856.38 +EDGE_SE3:QUAT 963 1012 -0.249065 -12.4433 -6.41272 0.0302198 -0.0883634 0.0307973 0.995153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4127.78 -5.98636 -736.885 3967.81 -6.33284 4127.64 +EDGE_SE3:QUAT 964 1014 1.04229 0.000707023 -6.33282 -0.0502489 0.105705 0.0258524 0.992791 1 2.52778e-19 2.52778e-19 -1.3769e-08 2.70156e-08 6.79297e-09 1 2.52778e-19 -1.3769e-08 2.70156e-08 6.79297e-09 1 -1.3769e-08 2.70156e-08 6.79297e-09 4180.3 -17.7489 893.242 3954.04 -1.59515 4187.73 +EDGE_SE3:QUAT 963 1014 -0.344218 12.6826 -6.24371 0.0314356 -0.0572032 -0.0205201 0.997657 1 1.20371e-20 1.20371e-20 -3.89236e-10 2.37217e-10 6.96656e-09 1 1.20371e-20 -3.89236e-10 2.37217e-10 6.96656e-09 1 -3.89236e-10 2.37217e-10 6.96656e-09 4046.89 -8.9175 -453.839 3987.66 7.21829 4049.16 +EDGE_SE3:QUAT 964 1013 -0.20812 -12.3762 -6.36601 0.0422732 -0.106593 -0.0638301 0.991351 1 4.81482e-20 4.81482e-20 -1.4049e-08 1.05123e-09 1.41405e-09 1 4.81482e-20 -1.4049e-08 1.05123e-09 1.41405e-09 1 -1.4049e-08 1.05123e-09 1.41405e-09 4162.8 -36.5972 -841.991 3961.77 40.8127 4153.65 +EDGE_SE3:QUAT 965 1015 0.964985 -0.314154 -6.2474 0.042071 -0.0725017 -0.118624 0.989395 1 2.40741e-19 2.40741e-19 1.55263e-08 -3.39181e-09 -2.85276e-08 1 2.40741e-19 1.55263e-08 -3.39181e-09 -2.85276e-08 1 1.55263e-08 -3.39181e-09 -2.85276e-08 4057.52 -23.295 -513.262 3986.94 34.8776 4008.31 +EDGE_SE3:QUAT 964 1015 0.304185 12.2636 -6.50822 0.00559712 0.00975965 0.0101986 0.999885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.37 0.239175 77.4016 3999.63 0.406515 4001.08 +EDGE_SE3:QUAT 965 1014 -0.000239217 -12.3205 -5.90138 0.125515 0.008989 -0.0164168 0.991915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3939.21 6.38156 94.7062 3999.38 -0.459919 4001.15 +EDGE_SE3:QUAT 966 1016 0.736301 0.0687948 -6.38604 -0.16745 0.0920686 0.0100341 0.981521 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.73 -65.8099 746.955 3971.53 -31.0975 4134.48 +EDGE_SE3:QUAT 965 1016 -0.0782514 12.1717 -6.29303 -0.0600648 0.00190314 0.138322 0.988562 1 4.81482e-20 4.81482e-20 1.37242e-08 1.9034e-09 2.53279e-10 1 4.81482e-20 1.37242e-08 1.9034e-09 2.53279e-10 1 1.37242e-08 1.9034e-09 2.53279e-10 3988.51 -3.9555 112.983 3998.7 9.91856 3926.41 +EDGE_SE3:QUAT 966 1015 -0.0669972 -12.8939 -6.21276 0.0599127 -0.160122 0.0315182 0.984773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4441.21 -32.2642 -1424.72 3895.49 14.0317 4451.6 +EDGE_SE3:QUAT 967 1017 0.977296 -0.0281962 -6.13186 -0.00426134 0.0261837 -0.0357994 0.999007 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.68 -1.02569 207.716 3997.35 -3.80039 4005.63 +EDGE_SE3:QUAT 966 1017 -0.144724 12.6246 -6.30317 0.00493245 0.125497 0.163746 0.978475 1 7.70372e-19 7.70372e-19 6.68318e-09 2.64917e-09 5.59468e-08 1 7.70372e-19 6.68318e-09 2.64917e-09 5.59468e-08 1 6.68318e-09 2.64917e-09 5.59468e-08 4236.73 65.0695 1002.19 3953.34 95.9148 4129.58 +EDGE_SE3:QUAT 967 1016 0.373735 -12.4831 -5.92193 -0.0360915 -0.0814568 -0.14211 0.985833 1 1.20371e-20 1.20371e-20 -6.94682e-09 9.71663e-10 6.21739e-10 1 1.20371e-20 -6.94682e-09 9.71663e-10 6.21739e-10 1 -6.94682e-09 9.71663e-10 6.21739e-10 4117.41 -12.0111 -711.02 3971.13 48.7661 4041.84 +EDGE_SE3:QUAT 968 1018 0.991799 -0.110763 -6.0342 -0.092589 -0.148031 -0.123578 0.976853 1 1.92593e-19 1.92593e-19 -4.82289e-09 -1.66119e-09 2.86183e-08 1 1.92593e-19 -4.82289e-09 -1.66119e-09 2.86183e-08 1 -4.82289e-09 -1.66119e-09 2.86183e-08 4413.04 -0.540548 -1410.65 3896.67 48.8673 4386.24 +EDGE_SE3:QUAT 967 1018 -0.0142333 12.5767 -6.33377 0.122319 -0.064035 0.0340959 0.989836 1 1.20371e-20 1.20371e-20 4.92642e-10 -8.31982e-10 -6.93493e-09 1 1.20371e-20 4.92642e-10 -8.31982e-10 -6.93493e-09 1 4.92642e-10 -8.31982e-10 -6.93493e-09 4016.85 -32.7446 -559.227 3981.28 3.66767 4072.05 +EDGE_SE3:QUAT 968 1017 -0.0505296 -12.2811 -6.34273 0.00144977 -0.0375181 -0.00661631 0.999273 1 4.70198e-23 4.70198e-23 4.34588e-10 -2.93298e-12 -1.63069e-11 1 4.70198e-23 4.34588e-10 -2.93298e-12 -1.63069e-11 1 4.34588e-10 -2.93298e-12 -1.63069e-11 4022.59 -0.446635 -301.491 3994.38 1.06126 4022.42 +EDGE_SE3:QUAT 969 1019 1.06175 0.0570824 -5.98883 0.213552 0.0745483 0.063083 0.972038 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3855.11 41.3588 397.228 3996.71 26.7661 4021.61 +EDGE_SE3:QUAT 968 1019 0.476132 12.8034 -6.52743 -0.023094 -0.0999538 0.117107 0.987807 1 1.92593e-19 1.92593e-19 -2.58692e-09 -1.31372e-09 2.7914e-08 1 1.92593e-19 -2.58692e-09 -1.31372e-09 2.7914e-08 1 -2.58692e-09 -1.31372e-09 2.7914e-08 4141.89 36.3726 -772.895 3969.21 -54.0717 4089.17 +EDGE_SE3:QUAT 969 1018 -0.00609531 -12.6709 -5.91099 0.183191 -0.0387207 -0.122153 0.97469 1 7.73381e-19 7.73381e-19 -5.36476e-08 1.04791e-08 -1.13629e-09 1 7.73381e-19 -5.36476e-08 1.04791e-08 -1.13629e-09 1 -5.36476e-08 1.04791e-08 -1.13629e-09 3863.66 6.10111 -27.1987 3999.89 -3.80344 3938.21 +EDGE_SE3:QUAT 970 1020 0.906563 -0.0544697 -6.1642 0.0981184 0.0733645 -0.0427994 0.991544 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.79 27.7309 641.371 3975.2 -0.292314 4092.97 +EDGE_SE3:QUAT 969 1020 0.0333468 12.4549 -6.35721 0.0243478 0.182504 0.150715 0.97128 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4502.04 151.432 1508.36 3910.59 170.747 4413.55 +EDGE_SE3:QUAT 970 1019 -0.250451 -12.3668 -5.57457 -0.0173019 -0.110706 -0.0729163 0.991024 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4206.21 -14.0122 -934.151 3950.82 33.1597 4186.14 +EDGE_SE3:QUAT 971 1021 0.792452 0.287936 -6.55978 -0.0165893 0.0863155 0.0861595 0.992397 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4124.24 9.92127 719.084 3970 30.4561 4095.65 +EDGE_SE3:QUAT 970 1021 -0.306843 12.5687 -6.46946 -0.0879014 -0.103082 0.0268208 0.990418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4127.69 45.6485 -812.297 3964.66 -33.7925 4155.72 +EDGE_SE3:QUAT 971 1020 0.212675 -12.622 -5.95968 0.0998145 -0.17414 -0.0528528 0.978222 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4415.99 -131.311 -1425.9 3912.18 123.631 4444.67 +EDGE_SE3:QUAT 972 1022 0.808794 0.0662492 -6.38327 0.0101798 0.0523395 -0.0298238 0.998132 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4044.43 0.22518 425.894 3988.87 -5.86451 4041.29 +EDGE_SE3:QUAT 971 1022 -0.390057 12.1046 -6.42982 0.15386 0.0177547 0.0487414 0.98673 1 4.81482e-20 4.81482e-20 2.80284e-11 2.14966e-09 1.36942e-08 1 4.81482e-20 2.80284e-11 2.14966e-09 1.36942e-08 1 2.80284e-11 2.14966e-09 1.36942e-08 3905.63 1.33355 48.0539 4000.03 0.664366 3990.82 +EDGE_SE3:QUAT 972 1021 -0.189658 -12.4364 -6.03227 0.0482956 0.000608611 0.00243699 0.99883 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.67 0.071616 3.44168 4000 0.00386875 3999.98 +EDGE_SE3:QUAT 973 1023 1.00948 0.0353458 -6.10334 0.143343 -0.120825 0.126576 0.97408 1 7.70372e-19 7.70372e-19 -5.05477e-09 5.42921e-08 -6.28461e-09 1 7.70372e-19 -5.05477e-09 5.42921e-08 -6.28461e-09 1 -5.05477e-09 5.42921e-08 -6.28461e-09 4260.76 -44.6733 -1221.1 3917.41 -23.4692 4278.86 +EDGE_SE3:QUAT 972 1023 -0.394991 12.2239 -6.44904 0.0537737 0.116735 0.00776146 0.991676 1 5.11575e-20 5.11575e-20 -1.45517e-08 -4.99212e-10 -5.17749e-09 1 5.11575e-20 -1.45517e-08 -4.99212e-10 -5.17749e-09 1 -1.45517e-08 -4.99212e-10 -5.17749e-09 4210.97 32.3991 969.367 3947.8 22.8122 4222.29 +EDGE_SE3:QUAT 973 1022 -0.0465809 -12.6732 -5.65963 -0.121484 -0.175617 -0.185337 0.959192 1 7.70372e-19 7.70372e-19 -5.79803e-08 9.02981e-09 1.23959e-08 1 7.70372e-19 -5.79803e-08 9.02981e-09 1.23959e-08 1 -5.79803e-08 9.02981e-09 1.23959e-08 4653.61 -46.1181 -1832.9 3847.13 109.122 4575.25 +EDGE_SE3:QUAT 974 1024 1.19569 0.237432 -5.93851 -0.0712007 -0.049166 -0.0544676 0.994759 1 4.81482e-20 4.81482e-20 7.83862e-10 9.18544e-10 -1.38878e-08 1 4.81482e-20 7.83862e-10 9.18544e-10 -1.38878e-08 1 7.83862e-10 9.18544e-10 -1.38878e-08 4027.46 12.8358 -439.762 3987.68 7.77431 4035.87 +EDGE_SE3:QUAT 973 1024 0.000154791 13.0741 -6.31311 -0.0451089 0.223781 0.259145 0.938473 1 7.70372e-19 7.70372e-19 1.48107e-08 -5.19764e-08 4.32269e-09 1 7.70372e-19 1.48107e-08 -5.19764e-08 4.32269e-09 1 1.48107e-08 -5.19764e-08 4.32269e-09 4879.01 327.74 2083.88 3891.42 356.433 4618.53 +EDGE_SE3:QUAT 974 1023 -0.215001 -12.7347 -6.18848 0.156078 0.131063 -0.229112 0.951824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4409.28 -11.8419 1512.62 3884.13 -116.828 4296.76 +EDGE_SE3:QUAT 975 1025 0.328473 0.0277402 -6.28377 0.0383437 -0.120408 0.112172 0.985621 1 1.92593e-19 1.92593e-19 -2.94201e-09 2.73754e-08 -3.07955e-10 1 1.92593e-19 -2.94201e-09 2.73754e-08 -3.07955e-10 1 -2.94201e-09 2.73754e-08 -3.07955e-10 4254.14 20.9801 -1052.48 3939.54 -53.9887 4209.69 +EDGE_SE3:QUAT 974 1025 0.294434 12.4117 -6.50075 -0.0455303 -0.0520854 0.0097778 0.997556 1 5.11575e-20 5.11575e-20 -1.40949e-08 -3.66139e-10 4.19027e-09 1 5.11575e-20 -1.40949e-08 -3.66139e-10 4.19027e-09 1 -1.40949e-08 -3.66139e-10 4.19027e-09 4034.05 10.2619 -413.744 3989.72 -4.99958 4041.96 +EDGE_SE3:QUAT 975 1024 -0.125894 -11.9628 -5.90117 -0.0339349 0.0189503 -0.0498968 0.997998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.64 -2.44636 130.608 3999.07 -3.32609 3994.29 +EDGE_SE3:QUAT 976 1026 0.920215 -0.255805 -6.207 -0.197933 0.17513 0.0830126 0.960865 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4481.98 -154.859 1721.26 3870.76 -100.188 4611.12 +EDGE_SE3:QUAT 975 1026 -0.0465469 12.3211 -6.11873 0.0551542 -0.186605 0.101311 0.97564 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4649.19 39.0493 -1755.8 3855.1 -66.5905 4620.3 +EDGE_SE3:QUAT 976 1025 -0.214974 -12.3371 -5.86859 0.0179442 -0.215726 0.0333611 0.975719 1 8.1852e-19 8.1852e-19 1.73431e-09 5.41067e-08 -1.5176e-08 1 8.1852e-19 1.73431e-09 5.41067e-08 -1.5176e-08 1 1.73431e-09 5.41067e-08 -1.5176e-08 4866.76 19.596 -2055.65 3813.35 -26.361 4863.59 +EDGE_SE3:QUAT 977 1027 0.61781 -0.094843 -6.30881 0.0259687 -0.0034335 -0.0116017 0.99959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.44 -0.296192 -23.8219 3999.97 0.137056 3999.6 +EDGE_SE3:QUAT 976 1027 -0.320147 12.4825 -6.45679 -0.0634688 -0.122316 0.182418 0.973516 1 1.92593e-19 1.92593e-19 2.75648e-08 5.70561e-09 -2.53141e-09 1 1.92593e-19 2.75648e-08 5.70561e-09 -2.53141e-09 1 2.75648e-08 5.70561e-09 -2.53141e-09 4139.68 77.0251 -809.05 3978.22 -94.7637 4022.68 +EDGE_SE3:QUAT 977 1026 -0.232392 -12.7437 -6.09333 0.120279 0.000580579 0.0424091 0.991834 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3942.82 -4.5706 -56.025 3999.64 -1.54087 3993.49 +EDGE_SE3:QUAT 978 1028 0.942538 -0.19845 -6.10503 -0.178344 -0.0487951 0.095227 0.978133 1 7.70372e-19 7.70372e-19 -5.43362e-08 -5.91729e-09 6.32453e-10 1 7.70372e-19 -5.43362e-08 -5.91729e-09 6.32453e-10 1 -5.43362e-08 -5.91729e-09 6.32453e-10 3878.26 10.0044 -167.757 4000.17 -7.59514 3969.21 +EDGE_SE3:QUAT 977 1028 -0.221437 12.2384 -6.39962 -0.0178743 -0.0373056 0.172068 0.984216 1 7.70372e-19 7.70372e-19 1.61239e-09 1.64232e-09 -5.47435e-08 1 7.70372e-19 1.61239e-09 1.64232e-09 -5.47435e-08 1 1.61239e-09 1.64232e-09 -5.47435e-08 4014.14 6.54561 -249.662 3997.2 -20.7514 3896.99 +EDGE_SE3:QUAT 978 1027 -0.138073 -12.5091 -6.15422 0.0192556 -0.0602331 -0.0940571 0.993556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.37 -12.0912 -458.509 3988.26 23.4493 4016.46 +EDGE_SE3:QUAT 979 1029 0.826271 0.264071 -6.66325 0.211664 0.0854902 -0.0591979 0.971795 1 9.62965e-19 9.62965e-19 -5.55804e-08 -2.59387e-08 -1.15867e-10 1 9.62965e-19 -5.55804e-08 -2.59387e-08 -1.15867e-10 1 -5.55804e-08 -2.59387e-08 -1.15867e-10 3978.78 83.8057 810.658 3964.58 22.0658 4143.97 +EDGE_SE3:QUAT 978 1029 -0.366746 12.5224 -6.24772 0.104889 -0.0256788 -0.0864328 0.990388 1 1.92593e-19 1.92593e-19 -2.74949e-08 2.49696e-09 1.8724e-10 1 1.92593e-19 -2.74949e-08 2.49696e-09 1.8724e-10 1 -2.74949e-08 2.49696e-09 1.8724e-10 3957.74 -3.29173 -92.2239 3999.9 2.88535 3971.87 +EDGE_SE3:QUAT 979 1028 0.10159 -12.1924 -5.76986 0.0412665 -0.0135601 0.0771773 0.996071 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.44 -2.71719 -145.453 3998.48 -5.81185 3981.42 +EDGE_SE3:QUAT 980 1030 0.516084 0.353893 -6.26999 -0.103335 -0.175899 0.0231148 0.978697 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4456.03 120.367 -1498.18 3898.69 -106.706 4496.6 +EDGE_SE3:QUAT 979 1030 0.262921 12.3685 -6.66757 0.0424058 -0.135997 0.174571 0.974285 1 7.82409e-19 7.82409e-19 -1.1795e-09 8.37025e-10 5.53574e-08 1 7.82409e-19 -1.1795e-09 8.37025e-10 5.53574e-08 1 -1.1795e-09 8.37025e-10 5.53574e-08 4329.81 60.2955 -1208.97 3928.78 -106.88 4215.11 +EDGE_SE3:QUAT 980 1029 0.226253 -12.5952 -5.97148 -0.0848619 0.0750796 0.0816763 0.990197 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4086.42 -18.5403 688.893 3970.79 16.7944 4088.54 +EDGE_SE3:QUAT 981 1031 0.97145 -0.16765 -6.2404 -0.118426 0.12247 0.0357237 0.984734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4211.33 -59.8019 1068.29 3938.47 -26.1735 4262.32 +EDGE_SE3:QUAT 980 1031 0.0586772 12.2917 -6.30741 -0.105935 -0.0187701 -0.0242111 0.993901 1 1.92593e-19 1.92593e-19 2.76139e-08 -5.48193e-10 -6.50984e-10 1 1.92593e-19 2.76139e-08 -5.48193e-10 -6.50984e-10 1 2.76139e-08 -5.48193e-10 -6.50984e-10 3963.03 9.71826 -178.388 3997.89 1.0996 4005.58 +EDGE_SE3:QUAT 981 1030 0.146255 -11.9874 -6.31703 0.0368144 -0.0598268 -0.1367 0.988119 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.5 -16.5607 -407.713 3992.11 29.537 3966.18 +EDGE_SE3:QUAT 982 1032 0.79876 0.0997322 -6.21252 0.0120197 0.0228876 -0.126619 0.991614 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.12 -0.582205 197.185 3997.62 -12.6797 3945.56 +EDGE_SE3:QUAT 981 1032 -0.316288 12.3782 -6.33659 -0.10938 0.0453099 0.0873222 0.98912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.72 -21.872 471.378 3985.08 14.4706 4024.07 +EDGE_SE3:QUAT 982 1031 0.0862577 -12.1616 -6.09957 -0.222842 -0.131064 -0.153096 0.953795 1 7.70372e-19 7.70372e-19 -5.63368e-08 5.07582e-09 1.06536e-08 1 7.70372e-19 -5.63368e-08 5.07582e-09 1.06536e-08 1 -5.63368e-08 5.07582e-09 1.06536e-08 4297.26 111.135 -1494.5 3886.19 -9.46374 4402.14 +EDGE_SE3:QUAT 983 1033 0.679282 -0.0394274 -6.17867 -0.0353195 -0.0630282 -0.0391334 0.996619 1 4.81482e-20 4.81482e-20 -1.39485e-08 4.88199e-10 9.16219e-10 1 4.81482e-20 -1.39485e-08 4.88199e-10 9.16219e-10 1 -1.39485e-08 4.88199e-10 9.16219e-10 4063.17 5.80296 -526.593 3983 7.24849 4062.03 +EDGE_SE3:QUAT 982 1033 0.0538117 12.726 -6.38263 -0.104845 -0.315921 0.0567509 0.941266 1 7.70372e-19 7.70372e-19 6.36514e-08 9.90811e-09 -1.95609e-08 1 7.70372e-19 6.36514e-08 9.90811e-09 -1.95609e-08 1 6.36514e-08 9.90811e-09 -1.95609e-08 5839.98 572.498 -3330.88 3774.61 -577.01 5871.06 +EDGE_SE3:QUAT 983 1032 0.263484 -12.6578 -6.20059 0.155914 -0.137649 0.129787 0.969484 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4348.57 -55.7671 -1408.45 3895.73 -14.4547 4378.43 +EDGE_SE3:QUAT 984 1034 0.902803 0.33535 -6.26988 -0.209386 0.0446152 -0.0460463 0.975729 1 4.81482e-20 4.81482e-20 -8.37909e-10 -1.35301e-08 -2.95592e-09 1 4.81482e-20 -8.37909e-10 -1.35301e-08 -2.95592e-09 1 -8.37909e-10 -1.35301e-08 -2.95592e-09 3836.09 -19.5498 220.462 3999.04 -9.06756 4002.98 +EDGE_SE3:QUAT 983 1034 0.0473924 12.7566 -6.38026 0.0808016 -0.0578344 0.128824 0.986677 1 3.85186e-19 3.85186e-19 2.5544e-08 5.12647e-09 2.5544e-08 1 3.85186e-19 2.5544e-08 5.12647e-09 2.5544e-08 1 2.5544e-08 5.12647e-09 2.5544e-08 4056.45 -11.0973 -581.394 3978.25 -32.1628 4016.19 +EDGE_SE3:QUAT 984 1033 -0.159782 -12.6897 -6.12674 0.0717502 -0.0455032 -0.131114 0.98772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.37 -10.8277 -240.894 3998.06 15.2229 3945.2 +EDGE_SE3:QUAT 985 1035 0.76088 0.595172 -6.15714 0.100678 -0.00188201 -0.0362008 0.994258 1 7.70372e-19 7.70372e-19 5.51935e-08 -1.98975e-09 3.00234e-10 1 7.70372e-19 5.51935e-08 -1.98975e-09 3.00234e-10 1 5.51935e-08 -1.98975e-09 3.00234e-10 3959.61 2.17354 28.6043 3999.88 -0.770428 3994.91 +EDGE_SE3:QUAT 984 1035 -0.271609 12.4888 -6.48593 -0.0916114 0.166065 -0.0467279 0.980738 1 1.54074e-18 1.54074e-18 -5.28444e-08 5.90002e-08 -2.71933e-09 1 1.54074e-18 -5.28444e-08 5.90002e-08 -2.71933e-09 1 -5.28444e-08 5.90002e-08 -2.71933e-09 4388.52 -111.296 1366.68 3914.99 -103.47 4413.36 +EDGE_SE3:QUAT 985 1034 -0.0414807 -12.4787 -5.59242 -0.0108508 -0.117586 -0.197116 0.973242 1 3.00927e-21 3.00927e-21 -3.47014e-09 7.13917e-10 4.01131e-10 1 3.00927e-21 -3.47014e-09 7.13917e-10 4.01131e-10 1 -3.47014e-09 7.13917e-10 4.01131e-10 4215.23 -61.9245 -954.027 3958.94 103.239 4060.28 +EDGE_SE3:QUAT 986 1036 0.416486 0.173878 -6.25705 -0.157546 -0.0578915 -0.141944 0.975541 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.7 42.7071 -715.022 3965.6 33.593 4042.39 +EDGE_SE3:QUAT 985 1036 0.210578 12.4452 -6.0777 -0.172426 0.0381694 0.075602 0.981375 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3930.2 -38.6317 447.666 3986.26 7.76993 4026.26 +EDGE_SE3:QUAT 986 1035 0.0697048 -12.4 -6.41442 -0.163411 -0.00229252 0.019158 0.986369 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3893.24 -2.61876 19.2893 3999.94 0.300603 3998.59 +EDGE_SE3:QUAT 987 1037 0.745205 -0.146854 -6.4783 -0.0998422 -0.0125594 0.023041 0.994657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3961.38 3.13983 -71.4944 3999.78 -0.940451 3999.13 +EDGE_SE3:QUAT 986 1037 0.0298243 12.3096 -6.21928 -0.0558497 0.128205 -0.030726 0.989697 1 4.81482e-20 4.81482e-20 1.77005e-09 -9.40773e-10 1.41779e-08 1 4.81482e-20 1.77005e-09 -9.40773e-10 1.41779e-08 1 1.77005e-09 -9.40773e-10 1.41779e-08 4248.48 -46.7999 1054.55 3940.73 -41.6944 4257.18 +EDGE_SE3:QUAT 987 1036 -0.0372665 -12.5684 -6.23244 -0.0181577 0.0371442 -0.0979849 0.994329 1 1.92593e-19 1.92593e-19 9.13951e-10 -6.98644e-10 2.76624e-08 1 1.92593e-19 9.13951e-10 -6.98644e-10 2.76624e-08 1 9.13951e-10 -6.98644e-10 2.76624e-08 4017.14 -5.28128 272.539 3995.89 -13.6352 3980.05 +EDGE_SE3:QUAT 988 1038 1.00213 0.140811 -6.13135 0.130306 0.0274421 0.0653767 0.988935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3934.85 5.38274 111.718 3999.77 3.3731 3985.67 +EDGE_SE3:QUAT 987 1038 -0.0484284 12.6488 -6.36055 0.117733 0.101309 0.0299126 0.987411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4088.53 55.7809 772.874 3969.78 39.5027 4140.39 +EDGE_SE3:QUAT 988 1037 -0.175183 -12.2427 -6.04488 -0.000784577 -0.0927978 -0.0013602 0.995684 1 1.92605e-19 1.92605e-19 -2.54008e-10 -2.76355e-08 5.41627e-12 1 1.92605e-19 -2.54008e-10 -2.76355e-08 5.41627e-12 1 -2.54008e-10 -2.76355e-08 5.41627e-12 4141.43 0.0343943 -765.325 3965.55 0.398817 4141.42 +EDGE_SE3:QUAT 989 1039 0.859458 -0.0381881 -6.33884 -0.139645 -0.000642059 -0.0807441 0.986904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3926.3 12.4363 -138.048 3997.96 6.77969 3978.23 +EDGE_SE3:QUAT 988 1039 -0.00233239 12.4756 -6.08487 -0.0473428 -0.141243 0.00783223 0.988811 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4324.86 38.5346 -1202.82 3922.93 -30.4222 4333.58 +EDGE_SE3:QUAT 989 1038 -0.0832312 -12.5765 -6.13582 0.061918 0.133955 -0.0392807 0.988271 1 4.81482e-20 4.81482e-20 -1.42497e-08 3.38012e-10 -1.98318e-09 1 4.81482e-20 -1.42497e-08 3.38012e-10 -1.98318e-09 1 -1.42497e-08 3.38012e-10 -1.98318e-09 4301.18 24.3665 1168.87 3925.32 2.60523 4310.34 +EDGE_SE3:QUAT 990 1040 0.612571 0.0823428 -6.32546 -0.0527523 0.0105262 -0.0248506 0.998243 1 4.81482e-20 4.81482e-20 -1.38554e-08 3.58458e-10 -1.0877e-10 1 4.81482e-20 -1.38554e-08 3.58458e-10 -1.0877e-10 1 -1.38554e-08 3.58458e-10 -1.0877e-10 3990.02 -1.70362 68.0979 3999.76 -0.881695 3998.68 +EDGE_SE3:QUAT 989 1040 -0.41177 12.2184 -6.2708 0.0344663 0.111393 -0.00349812 0.993172 1 1.92605e-19 1.92605e-19 1.42496e-10 -2.75583e-08 1.17979e-09 1 1.92605e-19 1.42496e-10 -2.75583e-08 1.17979e-09 1 1.42496e-10 -2.75583e-08 1.17979e-09 4201.36 17.0544 931.095 3950.64 9.06896 4206.06 +EDGE_SE3:QUAT 990 1039 0.161203 -12.5141 -6.17915 -0.0589852 0.11238 -0.0569767 0.990275 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4172.12 -45.6064 882.724 3958.92 -45.2157 4173.05 +EDGE_SE3:QUAT 991 1041 0.684531 0.207794 -6.11774 -0.0793929 0.108003 0.0744067 0.988178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4195.7 -19.5902 965.754 3946.26 15.1556 4198.77 +EDGE_SE3:QUAT 990 1041 -0.0815889 12.8565 -6.41259 -0.103889 -0.0482722 0.0125144 0.993338 1 2.0463e-19 2.0463e-19 -2.79975e-08 -1.35717e-09 8.16504e-09 1 2.0463e-19 -2.79975e-08 -1.35717e-09 8.16504e-09 1 -2.79975e-08 -1.35717e-09 8.16504e-09 3990.18 19.7684 -366.901 3992.45 -7.69531 4032.73 +EDGE_SE3:QUAT 991 1040 -0.247268 -12.5855 -5.90533 0.016903 -0.120469 -0.0394936 0.991787 1 1.20371e-20 1.20371e-20 7.08323e-09 -3.1998e-10 -8.47227e-10 1 1.20371e-20 7.08323e-09 -3.1998e-10 -8.47227e-10 1 7.08323e-09 -3.1998e-10 -8.47227e-10 4235.79 -24.2391 -1001.95 3944.39 28.9454 4230.7 +EDGE_SE3:QUAT 992 1042 0.593412 0.102136 -6.26431 0.0482923 0.13751 -0.135211 0.980039 1 1.20371e-20 1.20371e-20 -7.09754e-09 9.16725e-10 -1.05152e-09 1 1.20371e-20 -7.09754e-09 9.16725e-10 -1.05152e-09 1 -7.09754e-09 9.16725e-10 -1.05152e-09 4341.09 -36.523 1234.71 3921.09 -76.5019 4277.29 +EDGE_SE3:QUAT 991 1042 -0.114133 12.2738 -6.28149 0.0314922 -0.0521323 0.00987352 0.998095 1 1.50463e-20 1.50463e-20 7.14779e-09 -6.0705e-11 -3.84938e-09 1 1.50463e-20 7.14779e-09 -6.0705e-11 -3.84938e-09 1 7.14779e-09 -6.0705e-11 -3.84938e-09 4040.53 -6.22836 -424.22 3988.96 -0.0530521 4044.11 +EDGE_SE3:QUAT 992 1041 0.136429 -12.5985 -6.00634 -0.031121 -0.0392171 -0.017433 0.998594 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.8 4.44764 -321.465 3993.56 1.67305 4024.45 +EDGE_SE3:QUAT 993 1043 0.503989 0.0360185 -6.20481 -0.0817638 -0.0393651 0.0335 0.99531 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.66 12.135 -279.584 3995.76 -7.08712 4014.91 +EDGE_SE3:QUAT 992 1043 -0.0879235 12.541 -6.26354 0.0198688 0.0586438 0.117501 0.991141 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.23 13.0456 435.548 3989.86 27.1652 3991.59 +EDGE_SE3:QUAT 993 1042 0.0528786 -12.2103 -6.25475 0.0193551 -0.0891619 0.0320752 0.995312 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4131.09 -1.33788 -740.226 3967.61 -9.01858 4128.47 +EDGE_SE3:QUAT 994 1044 0.359602 -0.00407697 -6.39772 -0.209385 -0.105556 -0.070938 0.969527 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4066 99.9688 -1011.95 3946.58 -32.8934 4221.24 +EDGE_SE3:QUAT 993 1044 -0.200194 12.6637 -6.55307 -0.153912 -0.0518482 0.092077 0.982418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3917.11 15.4593 -228.175 3999.13 -11.9619 3977.95 +EDGE_SE3:QUAT 994 1043 -0.361625 -12.4464 -6.16575 -0.0215011 -0.0603945 -0.0245984 0.99764 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4058.55 3.31825 -495.241 3985 4.39924 4057.98 +EDGE_SE3:QUAT 995 1045 0.638183 -0.019264 -6.25678 0.0213998 -0.054078 -0.0754055 0.995455 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4040.34 -9.39818 -412.961 3990.24 17.128 4019.42 +EDGE_SE3:QUAT 994 1045 0.0884728 12.4754 -6.22043 0.0310852 -0.0399018 0.0422309 0.997827 1 4.81482e-20 4.81482e-20 1.38961e-08 5.54338e-10 -5.89285e-10 1 4.81482e-20 1.38961e-08 5.54338e-10 -5.89285e-10 1 1.38961e-08 5.54338e-10 -5.89285e-10 4024.11 -3.63927 -335.736 3992.9 -6.03116 4020.85 +EDGE_SE3:QUAT 995 1044 -0.192521 -12.4818 -5.9499 0.0894509 0.185272 -0.233479 0.950347 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4700.46 -153.924 1861.82 3864.9 -211.998 4514.42 +EDGE_SE3:QUAT 996 1046 0.910007 0.127676 -6.73475 -0.141274 -0.228518 0.117301 0.956066 1 7.70372e-19 7.70372e-19 -1.04501e-08 -1.2512e-08 5.72922e-08 1 7.70372e-19 -1.04501e-08 -1.2512e-08 5.72922e-08 1 -1.04501e-08 -1.2512e-08 5.72922e-08 4547.83 309.964 -1711.52 3942.8 -308.601 4572.62 +EDGE_SE3:QUAT 995 1046 -0.0942045 12.2525 -6.36602 0.0627553 0.0583517 0.124906 0.988461 1 7.70372e-19 7.70372e-19 -2.2527e-09 -4.21666e-09 -5.50952e-08 1 7.70372e-19 -2.2527e-09 -4.21666e-09 -5.50952e-08 1 -2.2527e-09 -4.21666e-09 -5.50952e-08 4016.37 17.556 362.068 3994.41 24.5008 3969.71 +EDGE_SE3:QUAT 996 1045 -0.0331416 -12.5293 -6.22196 0.0343954 -0.0450552 0.0391148 0.997626 1 9.62965e-20 9.62965e-20 -1.61481e-10 -1.34157e-08 1.43351e-08 1 9.62965e-20 -1.61481e-10 -1.34157e-08 1.43351e-08 1 -1.61481e-10 -1.34157e-08 1.43351e-08 4030.69 -4.67984 -378.089 3991.05 -5.85132 4029.3 +EDGE_SE3:QUAT 997 1047 0.610943 0.10204 -6.15324 -0.187671 -0.00836527 0.171369 0.967131 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3879.68 -38.1386 310.33 3988.45 34.2134 3903.09 +EDGE_SE3:QUAT 996 1047 -0.461841 12.6464 -6.31498 -0.11731 0.0490119 -0.0027311 0.991881 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.32 -22.9498 383.186 3991.69 -7.09465 4036.34 +EDGE_SE3:QUAT 997 1046 -0.276682 -12.7518 -6.60978 0.00598377 -0.106505 -0.182095 0.977478 1 1.20371e-20 1.20371e-20 6.92428e-09 -1.32849e-09 -6.87604e-10 1 1.20371e-20 6.92428e-09 -1.32849e-09 -6.87604e-10 1 6.92428e-09 -1.32849e-09 -6.87604e-10 4162.85 -50.4475 -824.398 3968.96 83.5859 4030.35 +EDGE_SE3:QUAT 998 1048 0.512501 -0.217568 -6.3991 0.0386009 -0.0407067 0.178683 0.982306 1 7.82409e-19 7.82409e-19 -3.97118e-09 -2.44899e-09 -5.4439e-08 1 7.82409e-19 -3.97118e-09 -2.44899e-09 -5.4439e-08 1 -3.97118e-09 -2.44899e-09 -5.4439e-08 4032.44 1.56003 -394.105 3990.45 -35.8706 3910.69 +EDGE_SE3:QUAT 997 1048 -0.099088 12.7762 -6.3696 -0.0175272 -0.118722 -0.0430418 0.991839 1 3.00927e-21 3.00927e-21 3.54251e-09 -1.42949e-10 -4.27731e-10 1 3.00927e-21 3.54251e-09 -1.42949e-10 -4.27731e-10 1 3.54251e-09 -1.42949e-10 -4.27731e-10 4237.46 -5.62578 -1005.84 3943.01 18.5376 4231.28 +EDGE_SE3:QUAT 998 1047 -0.154081 -12.6061 -6.16668 0.135536 0.170817 -0.0473925 0.974785 1 1.55278e-18 1.55278e-18 5.64583e-08 5.32038e-08 -3.77859e-09 1 1.55278e-18 5.64583e-08 5.32038e-08 -3.77859e-09 1 5.64583e-08 5.32038e-08 -3.77859e-09 4470.25 101.983 1571.8 3883.07 66.9129 4534.75 +EDGE_SE3:QUAT 999 1049 0.764472 -0.241132 -5.97074 0.0207049 -0.098188 -0.0657148 0.99278 1 1.20371e-20 1.20371e-20 7.01714e-09 -5.02164e-10 -6.67637e-10 1 1.20371e-20 7.01714e-09 -5.02164e-10 -6.67637e-10 1 7.01714e-09 -5.02164e-10 -6.67637e-10 4147.92 -24.1412 -788.063 3965.29 33.0274 4132.37 +EDGE_SE3:QUAT 998 1049 -0.692335 12.6823 -6.45256 -0.108291 0.0191517 0.147184 0.982977 1 9.62965e-19 9.62965e-19 -2.46344e-08 -9.36474e-09 5.33849e-08 1 9.62965e-19 -2.46344e-08 -9.36474e-09 5.33849e-08 1 -2.46344e-08 -9.36474e-09 5.33849e-08 3980.21 -16.8062 335.043 3990.84 25.8686 3940.47 +EDGE_SE3:QUAT 999 1048 0.0836325 -12.3973 -6.24504 0.0682735 -0.113535 -0.1125 0.98478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4141.54 -59.7818 -817.781 3969.59 67.4137 4109.56 +EDGE_SE3:QUAT 1000 1050 0.529003 -0.29689 -6.51695 -0.0499407 -0.00742833 -0.257791 0.96488 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.72 3.3757 -201.312 3996.52 31.8277 3743.87 +EDGE_SE3:QUAT 999 1050 -0.562026 12.6268 -6.24831 0.0983656 -0.097112 0.0152093 0.990284 1 7.52316e-22 7.52316e-22 1.73715e-10 -1.72048e-10 -1.7518e-09 1 7.52316e-22 1.73715e-10 -1.72048e-10 -1.7518e-09 1 1.73715e-10 -1.72048e-10 -1.7518e-09 4119.32 -40.3686 -810.594 3962.92 16.9527 4157.1 +EDGE_SE3:QUAT 1000 1049 0.154642 -12.4583 -6.00205 0.108471 -0.0753984 -0.125075 0.983314 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.46 -30.4133 -420.374 3994.32 32.1826 3979.95 +EDGE_SE3:QUAT 1001 1051 0.449509 -0.460695 -6.10359 0.0232625 -0.0776192 -0.121092 0.989329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4081 -22.9808 -583.125 3982.25 39.4815 4024.52 +EDGE_SE3:QUAT 1000 1051 -0.242482 12.46 -6.54027 -0.151772 0.00847428 -0.00192587 0.988377 1 7.71124e-19 7.71124e-19 -5.48597e-08 -2.02266e-11 1.29806e-09 1 7.71124e-19 -5.48597e-08 -2.02266e-11 1.29806e-09 1 -5.48597e-08 -2.02266e-11 1.29806e-09 3908.82 -4.56391 62.0235 3999.8 -0.288463 4000.94 +EDGE_SE3:QUAT 1001 1050 -0.268612 -12.5895 -6.20046 0.129165 0.00789826 -0.0235029 0.991313 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3935.62 6.98915 97.6298 3999.29 -0.889464 4000.14 +EDGE_SE3:QUAT 1002 1052 0.72885 0.321833 -5.92644 -0.0775991 0.0185668 -0.0880061 0.992919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.74 -1.62138 64.2429 3999.95 -1.78202 3969.85 +EDGE_SE3:QUAT 1001 1052 -0.257888 12.5507 -6.62987 -0.115219 -0.0623684 -0.00335779 0.991375 1 2.40929e-19 2.40929e-19 2.76303e-08 1.4168e-08 -9.80415e-10 1 2.40929e-19 2.76303e-08 1.4168e-08 -9.80415e-10 1 2.76303e-08 1.4168e-08 -9.80415e-10 4008.51 29.5863 -500.284 3985.74 -9.97914 4061.57 +EDGE_SE3:QUAT 1002 1051 -0.22518 -12.4932 -5.91213 0.135437 0.0477053 -0.203064 0.968579 1 7.70372e-19 7.70372e-19 -5.39528e-09 -5.98664e-09 -5.45623e-08 1 7.70372e-19 -5.39528e-09 -5.98664e-09 -5.45623e-08 1 -5.39528e-09 -5.98664e-09 -5.45623e-08 4039.29 25.9353 685.265 3967.09 -63.5501 3947.72 +EDGE_SE3:QUAT 1003 1053 0.132655 -0.276275 -6.03374 0.058536 -0.112021 0.0572339 0.990328 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4210.86 -13.3014 -974.049 3945.75 -12.1277 4211.46 +EDGE_SE3:QUAT 1002 1053 -0.0370886 12.3984 -6.82592 -0.118933 0.0195967 -0.0218897 0.992467 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3947.13 -6.75733 122.48 3999.3 -1.97712 4001.79 +EDGE_SE3:QUAT 1003 1052 -0.357313 -12.4114 -6.04047 -0.0723733 0.139841 -0.0933221 0.983106 1 1.92593e-19 1.92593e-19 3.49137e-09 -2.88305e-09 2.81995e-08 1 1.92593e-19 3.49137e-09 -2.88305e-09 2.81995e-08 1 3.49137e-09 -2.88305e-09 2.81995e-08 4246.36 -85.7335 1069.05 3947.95 -89.4761 4232.47 +EDGE_SE3:QUAT 1004 1054 0.51821 0.36962 -6.08709 -0.111088 0.0177466 0.112688 0.987242 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3970.48 -15.949 285.898 3993.39 16.2574 3969.05 +EDGE_SE3:QUAT 1003 1054 -0.229988 12.3662 -6.79485 0.0157792 0.040795 0.0967638 0.994346 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.09 5.87809 304.899 3994.79 15.1886 3985.63 +EDGE_SE3:QUAT 1004 1053 -0.0198251 -12.3644 -6.37034 -0.148671 -0.0602799 -0.11048 0.980845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.75 40.4317 -668.298 3970.76 20.1531 4059.34 +EDGE_SE3:QUAT 1005 1055 0.709114 0.0639608 -6.13232 0.0406567 -0.106416 0.0733469 0.990779 1 4.81482e-20 4.81482e-20 -1.40922e-08 -9.39733e-10 1.57883e-09 1 4.81482e-20 -1.40922e-08 -9.39733e-10 1.57883e-09 1 -1.40922e-08 -9.39733e-10 1.57883e-09 4193.78 1.11173 -917.488 3951.65 -25.8546 4178.88 +EDGE_SE3:QUAT 1004 1055 -0.230788 12.8269 -6.31686 0.000136565 -0.178707 -0.0703547 0.981384 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4554.73 -62.7412 -1589.57 3878.63 75.1861 4534.93 +EDGE_SE3:QUAT 1005 1054 -0.4077 -12.4409 -6.11084 0.0987784 0.06656 0.0228557 0.992618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.39 27.6217 503.79 3986.08 15.5505 4060.33 +EDGE_SE3:QUAT 1006 1056 0.630889 -0.0171263 -6.00164 -0.0858077 0.196235 -0.117934 0.96965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4494.65 -195.572 1542.33 3918.67 -199.528 4468.47 +EDGE_SE3:QUAT 1005 1056 -0.198634 11.9548 -6.42644 -0.0280779 0.134145 0.319993 0.937455 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4264.53 127.153 1071.69 3973.56 189.865 3858.1 +EDGE_SE3:QUAT 1006 1055 0.004509 -12.8014 -6.24434 -0.0114234 -0.18218 -0.0724208 0.980528 1 7.52316e-22 7.52316e-22 1.82227e-09 -1.36043e-10 -3.38016e-10 1 7.52316e-22 1.82227e-09 -1.36043e-10 -3.38016e-10 1 1.82227e-09 -1.36043e-10 -3.38016e-10 4587.21 -55.4859 -1642.06 3871.01 70.1772 4566.75 +EDGE_SE3:QUAT 1007 1057 0.538324 0.31711 -6.0591 0.0734956 0.0107963 -0.102919 0.991912 1 1.92593e-19 1.92593e-19 -2.75569e-08 2.78574e-09 -7.07441e-10 1 1.92593e-19 -2.75569e-08 2.78574e-09 -7.07441e-10 1 -2.75569e-08 2.78574e-09 -7.07441e-10 3985.79 6.58676 174.451 3997.48 -9.86232 3965.03 +EDGE_SE3:QUAT 1006 1057 -0.0634352 12.3041 -6.4471 -0.0619337 -0.0109479 0.230977 0.970924 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.69 -4.30964 84.9584 3998.7 16.6655 3787.63 +EDGE_SE3:QUAT 1007 1056 -0.504768 -12.5891 -6.03357 0.0873666 0.0859621 0.0529256 0.991048 1 1.92593e-19 1.92593e-19 1.88435e-09 -2.74818e-08 2.69686e-09 1 1.92593e-19 1.88435e-09 -2.74818e-08 2.69686e-09 1 1.88435e-09 -2.74818e-08 2.69686e-09 4067.37 36.9781 633.938 3979.17 31.0875 4086.69 +EDGE_SE3:QUAT 1008 1058 0.537716 0.264053 -6.15728 -0.0143169 -0.0922392 -0.102919 0.9903 1 7.52316e-22 7.52316e-22 -1.74845e-09 1.80133e-10 1.64565e-10 1 7.52316e-22 -1.74845e-09 1.80133e-10 1.64565e-10 1 -1.74845e-09 1.80133e-10 1.64565e-10 4141.18 -16.3087 -766.915 3966.73 40.0922 4099.63 +EDGE_SE3:QUAT 1007 1058 -0.397593 12.3576 -6.51827 0.0998628 0.106255 -0.0649238 0.987179 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4176.14 33.9436 954.471 3947.65 -3.3979 4199.17 +EDGE_SE3:QUAT 1008 1057 -0.507972 -12.7319 -6.07175 0.151794 -0.0728207 -0.106822 0.979921 1 7.70372e-19 7.70372e-19 5.4615e-08 -6.94356e-09 -1.98098e-09 1 7.70372e-19 5.4615e-08 -6.94356e-09 -1.98098e-09 1 5.4615e-08 -6.94356e-09 -1.98098e-09 3938.81 -29.6244 -362.723 3997.06 25.7814 3985.33 +EDGE_SE3:QUAT 1009 1059 0.25168 -0.170063 -6.66958 0.111073 -0.029044 -0.0107767 0.993329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3962.08 -11.8437 -214.278 3997.47 3.12654 4010.97 +EDGE_SE3:QUAT 1008 1059 -0.051946 12.3136 -6.64184 0.0269657 -0.114423 -0.0362134 0.992406 1 1.92593e-19 1.92593e-19 1.20457e-09 2.75368e-08 -1.00045e-09 1 1.92593e-19 1.20457e-09 2.75368e-08 -1.00045e-09 1 1.20457e-09 2.75368e-08 -1.00045e-09 4207.73 -26.192 -941.793 3950.6 28.1009 4205.4 +EDGE_SE3:QUAT 1009 1058 -0.0389247 -12.5292 -5.69933 -0.186179 -0.101118 0.0100644 0.977247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.05 78.9636 -766.927 3973.64 -46.863 4141.29 +EDGE_SE3:QUAT 1010 1060 0.505021 0.0760697 -6.45833 0.120217 0.107483 -0.0673765 0.984609 1 1.92593e-19 1.92593e-19 2.8108e-08 -1.17055e-09 3.42136e-09 1 1.92593e-19 2.8108e-08 -1.17055e-09 3.42136e-09 1 2.8108e-08 -1.17055e-09 3.42136e-09 4169.74 45.6677 980.971 3945.29 2.46774 4209.39 +EDGE_SE3:QUAT 1009 1060 -0.296313 12.6177 -6.27036 -0.134548 0.0509869 0.0950934 0.985015 1 7.70372e-19 7.70372e-19 5.51994e-08 4.40741e-09 4.12672e-09 1 7.70372e-19 5.51994e-08 4.40741e-09 4.12672e-09 1 5.51994e-08 4.40741e-09 4.12672e-09 4002.12 -32.0173 552.458 3979.63 15.7407 4038.36 +EDGE_SE3:QUAT 1010 1059 0.0959879 -12.6811 -6.2792 0.0046203 0.021304 -0.0166048 0.999624 1 7.52316e-22 7.52316e-22 -1.73566e-09 2.85142e-11 -3.72351e-11 1 7.52316e-22 -1.73566e-09 2.85142e-11 -3.72351e-11 1 -1.73566e-09 2.85142e-11 -3.72351e-11 4007.26 0.216166 171.553 3998.16 -1.38263 4006.24 +EDGE_SE3:QUAT 1011 1061 0.56774 -0.26519 -6.09143 -0.0994136 0.00102921 0.0341787 0.994458 1 4.81482e-20 4.81482e-20 -1.07762e-10 1.37555e-09 -1.38018e-08 1 4.81482e-20 -1.07762e-10 1.37555e-09 -1.38018e-08 1 -1.07762e-10 1.37555e-09 -1.38018e-08 3961.01 -3.06831 48.5781 3999.76 1.00355 3995.87 +EDGE_SE3:QUAT 1010 1061 -0.430666 12.6597 -6.37694 0.00945936 -0.0128487 -0.0316444 0.999372 1 4.81482e-20 4.81482e-20 -1.69667e-10 1.4238e-10 1.38733e-08 1 4.81482e-20 -1.69667e-10 1.4238e-10 1.38733e-08 1 -1.69667e-10 1.4238e-10 1.38733e-08 4002.09 -0.581981 -99.0834 3999.41 1.58591 3998.45 +EDGE_SE3:QUAT 1011 1060 -0.55844 -12.6417 -6.1125 -0.00270844 0.077343 -0.0207029 0.996786 1 1.93345e-19 1.93345e-19 -1.15673e-09 2.77035e-08 3.022e-11 1 1.93345e-19 -1.15673e-09 2.77035e-08 3.022e-11 1 -1.15673e-09 2.77035e-08 3.022e-11 4097.08 -3.95968 630.759 3976.23 -7.33651 4095.39 +EDGE_SE3:QUAT 1012 1062 0.475386 -0.0684436 -6.28739 0.063197 -0.133582 -0.00542022 0.989006 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4279.1 -44.6873 -1125.8 3932.1 32.7334 4294.96 +EDGE_SE3:QUAT 1011 1062 -0.279153 12.5982 -6.31974 -0.057481 0.0778321 -0.0420431 0.99442 1 2.40741e-19 2.40741e-19 1.25299e-08 -2.8308e-08 -7.78508e-10 1 2.40741e-19 1.25299e-08 -2.8308e-08 -7.78508e-10 1 1.25299e-08 -2.8308e-08 -7.78508e-10 4074.75 -23.7238 599.817 3979.83 -21.0214 4080.9 +EDGE_SE3:QUAT 1012 1061 -0.114285 -12.2811 -6.1289 -0.0645251 -0.0527708 -0.0299984 0.996068 1 1.20371e-20 1.20371e-20 -3.91836e-10 -4.30155e-10 6.95432e-09 1 1.20371e-20 -3.91836e-10 -4.30155e-10 6.95432e-09 1 -3.91836e-10 -4.30155e-10 6.95432e-09 4032.7 12.8956 -447.066 3987.6 2.29718 4045.75 +EDGE_SE3:QUAT 1013 1063 0.430086 0.40383 -6.17713 -0.144893 -0.0991836 -0.0628337 0.982456 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4114.17 57.4735 -912.214 3952.79 -9.74337 4182.35 +EDGE_SE3:QUAT 1012 1063 -0.19899 12.4119 -6.42308 0.0211833 0.0775981 0.120117 0.989496 1 3.97223e-19 3.97223e-19 5.44683e-09 2.94304e-08 2.71529e-08 1 3.97223e-19 5.44683e-09 2.94304e-08 2.71529e-08 1 5.44683e-09 2.94304e-08 2.71529e-08 4082.4 22.4268 586.738 3981.89 39.2544 4026.48 +EDGE_SE3:QUAT 1013 1062 -0.215053 -12.4697 -6.34621 0.0224713 0.0237062 -0.0683316 0.997128 1 2.40741e-20 2.40741e-20 7.39513e-09 6.45198e-09 5.21015e-11 1 2.40741e-20 7.39513e-09 6.45198e-09 5.21015e-11 1 7.39513e-09 6.45198e-09 5.21015e-11 4008.66 1.34522 207.055 3997.23 -6.96535 3992.01 +EDGE_SE3:QUAT 1014 1064 0.514314 0.0811559 -6.11402 0.063945 0.0261846 0.00653336 0.997588 1 1.20371e-20 1.20371e-20 -6.82344e-11 6.92197e-09 -4.46629e-10 1 1.20371e-20 -6.82344e-11 6.92197e-09 -4.46629e-10 1 -6.82344e-11 6.92197e-09 -4.46629e-10 3993.98 6.59171 203.629 3997.52 1.67172 4010.17 +EDGE_SE3:QUAT 1013 1064 -0.423611 12.3046 -6.34109 -0.190896 0.0530853 0.228952 0.953059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4047.99 -52.6273 909.148 3942.49 83.7911 3984.08 +EDGE_SE3:QUAT 1014 1063 -0.0391299 -12.591 -6.15879 -0.184024 -0.00663017 -0.0263997 0.982545 1 1.20371e-20 1.20371e-20 -1.09122e-10 -1.27341e-09 6.82026e-09 1 1.20371e-20 -1.09122e-10 -1.27341e-09 6.82026e-09 1 -1.09122e-10 -1.27341e-09 6.82026e-09 3867.35 11.499 -107.352 3999.08 1.02482 4000.02 +EDGE_SE3:QUAT 1015 1065 0.448723 -0.106011 -6.25224 -0.10137 0.0384148 -0.0834343 0.990599 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.43 -9.9066 199.168 3998.63 -8.76755 3981.68 +EDGE_SE3:QUAT 1014 1065 -0.451623 12.4818 -6.26245 -0.128513 -0.0467317 0.127309 0.982391 1 7.82409e-19 7.82409e-19 -3.06938e-10 1.43875e-08 -5.36254e-08 1 7.82409e-19 -3.06938e-10 1.43875e-08 -5.36254e-08 1 -3.06938e-10 1.43875e-08 -5.36254e-08 3939.22 8.06398 -163.03 4000 -8.02792 3940.45 +EDGE_SE3:QUAT 1015 1064 -0.307324 -12.1474 -5.8782 -0.0622188 0.033661 -0.0860842 0.993773 1 2.0463e-19 2.0463e-19 2.69949e-08 -9.38768e-09 1.51535e-10 1 2.0463e-19 2.69949e-08 -9.38768e-09 1.51535e-10 1 2.69949e-08 -9.38768e-09 1.51535e-10 3994.47 -7.11621 201.219 3998.19 -8.84328 3980.31 +EDGE_SE3:QUAT 1016 1066 0.0446924 0.0574546 -6.32853 -0.099099 -0.0591768 0.00962372 0.99327 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.93 24.0775 -460.071 3988 -10.2582 4051.85 +EDGE_SE3:QUAT 1015 1066 -0.163408 12.5811 -6.5062 -0.0272652 0.0855061 0.0565343 0.994359 1 4.81482e-20 4.81482e-20 -1.23963e-09 2.50042e-10 -1.40141e-08 1 4.81482e-20 -1.23963e-09 2.50042e-10 -1.40141e-08 1 -1.23963e-09 2.50042e-10 -1.40141e-08 4121.96 0.0295373 717.885 3969.42 16.9037 4112.15 +EDGE_SE3:QUAT 1016 1065 -0.166859 -12.6054 -6.20061 -0.0921155 -0.0371712 -0.128724 0.986693 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.65 14.4985 -431.21 3986.93 25.6099 3979.32 +EDGE_SE3:QUAT 1017 1067 0.598045 0.165958 -5.9739 -0.0991808 0.0393502 -0.0960763 0.989638 1 2.0463e-19 2.0463e-19 2.67905e-08 -9.70123e-09 -2.03192e-10 1 2.0463e-19 2.67905e-08 -9.70123e-09 -2.03192e-10 1 2.67905e-08 -9.70123e-09 -2.03192e-10 3969.48 -9.36922 192.945 3998.87 -9.18738 3971.91 +EDGE_SE3:QUAT 1016 1067 -0.189064 12.901 -6.40221 0.230934 -0.0189065 0.0999914 0.967633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3826.36 -53.0781 -406.901 3986.48 -14.0918 3999.69 +EDGE_SE3:QUAT 1017 1066 -0.659069 -12.5071 -6.16679 -0.00398654 -0.0169479 0.0052722 0.999835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.52 0.306929 -135.457 3998.86 -0.385362 4004.47 +EDGE_SE3:QUAT 1018 1068 0.406897 -0.00940669 -6.70853 0.0917309 0.0415313 -0.252041 0.962463 1 3.85186e-19 3.85186e-19 -3.37262e-08 -2.00001e-08 -5.77313e-10 1 3.85186e-19 -3.37262e-08 -2.00001e-08 -5.77313e-10 1 -3.37262e-08 -2.00001e-08 -5.77313e-10 4046.08 4.64321 573.376 3978.08 -75.6041 3825.64 +EDGE_SE3:QUAT 1017 1068 -0.0360462 12.0718 -6.03987 0.106109 0.0135817 0.211762 0.971449 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3959.52 -12.6452 -160.068 3996.08 -26.4024 3825.19 +EDGE_SE3:QUAT 1018 1067 -0.293731 -12.4847 -6.1634 0.118417 -0.130384 -0.027507 0.983982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4194.46 -81.4425 -1032.43 3948.29 64.007 4247.52 +EDGE_SE3:QUAT 1019 1069 0.53368 0.284891 -6.30108 0.066197 0.138603 0.135951 0.978736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4221.18 92.4837 1008.03 3958.72 104.086 4164.77 +EDGE_SE3:QUAT 1018 1069 -0.0850014 12.616 -6.32827 -0.135709 0.0264563 0.0192091 0.990209 1 3.00927e-21 3.00927e-21 -1.06477e-10 4.6855e-10 -3.44161e-09 1 3.00927e-21 -1.06477e-10 4.6855e-10 -3.44161e-09 1 -1.06477e-10 4.6855e-10 -3.44161e-09 3940.36 -16.4282 237.395 3996.49 -0.375376 4012.55 +EDGE_SE3:QUAT 1019 1068 -0.352188 -12.4375 -6.2398 0.0207742 -0.077282 -0.104177 0.991334 1 1.92593e-19 1.92593e-19 -3.0109e-09 -2.75022e-08 1.01848e-09 1 1.92593e-19 -3.0109e-09 -2.75022e-08 1.01848e-09 1 -3.0109e-09 -2.75022e-08 1.01848e-09 4084.12 -20.4234 -592.444 3980.96 34.8558 4042.43 +EDGE_SE3:QUAT 1020 1070 0.307015 0.253582 -6.26759 -0.0183002 -0.120467 0.0273785 0.992171 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4237.26 20.6968 -1005.64 3943.64 -22.5971 4235.6 +EDGE_SE3:QUAT 1019 1070 -0.275871 12.5875 -6.33036 -0.0788918 -0.0134796 0.134109 0.987729 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.76 -2.55725 20.9811 3999.74 4.33835 3927.71 +EDGE_SE3:QUAT 1020 1069 -0.427841 -12.7277 -6.14603 -0.0330127 -0.0816901 -0.0137119 0.996016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4106.05 9.63994 -673.656 3972.95 -0.566138 4109.65 +EDGE_SE3:QUAT 1021 1071 0.412277 -0.151784 -6.16183 0.0370777 0.0458508 -0.0367495 0.997583 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.17 5.39396 384.787 3990.73 -5.3107 4031.27 +EDGE_SE3:QUAT 1020 1071 -0.549234 12.5329 -6.29656 -0.0883837 0.0690263 -0.0296434 0.99325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.39 -26.6211 520.794 3985.11 -17.1467 4063.12 +EDGE_SE3:QUAT 1021 1070 -0.486427 -12.7952 -5.62544 0.287111 -0.0315825 -0.222597 0.931139 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3720.12 101.533 500.94 3965.3 -73.6042 3851.65 +EDGE_SE3:QUAT 1022 1072 0.244039 -0.216067 -6.41147 0.00519662 -0.0828166 -0.088157 0.992644 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4107.35 -16.4189 -664.39 3974.98 32.0399 4076.37 +EDGE_SE3:QUAT 1021 1072 -0.922065 12.8428 -6.46335 -0.0424494 -0.0293641 -0.0439299 0.9977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.21 4.60957 -256.898 3995.73 4.84214 4008.7 +EDGE_SE3:QUAT 1022 1071 -0.458107 -13.0793 -6.2085 -0.131764 -0.0405897 0.111548 0.984148 1 7.82409e-19 7.82409e-19 5.38356e-08 1.34017e-08 4.47803e-10 1 7.82409e-19 5.38356e-08 1.34017e-08 4.47803e-10 1 5.38356e-08 1.34017e-08 4.47803e-10 3934.18 6.22045 -137.041 4000 -5.71094 3953.86 +EDGE_SE3:QUAT 1023 1073 0.290323 0.115935 -6.47249 -0.102158 -0.026224 -0.107325 0.988614 1 2.40741e-19 2.40741e-19 2.89243e-08 1.09455e-08 7.71946e-12 1 2.40741e-19 2.89243e-08 1.09455e-08 7.71946e-12 1 2.89243e-08 1.09455e-08 7.71946e-12 3985.76 15.6357 -334.967 3991.64 16.8041 3981.43 +EDGE_SE3:QUAT 1022 1073 -0.645757 12.4988 -6.39558 0.081246 0.0316041 0.271627 0.958446 1 1.95602e-19 1.95602e-19 -2.56478e-08 -1.09022e-08 7.37264e-10 1 1.95602e-19 -2.56478e-08 -1.09022e-08 7.37264e-10 1 -2.56478e-08 -1.09022e-08 7.37264e-10 3971.6 -5.1517 -27.8655 3999.08 -17.2186 3702.88 +EDGE_SE3:QUAT 1023 1072 -0.426286 -12.9822 -6.23646 -0.0594928 0.0113549 -0.113222 0.991722 1 4.81482e-20 4.81482e-20 -1.37626e-08 1.57887e-09 3.30289e-11 1 4.81482e-20 -1.37626e-08 1.57887e-09 3.30289e-11 1 -1.37626e-08 1.57887e-09 3.30289e-11 3985.67 0.539207 8.65833 3999.98 1.06342 3948.55 +EDGE_SE3:QUAT 1024 1074 0.18564 -0.277643 -6.25475 0.0507213 0.159256 -0.0819922 0.982518 1 1.92593e-19 1.92593e-19 2.88253e-08 -2.03333e-09 4.84022e-09 1 1.92593e-19 2.88253e-08 -2.03333e-09 4.84022e-09 1 2.88253e-08 -2.03333e-09 4.84022e-09 4455.17 -12.4455 1441.73 3893.43 -39.4453 4438.57 +EDGE_SE3:QUAT 1023 1074 -0.647173 12.5303 -6.42404 -0.0492598 -0.156799 -0.0485424 0.985206 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4430.49 10.5031 -1398.07 3898.18 9.36927 4430.77 +EDGE_SE3:QUAT 1024 1073 -0.685176 -12.3004 -5.79916 0.0182159 0.121205 0.00649272 0.992439 1 2.07639e-19 2.07639e-19 7.21522e-09 2.76974e-08 3.84552e-09 1 2.07639e-19 7.21522e-09 2.76974e-08 3.84552e-09 1 7.21522e-09 2.76974e-08 3.84552e-09 4243.42 13.1786 1019.27 3941.7 10.7039 4244.58 +EDGE_SE3:QUAT 1025 1075 0.636784 0.124792 -6.32657 0.0026501 -0.0321779 0.00859888 0.999442 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.62 -0.131423 -258.604 3995.85 -1.05803 4016.35 +EDGE_SE3:QUAT 1024 1075 -0.473956 12.3211 -6.36782 -0.054708 -0.00854752 0.0038911 0.998458 1 4.81482e-20 4.81482e-20 -1.38583e-08 -6.66541e-11 1.12021e-10 1 4.81482e-20 -1.38583e-08 -6.66541e-11 1.12021e-10 1 -1.38583e-08 -6.66541e-11 1.12021e-10 3989.1 1.77431 -65.5373 3999.74 -0.215694 4001.01 +EDGE_SE3:QUAT 1025 1074 -0.0531777 -12.3711 -6.10526 -0.0175833 0.0133717 -0.0885641 0.995825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.65 -0.987423 87.1104 3999.61 -3.6233 3970.51 +EDGE_SE3:QUAT 1026 1076 0.398441 0.445327 -6.10668 -0.0417579 0.152826 -0.30502 0.939076 1 1.92593e-19 1.92593e-19 -2.67877e-08 9.41313e-09 -2.76472e-09 1 1.92593e-19 -2.67877e-08 9.41313e-09 -2.76472e-09 1 -2.67877e-08 9.41313e-09 -2.76472e-09 4194.18 -141.551 933.964 3999.16 -169.584 3829.01 +EDGE_SE3:QUAT 1025 1076 -0.539179 12.3412 -6.54786 0.0562438 -0.0394787 -0.183617 0.980593 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.59 -6.71675 -177.515 3999.46 13.0224 3872.38 +EDGE_SE3:QUAT 1026 1075 -0.260029 -12.6104 -5.92638 0.00797756 -0.0444799 0.0354862 0.998348 1 9.70488e-20 9.70488e-20 -1.59731e-09 1.37271e-08 -1.38995e-08 1 9.70488e-20 -1.59731e-09 1.37271e-08 -1.38995e-08 1 -1.59731e-09 1.37271e-08 -1.38995e-08 4032.08 0.248583 -361.08 3991.96 -6.17007 4027.3 +EDGE_SE3:QUAT 1027 1077 0.43996 0.355075 -6.39867 -0.0903994 0.106219 -0.0243215 0.989926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4137.04 -48.307 841.435 3962.23 -35.3597 4167.36 +EDGE_SE3:QUAT 1026 1077 -0.532175 12.7521 -6.46797 -0.124793 -0.117955 0.118595 0.977982 1 1.92593e-19 1.92593e-19 -4.07146e-09 2.70385e-08 4.21176e-09 1 1.92593e-19 -4.07146e-09 2.70385e-08 4.21176e-09 1 -4.07146e-09 2.70385e-08 4.21176e-09 4069 74.9375 -741.834 3981.67 -74.0741 4075.03 +EDGE_SE3:QUAT 1027 1076 -0.586902 -12.6138 -5.83027 0.015998 0.00062326 0.0362227 0.999215 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.98 -0.0343547 -1.97228 4000 -0.0777754 3994.75 +EDGE_SE3:QUAT 1028 1078 0.253235 -0.136465 -6.09979 -0.0402235 0.0744554 -0.0521164 0.995049 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4074.89 -18.6279 576.348 3981.15 -20.6834 4070.49 +EDGE_SE3:QUAT 1027 1078 -0.339257 11.9962 -6.23794 0.107172 -0.0457162 -0.202261 0.972376 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3953.55 -1.01066 -85.5542 4000.46 -0.241537 3835.86 +EDGE_SE3:QUAT 1028 1077 -0.469019 -12.4131 -5.69712 0.0146663 -0.139781 -0.0272977 0.989697 1 1.20371e-20 1.20371e-20 -1.00083e-09 1.66713e-10 7.14352e-09 1 1.20371e-20 -1.00083e-09 1.66713e-10 7.14352e-09 1 -1.00083e-09 1.66713e-10 7.14352e-09 4326.86 -24.4945 -1190.92 3923.64 27.1035 4324.74 +EDGE_SE3:QUAT 1029 1079 0.345157 0.0111143 -6.11381 0.0186085 0.0591486 0.0350423 0.99746 1 1.08334e-19 1.08334e-19 -7.25371e-09 -1.44224e-08 -1.40221e-08 1 1.08334e-19 -7.25371e-09 -1.44224e-08 -1.40221e-08 1 -7.25371e-09 -1.44224e-08 -1.40221e-08 4053.02 7.40571 469.694 3986.82 10.0172 4049.5 +EDGE_SE3:QUAT 1028 1079 -0.457604 12.1587 -6.32238 0.0150594 0.13757 0.101154 0.985198 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4297.63 58.0381 1132.98 3935.34 75.1148 4257.61 +EDGE_SE3:QUAT 1029 1078 -0.173947 -12.3689 -6.05445 0.119835 -0.0853087 -0.0882055 0.985181 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.58 -42.2819 -540.785 3988.15 37.9459 4039.91 +EDGE_SE3:QUAT 1030 1080 0.336338 0.0111419 -6.22755 0.11857 0.104393 0.0115193 0.987376 1 2.0463e-19 2.0463e-19 -3.12093e-10 2.82636e-08 3.56564e-09 1 2.0463e-19 -3.12093e-10 2.82636e-08 3.56564e-09 1 -3.12093e-10 2.82636e-08 3.56564e-09 4108.8 56.9683 829.267 3964.04 36.0041 4164.5 +EDGE_SE3:QUAT 1029 1080 -0.492993 12.6055 -6.75601 -0.146316 0.137795 0.0883719 0.9756 1 1.54074e-18 1.54074e-18 5.42109e-08 5.70656e-08 1.60896e-08 1 1.54074e-18 5.42109e-08 5.70656e-08 1.60896e-08 1 5.42109e-08 5.70656e-08 1.60896e-08 4310.26 -68.7646 1319.42 3908.66 -14.355 4364.65 +EDGE_SE3:QUAT 1030 1079 -0.5963 -12.4067 -6.34467 0.0749756 -0.0184659 -0.169816 0.982446 1 1.92593e-19 1.92593e-19 -2.7266e-08 4.7364e-09 -2.17528e-10 1 1.92593e-19 -2.7266e-08 4.7364e-09 -2.17528e-10 1 -2.7266e-08 4.7364e-09 -2.17528e-10 3976.85 2.3298 9.16073 3999.77 -5.31428 3883.98 +EDGE_SE3:QUAT 1031 1081 -0.133517 -0.0348487 -6.51043 0.119313 0.0482389 -0.0592154 0.989915 1 1.92593e-19 1.92593e-19 2.76613e-08 -1.29607e-09 1.69376e-09 1 1.92593e-19 2.76613e-08 -1.29607e-09 1.69376e-09 1 2.76613e-08 -1.29607e-09 1.69376e-09 3996.4 25.6367 465.462 3986.02 -5.92652 4039.32 +EDGE_SE3:QUAT 1030 1081 -0.458488 12.5684 -6.23003 -0.103127 0.0807189 0.00569957 0.991371 1 7.52316e-22 7.52316e-22 -1.40897e-10 1.82034e-10 -1.74247e-09 1 7.52316e-22 -1.40897e-10 1.82034e-10 -1.74247e-09 1 -1.40897e-10 1.82034e-10 -1.74247e-09 4062.68 -35.2635 657.259 3975.46 -14.6033 4105.09 +EDGE_SE3:QUAT 1031 1080 -0.186115 -12.6711 -6.68409 0.135159 -0.030981 -0.059566 0.988546 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3931.82 -8.08938 -144.539 3999.44 4.71493 3990.7 +EDGE_SE3:QUAT 1032 1082 0.419066 -0.0517654 -6.25672 0.154808 0.0442009 0.0324008 0.986423 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3923.74 21.3782 282.12 3996.54 9.45831 4015.41 +EDGE_SE3:QUAT 1031 1082 -0.68685 12.2557 -6.64481 0.0693167 -0.147111 0.0836308 0.983138 1 4.81482e-20 4.81482e-20 1.43263e-08 9.57904e-10 -2.26855e-09 1 4.81482e-20 1.43263e-08 9.57904e-10 -2.26855e-09 1 1.43263e-08 9.57904e-10 -2.26855e-09 4386.93 -5.94738 -1337.8 3905.37 -26.9866 4378.17 +EDGE_SE3:QUAT 1032 1081 -0.444998 -12.1005 -6.17594 0.0586707 0.0598953 -0.0752519 0.993633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4056.22 9.10139 533.894 3982.14 -15.5389 4047.34 +EDGE_SE3:QUAT 1033 1083 0.377613 -0.470524 -6.17845 0.0246892 0.0881014 0.0880143 0.991908 1 3.85186e-19 3.85186e-19 2.83639e-10 -2.86514e-08 -2.68074e-08 1 3.85186e-19 2.83639e-10 -2.86514e-08 -2.68074e-08 1 2.83639e-10 -2.86514e-08 -2.68074e-08 4111.93 24.735 686.137 3974.25 36.4535 4083.38 +EDGE_SE3:QUAT 1032 1083 -0.487624 12.3806 -6.46459 -0.187625 -0.186917 -0.108928 0.95812 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4638.98 132.302 -1930.75 3838.08 -77.112 4732.33 +EDGE_SE3:QUAT 1033 1082 -0.683912 -12.611 -6.04727 -0.0109273 0.0725235 -0.154993 0.985189 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4073.01 -21.1499 547.514 3984.88 -44.8452 3977.39 +EDGE_SE3:QUAT 1034 1084 0.201765 0.0856529 -6.25232 0.0372899 0.0267137 -0.0877028 0.99509 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.07 3.00296 250.755 3995.83 -10.8028 3984.86 +EDGE_SE3:QUAT 1033 1084 -0.11628 12.5235 -6.13347 0.0284122 0.0267642 0.094964 0.994715 1 2.0463e-19 2.0463e-19 6.32962e-09 -2.46904e-10 -2.74917e-08 1 2.0463e-19 6.32962e-09 -2.46904e-10 -2.74917e-08 1 6.32962e-09 -2.46904e-10 -2.74917e-08 4004.73 3.6392 179.051 3998.36 8.36462 3971.89 +EDGE_SE3:QUAT 1034 1083 -0.0444743 -12.4267 -6.41008 -0.0836642 0.060632 -0.0692685 0.992233 1 2.40741e-19 2.40741e-19 2.65903e-08 -1.59612e-08 5.41367e-11 1 2.40741e-19 2.65903e-08 -1.59612e-08 5.41367e-11 1 2.65903e-08 -1.59612e-08 5.41367e-11 4013.49 -21.3934 410.509 3991.66 -19.5223 4022.3 +EDGE_SE3:QUAT 1035 1085 -0.0358376 0.0512278 -6.61556 -0.0985935 0.0345248 0.181265 0.97787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.77 -14.4284 473.952 3983.7 43.0714 3923.22 +EDGE_SE3:QUAT 1034 1085 -0.415974 12.663 -6.33338 -0.109515 0.120096 0.253304 0.953635 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4326.82 51.4953 1280.99 3919.89 145.917 4118.14 +EDGE_SE3:QUAT 1035 1084 -0.412571 -12.4156 -6.01946 0.101318 0.12223 0.00981787 0.987268 1 1.20371e-20 1.20371e-20 8.39699e-10 7.63059e-10 7.05154e-09 1 1.20371e-20 8.39699e-10 7.63059e-10 7.05154e-09 1 8.39699e-10 7.63059e-10 7.05154e-09 4194.42 61.6471 998.809 3947.85 43.1038 4235.1 +EDGE_SE3:QUAT 1036 1086 0.129792 0.0441409 -5.97676 -0.21501 0.12871 -0.115348 0.961197 1 1.73334e-18 1.73334e-18 -5.31385e-08 4.93567e-08 -5.08748e-08 1 1.73334e-18 -5.31385e-08 4.93567e-08 -5.08748e-08 1 -5.31385e-08 4.93567e-08 -5.08748e-08 3913.64 -88.3593 654.495 3998.1 -79.7621 4045.33 +EDGE_SE3:QUAT 1035 1086 -0.527769 12.5619 -6.55828 -0.0202463 0.0223951 0.148758 0.988413 1 2.40741e-20 2.40741e-20 -7.8945e-09 5.83161e-09 -1.01346e-10 1 2.40741e-20 -7.8945e-09 5.83161e-09 -1.01346e-10 1 -7.8945e-09 5.83161e-09 -1.01346e-10 4009.27 0.0815295 209.29 3997.23 16.097 3922.39 +EDGE_SE3:QUAT 1036 1085 -0.522574 -12.261 -5.99111 0.0999573 0.0495562 0.0182802 0.993589 1 2.0463e-19 2.0463e-19 2.80089e-08 1.48946e-09 8.17482e-09 1 2.0463e-19 2.80089e-08 1.48946e-09 8.17482e-09 1 2.80089e-08 1.48946e-09 8.17482e-09 3994.15 19.5017 371.131 3992.36 8.73158 4032.77 +EDGE_SE3:QUAT 1037 1087 0.0160013 0.209761 -5.97093 -0.0896936 0.089328 -0.0418481 0.991072 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.28 -39.0925 674.201 3976.02 -30.558 4103.45 +EDGE_SE3:QUAT 1036 1087 -0.531363 12.2413 -6.30452 -0.0175849 0.0274817 -0.0964559 0.994802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.41 -3.15541 196.838 3997.88 -9.45122 3972.43 +EDGE_SE3:QUAT 1037 1086 -0.813484 -12.5139 -6.27617 0.147243 0.111115 0.0148735 0.982727 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4092.16 74.5068 865.079 3963.73 49.2402 4177.99 +EDGE_SE3:QUAT 1038 1088 0.403833 -0.136468 -6.14559 -0.0656418 0.00300152 -0.0191844 0.997654 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.78 -0.122024 8.77926 4000 -0.0389319 3998.54 +EDGE_SE3:QUAT 1037 1088 -0.664736 12.3774 -6.45901 0.153205 -0.0522767 0.0986799 0.981864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.11 -39.8246 -587.415 3976.98 -15.3913 4045.05 +EDGE_SE3:QUAT 1038 1087 -0.146446 -12.5179 -6.03613 0.0300858 -0.0519068 -0.00704739 0.998174 1 1.20371e-20 1.20371e-20 6.96321e-09 -7.12036e-11 -3.58427e-10 1 1.20371e-20 6.96321e-09 -7.12036e-11 -3.58427e-10 1 6.96321e-09 -7.12036e-11 -3.58427e-10 4039.18 -6.87379 -415.951 3989.49 3.45167 4042.6 +EDGE_SE3:QUAT 1039 1089 0.17432 -0.268977 -6.09029 0.135729 -0.061836 0.0615126 0.986899 1 8.1852e-19 8.1852e-19 5.64363e-08 6.15902e-10 -1.80939e-08 1 8.1852e-19 5.64363e-08 6.15902e-10 -1.80939e-08 1 5.64363e-08 6.15902e-10 -1.80939e-08 4011.09 -36.3792 -588.904 3978.44 -3.36643 4069.65 +EDGE_SE3:QUAT 1038 1089 -0.684593 12.4905 -6.47095 0.0850851 0.132473 0.0486524 0.986329 1 1.92593e-19 1.92593e-19 2.82549e-08 2.08123e-09 3.47291e-09 1 1.92593e-19 2.82549e-08 2.08123e-09 3.47291e-09 1 2.82549e-08 2.08123e-09 3.47291e-09 4228.9 71.6327 1048.22 3945.6 64.6615 4248.39 +EDGE_SE3:QUAT 1039 1088 -0.400218 -12.7989 -6.01475 0.107964 -0.0869941 -0.234382 0.962206 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.6 -27.3203 -334.361 4001.83 33.015 3803.48 +EDGE_SE3:QUAT 1040 1090 0.164403 -0.0745717 -6.30118 -0.179408 0.0622469 0.0986401 0.976836 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.6 -55.7405 693.657 3969.25 10.57 4077.43 +EDGE_SE3:QUAT 1039 1090 -0.565725 12.6876 -6.42679 -0.0397802 -0.137126 0.099611 0.984729 1 9.62965e-19 9.62965e-19 -2.72321e-09 5.65404e-08 -2.44868e-08 1 9.62965e-19 -2.72321e-09 5.65404e-08 -2.44868e-08 1 -2.72321e-09 5.65404e-08 -2.44868e-08 4271.29 69.863 -1090.19 3942.32 -81.2269 4237.93 +EDGE_SE3:QUAT 1040 1089 -0.566436 -12.8038 -6.13572 0.125941 -0.0770027 -0.0959243 0.984382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.29 -34.9904 -453.187 3992.58 31.4594 4012.93 +EDGE_SE3:QUAT 1041 1091 0.351255 -0.0738954 -6.05401 -0.025024 0.0440081 0.0232139 0.998448 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.81 -3.51627 360.986 3991.9 3.09343 4030.16 +EDGE_SE3:QUAT 1040 1091 -0.163977 12.5771 -6.06177 -0.0404651 0.0138316 0.187953 0.981247 1 8.1852e-19 8.1852e-19 1.51759e-08 7.81636e-10 5.4921e-08 1 8.1852e-19 1.51759e-08 7.81636e-10 5.4921e-08 1 1.51759e-08 7.81636e-10 5.4921e-08 4002.7 -2.30298 194.072 3997.18 20.5021 3867.94 +EDGE_SE3:QUAT 1041 1090 -0.573209 -12.5125 -6.15182 0.211521 -0.146843 0.0763956 0.963255 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4267.99 -140.553 -1409.83 3908.08 76.6979 4423.6 +EDGE_SE3:QUAT 1042 1092 0.357722 0.0152507 -6.25707 0.0392876 -0.0322878 -0.0928397 0.994382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.88 -5.59326 -211.295 3997.77 9.88248 3976.58 +EDGE_SE3:QUAT 1041 1092 -0.312002 12.5679 -6.59488 -0.000815891 -0.133876 0.0555444 0.98944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4299.59 26.4652 -1134.95 3930.43 -37.8661 4287.25 +EDGE_SE3:QUAT 1042 1091 -0.563888 -12.3998 -5.72744 -0.123415 0.0332237 -0.00624341 0.991779 1 3.00927e-21 3.00927e-21 -1.06632e-10 4.31361e-10 -3.44779e-09 1 3.00927e-21 -1.06632e-10 4.31361e-10 -3.44779e-09 1 -1.06632e-10 4.31361e-10 -3.44779e-09 3954.8 -15.5197 251.398 3996.5 -3.79849 4015.57 +EDGE_SE3:QUAT 1043 1093 0.305933 -0.229286 -6.59131 -0.0248181 0.0392715 0.204553 0.977752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.01 4.74823 356.269 3992.83 37.3886 3864.11 +EDGE_SE3:QUAT 1042 1093 -0.44931 12.8206 -6.5048 0.0846447 -0.0853148 0.185407 0.975285 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4148.08 5.03847 -859.841 3957.02 -70.8296 4039.24 +EDGE_SE3:QUAT 1043 1092 -0.541723 -12.5553 -5.99397 0.117651 0.130623 -0.0632228 0.982394 1 4.81482e-20 4.81482e-20 -2.0394e-09 -1.50549e-09 -1.41872e-08 1 4.81482e-20 -2.0394e-09 -1.50549e-09 -1.41872e-08 1 -2.0394e-09 -1.50549e-09 -1.41872e-08 4270.96 53.5876 1188.27 3923.79 12.8557 4310.34 +EDGE_SE3:QUAT 1044 1094 -0.0144593 -0.275609 -6.15996 0.0624296 0.0856157 0.0533382 0.992939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4087.85 30.0168 651.772 3976.92 28.396 4092.06 +EDGE_SE3:QUAT 1043 1094 -0.440547 12.682 -6.33044 0.0298696 -0.0746367 0.172218 0.981773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4097.94 15.8542 -645.248 3977.09 -55.6008 3982.87 +EDGE_SE3:QUAT 1044 1093 -0.391389 -12.876 -6.05294 0.159128 0.0340903 0.00894215 0.986629 1 7.73381e-19 7.73381e-19 -5.47721e-08 -5.13508e-10 1.78687e-09 1 7.73381e-19 -5.47721e-08 -5.13508e-10 1.78687e-09 1 -5.47721e-08 -5.13508e-10 1.78687e-09 3913.79 19.3003 246.351 3996.94 4.91337 4014.76 +EDGE_SE3:QUAT 1045 1095 0.567304 -0.1668 -6.24484 -0.141268 -0.0124983 -0.249062 0.958048 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.4 29.1716 -494.72 3978.05 70.6614 3809.1 +EDGE_SE3:QUAT 1044 1095 -0.424209 12.5575 -6.11966 0.108043 -0.0212482 -0.147607 0.982897 1 1.93345e-19 1.93345e-19 2.70198e-08 -5.83171e-09 5.10389e-10 1 1.93345e-19 2.70198e-08 -5.83171e-09 5.10389e-10 1 2.70198e-08 -5.83171e-09 5.10389e-10 3952.41 5.00007 25.6405 3999.48 -6.82421 3911.95 +EDGE_SE3:QUAT 1045 1094 -0.0609878 -12.8569 -5.88886 0.0735008 0.0372545 -0.134264 0.987514 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.43 9.1808 408.437 3988.55 -26.343 3968.93 +EDGE_SE3:QUAT 1046 1096 0.373502 0.128838 -6.2723 -0.0564865 0.112253 -0.143863 0.981587 1 1.92593e-19 1.92593e-19 2.77654e-08 -4.50053e-09 2.5518e-09 1 1.92593e-19 2.77654e-08 -4.50053e-09 2.5518e-09 1 2.77654e-08 -4.50053e-09 2.5518e-09 4137.42 -59.9779 791.45 3973.32 -74.566 4067.4 +EDGE_SE3:QUAT 1045 1096 -0.892872 12.5829 -6.31551 0.116508 -0.0622175 0.0924825 0.986915 1 1.92593e-19 1.92593e-19 -2.77208e-08 -2.14479e-09 2.2748e-09 1 1.92593e-19 -2.77208e-08 -2.14479e-09 2.2748e-09 1 -2.77208e-08 -2.14479e-09 2.2748e-09 4040.23 -28.1052 -622.959 3975.11 -16.5622 4060.32 +EDGE_SE3:QUAT 1046 1095 -0.446642 -12.4432 -6.36919 0.00622938 -0.0313288 0.00940598 0.999445 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.68 -0.570655 -252.158 3996.05 -1.05115 4015.48 +EDGE_SE3:QUAT 1047 1097 0.117571 0.0541119 -6.57929 0.101336 -0.171877 0.118814 0.972663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4566.89 -3.83885 -1673.91 3863.54 -40.5748 4551.5 +EDGE_SE3:QUAT 1046 1097 -0.780965 12.6269 -6.41172 -0.10791 -0.0371826 0.0108655 0.993406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3972.83 15.2599 -279.386 3995.64 -4.77071 4018.93 +EDGE_SE3:QUAT 1047 1096 -0.707034 -12.6434 -5.93557 -0.043826 -0.00129119 -0.0779448 0.995993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.92 1.36486 -50.9875 3999.74 2.48961 3976.3 +EDGE_SE3:QUAT 1048 1098 0.255071 -0.195248 -6.29053 -0.0309043 -0.0015387 -0.0671267 0.997265 1 1.92593e-19 1.92593e-19 -1.57092e-10 -8.44362e-10 2.76808e-08 1 1.92593e-19 -1.57092e-10 -8.44362e-10 2.76808e-08 1 -1.57092e-10 -8.44362e-10 2.76808e-08 3996.51 0.674814 -37.0155 3999.87 1.50841 3982.3 +EDGE_SE3:QUAT 1047 1098 -0.522173 12.6422 -6.06206 0.0171627 -0.0459291 0.0595485 0.997021 1 4.81482e-20 4.81482e-20 -6.63911e-10 1.62227e-10 1.38986e-08 1 4.81482e-20 -6.63911e-10 1.62227e-10 1.38986e-08 1 -6.63911e-10 1.62227e-10 1.38986e-08 4034.71 -0.184154 -380.584 3991.05 -10.7752 4021.7 +EDGE_SE3:QUAT 1048 1097 -0.82119 -12.8131 -6.45162 -0.185192 0.0626032 -0.117725 0.973615 1 7.70372e-19 7.70372e-19 5.41061e-08 -7.38524e-09 7.613e-10 1 7.70372e-19 5.41061e-08 -7.38524e-09 7.613e-10 1 5.41061e-08 -7.38524e-09 7.613e-10 3871.19 -13.9106 210.396 4000.62 -11.9738 3952.94 +EDGE_SE3:QUAT 1049 1099 0.366942 -0.0410271 -6.01085 0.0682602 -0.110701 -0.138561 0.981777 1 1.92593e-19 1.92593e-19 4.30751e-09 2.71806e-08 -2.71175e-09 1 1.92593e-19 4.30751e-09 2.71806e-08 -2.71175e-09 1 4.30751e-09 2.71806e-08 -2.71175e-09 4120.29 -59.8453 -760.723 3976.04 71.1627 4062.13 +EDGE_SE3:QUAT 1048 1099 -0.538645 12.3776 -6.48367 0.0974675 0.0822808 0.182072 0.974977 1 1.92593e-19 1.92593e-19 2.72004e-08 5.47705e-09 1.11498e-09 1 1.92593e-19 2.72004e-08 5.47705e-09 1.11498e-09 1 2.72004e-08 5.47705e-09 1.11498e-09 4001.35 31.7007 409.832 3997.01 39.1825 3906.75 +EDGE_SE3:QUAT 1049 1098 -0.604079 -12.9842 -6.22283 -0.0122185 0.0386036 0.0110228 0.999119 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.59 -1.5388 311.967 3993.97 1.30564 4023.7 +EDGE_SE3:QUAT 1050 1100 0.187617 -0.175624 -5.97758 0.0844833 -0.187595 -0.0575096 0.976915 1 9.62965e-19 9.62965e-19 -8.87094e-11 -5.74129e-08 -2.27021e-08 1 9.62965e-19 -8.87094e-11 -5.74129e-08 -2.27021e-08 1 -8.87094e-11 -5.74129e-08 -2.27021e-08 4520.51 -142.118 -1580.97 3893.73 138.006 4535.83 +EDGE_SE3:QUAT 1049 1100 -0.667959 12.5343 -6.37468 0.0846457 0.082873 0.230154 0.965917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.91 29.7164 378.661 3999.53 40.31 3820.68 +EDGE_SE3:QUAT 1050 1099 -0.699707 -12.5965 -6.27979 -0.0641846 0.00842583 -0.0186771 0.997728 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.21 -1.55276 52.6183 3999.86 -0.520768 3999.29 +EDGE_SE3:QUAT 1051 1101 0.129651 0.161482 -6.26277 -0.147285 0.104947 -0.0496255 0.982258 1 9.62965e-19 9.62965e-19 -5.76459e-08 -2.27235e-08 -9.22873e-09 1 9.62965e-19 -5.76459e-08 -2.27235e-08 -9.22873e-09 1 -5.76459e-08 -2.27235e-08 -9.22873e-09 4045.43 -68.0801 740.855 3976.1 -51.7775 4122.35 +EDGE_SE3:QUAT 1050 1101 -0.87364 12.6341 -6.35243 -0.043023 -0.0845329 0.121148 0.988092 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4082.75 31.1606 -608.122 3981.86 -43.9887 4031.45 +EDGE_SE3:QUAT 1051 1100 -0.860734 -12.6112 -6.2708 -0.00639545 0.139905 -0.143493 0.979692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4303.38 -74.227 1143.29 3938.49 -100.784 4221.18 +EDGE_SE3:QUAT 1052 1102 0.186704 0.036007 -6.13137 -0.0257824 -0.0997355 0.0860205 0.990953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4146.05 31.0434 -785.624 3966.65 -42.6783 4119.11 +EDGE_SE3:QUAT 1051 1102 -0.444621 12.5108 -6.46192 0.126258 -0.036833 -0.0256912 0.99098 1 4.81482e-20 4.81482e-20 4.74132e-10 1.37491e-08 -1.77984e-09 1 4.81482e-20 4.74132e-10 1.37491e-08 -1.77984e-09 1 4.74132e-10 1.37491e-08 -1.77984e-09 3951.67 -15.6199 -249.556 3996.92 6.25926 4012.79 +EDGE_SE3:QUAT 1052 1101 -0.566471 -12.3076 -6.18658 0.0701794 0.129651 -0.0125078 0.988994 1 1.88079e-22 1.88079e-22 1.16826e-10 6.22178e-11 8.8798e-10 1 1.88079e-22 1.16826e-10 6.22178e-11 8.8798e-10 1 1.16826e-10 6.22178e-11 8.8798e-10 4265.14 40.2886 1104.75 3933.65 22.8241 4284.21 +EDGE_SE3:QUAT 1053 1103 0.264919 -0.00674647 -6.13057 0.0165314 0.135874 -0.0443388 0.989595 1 8.1852e-19 8.1852e-19 3.26948e-10 5.48726e-08 -1.45285e-08 1 8.1852e-19 3.26948e-10 5.48726e-08 -1.45285e-08 1 3.26948e-10 5.48726e-08 -1.45285e-08 4314.86 -10.1455 1167.76 3925.7 -22.9733 4308.09 +EDGE_SE3:QUAT 1052 1103 -0.165859 12.3968 -6.53016 0.0151921 0.165357 0.0275673 0.985731 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4469.43 34.7676 1450.06 3893.18 37.133 4467.32 +EDGE_SE3:QUAT 1053 1102 -0.607473 -12.6179 -6.14926 -0.00272036 0.146964 0.0339595 0.988555 1 1.88079e-22 1.88079e-22 -8.96127e-10 -3.14257e-11 -1.33077e-10 1 1.88079e-22 -8.96127e-10 -3.14257e-11 -1.33077e-10 1 -8.96127e-10 -3.14257e-11 -1.33077e-10 4368.68 17.4531 1269.16 3914.26 24.9654 4364.09 +EDGE_SE3:QUAT 1054 1104 -0.148427 -0.108149 -6.46965 0.0889865 -0.147787 -0.0100914 0.984956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4324.69 -73.5386 -1246.05 3921.72 57.9605 4355.95 +EDGE_SE3:QUAT 1053 1104 -0.512408 12.3238 -6.09635 -0.0128749 -0.149237 0.0777868 0.985653 1 1.20371e-20 1.20371e-20 7.14693e-09 6.18677e-10 -1.05271e-09 1 1.20371e-20 7.14693e-09 6.18677e-10 -1.05271e-09 1 7.14693e-09 6.18677e-10 -1.05271e-09 4364.6 54.9837 -1262.78 3919.03 -67.7991 4341.06 +EDGE_SE3:QUAT 1054 1103 -0.740868 -12.6432 -6.13044 0.124806 -0.109904 0.0179071 0.985913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4141.15 -59.8175 -924.799 3953.98 29.7775 4202.18 +EDGE_SE3:QUAT 1055 1105 0.141174 0.0450205 -5.8128 -0.220669 -0.029246 -0.12567 0.966777 1 4.81482e-20 4.81482e-20 -1.40987e-09 -1.34559e-08 -2.8852e-09 1 4.81482e-20 -1.40987e-09 -1.34559e-08 -2.8852e-09 1 -1.40987e-09 -1.34559e-08 -2.8852e-09 3875.21 61.9837 -540.369 3977.41 22.4898 4006.82 +EDGE_SE3:QUAT 1054 1105 -0.480053 12.3634 -6.27455 -0.0280166 -0.192819 0.156424 0.968281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4555.28 178.394 -1596.8 3906.28 -196.131 4460.54 +EDGE_SE3:QUAT 1055 1104 -0.547274 -12.4453 -6.05763 0.0411466 -0.0817541 0.0190506 0.995621 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4104.93 -11.7752 -677.72 3972.62 0.0104219 4110.25 +EDGE_SE3:QUAT 1056 1106 0.322465 -0.0815175 -6.28626 0.0123754 -0.136955 -0.109021 0.984482 1 1.92593e-19 1.92593e-19 -3.76148e-09 1.23965e-09 2.8329e-08 1 1.92593e-19 -3.76148e-09 1.23965e-09 2.8329e-08 1 -3.76148e-09 1.23965e-09 2.8329e-08 4294.8 -59.4015 -1126.64 3936.51 78.5577 4247.87 +EDGE_SE3:QUAT 1055 1106 -0.649045 12.5148 -6.17405 0.118519 0.0294209 0.132306 0.983658 1 7.70372e-19 7.70372e-19 1.85287e-10 -6.77865e-09 -5.45991e-08 1 7.70372e-19 1.85287e-10 -6.77865e-09 -5.45991e-08 1 1.85287e-10 -6.77865e-09 -5.45991e-08 3943.12 -1.25536 39.8964 4000.05 -1.47184 3929.28 +EDGE_SE3:QUAT 1056 1105 -1.01983 -12.4675 -6.22348 0.0166053 0.134969 -0.12857 0.982333 1 4.23178e-22 4.23178e-22 1.32709e-09 -1.74093e-10 1.81968e-10 1 4.23178e-22 1.32709e-09 -1.74093e-10 1.81968e-10 1 1.32709e-09 -1.74093e-10 1.81968e-10 4306.41 -50.5158 1150.96 3932.74 -80.6218 4241.39 +EDGE_SE3:QUAT 1057 1107 0.33045 -0.0831493 -6.08923 -0.0171856 0.0859487 -0.0902079 0.992058 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4109.92 -21.7602 675.96 3974.71 -35.3377 4078.56 +EDGE_SE3:QUAT 1056 1107 -0.453823 12.3458 -6.55079 -0.0313898 -0.0809396 -0.083421 0.992726 1 1.20371e-20 1.20371e-20 6.98763e-09 -5.58073e-10 -5.97888e-10 1 1.20371e-20 6.98763e-09 -5.58073e-10 -5.97888e-10 1 6.98763e-09 -5.58073e-10 -5.97888e-10 4111.25 -2.70167 -688.515 3971.87 25.7185 4087.35 +EDGE_SE3:QUAT 1057 1106 -0.421361 -12.7244 -5.67158 0.139704 -0.00593899 0.0393018 0.989395 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3924.91 -9.12656 -111.07 3998.95 -2.1103 3996.8 +EDGE_SE3:QUAT 1058 1108 0.0532547 0.0275193 -6.55824 0.0295159 0.0967621 0.0256683 0.994539 1 1.92593e-19 1.92593e-19 8.8516e-10 -2.7599e-08 9.7318e-10 1 1.92593e-19 8.8516e-10 -2.7599e-08 9.7318e-10 1 8.8516e-10 -2.7599e-08 9.7318e-10 4146.11 18.6126 787.902 3964.32 17.8406 4146.96 +EDGE_SE3:QUAT 1057 1108 -0.250463 12.4789 -6.40426 0.00814173 -0.111563 -0.00348633 0.993718 1 1.95602e-19 1.95602e-19 3.38497e-09 -2.76003e-08 -1.4292e-10 1 1.95602e-19 3.38497e-09 -2.76003e-08 -1.4292e-10 1 3.38497e-09 -2.76003e-08 -1.4292e-10 4206.34 -5.40198 -932.269 3950.31 4.42253 4206.56 +EDGE_SE3:QUAT 1058 1107 -0.27777 -12.4757 -6.05809 0.0165207 -0.00455379 -0.0158885 0.999727 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.18 -0.27287 -33.2547 3999.94 0.262964 3999.27 +EDGE_SE3:QUAT 1059 1109 0.385304 -0.000970483 -6.26645 -0.0593595 -0.0205443 -0.0908943 0.993878 1 6.01853e-20 6.01853e-20 -1.44252e-08 -5.67611e-09 4.8293e-11 1 6.01853e-20 -1.44252e-08 -5.67611e-09 4.8293e-11 1 -1.44252e-08 -5.67611e-09 4.8293e-11 3998.59 5.82919 -226.423 3996.32 10.2853 3979.64 +EDGE_SE3:QUAT 1058 1109 -0.663999 12.2897 -6.34786 0.0560554 -0.119347 0.15636 0.978859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4262.25 29.1381 -1083.93 3937.56 -77.451 4177.03 +EDGE_SE3:QUAT 1059 1108 -0.783868 -12.7798 -6.18031 0.0567079 -0.0138643 0.116077 0.991523 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.69 -4.77052 -186.68 3997.3 -11.7349 3954.66 +EDGE_SE3:QUAT 1060 1110 0.281653 0.118662 -6.02761 0.0045737 0.0870189 -0.184816 0.978902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4114.62 -31.7213 687.309 3977.03 -66.9377 3978.07 +EDGE_SE3:QUAT 1059 1110 -0.805317 12.5003 -6.28408 0.191166 0.0341991 0.0834263 0.977408 1 3.08149e-18 3.08149e-18 -1.08514e-07 -1.00163e-08 3.61343e-12 1 3.08149e-18 -1.08514e-07 -1.00163e-08 3.61343e-12 1 -1.08514e-07 -1.00163e-08 3.61343e-12 3853.81 0.405711 69.7854 4000.22 0.916592 3972.15 +EDGE_SE3:QUAT 1060 1109 -0.896505 -12.9443 -6.43586 0.0303675 -0.117875 -0.147825 0.981494 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4185.22 -60.454 -890.507 3963.67 81.951 4101.5 +EDGE_SE3:QUAT 1061 1111 0.275879 -0.177943 -6.54582 -0.00507045 -0.224842 -0.00842831 0.974346 1 3.00927e-21 3.00927e-21 8.68049e-10 5.91255e-12 -3.76085e-09 1 3.00927e-21 8.68049e-10 5.91255e-12 -3.76085e-09 1 8.68049e-10 5.91255e-12 -3.76085e-09 4950.73 -4.69093 -2169.66 3797.74 6.26849 4950.55 +EDGE_SE3:QUAT 1060 1111 -0.766224 12.4738 -6.46981 -0.00274533 -0.0706052 -0.158034 0.984902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4076.32 -17.9469 -558.01 3983.62 45.6439 3976.45 +EDGE_SE3:QUAT 1061 1110 -0.64655 -12.1988 -6.30252 0.177166 0.100263 -0.0635931 0.976993 1 1.92593e-19 1.92593e-19 -7.07984e-10 -2.71652e-08 4.64393e-09 1 1.92593e-19 -7.07984e-10 -2.71652e-08 4.64393e-09 1 -7.07984e-10 -2.71652e-08 4.64393e-09 4082.72 76.4908 936.353 3951.96 20.3991 4192.1 +EDGE_SE3:QUAT 1062 1112 0.157806 0.361977 -6.62045 -0.214859 0.0177724 -0.144341 0.965756 1 7.73381e-19 7.73381e-19 -5.41591e-08 4.33446e-09 1.74154e-09 1 7.73381e-19 -5.41591e-08 4.33446e-09 1.74154e-09 1 -5.41591e-08 4.33446e-09 1.74154e-09 3824.89 37.199 -227.873 3992.26 24.0576 3926.21 +EDGE_SE3:QUAT 1061 1112 -0.517143 12.6504 -6.24802 0.0773875 0.0132783 0.23129 0.969711 1 1.92593e-19 1.92593e-19 -2.69213e-08 -6.39864e-09 6.38987e-10 1 1.92593e-19 -2.69213e-08 -6.39864e-09 6.38987e-10 1 -2.69213e-08 -6.39864e-09 6.38987e-10 3977.84 -6.82292 -109.42 3997.9 -21.2001 3787.82 +EDGE_SE3:QUAT 1062 1111 -0.721921 -12.6094 -6.23059 -0.150442 -0.0155019 0.00080151 0.988497 1 1.88079e-22 1.88079e-22 1.26355e-11 1.3063e-10 -8.57769e-10 1 1.88079e-22 1.26355e-11 1.3063e-10 -8.57769e-10 1 1.26355e-11 1.3063e-10 -8.57769e-10 3912.97 8.79564 -118.492 3999.24 -0.864338 4003.5 +EDGE_SE3:QUAT 1063 1113 -0.0366203 0.449863 -6.81171 -0.00782403 -0.1856 -0.0668 0.980321 1 7.70372e-19 7.70372e-19 -3.81259e-09 -5.44115e-08 9.87004e-10 1 7.70372e-19 -3.81259e-09 -5.44115e-08 9.87004e-10 1 -3.81259e-09 -5.44115e-08 9.87004e-10 4610.22 -56.5457 -1677.66 3866.32 69.3163 4592.61 +EDGE_SE3:QUAT 1062 1113 -0.551341 12.2934 -6.4994 0.147015 -0.0574052 0.152971 0.975547 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.7 -36.505 -712.622 3965.73 -39.9689 4028.55 +EDGE_SE3:QUAT 1063 1112 -0.721768 -12.6188 -6.65658 -0.160953 -0.0629759 -0.162502 0.971453 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4048.74 43.4418 -798.784 3957.65 44.4949 4046.73 +EDGE_SE3:QUAT 1064 1114 0.382165 0.0614675 -6.03858 -0.137425 0.0737991 0.0910261 0.983556 1 1.15556e-18 1.15556e-18 -5.47388e-08 1.99976e-08 2.58385e-08 1 1.15556e-18 -5.47388e-08 1.99976e-08 2.58385e-08 1 -5.47388e-08 1.99976e-08 2.58385e-08 4055.68 -40.3418 737.064 3966.31 12.3068 4098.08 +EDGE_SE3:QUAT 1063 1114 -0.615494 12.3976 -6.83368 -0.0107667 -0.115604 0.201096 0.972667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4182.2 65.5317 -875.364 3968.41 -100.182 4020.91 +EDGE_SE3:QUAT 1064 1113 -0.68293 -12.6753 -6.26771 -0.0306027 -0.0319443 0.0635939 0.996995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.53 4.77492 -230.975 3997 -7.78924 3997.1 +EDGE_SE3:QUAT 1065 1115 0.0869922 -0.0439736 -6.21232 -0.0276559 -0.0742914 0.0746813 0.994052 1 1.92593e-19 1.92593e-19 1.93908e-09 1.08761e-09 -2.78689e-08 1 1.92593e-19 1.93908e-09 1.08761e-09 -2.78689e-08 1 1.93908e-09 1.08761e-09 -2.78689e-08 4077.51 17.5985 -573.512 3981.54 -25.6858 4058.26 +EDGE_SE3:QUAT 1064 1115 -0.611651 12.2914 -6.3804 0.0318091 -0.0606086 0.0739665 0.994909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.39 -1.48248 -515.833 3983.67 -17.0656 4043.56 +EDGE_SE3:QUAT 1065 1114 -0.623857 -12.381 -6.30569 0.0295345 -0.32362 -0.0964465 0.940795 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 6165.1 -517.898 -3658.02 3700.6 510.705 6131.38 +EDGE_SE3:QUAT 1066 1116 -0.00213839 -0.0827102 -6.13651 -0.0374838 -0.0924762 0.0845513 0.99141 1 4.81482e-20 4.81482e-20 -1.39692e-08 -1.30641e-09 1.18953e-09 1 4.81482e-20 -1.39692e-08 -1.30641e-09 1.18953e-09 1 -1.39692e-08 -1.30641e-09 1.18953e-09 4116.57 30.4431 -709.98 3973.01 -39.1078 4093.59 +EDGE_SE3:QUAT 1065 1116 -0.96123 12.7769 -6.22727 0.031009 -0.104369 0.0399524 0.993252 1 1.20371e-20 1.20371e-20 7.05048e-09 2.42768e-10 -7.55037e-10 1 1.20371e-20 7.05048e-09 2.42768e-10 -7.55037e-10 1 7.05048e-09 2.42768e-10 -7.55037e-10 4181.73 -4.04232 -881.331 3955.04 -10.9934 4179.19 +EDGE_SE3:QUAT 1066 1115 -0.706193 -12.3659 -6.04744 0.142316 0.0879861 0.106197 0.980167 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3978 44.0653 496.15 3992.63 39.9517 4013.91 +EDGE_SE3:QUAT 1067 1117 0.184366 0.230863 -6.43796 -0.0179276 -0.0493727 0.0371952 0.997927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4036.21 5.67297 -389.085 3990.91 -8.38527 4031.96 +EDGE_SE3:QUAT 1066 1117 -0.828617 12.5797 -6.10726 0.0666083 -0.0381993 0.0248248 0.996739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.48 -10.2385 -324.992 3993.35 -1.60131 4023.76 +EDGE_SE3:QUAT 1067 1116 -0.237633 -12.6709 -6.12529 -0.032734 -0.113867 -0.0986994 0.988039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4224.03 -15.8968 -982.546 3946.27 44.4549 4189.35 +EDGE_SE3:QUAT 1068 1118 0.132129 -0.0878731 -6.43097 0.0356009 -0.0176873 -0.00349882 0.999203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.82 -2.51336 -139.882 3998.8 0.507163 4004.84 +EDGE_SE3:QUAT 1067 1118 -0.590624 12.6393 -6.52159 -0.149052 -0.00120398 0.0399437 0.988022 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3911.93 -6.30178 61.0323 3999.56 1.58314 3994.42 +EDGE_SE3:QUAT 1068 1117 -0.620357 -12.8843 -6.01342 0.0393567 0.0793769 -0.00971716 0.99602 1 4.89006e-20 4.89006e-20 -1.38606e-08 1.1661e-10 6.27127e-10 1 4.89006e-20 -1.38606e-08 1.1661e-10 6.27127e-10 1 -1.38606e-08 1.1661e-10 6.27127e-10 4097.57 12.1942 652.572 3974.62 2.80176 4103.39 +EDGE_SE3:QUAT 1069 1119 0.126637 -0.289297 -6.39323 -0.119326 0.0966402 -0.126975 0.979949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.64 -49.8263 565.017 3989.93 -50.7701 4012.11 +EDGE_SE3:QUAT 1068 1119 -0.77084 12.3534 -6.02458 0.186865 0.0352456 0.0424771 0.980834 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3867.46 13.5188 173.663 3999.28 5.69846 3999.91 +EDGE_SE3:QUAT 1069 1118 -0.604372 -12.6309 -6.11296 -0.102979 0.0413607 0.110131 0.987702 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.41 -18.7399 459.723 3985.4 21.0798 4003.31 +EDGE_SE3:QUAT 1070 1120 0.470535 -0.406661 -6.28377 0.0359958 -0.00678847 -0.0491456 0.99812 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.07 -0.487841 -32.8297 3999.96 0.649609 3990.6 +EDGE_SE3:QUAT 1069 1120 -0.392165 12.2292 -6.0335 -0.141849 0.117575 -0.0312112 0.982385 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4108.82 -79.393 891.404 3963.06 -59.0254 4185.41 +EDGE_SE3:QUAT 1070 1119 -0.510585 -12.9107 -6.0753 -0.20111 0.0935778 -0.110702 0.968784 1 7.70372e-19 7.70372e-19 5.40796e-08 -7.81854e-09 2.20277e-09 1 7.70372e-19 5.40796e-08 -7.81854e-09 2.20277e-09 1 5.40796e-08 -7.81854e-09 2.20277e-09 3880.52 -45.249 431.1 3998.94 -38.4242 3993.28 +EDGE_SE3:QUAT 1071 1121 0.319567 -0.15763 -6.18456 0.0336923 0.0857211 -0.192949 0.976876 1 2.0463e-19 2.0463e-19 -1.62247e-09 2.84702e-08 -6.17806e-10 1 2.0463e-19 -1.62247e-09 2.84702e-08 -6.17806e-10 1 -1.62247e-09 2.84702e-08 -6.17806e-10 4129.81 -25.4484 745.292 3970.93 -72.4977 3985.43 +EDGE_SE3:QUAT 1070 1121 -0.485837 12.5012 -6.33844 0.17457 -0.0416503 0.0137364 0.983668 1 7.52316e-22 7.52316e-22 7.63281e-11 -3.03044e-10 -1.71301e-09 1 7.52316e-22 7.63281e-11 -3.03044e-10 -1.71301e-09 1 7.63281e-11 -3.03044e-10 -1.71301e-09 3908.25 -30.7881 -348.577 3993.23 5.44033 4029.39 +EDGE_SE3:QUAT 1071 1120 -0.778527 -12.5294 -6.09362 -0.115059 0.00278985 -0.067839 0.991036 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3948.07 5.82156 -70.8445 3999.35 3.36345 3982.61 +EDGE_SE3:QUAT 1072 1122 0.0586912 0.340529 -6.00657 0.0197257 0.0248211 0.0174855 0.999344 1 1.20371e-20 1.20371e-20 -6.94253e-09 -1.28333e-10 -1.67397e-10 1 1.20371e-20 -6.94253e-09 -1.28333e-10 -1.67397e-10 1 -6.94253e-09 -1.28333e-10 -1.67397e-10 4007.89 2.16793 194.619 3997.68 1.98229 4008.22 +EDGE_SE3:QUAT 1071 1122 -0.680273 12.4191 -6.17113 0.0879968 -0.105587 0.0646795 0.988395 1 4.81482e-20 4.81482e-20 1.63294e-09 -1.07575e-09 -1.40762e-08 1 4.81482e-20 1.63294e-09 -1.07575e-09 -1.40762e-08 1 1.63294e-09 -1.07575e-09 -1.40762e-08 4179.18 -27.1242 -940.733 3948.91 -7.17557 4193.42 +EDGE_SE3:QUAT 1072 1121 -1.16841 -12.1395 -6.34611 -0.0623895 -0.0892643 -0.188034 0.976106 1 2.40741e-19 2.40741e-19 -1.88172e-08 -2.46008e-08 7.84385e-10 1 2.40741e-19 -1.88172e-08 -2.46008e-08 7.84385e-10 1 -1.88172e-08 -2.46008e-08 7.84385e-10 4154.76 -17.1913 -843.019 3960.54 74.866 4028.91 +EDGE_SE3:QUAT 1073 1123 -0.455924 0.254683 -6.39193 -0.0322081 0.195232 -0.0103973 0.980173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4676.06 -52.023 1784.24 3850.98 -48.5444 4679.77 +EDGE_SE3:QUAT 1072 1123 -0.784429 12.6672 -6.44025 -0.041001 -0.0190182 0.10621 0.993316 1 1.95602e-19 1.95602e-19 9.8873e-11 -4.67054e-09 2.7425e-08 1 1.95602e-19 9.8873e-11 -4.67054e-09 2.7425e-08 1 9.8873e-11 -4.67054e-09 2.7425e-08 3995.56 2.10295 -97.4007 3999.66 -4.39144 3957.16 +EDGE_SE3:QUAT 1073 1122 -0.707397 -12.673 -6.34895 0.0554045 0.0722047 -0.0565331 0.994244 1 2.40741e-19 2.40741e-19 1.53152e-08 2.69225e-08 -2.27596e-10 1 2.40741e-19 1.53152e-08 2.69225e-08 -2.27596e-10 1 1.53152e-08 2.69225e-08 -2.27596e-10 4082.43 10.6252 622.825 3976.31 -11.1622 4081.93 +EDGE_SE3:QUAT 1074 1124 0.0021953 0.17713 -6.19746 -0.00420495 -0.0575792 -0.0511 0.997023 1 4.70198e-23 4.70198e-23 -4.35294e-10 2.22464e-11 2.51946e-11 1 4.70198e-23 -4.35294e-10 2.22464e-11 2.51946e-11 1 -4.35294e-10 2.22464e-11 2.51946e-11 4053.69 -3.13194 -466.832 3986.82 12.0113 4043.32 +EDGE_SE3:QUAT 1073 1124 -0.735944 12.5409 -6.26031 -0.0149626 -0.0404561 -0.03202 0.998556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4026.27 1.23038 -330.766 3993.2 4.80837 4023.07 +EDGE_SE3:QUAT 1074 1123 -0.738247 -12.3434 -5.92125 0.115117 -0.0348296 -0.152534 0.980953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3946.41 0.40566 -57.5877 4000.15 -0.888433 3906.35 +EDGE_SE3:QUAT 1075 1125 -0.228838 -0.208467 -6.17262 -0.0765101 -0.0818965 -0.0664293 0.991477 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4104.43 18.0714 -726.582 3968.09 12.1295 4110.19 +EDGE_SE3:QUAT 1074 1125 -0.711096 12.5168 -6.57334 -0.0688573 0.0963189 0.130891 0.984301 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4170.08 1.50049 890.124 3954.07 47.4703 4120.51 +EDGE_SE3:QUAT 1075 1124 -0.620518 -12.6775 -5.8406 -0.0928961 0.142559 -0.088237 0.981459 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4231.93 -96.3261 1067.68 3950.56 -95.5258 4235.3 +EDGE_SE3:QUAT 1076 1126 0.0223796 0.160987 -6.2751 -0.0622736 0.098743 0.104319 0.987669 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4172.19 -2.21101 886.72 3954.26 35.194 4144.17 +EDGE_SE3:QUAT 1075 1126 -0.777465 12.4546 -6.16583 0.046008 -0.0345284 0.0760227 0.995445 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.4 -4.98376 -316.58 3993.44 -11.0666 4001.75 +EDGE_SE3:QUAT 1076 1125 -0.506808 -12.4601 -6.15834 0.164761 -0.116896 -0.00124888 0.979381 1 9.62965e-19 9.62965e-19 -5.46891e-08 2.94395e-08 1.55875e-09 1 9.62965e-19 -5.46891e-08 2.94395e-08 1.55875e-09 1 -5.46891e-08 2.94395e-08 1.55875e-09 4098.82 -87.2285 -934.546 3958.41 55.1072 4207.4 +EDGE_SE3:QUAT 1077 1127 0.143273 0.13124 -6.08872 0.0701588 0.0183817 0.254221 0.964423 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3980.34 -5.21295 -72.1485 3998.62 -18.903 3741.52 +EDGE_SE3:QUAT 1076 1127 -0.794636 12.6369 -6.40584 0.055514 0.0105821 0.111398 0.992168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.53 -0.423228 9.24399 3999.99 -0.887231 3950.22 +EDGE_SE3:QUAT 1077 1126 -0.784347 -12.4031 -6.13299 0.0966221 0.229772 0.128085 0.959929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4678.54 296.788 1841.46 3911.86 298.947 4650.26 +EDGE_SE3:QUAT 1078 1128 0.368472 0.350729 -6.29982 -0.0140431 -0.0774262 0.0142173 0.996798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4095.98 6.78425 -629.638 3976.36 -6.81683 4095.96 +EDGE_SE3:QUAT 1077 1128 -0.673165 12.5572 -6.87381 -0.148751 0.0867364 -0.0973336 0.980243 1 1.92593e-19 1.92593e-19 -1.46028e-09 4.60141e-09 -2.74132e-08 1 1.92593e-19 -1.46028e-09 4.60141e-09 -2.74132e-08 1 -1.46028e-09 4.60141e-09 -2.74132e-08 3970.14 -44.3828 494.167 3992.5 -38.4436 4020.76 +EDGE_SE3:QUAT 1078 1127 -0.775358 -12.4349 -6.319 0.0492989 0.0629937 -0.0902566 0.992701 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4066.84 4.67287 558.802 3980.67 -21.559 4043.97 +EDGE_SE3:QUAT 1079 1129 -0.268579 0.0597532 -6.34525 0.0541413 -0.124798 -0.185199 0.97324 1 3.85186e-19 3.85186e-19 2.19959e-08 -3.26792e-08 2.671e-11 1 3.85186e-19 2.19959e-08 -3.26792e-08 2.671e-11 1 2.19959e-08 -3.26792e-08 2.671e-11 4160.17 -79.9478 -850.537 3974.86 100.312 4034.7 +EDGE_SE3:QUAT 1078 1129 -0.782167 12.6536 -6.6305 -0.0292343 0.0648515 0.0618946 0.995544 1 1.20371e-20 1.20371e-20 -6.97108e-09 -4.09773e-10 -4.75371e-10 1 1.20371e-20 -6.97108e-09 -4.09773e-10 -4.75371e-10 1 -6.97108e-09 -4.09773e-10 -4.75371e-10 4069.67 -1.68128 545.643 3981.84 14.6679 4057.77 +EDGE_SE3:QUAT 1079 1128 -0.812404 -12.2804 -6.05394 0.0998474 0.120746 -0.0413749 0.986782 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4222.39 45.3999 1057.32 3938.32 14.3383 4255.42 +EDGE_SE3:QUAT 1080 1130 -0.167898 -0.23723 -5.93382 0.0756616 0.053386 0.0656595 0.993536 1 3.85186e-19 3.85186e-19 -2.65092e-08 2.53263e-10 2.65092e-08 1 3.85186e-19 -2.65092e-08 2.53263e-10 2.65092e-08 1 -2.65092e-08 2.53263e-10 2.65092e-08 4009.74 16.7917 363.584 3993.28 15.5759 4015.39 +EDGE_SE3:QUAT 1079 1130 -0.764347 12.3625 -6.35744 -0.0237384 -0.047085 0.144729 0.988065 1 9.62965e-20 9.62965e-20 1.17135e-08 1.5759e-08 -2.77622e-11 1 9.62965e-20 1.17135e-08 1.5759e-08 -2.77622e-11 1 1.17135e-08 1.5759e-08 -2.77622e-11 4023.95 9.95023 -325.539 3994.85 -23.7557 3942.42 +EDGE_SE3:QUAT 1080 1129 -0.65664 -12.782 -5.95335 -0.0168223 0.049641 -0.105261 0.993062 1 6.01853e-20 6.01853e-20 -8.41026e-09 -1.30302e-08 -6.87355e-10 1 6.01853e-20 -8.41026e-09 -1.30302e-08 -6.87355e-10 1 -8.41026e-09 -1.30302e-08 -6.87355e-10 4033.12 -8.77695 371.891 3992.36 -20.4546 3989.93 +EDGE_SE3:QUAT 1081 1131 -0.0368349 -0.327394 -6.70597 -0.16077 -0.101983 -0.0658168 0.9795 1 1.01111e-18 1.01111e-18 5.66562e-08 -2.68688e-08 -2.48021e-08 1 1.01111e-18 5.66562e-08 -2.68688e-08 -2.48021e-08 1 5.66562e-08 -2.68688e-08 -2.48021e-08 4110.56 67.7237 -949.687 3949.74 -14.8746 4196.62 +EDGE_SE3:QUAT 1080 1131 -0.846908 12.6968 -6.12987 -0.0954004 -0.142322 0.140398 0.975157 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4183.02 105.045 -966.557 3968.01 -111.67 4140.58 +EDGE_SE3:QUAT 1081 1130 -0.728226 -12.4016 -6.36543 0.0693785 0.0381494 -0.100295 0.991802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.25 9.41433 384.541 3990.04 -17.4442 3996.27 +EDGE_SE3:QUAT 1082 1132 0.131504 0.0887134 -6.26515 -0.00599245 -0.00748064 -0.118647 0.99289 1 1.92593e-19 1.92593e-19 2.40997e-10 1.12752e-10 -2.75622e-08 1 1.92593e-19 2.40997e-10 1.12752e-10 -2.75622e-08 1 2.40997e-10 1.12752e-10 -2.75622e-08 4000.98 0.0163002 -67.0521 3999.71 4.11417 3944.81 +EDGE_SE3:QUAT 1081 1132 -0.733629 12.689 -6.59374 -0.0334658 0.0695519 0.0805457 0.993758 1 2.0463e-19 2.0463e-19 -4.89616e-09 -1.15719e-09 2.73617e-08 1 2.0463e-19 -4.89616e-09 -1.15719e-09 2.73617e-08 1 -4.89616e-09 -1.15719e-09 2.73617e-08 4081.76 -0.272608 593.666 3978.66 21.2604 4060.29 +EDGE_SE3:QUAT 1082 1131 -0.716283 -12.4791 -6.10179 -0.145309 -0.196156 -0.103167 0.964243 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4736.91 80.1814 -1990.12 3824.81 -37.717 4778.79 +EDGE_SE3:QUAT 1083 1133 -0.197548 -0.312329 -6.24454 -0.133297 0.0352944 -0.239047 0.961167 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3927.94 16.8159 -112.223 3996.08 30.0234 3770.43 +EDGE_SE3:QUAT 1082 1133 -0.640118 12.1989 -6.39507 0.0486273 -0.0793855 0.0477832 0.99451 1 4.81482e-20 4.81482e-20 1.17269e-09 -5.82439e-10 -1.39922e-08 1 4.81482e-20 1.17269e-09 -5.82439e-10 -1.39922e-08 1 1.17269e-09 -5.82439e-10 -1.39922e-08 4101.33 -9.82108 -674.889 3972.56 -9.37301 4101.66 +EDGE_SE3:QUAT 1083 1132 -1.29485 -12.4959 -5.59498 -0.0171598 -0.135879 -0.238822 0.961357 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4284.28 -100.161 -1107.05 3953.85 148.884 4057.31 +EDGE_SE3:QUAT 1084 1134 -0.217776 -0.0755332 -6.05554 0.150564 0.125901 0.206836 0.958488 1 7.70372e-19 7.70372e-19 -2.62266e-09 -1.07589e-08 -5.36764e-08 1 7.70372e-19 -2.62266e-09 -1.07589e-08 -5.36764e-08 1 -2.62266e-09 -1.07589e-08 -5.36764e-08 3974.77 66.5831 546.725 4003.66 69.6836 3894.32 +EDGE_SE3:QUAT 1083 1134 -0.806277 12.4925 -6.64692 0.0628936 0.00226003 0.227206 0.971811 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.03 -5.40857 -148.711 3997.47 -23.1558 3798.36 +EDGE_SE3:QUAT 1084 1133 -0.844585 -12.4511 -6.02089 0.023729 0.0759427 0.0364335 0.996164 1 2.0463e-19 2.0463e-19 -5.86746e-09 -2.79286e-08 3.00543e-10 1 2.0463e-19 -5.86746e-09 -2.79286e-08 3.00543e-10 1 -5.86746e-09 -2.79286e-08 3.00543e-10 4087.82 12.6083 606.994 3978.39 14.9155 4084.77 +EDGE_SE3:QUAT 1085 1135 -0.0575799 0.0925546 -6.0718 -0.131828 -0.0936932 0.0162414 0.986701 1 9.62965e-19 9.62965e-19 -5.45186e-08 -2.96651e-08 1.04694e-09 1 9.62965e-19 -5.45186e-08 -2.96651e-08 1.04694e-09 1 -5.45186e-08 -2.96651e-08 1.04694e-09 4057.04 54.0984 -722.989 3973.22 -32.6907 4125.49 +EDGE_SE3:QUAT 1084 1135 -0.940992 12.3141 -6.44139 -0.138389 -0.0562678 0.0149577 0.988665 1 4.81482e-20 4.81482e-20 4.15698e-10 -1.37158e-08 -1.95401e-09 1 4.81482e-20 4.15698e-10 -1.37158e-08 -1.95401e-09 1 4.15698e-10 -1.37158e-08 -1.95401e-09 3966.17 29.8192 -416.192 3990.99 -12.5126 4041.88 +EDGE_SE3:QUAT 1085 1134 -0.783517 -12.7737 -6.02595 0.0460441 -0.111594 -0.141709 0.98252 1 1.92593e-19 1.92593e-19 2.78147e-08 -4.38322e-09 -2.63905e-09 1 1.92593e-19 2.78147e-08 -4.38322e-09 -2.63905e-09 1 2.78147e-08 -4.38322e-09 -2.63905e-09 4148.73 -56.8239 -809.82 3970.67 73.4653 4076.88 +EDGE_SE3:QUAT 1086 1136 -0.300816 -0.054362 -6.16262 -0.0517271 0.00451125 0.0309082 0.998173 1 6.01853e-20 6.01853e-20 1.38005e-08 7.76604e-10 -6.8204e-09 1 6.01853e-20 1.38005e-08 7.76604e-10 -6.8204e-09 1 1.38005e-08 7.76604e-10 -6.8204e-09 3990.04 -1.55789 55.0433 3999.77 0.898637 3996.93 +EDGE_SE3:QUAT 1085 1136 -0.743402 12.3194 -6.41957 0.0723124 0.0600168 0.0906475 0.991439 1 2.40741e-19 2.40741e-19 -2.62797e-08 -1.65075e-08 -1.19221e-10 1 2.40741e-19 -2.62797e-08 -1.65075e-08 -1.19221e-10 1 -2.62797e-08 -1.65075e-08 -1.19221e-10 4017.47 19.5142 395.075 3992.57 21.7896 4005.52 +EDGE_SE3:QUAT 1086 1135 -1.02128 -12.4741 -6.32276 0.0488085 -0.161964 -0.0758589 0.982665 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4398.41 -91.1565 -1341.28 3915.16 96.0388 4384.92 +EDGE_SE3:QUAT 1087 1137 -0.138848 0.131076 -6.30769 0.0483876 0.204824 -0.044759 0.976577 1 4.81482e-20 4.81482e-20 -3.15373e-09 -5.02499e-10 -1.4828e-08 1 4.81482e-20 -3.15373e-09 -5.02499e-10 -1.4828e-08 1 -3.15373e-09 -5.02499e-10 -1.4828e-08 4776.15 11.8654 1938.84 3828.66 -2.06983 4777.5 +EDGE_SE3:QUAT 1086 1137 -0.529157 12.3717 -6.34612 -0.0699095 -0.012435 -0.0397287 0.996684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.77 4.76438 -131.845 3998.75 2.43107 3998 +EDGE_SE3:QUAT 1087 1136 -0.54618 -12.5367 -5.85721 -0.110263 0.104822 -0.0412264 0.987499 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4101.66 -56.8524 790.388 3968.86 -44.1941 4143.49 +EDGE_SE3:QUAT 1088 1138 -0.232081 0.0282141 -6.08326 0.199274 -0.0111967 -0.0150343 0.979764 1 7.73381e-19 7.73381e-19 5.4455e-08 2.3878e-09 -9.38211e-10 1 7.73381e-19 5.4455e-08 2.3878e-09 -9.38211e-10 1 5.4455e-08 2.3878e-09 -9.38211e-10 3841.71 -3.55452 -49.2643 3999.96 0.521758 3999.65 +EDGE_SE3:QUAT 1087 1138 -0.88633 12.7125 -6.54703 -0.0219328 0.0318259 0.0531001 0.997841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016 -1.62023 268.381 3995.44 6.73945 4006.64 +EDGE_SE3:QUAT 1088 1137 -0.546506 -12.7792 -5.98337 -0.0439029 -0.120559 -0.0967707 0.987002 1 4.81482e-20 4.81482e-20 -1.41443e-08 1.26994e-09 1.81322e-09 1 4.81482e-20 -1.41443e-08 1.26994e-09 1.81322e-09 1 -1.41443e-08 1.26994e-09 1.81322e-09 4254.87 -11.5081 -1057.99 3938.01 42.5375 4225.12 +EDGE_SE3:QUAT 1089 1139 0.124014 0.1112 -6.21827 -0.0907217 -0.148107 -0.097974 0.979916 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4399.18 15.1355 -1384 3899.5 26.3632 4393.71 +EDGE_SE3:QUAT 1088 1139 -0.481461 12.4187 -6.74998 0.181022 0.157466 0.0602785 0.968918 1 7.70372e-19 7.70372e-19 -5.57873e-08 -6.73363e-09 -7.06449e-09 1 7.70372e-19 -5.57873e-08 -6.73363e-09 -7.06449e-09 1 -5.57873e-08 -6.73363e-09 -7.06449e-09 4158.81 148.785 1119.28 3960.04 131.25 4275.35 +EDGE_SE3:QUAT 1089 1138 -0.888474 -12.2152 -6.19056 0.133854 0.0139959 0.00549897 0.990887 1 3.00927e-21 3.00927e-21 -3.12864e-11 3.43774e-09 -4.65059e-10 1 3.00927e-21 -3.12864e-11 3.43774e-09 -4.65059e-10 1 -3.12864e-11 3.43774e-09 -4.65059e-10 3930.84 6.48121 100.289 3999.47 0.8011 4002.39 +EDGE_SE3:QUAT 1090 1140 -0.0295533 0.0417885 -6.07774 0.0161006 -0.0159253 0.156971 0.987344 1 7.94446e-19 7.94446e-19 6.82394e-09 -5.18856e-09 5.47816e-08 1 7.94446e-19 6.82394e-09 -5.18856e-09 5.47816e-08 1 6.82394e-09 -5.18856e-09 5.47816e-08 4004.77 -0.0120284 -152.717 3998.51 -12.5614 3907.25 +EDGE_SE3:QUAT 1089 1140 -0.566532 12.5078 -6.42394 0.0767252 0.0652032 0.0899033 0.990848 1 2.40741e-19 2.40741e-19 -2.62814e-08 -1.65163e-08 -1.6591e-10 1 2.40741e-19 -2.62814e-08 -1.65163e-08 -1.6591e-10 1 -2.62814e-08 -1.65163e-08 -1.6591e-10 4022.3 22.9076 432.087 3991.15 24.6347 4013.52 +EDGE_SE3:QUAT 1090 1139 -0.535072 -12.4999 -6.44809 0.0026679 0.28308 -0.0298864 0.958627 1 4.81482e-20 4.81482e-20 4.67052e-09 -2.66773e-10 1.58392e-08 1 4.81482e-20 4.67052e-09 -2.66773e-10 1.58392e-08 1 4.67052e-09 -2.66773e-10 1.58392e-08 5668.24 -80.1344 3075.09 3682.83 -80.1474 5664.69 +EDGE_SE3:QUAT 1091 1141 -0.084303 0.0590998 -6.21844 -0.0100654 -0.0195064 7.79202e-05 0.999759 1 2.40741e-20 2.40741e-20 6.93924e-09 6.94049e-09 -6.55007e-11 1 2.40741e-20 6.93924e-09 6.94049e-09 -6.55007e-11 1 6.93924e-09 6.94049e-09 -6.55007e-11 4005.69 0.79004 -156.226 3998.48 -0.0981715 4006.09 +EDGE_SE3:QUAT 1090 1141 -0.982152 12.5152 -6.60104 -0.0707263 -0.0897375 0.192594 0.974604 1 9.62965e-19 9.62965e-19 2.62294e-09 -3.26063e-08 5.17725e-08 1 9.62965e-19 2.62294e-09 -3.26063e-08 5.17725e-08 1 2.62294e-09 -3.26063e-08 5.17725e-08 4044.31 40.2573 -517.858 3992.65 -54.6826 3915.94 +EDGE_SE3:QUAT 1091 1140 -0.630551 -12.3459 -6.34243 0.118514 -0.0687809 0.018069 0.990402 1 1.95602e-19 1.95602e-19 2.80184e-08 -3.70413e-10 -5.46437e-09 1 1.95602e-19 2.80184e-08 -3.70413e-10 -5.46437e-09 1 2.80184e-08 -3.70413e-10 -5.46437e-09 4024.59 -33.8711 -574.117 3980.88 8.93523 4079.47 +EDGE_SE3:QUAT 1092 1142 -0.0379187 0.108961 -6.57462 0.0659554 -0.0375191 0.133591 0.988127 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.69 -7.31011 -398.29 3989.26 -25.7713 3967.7 +EDGE_SE3:QUAT 1091 1142 -0.901259 12.4611 -6.22325 -0.268251 0.0285366 -0.0457734 0.961838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3712.32 -0.886097 63.1543 4000.28 -1.09465 3991.77 +EDGE_SE3:QUAT 1092 1141 -0.85882 -12.1222 -6.15869 -0.137179 0.0828852 -0.0511825 0.985744 1 7.70372e-19 7.70372e-19 -5.52655e-08 4.0694e-09 -3.65368e-09 1 7.70372e-19 -5.52655e-08 4.0694e-09 -3.65368e-09 1 -5.52655e-08 4.0694e-09 -3.65368e-09 4003.03 -45.5118 566.688 3985.5 -32.4606 4067.82 +EDGE_SE3:QUAT 1093 1143 -0.136259 0.161337 -6.17319 0.0868399 -0.121545 -0.0568509 0.987144 1 1.92593e-19 1.92593e-19 2.81108e-08 -2.25173e-09 -3.0945e-09 1 1.92593e-19 2.81108e-08 -2.25173e-09 -3.0945e-09 1 2.81108e-08 -2.25173e-09 -3.0945e-09 4177.69 -64.4522 -935.767 3956.66 58.8087 4194.92 +EDGE_SE3:QUAT 1092 1143 -0.643183 12.5131 -6.56259 0.147482 -0.0288153 0.200279 0.968146 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.02 -32.5418 -560.602 3975.14 -55.5419 3914.58 +EDGE_SE3:QUAT 1093 1142 -0.861299 -12.6989 -6.15466 0.101438 -0.0100947 -0.0627485 0.99281 1 1.92781e-19 1.92781e-19 -2.76105e-08 9.01223e-10 9.74305e-12 1 1.92781e-19 -2.76105e-08 9.01223e-10 9.74305e-12 1 -2.76105e-08 9.01223e-10 9.74305e-12 3958.68 1.1414 -3.37608 3999.97 -0.697946 3984.09 +EDGE_SE3:QUAT 1094 1144 -0.478819 0.121243 -6.33238 -0.00243319 0.11752 0.0825166 0.989633 1 7.52316e-22 7.52316e-22 1.76507e-09 1.50321e-10 2.07404e-10 1 7.52316e-22 1.76507e-09 1.50321e-10 2.07404e-10 1 1.76507e-09 1.50321e-10 2.07404e-10 4226.74 27.6398 979.034 3947.62 45.3654 4199.53 +EDGE_SE3:QUAT 1093 1144 -0.942841 12.5311 -6.57435 0.0297705 0.0226433 0.128288 0.991031 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.67 2.68956 131.219 3999.28 7.59405 3938.39 +EDGE_SE3:QUAT 1094 1143 -0.580451 -12.4836 -6.12642 -0.0898784 0.181151 -0.109182 0.973235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4407.32 -162.527 1399.3 3927.91 -165.243 4391.95 +EDGE_SE3:QUAT 1095 1145 -0.0920085 0.0245241 -6.26526 0.121988 0.0139966 -0.0498134 0.991182 1 4.81482e-20 4.81482e-20 -3.5516e-10 -1.66799e-09 -1.37696e-08 1 4.81482e-20 -3.5516e-10 -1.66799e-09 -1.37696e-08 1 -3.5516e-10 -1.66799e-09 -1.37696e-08 3948.58 12.0193 181.531 3997.49 -3.84897 3998.18 +EDGE_SE3:QUAT 1094 1145 -0.948548 12.3075 -6.15326 0.023109 -0.0320563 0.280181 0.959134 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.53 5.61315 -301.977 3995.51 -44.2638 3708.66 +EDGE_SE3:QUAT 1095 1144 -0.927157 -12.3192 -6.17855 -0.0584134 -0.18309 -0.170236 0.966481 1 7.70372e-19 7.70372e-19 1.14971e-08 -3.36834e-10 -5.7948e-08 1 7.70372e-19 1.14971e-08 -3.36834e-10 -5.7948e-08 1 1.14971e-08 -3.36834e-10 -5.7948e-08 4632.88 -105.67 -1733.25 3869.04 146.452 4530.61 +EDGE_SE3:QUAT 1096 1146 -0.152379 0.0419753 -6.56064 -0.0842946 0.0321631 -0.0763259 0.992993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.1 -7.3916 175.899 3998.78 -6.90789 3984.22 +EDGE_SE3:QUAT 1095 1146 -0.687025 12.3645 -6.26941 0.0872365 0.0417744 0.012166 0.995237 1 6.01853e-20 6.01853e-20 -3.66723e-12 -1.44263e-08 -5.69947e-09 1 6.01853e-20 -3.66723e-12 -1.44263e-08 -5.69947e-09 1 -3.66723e-12 -1.44263e-08 -5.69947e-09 3994.88 14.4056 319.332 3994.13 5.35861 4024.73 +EDGE_SE3:QUAT 1096 1145 -1.13197 -12.5737 -6.53359 0.0935516 0.110828 -0.114701 0.982756 1 1.92593e-19 1.92593e-19 -2.8153e-08 2.71788e-09 -3.66077e-09 1 1.92593e-19 -2.8153e-08 2.71788e-09 -3.66077e-09 1 -2.8153e-08 2.71788e-09 -3.66077e-09 4221.1 14.2429 1044.36 3937.72 -35.3703 4203.48 +EDGE_SE3:QUAT 1097 1147 -0.198538 -0.12241 -6.10088 0.0351496 0.142799 0.0311996 0.988635 1 4.81482e-20 4.81482e-20 2.02067e-09 6.60983e-10 1.42862e-08 1 4.81482e-20 2.02067e-09 6.60983e-10 1.42862e-08 1 2.02067e-09 6.60983e-10 1.42862e-08 4331 42.1361 1206.93 3923.19 41.3362 4332.05 +EDGE_SE3:QUAT 1096 1147 -0.987314 12.6404 -6.12806 0.05614 -0.0677502 0.210582 0.973608 1 4.81482e-20 4.81482e-20 -1.36967e-08 -2.87069e-09 1.19056e-09 1 4.81482e-20 -1.36967e-08 -2.87069e-09 1.19056e-09 1 -1.36967e-08 -2.87069e-09 1.19056e-09 4092.77 11.5417 -658.012 3975.47 -68.6942 3928 +EDGE_SE3:QUAT 1097 1146 -0.71996 -12.4168 -5.65933 -0.0758576 -0.000210886 -0.110493 0.990978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.27 4.84975 -101.077 3998.89 7.26209 3953.46 +EDGE_SE3:QUAT 1098 1148 -0.210893 0.202866 -6.32661 -0.0401935 -0.0389896 -0.0586577 0.996706 1 9.62965e-20 9.62965e-20 -1.32785e-08 1.26736e-09 -1.32785e-08 1 9.62965e-20 -1.32785e-08 1.26736e-09 -1.32785e-08 1 -1.32785e-08 1.26736e-09 -1.32785e-08 4022.22 4.67517 -339.996 3992.61 8.72152 4014.92 +EDGE_SE3:QUAT 1097 1148 -0.914457 12.6629 -6.51868 0.0492598 0.0184273 0.170388 0.983973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.41 0.411256 41.8613 4000.05 0.58467 3883.99 +EDGE_SE3:QUAT 1098 1147 -0.724688 -12.3802 -6.12128 -0.148555 0.0467177 -0.0407098 0.986961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3932.38 -21.2511 289.986 3996.46 -10.7809 4014.03 +EDGE_SE3:QUAT 1099 1149 -0.047982 0.136572 -6.21759 0.00289774 0.00464486 -0.0162905 0.999852 1 1.20371e-20 1.20371e-20 -3.2869e-11 -1.90482e-11 -6.93818e-09 1 1.20371e-20 -3.2869e-11 -1.90482e-11 -6.93818e-09 1 -3.2869e-11 -1.90482e-11 -6.93818e-09 4000.32 0.046287 37.7129 3999.91 -0.307213 3999.29 +EDGE_SE3:QUAT 1098 1149 -0.812908 12.6992 -6.18137 -0.00814225 -0.0199804 0.0650169 0.997651 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.55 1.19529 -152.667 3998.62 -4.9755 3988.91 +EDGE_SE3:QUAT 1099 1148 -0.999046 -12.3767 -6.73337 0.098481 -0.0740857 0.0316569 0.991872 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4059.34 -28.984 -634.198 3976.05 3.6263 4094.13 +EDGE_SE3:QUAT 1100 1150 -0.196413 0.197742 -6.4012 -0.111843 0.121223 0.135294 0.976981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4277.1 -16.1153 1190.28 3921.44 44.6674 4253.92 +EDGE_SE3:QUAT 1099 1150 -0.816774 13.0108 -6.40538 0.00556166 -0.141518 0.0340921 0.989333 1 7.70419e-19 7.70419e-19 2.32839e-09 -5.49041e-08 -2.95146e-10 1 7.70419e-19 2.32839e-09 -5.49041e-08 -2.95146e-10 1 2.32839e-09 -5.49041e-08 -2.95146e-10 4340.85 14.0044 -1216.63 3920.23 -22.2359 4336.33 +EDGE_SE3:QUAT 1100 1149 -0.772759 -12.5113 -6.12757 -0.0283406 0.128185 0.0763868 0.988398 1 7.82409e-19 7.82409e-19 3.13187e-09 5.54009e-08 1.43777e-09 1 7.82409e-19 3.13187e-09 5.54009e-08 1.43777e-09 1 3.13187e-09 5.54009e-08 1.43777e-09 4282.79 15.093 1107.17 3932.86 37.6024 4262.67 +EDGE_SE3:QUAT 1101 1151 0.0495967 -0.0271921 -6.39251 0.0203481 0.164605 0.0010567 0.986149 1 1.20371e-20 1.20371e-20 7.2343e-09 5.94266e-11 1.20613e-09 1 1.20371e-20 7.2343e-09 5.94266e-11 1.20613e-09 1 7.2343e-09 5.94266e-11 1.20613e-09 4468.95 19.8441 1450.49 3892.13 16.1177 4470.6 +EDGE_SE3:QUAT 1100 1151 -1.01874 12.3332 -6.58815 -0.0509603 0.0801334 0.102461 0.990194 1 1.92593e-19 1.92593e-19 -2.49574e-09 9.60916e-10 -2.79055e-08 1 1.92593e-19 -2.49574e-09 9.60916e-10 -2.79055e-08 1 -2.49574e-09 9.60916e-10 -2.79055e-08 4111.94 -1.33779 710.237 3969.79 30.7633 4080.33 +EDGE_SE3:QUAT 1101 1150 -0.874585 -12.4783 -6.21902 0.0566944 0.0905895 0.0227116 0.994014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4114.28 26.5444 724.426 3970.19 19.9828 4125.08 +EDGE_SE3:QUAT 1102 1152 -0.0661579 0.0958913 -6.33134 -0.0480287 -0.108927 -0.00741754 0.992861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4188.19 22.3887 -910.298 3952.81 -10.7438 4197.2 +EDGE_SE3:QUAT 1101 1152 -1.08416 12.47 -6.48702 -0.124886 0.0523045 -0.0602999 0.988955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3962.44 -20.8068 318.313 3995.73 -14.2469 4010.28 +EDGE_SE3:QUAT 1102 1151 -1.61462 -12.1624 -6.30665 0.17241 0.12529 0.086924 0.97315 1 1.92593e-19 1.92593e-19 2.40967e-09 5.55548e-09 2.75257e-08 1 1.92593e-19 2.40967e-09 5.55548e-09 2.75257e-08 1 2.40967e-09 5.55548e-09 2.75257e-08 4028.42 93.0504 787.907 3981.64 81.3735 4117.09 +EDGE_SE3:QUAT 1103 1153 -0.347573 0.302731 -6.19897 0.0118654 -0.0658003 -0.0217581 0.997525 1 1.50463e-20 1.50463e-20 -3.94699e-09 1.86128e-10 7.20953e-09 1 1.50463e-20 -3.94699e-09 1.86128e-10 7.20953e-09 1 -3.94699e-09 1.86128e-10 7.20953e-09 4068.65 -5.56851 -530.688 3983.05 7.26774 4067.32 +EDGE_SE3:QUAT 1102 1153 -0.682831 12.3035 -6.56279 0.022223 -0.0894087 0.123046 0.988115 1 1.95602e-19 1.95602e-19 8.86825e-10 4.21538e-10 2.75744e-08 1 1.95602e-19 8.86825e-10 4.21538e-10 2.75744e-08 1 8.86825e-10 4.21538e-10 2.75744e-08 4135.28 16.4956 -753.553 3968.06 -46.1559 4076.69 +EDGE_SE3:QUAT 1103 1152 -1.08557 -12.2962 -6.16336 0.109704 0.022445 -0.132127 0.984888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3980.76 17.4375 344.843 3990.64 -22.781 3959.07 +EDGE_SE3:QUAT 1104 1154 0.236439 -0.206665 -6.36859 -0.0249294 0.0968543 0.0988937 0.990059 1 3.00927e-21 3.00927e-21 3.50447e-09 3.39219e-10 3.53346e-10 1 3.00927e-21 3.50447e-09 3.39219e-10 3.53346e-10 1 3.50447e-09 3.39219e-10 3.53346e-10 4159.41 12.9661 820.843 3961.6 38.9403 4122.77 +EDGE_SE3:QUAT 1103 1154 -1.06579 12.9936 -6.38088 -0.186079 -0.0971913 0.0112381 0.977651 1 7.82409e-19 7.82409e-19 -5.57811e-08 -3.98703e-09 1.17559e-08 1 7.82409e-19 -5.57811e-08 -3.98703e-09 1.17559e-08 1 -5.57811e-08 -3.98703e-09 1.17559e-08 3990.86 74.7599 -731.744 3975.97 -43.3837 4128.85 +EDGE_SE3:QUAT 1104 1153 -1.15703 -12.4948 -5.94497 0.00985119 -0.0501721 -0.181648 0.982034 1 8.1852e-19 8.1852e-19 -1.31934e-10 -1.5142e-08 -5.43652e-08 1 8.1852e-19 -1.31934e-10 -1.5142e-08 -5.43652e-08 1 -1.31934e-10 -1.5142e-08 -5.43652e-08 4032.18 -11.3099 -362.97 3993.76 33.0139 3900.59 +EDGE_SE3:QUAT 1105 1155 -0.171016 0.313183 -6.56195 -0.062239 0.145904 0.019375 0.987149 1 3.00927e-21 3.00927e-21 5.33635e-10 -2.14508e-10 3.57987e-09 1 3.00927e-21 5.33635e-10 -2.14508e-10 3.57987e-09 1 5.33635e-10 -2.14508e-10 3.57987e-09 4353.3 -37.5458 1269.32 3914.65 -20.6591 4367.29 +EDGE_SE3:QUAT 1104 1155 -0.85659 12.3885 -6.32017 -0.00361664 -0.011071 0.0666431 0.997709 1 3.76158e-21 3.76158e-21 -1.4996e-09 -3.57727e-09 6.55363e-13 1 3.76158e-21 -1.4996e-09 -3.57727e-09 6.55363e-13 1 -1.4996e-09 -3.57727e-09 6.55363e-13 4001.76 0.336781 -85.1262 3999.57 -2.81134 3984.05 +EDGE_SE3:QUAT 1105 1154 -0.678247 -12.4219 -6.08643 -0.0211021 0.0917117 -0.184038 0.978404 1 4.81482e-20 4.81482e-20 1.37653e-08 -2.68343e-09 1.09069e-09 1 4.81482e-20 1.37653e-08 -2.68343e-09 1.09069e-09 1 1.37653e-08 -2.68343e-09 1.09069e-09 4105.3 -39.6864 664.404 3980.78 -67.1378 3971.6 +EDGE_SE3:QUAT 1106 1156 -0.331549 0.223577 -5.95949 -0.158297 -0.00922181 0.10775 0.981451 1 7.73381e-19 7.73381e-19 5.48688e-08 2.43607e-09 8.41307e-10 1 7.73381e-19 5.48688e-08 2.43607e-09 8.41307e-10 1 5.48688e-08 2.43607e-09 8.41307e-10 3902.91 -15.5193 130.008 3997.55 10.3424 3956.7 +EDGE_SE3:QUAT 1105 1156 -1.22942 12.7534 -6.42134 -0.0148827 -0.0374424 0.158714 0.986502 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.03 6.24882 -261.167 3996.7 -20.3445 3916.15 +EDGE_SE3:QUAT 1106 1155 -1.19706 -12.6653 -6.12748 -0.067419 -0.0499201 -0.0148682 0.996364 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.88 13.4443 -412.335 3989.59 -1.06984 4041.18 +EDGE_SE3:QUAT 1107 1157 -0.543791 -0.21701 -6.03959 -0.0878143 0.0380376 0.0804579 0.992153 1 1.92593e-19 1.92593e-19 -2.76653e-08 -2.03106e-09 -1.42331e-09 1 1.92593e-19 -2.76653e-08 -2.03106e-09 -1.42331e-09 1 -2.76653e-08 -2.03106e-09 -1.42331e-09 4005.8 -14.3247 385.313 3989.95 12.4086 4010.75 +EDGE_SE3:QUAT 1106 1157 -1.07565 12.8378 -6.24027 0.102783 0.0306474 0.123901 0.986481 1 7.70372e-19 7.70372e-19 2.15409e-10 5.95362e-09 5.47682e-08 1 7.70372e-19 2.15409e-10 5.95362e-09 5.47682e-08 1 2.15409e-10 5.95362e-09 5.47682e-08 3958.81 2.28173 85.3254 4000.08 2.49982 3939.67 +EDGE_SE3:QUAT 1107 1156 -1.03162 -12.4426 -6.01303 -0.0942789 -0.0791683 0.0313598 0.991897 1 1.92593e-19 1.92593e-19 -2.78344e-08 -1.2955e-09 2.00955e-09 1 1.92593e-19 -2.78344e-08 -1.2955e-09 2.00955e-09 1 -2.78344e-08 -1.2955e-09 2.00955e-09 4052.24 33.6238 -599.344 3980.65 -22.803 4083.86 +EDGE_SE3:QUAT 1108 1158 -0.409568 -0.0360325 -6.22183 0.0946477 0.0243344 0.0728899 0.992541 1 1.92593e-19 1.92593e-19 -2.75557e-10 -2.70003e-09 -2.7558e-08 1 1.92593e-19 -2.75557e-10 -2.70003e-09 -2.7558e-08 1 -2.75557e-10 -2.70003e-09 -2.7558e-08 3966.89 4.22373 108.492 3999.68 3.48797 3981.47 +EDGE_SE3:QUAT 1107 1158 -1.02164 12.5558 -6.34093 0.228801 -0.0055368 0.0807747 0.9701 1 7.70372e-19 7.70372e-19 5.39595e-08 3.88684e-09 -2.2668e-09 1 7.70372e-19 5.39595e-08 3.88684e-09 -2.2668e-09 1 5.39595e-08 3.88684e-09 -2.2668e-09 3805.75 -36.2071 -254.546 3993.85 -9.44187 3989.05 +EDGE_SE3:QUAT 1108 1157 -0.949792 -12.359 -6.03801 -0.0401199 -0.0111565 -0.0848141 0.995526 1 1.92593e-19 1.92593e-19 4.92585e-10 1.04612e-09 -2.76457e-08 1 1.92593e-19 4.92585e-10 1.04612e-09 -2.76457e-08 1 4.92585e-10 1.04612e-09 -2.76457e-08 3997.67 2.39473 -128.805 3998.77 5.81678 3975.33 +EDGE_SE3:QUAT 1109 1159 -0.160224 0.0614772 -6.24262 0.0142397 -0.0794245 0.0020862 0.996737 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4102.12 -4.60975 -649.854 3974.77 1.50115 4102.91 +EDGE_SE3:QUAT 1108 1159 -1.27706 12.4394 -6.20877 -0.0836765 0.00687998 -0.0476181 0.995331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3971.94 0.389998 6.75498 4000 0.216079 3990.88 +EDGE_SE3:QUAT 1109 1158 -1.11804 -12.1737 -6.05551 -0.039135 -0.0672887 -0.0216224 0.996731 1 4.81482e-20 4.81482e-20 1.39632e-08 -2.30555e-10 -9.62801e-10 1 4.81482e-20 1.39632e-08 -2.30555e-10 -9.62801e-10 1 1.39632e-08 -2.30555e-10 -9.62801e-10 4069.73 9.00049 -556.028 3981.22 1.87197 4073.98 +EDGE_SE3:QUAT 1110 1160 -0.578507 0.0293399 -6.56387 -0.112821 -0.010135 0.0365465 0.992891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3949.24 0.773466 -30.3537 4000 -0.315126 3994.81 +EDGE_SE3:QUAT 1109 1160 -1.25461 12.7261 -6.26984 -0.0407898 0.12304 0.045438 0.990522 1 4.81482e-20 4.81482e-20 -1.41928e-08 -5.22496e-10 -1.80454e-09 1 4.81482e-20 -1.41928e-08 -5.22496e-10 -1.80454e-09 1 -1.41928e-08 -5.22496e-10 -1.80454e-09 4256.6 -6.93896 1059.41 3937.1 11.6987 4255 +EDGE_SE3:QUAT 1110 1159 -1.15445 -12.4508 -6.09947 -0.0786923 0.0561183 0.00539089 0.995304 1 8.18532e-19 8.18532e-19 -5.55436e-08 1.39905e-08 -1.83572e-09 1 8.18532e-19 -5.55436e-08 1.39905e-08 -1.83572e-09 1 -5.55436e-08 1.39905e-08 -1.83572e-09 4026.31 -18.0926 454.884 3987.65 -4.80995 4050.96 +EDGE_SE3:QUAT 1111 1161 -0.404643 -0.00863994 -6.15196 0.124877 0.0190644 0.188528 0.973909 1 1.54074e-18 1.54074e-18 -5.24823e-08 -1.7226e-08 -5.24823e-08 1 1.54074e-18 -5.24823e-08 -1.7226e-08 -5.24823e-08 1 -5.24823e-08 -1.7226e-08 -5.24823e-08 3939.85 -14.0787 -131.982 3996.71 -21.4992 3860.06 +EDGE_SE3:QUAT 1110 1161 -1.08638 12.7408 -6.42841 -0.204959 0.0501845 0.165426 0.963383 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.77 -66.9544 777.924 3957.38 40.8592 4034.34 +EDGE_SE3:QUAT 1111 1160 -1.25118 -12.5077 -6.4653 -0.018031 -0.0646311 0.159705 0.984882 1 1.20371e-20 1.20371e-20 6.88114e-09 1.14023e-09 -3.87925e-10 1 1.20371e-20 6.88114e-09 1.14023e-09 -3.87925e-10 1 6.88114e-09 1.14023e-09 -3.87925e-10 4052.61 18.1288 -468.136 3989.36 -38.9741 3951.89 +EDGE_SE3:QUAT 1112 1162 -0.260996 0.270267 -6.4075 -0.00248748 -0.00710608 -0.126613 0.991924 1 4.70198e-23 4.70198e-23 -4.30226e-10 5.49057e-11 3.25429e-12 1 4.70198e-23 -4.30226e-10 5.49057e-11 3.25429e-12 1 -4.30226e-10 5.49057e-11 3.25429e-12 4000.85 -0.0902647 -59.2374 3999.79 3.79955 3936.75 +EDGE_SE3:QUAT 1111 1162 -1.04475 12.5876 -6.66181 -0.181585 -0.00706676 -0.0922003 0.979018 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3882.72 27.2209 -249.378 3994.17 11.6287 3980.61 +EDGE_SE3:QUAT 1112 1161 -1.10358 -12.5025 -6.39311 -0.0111445 -0.02369 -0.155379 0.987508 1 7.70372e-19 7.70372e-19 1.44325e-09 1.8568e-10 -5.48902e-08 1 7.70372e-19 1.44325e-09 1.8568e-10 -5.48902e-08 1 1.44325e-09 1.8568e-10 -5.48902e-08 4009.84 -1.20236 -203.596 3997.55 16.1081 3913.76 +EDGE_SE3:QUAT 1113 1163 -0.405068 0.145036 -6.46218 -0.0969587 -0.119271 -0.180618 0.971468 1 1.92593e-19 1.92593e-19 -2.80787e-08 4.62434e-09 4.17985e-09 1 1.92593e-19 -2.80787e-08 4.62434e-09 4.17985e-09 1 -2.80787e-08 4.62434e-09 4.17985e-09 4287.52 -16.3432 -1186.28 3924.43 85.2405 4194.63 +EDGE_SE3:QUAT 1112 1163 -1.20096 12.5856 -6.60806 0.225872 -0.0409335 -0.108573 0.967222 1 7.70372e-19 7.70372e-19 5.36719e-08 -6.41071e-09 6.54793e-10 1 7.70372e-19 5.36719e-08 -6.41071e-09 6.54793e-10 1 5.36719e-08 -6.41071e-09 6.54793e-10 3793.18 10.4158 -14.6118 3999.68 -4.64332 3950.1 +EDGE_SE3:QUAT 1113 1162 -0.893788 -12.226 -5.73225 -0.0609678 -0.0447054 -0.120814 0.989792 1 2.88889e-19 2.88889e-19 -1.38049e-08 -1.07786e-08 -2.75092e-08 1 2.88889e-19 -1.38049e-08 -1.07786e-08 -2.75092e-08 1 -1.38049e-08 -1.07786e-08 -2.75092e-08 4032.9 6.47655 -440.305 3987.32 24.8158 3989.39 +EDGE_SE3:QUAT 1114 1164 -0.00772457 0.167814 -6.34367 0.0294692 0.0170971 -0.0554803 0.997878 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.57 1.91724 155.759 3998.38 -4.25617 3993.73 +EDGE_SE3:QUAT 1113 1164 -1.33456 12.4547 -6.24893 -0.0736929 -0.198847 0.0361373 0.976588 1 4.81482e-20 4.81482e-20 2.85019e-09 1.42371e-09 -1.46447e-08 1 4.81482e-20 2.85019e-09 1.42371e-09 -1.46447e-08 1 2.85019e-09 1.42371e-09 -1.46447e-08 4642.43 130.999 -1760.22 3865.55 -125.51 4658.93 +EDGE_SE3:QUAT 1114 1163 -0.827459 -12.3104 -6.46714 -0.000210956 -0.000188617 -0.165402 0.986226 1 7.34684e-25 7.34684e-25 5.34634e-11 -8.96648e-12 -1.33964e-14 1 7.34684e-25 5.34634e-11 -8.96648e-12 -1.33964e-14 1 5.34634e-11 -8.96648e-12 -1.33964e-14 4000 8.91561e-06 -1.85851 4000 0.163497 3890.57 +EDGE_SE3:QUAT 1115 1165 -0.350262 0.0122374 -6.29478 -0.196274 0.0580024 -0.160964 0.965506 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3841.8 7.34499 55.4793 4000.2 5.56811 3892.26 +EDGE_SE3:QUAT 1114 1165 -1.13339 12.5967 -6.12569 0.132579 -0.0325117 0.232934 0.962864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.56 -24.0539 -599.283 3972.75 -71.5835 3868.83 +EDGE_SE3:QUAT 1115 1164 -1.30651 -12.5424 -6.21633 -0.0364499 -0.0138193 -0.0440208 0.99827 1 4.81482e-20 4.81482e-20 1.3861e-08 -5.95897e-10 -2.35137e-10 1 4.81482e-20 1.3861e-08 -5.95897e-10 -2.35137e-10 1 1.3861e-08 -5.95897e-10 -2.35137e-10 3998.86 2.21797 -129.356 3998.86 2.77699 3996.42 +EDGE_SE3:QUAT 1116 1166 -0.171643 0.152262 -6.24178 -0.0903929 0.005355 -0.0463553 0.994812 1 4.81482e-20 4.81482e-20 4.29205e-11 1.25592e-09 -1.38057e-08 1 4.81482e-20 4.29205e-11 1.25592e-09 -1.38057e-08 1 4.29205e-11 1.25592e-09 -1.38057e-08 3967.26 1.1186 -7.75868 3999.96 0.574145 3991.35 +EDGE_SE3:QUAT 1115 1166 -1.5475 12.9655 -6.49023 -0.110143 0.0324671 0.142763 0.983073 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.04 -19.2757 437.117 3985.87 29.4784 3965.04 +EDGE_SE3:QUAT 1116 1165 -1.05858 -12.5254 -6.26974 -0.0326868 0.0337114 -0.153315 0.987061 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.63 -5.64292 200.923 3998.37 -14.3191 3915.88 +EDGE_SE3:QUAT 1117 1167 -0.28472 0.0613876 -6.15149 -0.0743411 0.0847424 0.0387673 0.992869 1 4.81482e-20 4.81482e-20 1.2602e-09 -9.67358e-10 1.39982e-08 1 4.81482e-20 1.2602e-09 -9.67358e-10 1.39982e-08 1 1.2602e-09 -9.67358e-10 1.39982e-08 4105.42 -22.0639 725.558 3968.69 1.15613 4121.52 +EDGE_SE3:QUAT 1116 1167 -0.962075 12.3526 -6.59574 -0.150068 0.0186194 -0.0738062 0.985741 1 1.92593e-19 1.92593e-19 1.18568e-10 4.19592e-09 -2.73581e-08 1 1.92593e-19 1.18568e-10 4.19592e-09 -2.73581e-08 1 1.18568e-10 4.19592e-09 -2.73581e-08 3909.43 2.51969 12.2656 3999.95 1.17248 3977.72 +EDGE_SE3:QUAT 1117 1166 -1.07543 -12.6585 -5.85385 -0.100963 -0.152577 0.00421248 0.983112 1 1.20371e-20 1.20371e-20 -1.07851e-09 -7.79031e-10 7.14435e-09 1 1.20371e-20 -1.07851e-09 -7.79031e-10 7.14435e-09 1 -1.07851e-09 -7.79031e-10 7.14435e-09 4342.21 83.7315 -1295.71 3917.04 -64.8781 4382.92 +EDGE_SE3:QUAT 1118 1168 -0.246636 0.0562827 -6.11735 -0.051566 0.130894 0.00893021 0.990014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4279.07 -30.0213 1114.78 3932 -17.2649 4289.38 +EDGE_SE3:QUAT 1117 1168 -1.18264 12.6081 -6.48012 -0.074814 -0.0878434 0.289275 0.950266 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.05 31.2283 -364.075 4002.82 -43.0945 3693.72 +EDGE_SE3:QUAT 1118 1167 -1.23846 -12.6863 -6.13152 -0.0319871 0.0547016 -0.25867 0.963885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.38 -14.9812 299.551 3998.42 -34.6313 3753.84 +EDGE_SE3:QUAT 1119 1169 -0.82283 0.268476 -6.2285 0.15972 -0.040836 -0.00868252 0.986279 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3920.17 -23.8057 -299.216 3995.46 6.92771 4021.91 +EDGE_SE3:QUAT 1118 1169 -1.20456 12.3869 -6.5323 -0.0529746 0.0327049 -0.14967 0.986774 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.69 -5.14383 158.25 3999.31 -9.95111 3916.31 +EDGE_SE3:QUAT 1119 1168 -1.309 -12.2619 -6.32413 -0.0478295 0.116985 0.014598 0.991874 1 1.92593e-19 1.92593e-19 -9.79489e-11 2.75328e-08 1.26798e-09 1 1.92593e-19 -9.79489e-11 2.75328e-08 1.26798e-09 1 -9.79489e-11 2.75328e-08 1.26798e-09 4221.76 -21.9675 988.411 3944.94 -8.69045 4230.06 +EDGE_SE3:QUAT 1120 1170 -0.352675 0.241386 -6.18825 -0.0941746 -0.135577 0.0283948 0.985872 1 9.62965e-19 9.62965e-19 3.13737e-08 -5.3083e-08 -9.50127e-09 1 9.62965e-19 3.13737e-08 -5.3083e-08 -9.50127e-09 1 3.13737e-08 -5.3083e-08 -9.50127e-09 4246.25 73.4513 -1098.55 3939.5 -60.5852 4278.5 +EDGE_SE3:QUAT 1119 1170 -0.81465 12.6256 -6.41257 -0.106126 0.0118324 -0.0196202 0.994089 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3956.09 -3.19308 68.2266 3999.8 -0.802064 3999.6 +EDGE_SE3:QUAT 1120 1169 -1.21228 -12.5525 -6.34369 -0.140395 -0.00129759 -0.100455 0.984985 1 9.65974e-19 9.65974e-19 -5.42552e-08 5.73742e-09 -2.62287e-08 1 9.65974e-19 -5.42552e-08 5.73742e-09 -2.62287e-08 1 -5.42552e-08 5.73742e-09 -2.62287e-08 3928.2 15.6003 -176.118 3996.74 10.6613 3966.68 +EDGE_SE3:QUAT 1121 1171 -0.471856 -0.235289 -5.79818 -0.107519 -0.112331 0.0778236 0.984766 1 1.92593e-19 1.92593e-19 2.78603e-08 2.89125e-09 -2.57976e-09 1 1.92593e-19 2.78603e-08 2.89125e-09 -2.57976e-09 1 2.78603e-08 2.89125e-09 -2.57976e-09 4106.4 65.3857 -797.803 3971.48 -60.3598 4128.41 +EDGE_SE3:QUAT 1120 1171 -1.18054 12.4582 -6.59207 0.0571187 -0.167256 0.0926959 0.979883 1 1.01111e-18 1.01111e-18 -1.36478e-08 5.25085e-08 -2.7884e-08 1 1.01111e-18 -1.36478e-08 5.25085e-08 -2.7884e-08 1 -1.36478e-08 5.25085e-08 -2.7884e-08 4510.67 17.9796 -1539.24 3881.58 -47.6086 4489.35 +EDGE_SE3:QUAT 1121 1170 -0.853408 -12.4399 -6.10545 0.117858 -0.0986617 -0.083658 0.984569 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4049.64 -54.3368 -659.639 3981.57 49.0838 4077.21 +EDGE_SE3:QUAT 1122 1172 -0.840124 -0.0815425 -6.41878 -0.0970128 -0.00326116 0.0986895 0.990373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3963.95 -6.00247 88.112 3999.01 6.11109 3962.63 +EDGE_SE3:QUAT 1121 1172 -1.56951 12.7859 -6.14378 -0.0563376 -0.0272972 0.180663 0.981551 1 1.92593e-19 1.92593e-19 -2.72484e-08 -5.07198e-09 1.47841e-10 1 1.92593e-19 -2.72484e-08 -5.07198e-09 1.47841e-10 1 -2.72484e-08 -5.07198e-09 1.47841e-10 3988.69 2.12215 -87.4019 4000.05 -4.16406 3870.83 +EDGE_SE3:QUAT 1122 1171 -1.05452 -12.3397 -5.97017 -0.0403944 -0.122577 -0.053128 0.990212 1 4.81482e-20 4.81482e-20 1.41876e-08 -6.3773e-10 -1.8039e-09 1 4.81482e-20 1.41876e-08 -6.3773e-10 -1.8039e-09 1 1.41876e-08 -6.3773e-10 -1.8039e-09 4256.11 3.63103 -1058.08 3937.26 16.6447 4251.34 +EDGE_SE3:QUAT 1123 1173 -0.142673 -0.0323794 -6.69122 -0.131665 0.197962 0.173804 0.95565 1 1.92593e-19 1.92593e-19 -2.95011e-08 -3.99222e-09 -7.01782e-09 1 1.92593e-19 -2.95011e-08 -3.99222e-09 -7.01782e-09 1 -2.95011e-08 -3.99222e-09 -7.01782e-09 4842.52 38.5422 2116.62 3808.76 91.4305 4791.03 +EDGE_SE3:QUAT 1122 1173 -1.14356 12.3988 -6.38994 -0.0425371 0.0452325 0.0833405 0.994585 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.97 -4.1923 403.182 3989.66 15.2571 4012.42 +EDGE_SE3:QUAT 1123 1172 -1.44526 -12.6634 -5.82185 0.051261 0.13287 -0.17349 0.974484 1 1.20371e-20 1.20371e-20 7.04636e-09 -1.19707e-09 1.02808e-09 1 1.20371e-20 7.04636e-09 -1.19707e-09 1.02808e-09 1 7.04636e-09 -1.19707e-09 1.02808e-09 4322.6 -51.585 1201.42 3928.04 -101.147 4212.71 +EDGE_SE3:QUAT 1124 1174 -0.328591 -0.2982 -6.05816 0.0649073 -0.0992781 -0.19207 0.974187 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4071.84 -50.119 -607.638 3988.77 67.0034 3941.12 +EDGE_SE3:QUAT 1123 1174 -1.23655 12.5867 -6.67678 0.0478102 0.0681208 0.165327 0.982721 1 9.62965e-20 9.62965e-20 1.13282e-08 1.60279e-08 -2.66603e-10 1 9.62965e-20 1.13282e-08 1.60279e-08 -2.66603e-10 1 1.13282e-08 1.60279e-08 -2.66603e-10 4036.23 22.8315 430.975 3992.62 37.468 3936.04 +EDGE_SE3:QUAT 1124 1173 -1.34247 -12.3369 -6.35638 0.117079 0.0423075 -0.134001 0.983131 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.91 23.0226 515.397 3981.3 -29.4649 3992.92 +EDGE_SE3:QUAT 1125 1175 -0.507681 0.153493 -6.28244 -0.117902 0.0175465 0.0266545 0.992512 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3952.01 -10.7582 174.981 3997.93 1.24988 4004.77 +EDGE_SE3:QUAT 1124 1175 -0.857116 12.476 -6.13278 0.0149981 0.170878 0.107021 0.979348 1 1.92593e-19 1.92593e-19 -4.79466e-09 -1.57388e-09 -2.87717e-08 1 1.92593e-19 -4.79466e-09 -1.57388e-09 -2.87717e-08 1 -4.79466e-09 -1.57388e-09 -2.87717e-08 4473.98 96.5085 1457.96 3902.12 112.775 4429.06 +EDGE_SE3:QUAT 1125 1174 -0.888716 -12.1681 -5.87788 0.0537206 0.124582 -0.0600408 0.988933 1 4.81482e-20 4.81482e-20 1.41946e-08 -6.8876e-10 1.86029e-09 1 4.81482e-20 1.41946e-08 -6.8876e-10 1.86029e-09 1 1.41946e-08 -6.8876e-10 1.86029e-09 4265.81 9.09298 1089.21 3933.78 -15.8416 4262.93 +EDGE_SE3:QUAT 1126 1176 -0.219488 0.00556362 -6.13997 0.215602 0.1316 -0.00570458 0.967556 1 7.70372e-19 7.70372e-19 5.55011e-08 2.95607e-09 6.96521e-09 1 7.70372e-19 5.55011e-08 2.95607e-09 6.96521e-09 1 5.55011e-08 2.95607e-09 6.96521e-09 4072.11 129.161 1049.22 3955.84 87.3515 4257.92 +EDGE_SE3:QUAT 1125 1176 -1.40508 12.316 -6.37343 0.00820255 -0.0664578 0.170079 0.983153 1 1.88079e-22 1.88079e-22 -8.60382e-10 -1.49229e-10 5.71892e-11 1 1.88079e-22 -8.60382e-10 -1.49229e-10 5.71892e-11 1 -8.60382e-10 -1.49229e-10 5.71892e-11 4069.56 16.0533 -533.21 3985.04 -46.4193 3954.13 +EDGE_SE3:QUAT 1126 1175 -1.22745 -12.7946 -6.25409 -0.135991 -0.147521 -0.0436848 0.978691 1 7.82409e-19 7.82409e-19 -5.59008e-08 1.10813e-09 1.82571e-09 1 7.82409e-19 -5.59008e-08 1.10813e-09 1.82571e-09 1 -5.59008e-08 1.10813e-09 1.82571e-09 4324.48 85.9937 -1323.85 3911.95 -48.1709 4390.82 +EDGE_SE3:QUAT 1127 1177 -0.384998 -0.213134 -6.61261 -0.0263722 0.0886977 -0.0217605 0.995472 1 1.92593e-19 1.92593e-19 -7.43934e-10 -2.76265e-08 -8.51141e-10 1 1.92593e-19 -7.43934e-10 -2.76265e-08 -8.51141e-10 1 -7.43934e-10 -2.76265e-08 -8.51141e-10 4123.06 -14.4383 720.568 3969.72 -13.535 4123.95 +EDGE_SE3:QUAT 1126 1177 -1.2875 12.5704 -6.3217 -0.0457306 0.0138354 0.0134223 0.998768 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.1 -2.68359 117.754 3999.11 0.575912 4002.74 +EDGE_SE3:QUAT 1127 1176 -1.29567 -12.5062 -6.20037 -0.0884609 0.0961263 -0.241581 0.961547 1 3.85186e-19 3.85186e-19 1.9725e-08 -3.37785e-08 -2.29511e-09 1 3.85186e-19 1.9725e-08 -3.37785e-08 -2.29511e-09 1 1.9725e-08 -3.37785e-08 -2.29511e-09 4014.2 -41.0095 447.535 4000 -52.7127 3812.05 +EDGE_SE3:QUAT 1128 1178 -0.14969 0.100462 -6.18207 0.176268 0.0366737 -0.130488 0.974965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3948.81 45.5079 550.295 3977.54 -26.297 4004.98 +EDGE_SE3:QUAT 1127 1178 -1.32946 12.6453 -6.23302 0.0152826 0.0971346 0.0647186 0.993047 1 1.92593e-19 1.92593e-19 -1.91248e-09 2.75548e-08 -7.81544e-10 1 1.92593e-19 -1.91248e-09 2.75548e-08 -7.81544e-10 1 -1.91248e-09 2.75548e-08 -7.81544e-10 4147.34 21.3661 784.312 3965.34 31.1798 4131.52 +EDGE_SE3:QUAT 1128 1177 -0.843917 -12.4894 -6.29514 0.0826514 0.0998247 -0.101278 0.986381 1 1.92593e-19 1.92593e-19 -2.8067e-08 2.43189e-09 -3.22642e-09 1 1.92593e-19 -2.8067e-08 2.43189e-09 -3.22642e-09 1 -2.8067e-08 2.43189e-09 -3.22642e-09 4173.61 13.5454 919.004 3950.57 -28.9343 4159.91 +EDGE_SE3:QUAT 1129 1179 -0.600137 0.150675 -6.4778 0.0739701 -0.0741168 0.00344324 0.994496 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4066.92 -23.0947 -602.593 3978.71 8.89889 4088.76 +EDGE_SE3:QUAT 1128 1179 -1.00799 12.3098 -6.18633 -0.0341743 0.00410776 0.131204 0.990758 1 4.81482e-20 4.81482e-20 1.37526e-08 1.81323e-09 1.78261e-10 1 4.81482e-20 1.37526e-08 1.81323e-09 1.78261e-10 1 1.37526e-08 1.81323e-09 1.78261e-10 3997.07 -1.48947 85.1459 3999.36 6.67614 3932.88 +EDGE_SE3:QUAT 1129 1178 -1.01885 -12.3449 -6.05544 -0.0321563 0.0308895 -0.0831195 0.995542 1 4.81482e-20 4.81482e-20 1.38355e-08 -1.1823e-09 3.48293e-10 1 4.81482e-20 1.38355e-08 -1.1823e-09 3.48293e-10 1 1.38355e-08 -1.1823e-09 3.48293e-10 4007.1 -4.77985 212.714 3997.6 -9.01709 3983.61 +EDGE_SE3:QUAT 1130 1180 -0.692804 -0.0251611 -5.997 0.141087 0.042061 0.109684 0.983003 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3923.97 6.43015 138.294 4000.07 5.69058 3955.47 +EDGE_SE3:QUAT 1129 1180 -1.45125 12.4278 -6.59171 -0.0408007 -0.147897 0.0255474 0.987831 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4355.95 46.0646 -1257.76 3917.49 -43.01 4359.99 +EDGE_SE3:QUAT 1130 1179 -1.38912 -12.6362 -5.89114 -0.0229496 -0.0963029 -0.00718908 0.995061 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4151.07 8.37897 -797.595 3962.8 -2.21089 4152.97 +EDGE_SE3:QUAT 1131 1181 -0.293103 -0.0326827 -6.09237 -0.154911 -0.204844 -0.117914 0.959238 1 1.92593e-19 1.92593e-19 -7.05087e-09 -3.54858e-09 2.96527e-08 1 1.92593e-19 -7.05087e-09 -3.54858e-09 2.96527e-08 1 -7.05087e-09 -3.54858e-09 2.96527e-08 4836.58 80.2466 -2144.91 3804.48 -36.7807 4876.95 +EDGE_SE3:QUAT 1130 1181 -1.46219 12.3794 -6.1772 0.150247 0.0714131 0.0336916 0.98549 1 7.70372e-19 7.70372e-19 5.51286e-08 3.01114e-09 3.2372e-09 1 7.70372e-19 5.51286e-08 3.01114e-09 3.2372e-09 1 5.51286e-08 3.01114e-09 3.2372e-09 3970.23 40.3772 496.87 3988.52 23.3182 4055.98 +EDGE_SE3:QUAT 1131 1180 -1.1636 -12.466 -6.20427 -0.016144 -0.186468 -0.0757039 0.979407 1 7.52316e-22 7.52316e-22 1.82709e-09 -1.39949e-10 -3.48351e-10 1 7.52316e-22 1.82709e-09 -1.39949e-10 -3.48351e-10 1 1.82709e-09 -1.39949e-10 -3.48351e-10 4621.12 -56.8137 -1695.8 3864.13 72.5033 4599.23 +EDGE_SE3:QUAT 1132 1182 -0.491059 -0.134198 -6.22522 -0.0542507 0.0104919 0.0891041 0.994488 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3993.06 -3.77959 140.334 3998.46 6.77394 3973.08 +EDGE_SE3:QUAT 1131 1182 -1.23327 12.5568 -6.60351 -0.0390683 -0.120078 0.0694267 0.989563 1 3.85186e-19 3.85186e-19 -2.59734e-08 -2.97451e-08 1.64411e-09 1 3.85186e-19 -2.59734e-08 -2.97451e-08 1.64411e-09 1 -2.59734e-08 -2.97451e-08 1.64411e-09 4212.91 45.2568 -961.441 3951.32 -51.2839 4199.74 +EDGE_SE3:QUAT 1132 1181 -1.36952 -12.2131 -5.84176 0.120859 0.0249503 -0.017314 0.992205 1 1.95602e-19 1.95602e-19 -2.7483e-08 7.18592e-10 2.65917e-09 1 1.95602e-19 -2.7483e-08 7.18592e-10 2.65917e-09 1 -2.7483e-08 7.18592e-10 2.65917e-09 3953.7 13.5436 220.646 3996.95 0.144876 4010.93 +EDGE_SE3:QUAT 1133 1183 -0.620685 -0.117699 -6.40101 -0.152675 -0.0762457 -0.0296339 0.984885 1 7.82409e-19 7.82409e-19 -5.48292e-08 1.35652e-09 -2.33575e-09 1 7.82409e-19 -5.48292e-08 1.35652e-09 -2.33575e-09 1 -5.48292e-08 1.35652e-09 -2.33575e-09 4011.88 49.6516 -656.912 3975.69 -13.5605 4101.61 +EDGE_SE3:QUAT 1132 1183 -0.952854 12.7638 -6.01626 0.0212874 0.0289108 0.0250584 0.999041 1 1.20371e-20 1.20371e-20 6.94319e-09 1.8284e-10 1.93065e-10 1 1.20371e-20 6.94319e-09 1.8284e-10 1.93065e-10 1 6.94319e-09 1.8284e-10 1.93065e-10 4010.82 2.8745 225.12 3996.93 3.22575 4010.12 +EDGE_SE3:QUAT 1133 1182 -1.12323 -12.4374 -5.92547 0.114643 -0.0696188 0.026743 0.990603 1 1.20371e-20 1.20371e-20 -5.17902e-10 7.85052e-10 6.9483e-09 1 1.20371e-20 -5.17902e-10 7.85052e-10 6.9483e-09 1 -5.17902e-10 7.85052e-10 6.9483e-09 4033.56 -32.9091 -593.281 3979.25 6.28666 4083.27 +EDGE_SE3:QUAT 1134 1184 -0.64569 -0.226577 -6.22061 0.0720017 0.0898442 0.0320244 0.992833 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4098.73 32.8728 701.669 3972.82 25.4016 4115.36 +EDGE_SE3:QUAT 1133 1184 -0.987427 12.5341 -6.49687 -0.0193064 0.0570077 0.109846 0.992125 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4055.04 4.437 478.869 3986.33 25.9338 4008.26 +EDGE_SE3:QUAT 1134 1183 -1.27348 -12.3091 -6.26669 0.0968603 -0.0350921 -0.199142 0.97454 1 3.00927e-21 3.00927e-21 7.01245e-10 3.37899e-09 -3.56813e-10 1 3.00927e-21 7.01245e-10 3.37899e-09 -3.56813e-10 1 7.01245e-10 3.37899e-09 -3.56813e-10 3961.07 1.78391 -36.088 4000.04 -4.5266 3839.97 +EDGE_SE3:QUAT 1135 1185 -0.507486 -0.112606 -6.3542 0.00145239 -0.201922 0.20647 0.95739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4636.31 223.633 -1719.29 3906.21 -249.712 4465.8 +EDGE_SE3:QUAT 1134 1185 -1.09867 12.5648 -6.21164 -0.00188189 0.110799 0.0889644 0.989851 1 1.95602e-19 1.95602e-19 -1.00032e-09 -2.77921e-08 1.137e-10 1 1.95602e-19 -1.00032e-09 -2.77921e-08 1.137e-10 1 -1.00032e-09 -2.77921e-08 1.137e-10 4199.79 26.5397 916.057 3953.93 45.3406 4168.14 +EDGE_SE3:QUAT 1135 1184 -1.11259 -12.3764 -6.08768 -0.1829 0.0182544 -0.0690289 0.980535 1 7.71124e-19 7.71124e-19 -5.43029e-08 5.64012e-09 7.57829e-10 1 7.71124e-19 -5.43029e-08 5.64012e-09 7.57829e-10 1 -5.43029e-08 5.64012e-09 7.57829e-10 3865.54 5.78198 -9.94221 3999.77 2.16612 3980.29 +EDGE_SE3:QUAT 1136 1186 -0.506283 -0.0836625 -6.22897 0.0315656 -0.144798 -0.220055 0.964164 1 7.70372e-19 7.70372e-19 6.62954e-09 -5.37147e-09 -5.52809e-08 1 7.70372e-19 6.62954e-09 -5.37147e-09 -5.52809e-08 1 6.62954e-09 -5.37147e-09 -5.52809e-08 4248.46 -115.133 -1039.87 3966.6 144.522 4058.75 +EDGE_SE3:QUAT 1135 1186 -1.27497 12.316 -6.48441 -0.0432 0.0854647 0.0805956 0.992136 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4124.41 -1.60391 738.204 3967.6 24.1317 4105.89 +EDGE_SE3:QUAT 1136 1185 -1.37119 -11.9119 -6.2919 -0.295766 0.0775665 -0.217043 0.927038 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3642.86 75.5348 -203.609 3984.12 55.8427 3804.34 +EDGE_SE3:QUAT 1137 1187 -0.643224 0.00049233 -6.05756 -0.0777051 -0.196952 -0.000310869 0.977329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4662.27 98.5318 -1793.59 3854.59 -86.4426 4686.42 +EDGE_SE3:QUAT 1136 1187 -1.23311 12.3036 -6.2778 0.218483 -0.079002 -0.0343196 0.972032 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3870.77 -56.6729 -504.093 3991.66 32.0999 4057 +EDGE_SE3:QUAT 1137 1186 -1.52905 -12.2723 -6.44317 -0.202676 0.00579082 -0.00925068 0.979185 1 1.88079e-22 1.88079e-22 9.35837e-12 8.49294e-10 1.7586e-10 1 1.88079e-22 9.35837e-12 8.49294e-10 1.7586e-10 1 9.35837e-12 8.49294e-10 1.7586e-10 3835.79 -1.33419 21.6134 4000 -0.116629 3999.76 +EDGE_SE3:QUAT 1138 1188 -0.779524 -0.089837 -6.84592 0.174265 0.0231804 0.135004 0.975125 1 7.70372e-19 7.70372e-19 -1.38667e-09 9.65985e-09 5.41329e-08 1 7.70372e-19 -1.38667e-09 9.65985e-09 5.41329e-08 1 -1.38667e-09 9.65985e-09 5.41329e-08 3878.89 -17.3859 -101.13 3997.5 -13.4552 3927.46 +EDGE_SE3:QUAT 1137 1188 -1.1499 12.3919 -6.64408 -0.0579732 -0.0509415 -0.0370754 0.996328 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.29 10.6421 -434.941 3988.17 4.44288 4041.24 +EDGE_SE3:QUAT 1138 1187 -1.16318 -12.3543 -5.55568 0.0938413 -0.110265 0.0154108 0.989342 1 1.93345e-19 1.93345e-19 2.83572e-08 -3.20621e-10 -4.92476e-09 1 1.93345e-19 2.83572e-08 -3.20621e-10 -4.92476e-09 1 2.83572e-08 -3.20621e-10 -4.92476e-09 4169.37 -44.4786 -927.491 3952.31 21.4163 4203.64 +EDGE_SE3:QUAT 1139 1189 -0.468356 -0.0519991 -6.04496 -0.129184 -0.0238303 -0.0665057 0.989101 1 7.70372e-19 7.70372e-19 5.50488e-08 -3.24395e-09 -2.21811e-09 1 7.70372e-19 5.50488e-08 -3.24395e-09 -2.21811e-09 1 5.50488e-08 -3.24395e-09 -2.21811e-09 3953.64 19.0878 -287.805 3993.96 7.2817 4002.7 +EDGE_SE3:QUAT 1138 1189 -1.55293 12.0222 -6.73874 -0.0246868 0.0642703 -0.00418888 0.997618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4064.02 -7.10979 519.866 3983.67 -3.61923 4066.39 +EDGE_SE3:QUAT 1139 1188 -1.01018 -12.3762 -6.14181 -0.0695692 0.0101615 -0.0182065 0.997359 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.71 -2.13025 65.5266 3999.78 -0.673489 3999.74 +EDGE_SE3:QUAT 1140 1190 -0.374789 -0.0641854 -6.12701 0.0739521 0.0889666 -0.0417971 0.992406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4119.29 22.2873 764.616 3965.4 -1.93195 4134.17 +EDGE_SE3:QUAT 1139 1190 -1.19792 12.4655 -6.56229 -0.0257501 0.0983735 0.205274 0.973407 1 3.00927e-21 3.00927e-21 3.44907e-09 7.23689e-10 3.55709e-10 1 3.00927e-21 3.44907e-09 7.23689e-10 3.55709e-10 1 3.44907e-09 7.23689e-10 3.55709e-10 4162.13 40.6011 828.519 3966.82 88.2071 3996.23 +EDGE_SE3:QUAT 1140 1189 -1.55568 -11.9829 -6.38571 0.0772957 0.0550283 -0.0262527 0.995142 1 1.20371e-20 1.20371e-20 4.07718e-10 5.22395e-10 6.9515e-09 1 1.20371e-20 4.07718e-10 5.22395e-10 6.9515e-09 1 4.07718e-10 5.22395e-10 6.9515e-09 4029.59 16.7794 465.659 3986.68 -0.268584 4050.73 +EDGE_SE3:QUAT 1141 1191 -1.13484 -0.402648 -6.16169 -0.0772308 0.0839701 -0.0662851 0.991257 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4067.21 -33.9588 611.024 3980.81 -32.1337 4073.49 +EDGE_SE3:QUAT 1140 1191 -1.61536 12.4306 -6.07967 -0.0999393 -0.0492669 0.0727836 0.991104 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.08 16.4723 -299.651 3996.09 -13.8178 4000.84 +EDGE_SE3:QUAT 1141 1190 -1.46802 -12.3874 -6.09065 -0.0173199 -0.0904364 -0.084125 0.992192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4136.67 -10.4796 -755.305 3967.04 31.0915 4109.56 +EDGE_SE3:QUAT 1142 1192 -0.728385 -0.0930654 -6.28548 0.174671 0.14839 -0.0491702 0.972138 1 7.70372e-19 7.70372e-19 -5.67494e-08 -2.58707e-10 -9.11036e-09 1 7.70372e-19 -5.67494e-08 -2.58707e-10 -9.11036e-09 1 -5.67494e-08 -2.58707e-10 -9.11036e-09 4288.26 117.383 1345.21 3913.93 70.3494 4400.63 +EDGE_SE3:QUAT 1141 1192 -1.55593 12.1035 -6.28122 0.163353 0.138477 0.1398 0.966745 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.48 101.537 775.404 3990.58 99.1003 4062.04 +EDGE_SE3:QUAT 1142 1191 -1.12714 -12.1367 -5.92794 -0.173837 0.0991637 -0.248832 0.947644 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3876.76 -8.02254 191.092 4004.61 -4.53066 3749.97 +EDGE_SE3:QUAT 1143 1193 -0.536303 -0.133169 -6.04 -0.019488 -0.00793883 0.0833763 0.996296 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.94 0.429308 -43.4124 3999.92 -1.54662 3972.65 +EDGE_SE3:QUAT 1142 1193 -1.3172 12.2441 -6.32553 0.0148501 -0.0779233 -0.0912854 0.99266 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4090.29 -17.6671 -610.821 3979.14 31.331 4057.84 +EDGE_SE3:QUAT 1143 1192 -1.66479 -12.5554 -6.054 -0.0933595 -0.149528 -0.0469529 0.98322 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4373.26 49.0734 -1341.31 3906.22 -19.575 4399.31 +EDGE_SE3:QUAT 1144 1194 -0.807893 -0.0828636 -6.07014 0.0225898 -0.174328 0.104627 0.978853 1 1.93345e-19 1.93345e-19 -6.9926e-09 -6.19972e-10 2.92857e-08 1 1.93345e-19 -6.9926e-09 -6.19972e-10 2.92857e-08 1 -6.9926e-09 -6.19972e-10 2.92857e-08 4537.27 66.5049 -1564.66 3883.15 -89.8663 4495.53 +EDGE_SE3:QUAT 1143 1194 -1.23072 12.7233 -6.46437 0.0189124 0.1641 -0.120577 0.978864 1 1.05794e-20 1.05794e-20 6.73488e-09 -8.32694e-10 1.12688e-09 1 1.05794e-20 6.73488e-09 -8.32694e-10 1.12688e-09 1 6.73488e-09 -8.32694e-10 1.12688e-09 4466.04 -72.0698 1445.18 3899.89 -98.7165 4409.32 +EDGE_SE3:QUAT 1144 1193 -1.43341 -12.4476 -6.14792 0.0210704 0.0804439 0.0116527 0.996468 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4102.62 9.20416 654.586 3974.58 7.41449 4103.85 +EDGE_SE3:QUAT 1145 1195 -0.731233 0.0506351 -6.11879 0.0494892 -0.00220584 -0.0910489 0.994614 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.45 1.32795 36.3229 3999.82 -2.46801 3967.09 +EDGE_SE3:QUAT 1144 1195 -1.07198 12.4876 -6.41394 -0.0187057 0.0201474 -0.0517413 0.998282 1 1.20371e-20 1.20371e-20 6.93178e-09 -3.64532e-10 1.25616e-10 1 1.20371e-20 6.93178e-09 -3.64532e-10 1.25616e-10 1 6.93178e-09 -3.64532e-10 1.25616e-10 4004.14 -1.80797 149.024 3998.71 -3.92555 3994.83 +EDGE_SE3:QUAT 1145 1194 -0.737422 -12.5032 -5.76831 0.0595913 -0.181398 0.083201 0.97807 1 7.70372e-19 7.70372e-19 -3.66445e-09 5.43665e-08 -1.74344e-09 1 7.70372e-19 -3.66445e-09 5.43665e-08 -1.74344e-09 1 -3.66445e-09 5.43665e-08 -1.74344e-09 4606.63 12.3959 -1693.77 3861.4 -38.4798 4593.15 +EDGE_SE3:QUAT 1146 1196 -0.404549 0.0310242 -6.38959 0.104418 0.0896349 -0.0525981 0.989088 1 4.81482e-20 4.81482e-20 -1.39e-09 -1.35986e-09 -1.39881e-08 1 4.81482e-20 -1.39e-09 -1.35986e-09 -1.39881e-08 1 -1.39e-09 -1.35986e-09 -1.39881e-08 4108.47 34.3765 794.738 3962.82 0.326882 4141.01 +EDGE_SE3:QUAT 1145 1196 -1.40053 12.6562 -6.72567 -0.0518635 0.0571681 0.126471 0.988963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4058.46 -2.28546 531.007 3982.44 31.1833 4005.24 +EDGE_SE3:QUAT 1146 1195 -1.19788 -12.7094 -6.19313 0.104889 -0.163571 -0.106346 0.975158 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4288.59 -136.464 -1203.24 3946.51 136.682 4287.36 +EDGE_SE3:QUAT 1147 1197 -0.465228 0.188479 -6.33493 0.0672688 0.00769781 -0.0385322 0.996961 1 1.92593e-19 1.92593e-19 -2.76785e-08 1.03158e-09 -3.54662e-10 1 1.92593e-19 -2.76785e-08 1.03158e-09 -3.54662e-10 1 -2.76785e-08 1.03158e-09 -3.54662e-10 3983.99 3.33674 92.0574 3999.36 -1.78782 3996.15 +EDGE_SE3:QUAT 1146 1197 -1.22417 12.2346 -6.45081 -0.145964 0.0883251 0.00864487 0.985301 1 7.71124e-19 7.71124e-19 -5.54085e-08 7.22833e-10 -3.17162e-09 1 7.71124e-19 -5.54085e-08 7.22833e-10 -3.17162e-09 1 -5.54085e-08 7.22833e-10 -3.17162e-09 4039.79 -54.9319 718.168 3972.52 -24.8634 4124.71 +EDGE_SE3:QUAT 1147 1196 -1.41871 -12.339 -6.42113 -0.164233 0.0468071 -0.0156707 0.985186 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3919.16 -27.1237 330.671 3994.75 -9.7489 4026.07 +EDGE_SE3:QUAT 1148 1198 -0.885712 0.385697 -6.53708 -0.0500517 -0.0674294 -0.139105 0.986711 1 1.92593e-19 1.92593e-19 3.69689e-09 2.74093e-08 8.30712e-10 1 1.92593e-19 3.69689e-09 2.74093e-08 8.30712e-10 1 3.69689e-09 2.74093e-08 8.30712e-10 4083.11 -2.01826 -617.6 3977.02 40.1145 4015.73 +EDGE_SE3:QUAT 1147 1198 -1.53087 12.6262 -6.455 0.0437321 -0.0141548 -0.0572094 0.997303 1 9.93058e-20 9.93058e-20 1.37663e-08 -4.89404e-09 -1.3812e-08 1 9.93058e-20 1.37663e-08 -4.89404e-09 -1.3812e-08 1 1.37663e-08 -4.89404e-09 -1.3812e-08 3994.02 -1.75156 -82.4564 3999.69 2.19826 3988.58 +EDGE_SE3:QUAT 1148 1197 -1.10893 -12.8091 -6.02616 -0.0510521 0.00201099 -0.164479 0.985056 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.06 2.76285 -83.4241 3999.16 9.5724 3893.27 +EDGE_SE3:QUAT 1149 1199 -0.668538 -0.0179309 -6.60088 0.0652923 0.00436244 -0.00307984 0.997852 1 1.88079e-22 1.88079e-22 -4.09977e-12 -5.66124e-11 -8.65536e-10 1 1.88079e-22 -4.09977e-12 -5.66124e-11 -8.65536e-10 1 -4.09977e-12 -5.66124e-11 -8.65536e-10 3983.29 1.23322 37.0852 3999.91 -0.0253762 4000.31 +EDGE_SE3:QUAT 1148 1199 -1.33129 12.5546 -6.39779 -0.0229928 0.120729 0.0521463 0.991048 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4247.1 6.24205 1029.07 3940.64 22.338 4238.34 +EDGE_SE3:QUAT 1149 1198 -1.43873 -12.1847 -5.91218 0.138909 0.130657 0.0584476 0.979907 1 3.85186e-19 3.85186e-19 4.49587e-10 3.16232e-08 2.35627e-08 1 3.85186e-19 4.49587e-10 3.16232e-08 2.35627e-08 1 4.49587e-10 3.16232e-08 2.35627e-08 4136.61 94.4043 951.023 3962.02 80.6902 4200.13 +EDGE_SE3:QUAT 1150 1200 -0.653549 -0.0618522 -6.45581 0.148193 0.134638 -0.14048 0.969627 1 7.70372e-19 7.70372e-19 -5.67649e-08 5.84333e-09 -9.71071e-09 1 7.70372e-19 -5.67649e-08 5.84333e-09 -9.71071e-09 1 -5.67649e-08 5.84333e-09 -9.71071e-09 4345.39 41.9369 1386.58 3897.84 -30.0493 4354.29 +EDGE_SE3:QUAT 1149 1200 -1.29809 11.9925 -6.57327 0.00126044 0.178103 0.185805 0.96631 1 7.70372e-19 7.70372e-19 -9.69747e-09 -4.09975e-09 -5.69743e-08 1 7.70372e-19 -9.69747e-09 -4.09975e-09 -5.69743e-08 1 -9.69747e-09 -4.09975e-09 -5.69743e-08 4493.05 154.052 1489.41 3916.01 183.4 4354.96 +EDGE_SE3:QUAT 1150 1199 -1.36885 -12.6986 -6.26488 0.152807 -0.0304993 -0.154727 0.975592 1 7.70372e-19 7.70372e-19 -5.41436e-08 8.69403e-09 -1.03126e-09 1 7.70372e-19 -5.41436e-08 8.69403e-09 -1.03126e-09 1 -5.41436e-08 8.69403e-09 -1.03126e-09 3904.83 11.4061 48.0443 3998.65 -11.5481 3902.47 +EDGE_SE3:QUAT 1151 1201 -0.34604 -0.0395454 -6.36282 -0.00285798 0.0270988 0.0917086 0.995413 1 1.92605e-19 1.92605e-19 9.71265e-10 7.94206e-11 2.76753e-08 1 1.92605e-19 9.71265e-10 7.94206e-11 2.76753e-08 1 9.71265e-10 7.94206e-11 2.76753e-08 4011.79 1.31984 217.752 3997.15 10.0179 3978.18 +EDGE_SE3:QUAT 1150 1201 -1.55153 12.2567 -6.56911 0.0630593 0.119505 -0.114675 0.984171 1 4.81482e-20 4.81482e-20 1.41246e-08 -1.46422e-09 1.86829e-09 1 4.81482e-20 1.41246e-08 -1.46422e-09 1.86829e-09 1 1.41246e-08 -1.46422e-09 1.86829e-09 4257.79 -7.00826 1081.62 3935.14 -47.4972 4221.1 +EDGE_SE3:QUAT 1151 1200 -1.55324 -12.2776 -6.03471 0.116772 0.014169 -0.137392 0.983507 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3966.73 17.7341 297.918 3992.36 -21.9901 3945.76 +EDGE_SE3:QUAT 1152 1202 -0.372741 -0.00315083 -6.51614 0.0356277 0.115485 0.048933 0.991463 1 2.88889e-19 2.88889e-19 -1.40734e-08 -2.90195e-08 -1.4367e-08 1 2.88889e-19 -1.40734e-08 -2.90195e-08 -1.4367e-08 1 -1.40734e-08 -2.90195e-08 -1.4367e-08 4203.92 34.8163 937.979 3951.98 37.516 4199.42 +EDGE_SE3:QUAT 1151 1202 -1.28729 12.519 -6.52194 0.0140223 0.0815367 -0.0401072 0.995764 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4109.48 -1.63209 673.22 3973.02 -12.1508 4103.83 +EDGE_SE3:QUAT 1152 1201 -1.32913 -12.6593 -6.12251 0.0613423 0.0249537 -0.0850173 0.994176 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.64 6.69932 259.553 3995.3 -10.5743 3987.78 +EDGE_SE3:QUAT 1153 1203 -1.02261 -0.0973322 -6.12869 0.0611291 -0.0520948 0.0906854 0.992636 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.19 -8.38538 -481.792 3985.15 -18.4655 4024.25 +EDGE_SE3:QUAT 1152 1203 -1.6053 12.7801 -6.39396 -0.0157928 0.0679944 0.143167 0.987234 1 7.52316e-22 7.52316e-22 1.72952e-09 2.49355e-10 1.22062e-10 1 7.52316e-22 1.72952e-09 2.49355e-10 1.22062e-10 1 1.72952e-09 2.49355e-10 1.22062e-10 4076.89 12.2094 563.564 3982.17 40.7765 3995.9 +EDGE_SE3:QUAT 1153 1202 -1.35103 -12.1811 -6.46708 -0.0863763 0.0991858 -0.0260746 0.99097 1 4.81482e-20 4.81482e-20 1.3135e-09 -1.3168e-09 1.40048e-08 1 4.81482e-20 1.3135e-09 -1.3168e-09 1.40048e-08 1 1.3135e-09 -1.3168e-09 1.40048e-08 4116.92 -42.5198 780.301 3967.11 -30.902 4144.05 +EDGE_SE3:QUAT 1154 1204 -0.185123 0.0453183 -6.21462 -0.139234 0.0464225 0.16106 0.97597 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.01 -31.3082 622.564 3972.6 41.9637 3989.79 +EDGE_SE3:QUAT 1153 1204 -1.71549 12.5548 -6.41274 0.0504876 -0.110823 0.116498 0.985696 1 2.40741e-19 2.40741e-19 1.06676e-08 2.23049e-09 2.64404e-08 1 2.40741e-19 1.06676e-08 2.23049e-09 2.64404e-08 1 1.06676e-08 2.23049e-09 2.64404e-08 4218.81 11.5518 -984.164 3945.78 -48.9464 4174.72 +EDGE_SE3:QUAT 1154 1203 -1.44141 -11.955 -6.14279 -0.0886634 0.00991157 0.00953364 0.995967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3970.51 -4.03612 88.4791 3999.49 0.187475 4001.59 +EDGE_SE3:QUAT 1155 1205 -0.579714 -0.0320305 -6.45524 -0.107665 -0.0522506 0.00743811 0.992785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.14 22.5476 -404.64 3990.75 -8.26489 4040.29 +EDGE_SE3:QUAT 1154 1205 -1.32565 12.4624 -6.82737 0.0594986 0.0305652 0.116798 0.990901 1 2.0463e-19 2.0463e-19 2.66928e-08 1.01995e-08 -1.48602e-11 1 2.0463e-19 2.66928e-08 1.01995e-08 -1.48602e-11 1 2.66928e-08 1.01995e-08 -1.48602e-11 3991.66 5.12851 155.84 3999.18 8.09772 3951.25 +EDGE_SE3:QUAT 1155 1204 -1.71553 -12.4495 -6.11479 0.00803783 -0.0985553 -0.0889512 0.991116 1 1.92593e-19 1.92593e-19 -2.56077e-09 -2.75006e-08 7.15468e-10 1 1.92593e-19 -2.56077e-09 -2.75006e-08 7.15468e-10 1 -2.56077e-09 -2.75006e-08 7.15468e-10 4152.22 -24.5171 -795.775 3964.98 40.5995 4120.83 +EDGE_SE3:QUAT 1156 1206 -0.60727 -0.0132786 -6.25337 0.0453696 0.0278205 0.109042 0.992611 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.97 4.38099 159.219 3998.94 8.07796 3958.64 +EDGE_SE3:QUAT 1155 1206 -1.57068 12.5132 -6.30155 -0.0376134 0.0964875 0.0967219 0.989909 1 1.20371e-20 1.20371e-20 -7.01184e-09 -6.4474e-10 -7.20959e-10 1 1.20371e-20 -7.01184e-09 -6.4474e-10 -7.20959e-10 1 -7.01184e-09 -6.4474e-10 -7.20959e-10 4160.91 6.7948 833.096 3959.93 35.5668 4129.14 +EDGE_SE3:QUAT 1156 1205 -1.44007 -12.5426 -6.33418 -0.0284454 0.0685126 -0.100407 0.992177 1 1.92593e-19 1.92593e-19 1.7141e-09 -1.17237e-09 2.77617e-08 1 1.92593e-19 1.7141e-09 -1.17237e-09 2.77617e-08 1 1.7141e-09 -1.17237e-09 2.77617e-08 4061.12 -17.6218 511.756 3985.89 -29.0289 4024.03 +EDGE_SE3:QUAT 1157 1207 -0.618301 -0.330244 -6.33836 0.0857557 -0.0137096 -0.0225994 0.995965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3972.38 -3.38068 -85.2742 3999.65 1.13771 3999.76 +EDGE_SE3:QUAT 1156 1207 -1.82949 12.437 -6.89061 0.249831 -0.0917044 0.196238 0.943751 1 7.70372e-19 7.70372e-19 -9.83755e-09 1.17808e-08 5.50561e-08 1 7.70372e-19 -9.83755e-09 1.17808e-08 5.50561e-08 1 -9.83755e-09 1.17808e-08 5.50561e-08 4131.6 -109.987 -1297.04 3902.51 -36.4172 4227.22 +EDGE_SE3:QUAT 1157 1206 -1.65347 -12.2111 -6.15042 0.00457776 0.042928 -0.165003 0.985348 1 8.18708e-19 8.18708e-19 -9.09232e-10 1.43564e-08 -5.48021e-08 1 8.18708e-19 -9.09232e-10 1.43564e-08 -5.48021e-08 1 -9.09232e-10 1.43564e-08 -5.48021e-08 4028.69 -6.50341 340.524 3993.74 -28.2995 3919.87 +EDGE_SE3:QUAT 1158 1208 -0.844811 -0.153411 -6.34861 0.110952 0.0192381 0.0552673 0.992101 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3952.09 3.06538 77.5128 3999.88 1.80529 3989.11 +EDGE_SE3:QUAT 1157 1208 -1.25926 12.2342 -6.51239 0.0714899 -0.105847 0.069896 0.989343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4187.8 -16.4457 -936.214 3949.29 -15.0919 4188.7 +EDGE_SE3:QUAT 1158 1207 -1.30655 -12.4979 -5.88013 0.120619 -0.0273387 -0.0478773 0.991167 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3946.86 -7.73484 -144.732 3999.24 4.06436 3995.89 +EDGE_SE3:QUAT 1159 1209 -0.903548 -0.212965 -6.03841 -0.0679032 -0.155046 -0.232047 0.957865 1 7.70372e-19 7.70372e-19 -9.93468e-09 5.18552e-10 5.64361e-08 1 7.70372e-19 -9.93468e-09 5.18552e-10 5.64361e-08 1 -9.93468e-09 5.18552e-10 5.64361e-08 4459.78 -109.89 -1463.43 3909.62 172.412 4262.84 +EDGE_SE3:QUAT 1158 1209 -1.28107 12.6103 -6.30802 -0.112458 0.117443 -0.0805485 0.983398 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4113.97 -72.1836 829.773 3970.13 -66.8414 4138.6 +EDGE_SE3:QUAT 1159 1208 -1.66868 -12.5228 -5.70986 -0.00375116 -0.0379194 -0.0443265 0.99829 1 7.52316e-22 7.52316e-22 1.7368e-09 -7.68438e-11 -6.62893e-11 1 7.52316e-22 1.7368e-09 -7.68438e-11 -6.62893e-11 1 1.7368e-09 -7.68438e-11 -6.62893e-11 4023.22 -0.967296 -306.004 3994.24 6.76212 4015.41 +EDGE_SE3:QUAT 1160 1210 -0.862494 0.26412 -6.36701 -0.00203495 0.0127862 -0.0992044 0.994983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.4 -0.467433 98.4264 3999.44 -4.8326 3963.05 +EDGE_SE3:QUAT 1159 1210 -1.19419 12.229 -6.58769 0.189498 0.0619667 -0.011333 0.979858 1 4.23178e-22 4.23178e-22 8.09466e-11 2.48622e-10 1.28501e-09 1 4.23178e-22 8.09466e-11 2.48622e-10 1.28501e-09 1 8.09466e-11 2.48622e-10 1.28501e-09 3918.17 48.3499 501.151 3987.08 15.094 4061.3 +EDGE_SE3:QUAT 1160 1209 -1.62032 -12.2442 -5.95232 -0.0735438 0.196841 -0.0720403 0.975016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4585.55 -158.085 1673.19 3885.29 -157.874 4586.43 +EDGE_SE3:QUAT 1161 1211 -0.706613 -0.271248 -6.3407 -0.0587054 -0.0255822 -0.0354517 0.997318 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.25 6.33482 -228.812 3996.57 3.1262 4008.01 +EDGE_SE3:QUAT 1160 1211 -1.27596 12.4834 -6.34337 0.029669 -0.130987 0.0762578 0.988001 1 1.20371e-20 1.20371e-20 -7.10935e-09 -5.10322e-10 9.63383e-10 1 1.20371e-20 -7.10935e-09 -5.10322e-10 9.63383e-10 1 -7.10935e-09 -5.10322e-10 9.63383e-10 4296.17 15.184 -1135.17 3929.77 -37.9156 4276.43 +EDGE_SE3:QUAT 1161 1210 -1.71164 -12.4722 -6.34492 0.117678 -0.006133 -0.107362 0.987212 1 1.92593e-19 1.92593e-19 -2.74076e-08 2.93741e-09 -5.30882e-10 1 1.92593e-19 -2.74076e-08 2.93741e-09 -5.30882e-10 1 -2.74076e-08 2.93741e-09 -5.30882e-10 3946.6 8.82439 101.88 3998.55 -8.01744 3955.88 +EDGE_SE3:QUAT 1162 1212 -0.704099 -0.064267 -6.35813 -0.0298135 -0.0634467 -0.0460827 0.996475 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.42 3.5629 -529.786 3982.82 9.77873 4060.48 +EDGE_SE3:QUAT 1161 1212 -1.38683 12.4952 -6.15936 0.0802279 -0.00164306 0.157176 0.984305 1 1.92593e-19 1.92593e-19 -2.73408e-08 -4.30264e-09 7.32361e-10 1 1.92593e-19 -2.73408e-08 -4.30264e-09 7.32361e-10 1 -2.73408e-08 -4.30264e-09 7.32361e-10 3980.17 -7.5075 -160.96 3997.31 -16.1195 3907.1 +EDGE_SE3:QUAT 1162 1211 -1.40477 -12.3151 -5.98246 0.0954338 0.0546109 0.0774123 0.990917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.07 18.9053 340.714 3994.81 16.9511 4004.53 +EDGE_SE3:QUAT 1163 1213 -0.85105 -0.120832 -6.38909 0.169159 0.0236508 0.0671227 0.983016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3885.49 -0.0230725 46.5341 4000.08 0.304579 3981.93 +EDGE_SE3:QUAT 1162 1213 -1.49287 12.42 -6.39909 -0.131135 -0.0582568 0.191696 0.970908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3932.57 4.67462 -136.513 4000.93 -4.4326 3854.37 +EDGE_SE3:QUAT 1163 1212 -1.69452 -12.2253 -6.26235 0.125181 0.0200739 0.0739108 0.989173 1 1.92593e-19 1.92593e-19 2.51346e-11 3.51957e-09 2.74556e-08 1 1.92593e-19 2.51346e-11 3.51957e-09 2.74556e-08 1 2.51346e-11 3.51957e-09 2.74556e-08 3937.47 0.595658 46.0022 4000.04 0.503155 3978.3 +EDGE_SE3:QUAT 1164 1214 -0.765407 -0.0950019 -6.29887 0.0945782 0.0250045 0.121696 0.987735 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3964.44 0.752104 56.8985 4000.07 0.790314 3940.98 +EDGE_SE3:QUAT 1163 1214 -1.75666 12.374 -6.52217 -0.336057 -0.0605097 0.286688 0.895105 1 3.12964e-18 3.12964e-18 1.04258e-07 1.63492e-08 1.08663e-08 1 3.12964e-18 1.04258e-07 1.63492e-08 1.08663e-08 1 1.04258e-07 1.63492e-08 1.08663e-08 3632.09 -165.412 669.105 3930.2 134.474 3755.07 +EDGE_SE3:QUAT 1164 1213 -1.66468 -12.4551 -6.22497 -0.00652016 -0.0947561 0.0746489 0.992676 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4142.52 19.1411 -768.864 3966.58 -32.6711 4120.4 +EDGE_SE3:QUAT 1165 1215 -0.667566 -0.177292 -5.85404 -0.00633102 0.0152051 -0.17612 0.984231 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.47 -1.07469 102.965 3999.51 -8.55055 3878.56 +EDGE_SE3:QUAT 1164 1215 -1.57284 12.3492 -6.8322 0.0185656 -0.0356246 0.0770542 0.996217 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.13 -0.317271 -300.944 3994.34 -11.3289 3998.76 +EDGE_SE3:QUAT 1165 1214 -1.42019 -12.5683 -6.26165 -0.0871886 -0.25354 -0.071609 0.960723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5310.67 41.2336 -2676.35 3732.63 -30.9223 5320.57 +EDGE_SE3:QUAT 1166 1216 -0.488195 0.091498 -6.07498 -0.0174969 -0.00422762 -0.0394002 0.999061 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.21 0.367456 -41.9936 3999.88 0.87059 3994.23 +EDGE_SE3:QUAT 1165 1216 -1.70875 12.0902 -6.41706 0.0214159 -0.0461944 0.265924 0.962648 1 3.00927e-21 3.00927e-21 3.35757e-09 9.24459e-10 -1.76589e-10 1 3.00927e-21 3.35757e-09 9.24459e-10 -1.76589e-10 1 3.35757e-09 9.24459e-10 -1.76589e-10 4037.7 11.4649 -399.668 3992.6 -54.4562 3756.67 +EDGE_SE3:QUAT 1166 1215 -1.51134 -12.2201 -6.10474 -0.038656 0.101139 -0.0459144 0.99306 1 4.81482e-20 4.81482e-20 -1.36914e-09 6.89021e-10 -1.40516e-08 1 4.81482e-20 -1.36914e-09 6.89021e-10 -1.40516e-08 1 -1.36914e-09 6.89021e-10 -1.40516e-08 4151.71 -28.3785 809.777 3963.45 -29.8148 4149.26 +EDGE_SE3:QUAT 1167 1217 -0.595955 -0.45685 -5.9961 0.212122 -0.0298721 0.0377998 0.976055 1 1.20371e-20 1.20371e-20 2.97921e-10 -1.46046e-09 -6.79489e-09 1 1.20371e-20 2.97921e-10 -1.46046e-09 -6.79489e-09 1 2.97921e-10 -1.46046e-09 -6.79489e-09 3845.02 -35.6673 -317.805 3993.66 0.753176 4019.29 +EDGE_SE3:QUAT 1166 1217 -1.53572 12.4175 -6.35341 0.0314151 0.0528047 0.0161942 0.997979 1 9.62965e-20 9.62965e-20 -1.36532e-08 -1.41221e-08 -2.58702e-10 1 9.62965e-20 -1.36532e-08 -1.41221e-08 -2.58702e-10 1 -1.36532e-08 -1.41221e-08 -2.58702e-10 4039.56 7.81312 419.448 3989.4 5.55301 4042.46 +EDGE_SE3:QUAT 1167 1216 -1.53818 -12.5716 -6.03269 0.130607 0.103258 0.165599 0.972037 1 7.70372e-19 7.70372e-19 -5.44055e-08 -1.05972e-08 -2.83603e-09 1 7.70372e-19 -5.44055e-08 -1.05972e-08 -2.83603e-09 1 -5.44055e-08 -1.05972e-08 -2.83603e-09 3994.85 51.3956 520.222 3995.99 54.6342 3953.39 +EDGE_SE3:QUAT 1168 1218 -0.735357 0.0314314 -6.77307 -0.084859 -0.140315 0.050019 0.985195 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4262.9 79.4274 -1119.31 3939.04 -72.8378 4281.7 +EDGE_SE3:QUAT 1167 1218 -1.79539 12.3529 -6.33161 0.19255 -0.0848817 0.141984 0.967244 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4084.12 -70.3461 -994.123 3940.04 -23.4914 4151.78 +EDGE_SE3:QUAT 1168 1217 -1.76568 -12.9613 -5.99259 0.212608 -0.0385142 -0.0428381 0.975438 1 3.14167e-18 3.14167e-18 1.08258e-07 -1.58777e-08 -1.39503e-08 1 3.14167e-18 1.08258e-07 -1.58777e-08 -1.39503e-08 1 1.08258e-07 -1.58777e-08 -1.39503e-08 3826.78 -15.4234 -180.704 3999.48 6.49227 4000.25 +EDGE_SE3:QUAT 1169 1219 -0.64466 0.0969866 -6.17309 0.080645 -0.127398 -0.0208406 0.988348 1 9.62965e-19 9.62965e-19 -2.59581e-08 5.60358e-08 -1.42263e-09 1 9.62965e-19 -2.59581e-08 5.60358e-08 -1.42263e-09 1 -2.59581e-08 5.60358e-08 -1.42263e-09 4229.25 -57.0516 -1042.33 3943 44.9801 4253.53 +EDGE_SE3:QUAT 1168 1219 -1.55234 12.3625 -6.43121 -0.105165 0.0284062 0.069622 0.991608 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.59 -15.7472 310.653 3993.2 8.52379 4004.44 +EDGE_SE3:QUAT 1169 1218 -1.5218 -12.1563 -6.03224 0.109249 0.05488 0.0893469 0.988469 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.78 18.8844 311.169 3996.35 17.0216 3991.59 +EDGE_SE3:QUAT 1170 1220 -0.928462 0.606171 -6.59563 0.0902516 -0.0934992 -0.107242 0.985704 1 3.85186e-19 3.85186e-19 2.96559e-08 -6.56449e-09 -2.96559e-08 1 3.85186e-19 2.96559e-08 -6.56449e-09 -2.96559e-08 1 2.96559e-08 -6.56449e-09 -2.96559e-08 4060.94 -45.1642 -621.089 3983.42 47.7252 4047.51 +EDGE_SE3:QUAT 1169 1220 -1.48971 12.297 -6.28639 -0.0794886 0.0132158 0.0901561 0.992662 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.47 -7.66439 189.048 3997.15 8.94247 3976.23 +EDGE_SE3:QUAT 1170 1219 -1.43535 -12.3343 -6.02947 -0.0916427 -0.115896 -0.222932 0.963572 1 7.70372e-19 7.70372e-19 -8.27647e-09 -1.95396e-09 5.56757e-08 1 7.70372e-19 -8.27647e-09 -1.95396e-09 5.56757e-08 1 -8.27647e-09 -1.95396e-09 5.56757e-08 4282.48 -38.8356 -1168.32 3930.38 117.548 4117.28 +EDGE_SE3:QUAT 1171 1221 -0.696767 0.0738276 -6.22297 -0.0154763 -0.0446227 -0.0748021 0.996079 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.07 -0.836378 -370.509 3991.56 13.5097 4011.65 +EDGE_SE3:QUAT 1170 1221 -1.36847 12.2662 -6.25908 0.0723426 -0.0132863 0.135737 0.988011 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.74 -7.40711 -219.2 3996.07 -16.4988 3937.97 +EDGE_SE3:QUAT 1171 1220 -1.51158 -12.2869 -6.10922 0.0269066 -0.25079 -0.133006 0.958483 1 7.70372e-19 7.70372e-19 -1.45376e-08 6.4333e-09 6.00915e-08 1 7.70372e-19 -1.45376e-08 6.4333e-09 6.00915e-08 1 -1.45376e-08 6.4333e-09 6.00915e-08 5071.21 -303.885 -2335.52 3830.92 309.381 5003.34 +EDGE_SE3:QUAT 1172 1222 -0.756475 0.213252 -6.18896 -0.0087811 -0.0757592 0.136703 0.987672 1 2.40741e-19 2.40741e-19 -9.97988e-09 -2.936e-08 1.77095e-10 1 2.40741e-19 -9.97988e-09 -2.936e-08 1.77095e-10 1 -9.97988e-09 -2.936e-08 1.77095e-10 4083.43 20.6296 -585.018 3981.95 -42.7414 4008.99 +EDGE_SE3:QUAT 1171 1222 -1.96863 12.2128 -6.6361 -0.00417663 -0.164692 0.0132991 0.986247 1 7.52316e-22 7.52316e-22 1.80884e-09 2.84203e-11 -3.01714e-10 1 7.52316e-22 1.80884e-09 2.84203e-11 -3.01714e-10 1 1.80884e-09 2.84203e-11 -3.01714e-10 4471.09 13.8133 -1451.42 3891.91 -15.5752 4470.45 +EDGE_SE3:QUAT 1172 1221 -1.44823 -12.1418 -6.05559 -0.0771807 -0.0362073 0.0570296 0.994726 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.68 9.68422 -233.686 3997.31 -7.9548 4000.5 +EDGE_SE3:QUAT 1173 1223 -0.607549 -0.215937 -6.52647 -0.188247 -0.0602906 0.159918 0.967137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3855.74 -2.44827 -90.5034 4000.74 1.50124 3895.19 +EDGE_SE3:QUAT 1172 1223 -1.66048 12.3518 -6.22956 0.107235 0.0560709 -0.0929688 0.988288 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.72 23.3191 563.779 3979.3 -17.3118 4043.15 +EDGE_SE3:QUAT 1173 1222 -1.60416 -12.263 -5.99652 -0.0808797 -0.0626689 -0.107929 0.988879 1 1.92593e-19 1.92593e-19 2.70537e-09 2.7477e-08 1.83976e-09 1 1.92593e-19 2.70537e-09 2.7477e-08 1.83976e-09 1 2.70537e-09 2.7477e-08 1.83976e-09 4062.9 13.2127 -604.048 3976.83 25.6541 4042.47 +EDGE_SE3:QUAT 1174 1224 -0.733261 -0.196636 -6.33399 -0.0340404 -0.0863919 0.00962544 0.995633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4115.59 14.6546 -703.826 3970.95 -9.89362 4119.86 +EDGE_SE3:QUAT 1173 1224 -1.47705 12.4876 -6.0738 -0.111146 -0.0380974 -0.0416995 0.992198 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982 19.2033 -356.134 3991.8 2.92719 4024.46 +EDGE_SE3:QUAT 1174 1223 -1.2233 -12.6562 -6.36875 0.0343436 -0.124812 -0.0546498 0.990079 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4240.56 -41.2057 -1020.51 3944.29 45.3244 4233.33 +EDGE_SE3:QUAT 1175 1225 -0.670251 -0.224004 -6.56083 0.119112 -0.119581 -0.0866881 0.981834 1 1.92593e-19 1.92593e-19 3.18809e-09 2.7171e-08 -3.91209e-09 1 1.92593e-19 3.18809e-09 2.7171e-08 -3.91209e-09 1 3.18809e-09 2.7171e-08 -3.91209e-09 4106.47 -76.486 -826.865 3971.87 71.2426 4133.16 +EDGE_SE3:QUAT 1174 1225 -1.68002 12.4994 -6.61941 0.0272807 -0.0609264 0.2238 0.972346 1 3.00927e-21 3.00927e-21 -3.40402e-09 -7.77372e-10 2.33504e-10 1 3.00927e-21 -3.40402e-09 -7.77372e-10 2.33504e-10 1 -3.40402e-09 -7.77372e-10 2.33504e-10 4066.06 15.5593 -530.035 3985.62 -60.4545 3868.7 +EDGE_SE3:QUAT 1175 1224 -1.53338 -12.2878 -5.95448 0.166224 -0.0222322 0.0319059 0.985321 1 1.20371e-20 1.20371e-20 2.18443e-10 -1.14476e-09 -6.84892e-09 1 1.20371e-20 2.18443e-10 -1.14476e-09 -6.84892e-09 1 2.18443e-10 -1.14476e-09 -6.84892e-09 3903.01 -20.5064 -233.497 3996.38 -0.958274 4009.46 +EDGE_SE3:QUAT 1176 1226 -0.990926 0.0405177 -6.40107 -0.0722603 -0.0382036 -0.0779087 0.993604 1 1.92593e-19 1.92593e-19 -1.35413e-09 -1.83103e-09 2.76961e-08 1 1.92593e-19 -1.35413e-09 -1.83103e-09 2.76961e-08 1 -1.35413e-09 -1.83103e-09 2.76961e-08 4013.07 10.6851 -370.568 3990.84 12.0804 4009.67 +EDGE_SE3:QUAT 1175 1226 -1.41572 12.336 -6.29511 0.135269 -0.103168 0.11033 0.979227 1 7.70372e-19 7.70372e-19 5.60438e-08 4.63236e-09 -7.26947e-09 1 7.70372e-19 5.60438e-08 4.63236e-09 -7.26947e-09 1 5.60438e-08 4.63236e-09 -7.26947e-09 4172.09 -42.5973 -1021.08 3939.48 -18.5386 4196.59 +EDGE_SE3:QUAT 1176 1225 -1.57462 -12.2355 -6.3932 -0.123388 0.0676961 -0.128273 0.981702 1 8.1852e-19 8.1852e-19 -5.66391e-08 -5.70354e-09 -3.68095e-09 1 8.1852e-19 -5.66391e-08 -5.70354e-09 -3.68095e-09 1 -5.66391e-08 -5.70354e-09 -3.68095e-09 3964.67 -23.4045 330.044 3997.54 -23.7937 3959.75 +EDGE_SE3:QUAT 1177 1227 -0.608801 -0.0532926 -6.40507 -0.0456626 0.161327 -0.169181 0.971219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4330.86 -131.384 1215.65 3946.29 -150.634 4224.71 +EDGE_SE3:QUAT 1176 1227 -1.45744 12.2359 -6.6402 -0.0570579 0.146808 0.00179329 0.987516 1 4.89006e-20 4.89006e-20 -1.45836e-08 3.30796e-10 -3.9072e-09 1 4.89006e-20 -1.45836e-08 3.30796e-10 -3.9072e-09 1 -1.45836e-08 3.30796e-10 -3.9072e-09 4352.39 -43.2768 1263.01 3916.1 -31.2883 4365.4 +EDGE_SE3:QUAT 1177 1226 -1.41845 -12.3165 -5.85299 0.0987085 0.0982482 -0.142859 0.979896 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4181.8 10.067 965.927 3945.52 -49.3181 4139.14 +EDGE_SE3:QUAT 1178 1228 -0.83419 0.167993 -6.40483 -0.0671966 -0.1023 0.00258399 0.992478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4151.42 31.9474 -840.636 3960.07 -18.7352 4169.45 +EDGE_SE3:QUAT 1177 1228 -1.26183 12.5276 -6.15176 -0.261667 -0.000722142 0.181682 0.947904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3790.9 -83.8651 536.071 3970.66 49.0065 3932.74 +EDGE_SE3:QUAT 1178 1227 -1.58071 -12.4425 -5.90224 0.0469633 -0.166912 0.08396 0.981267 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4502.75 20.5765 -1519.22 3884.19 -46.2661 4483.37 +EDGE_SE3:QUAT 1179 1229 -0.838677 -0.0293328 -5.96662 0.0501018 0.027342 -0.0228277 0.998109 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.38 5.52101 232.148 3996.56 -1.733 4011.34 +EDGE_SE3:QUAT 1178 1229 -1.47204 12.5389 -6.02475 -0.0714887 0.0166401 -0.110901 0.991117 1 1.92593e-19 1.92593e-19 2.75092e-08 -3.11301e-09 9.32978e-12 1 1.92593e-19 2.75092e-08 -3.11301e-09 9.32978e-12 1 2.75092e-08 -3.11301e-09 9.32978e-12 3979.6 -0.229154 35.5895 4000.02 -0.236186 3950.85 +EDGE_SE3:QUAT 1179 1228 -1.59207 -11.9963 -6.09337 0.0153044 -0.0476434 -0.0654949 0.996597 1 4.81482e-20 4.81482e-20 9.32707e-10 1.3829e-08 -2.98174e-10 1 4.81482e-20 9.32707e-10 1.3829e-08 -2.98174e-10 1 9.32707e-10 1.3829e-08 -2.98174e-10 4032.85 -6.25299 -369.195 3992 13.002 4016.62 +EDGE_SE3:QUAT 1180 1230 -0.835321 0.140599 -6.31355 -0.0240817 0.112948 0.0746116 0.990503 1 2.0463e-19 2.0463e-19 9.03023e-09 -2.69935e-08 6.18339e-10 1 2.0463e-19 9.03023e-09 -2.69935e-08 6.18339e-10 1 9.03023e-09 -2.69935e-08 6.18339e-10 4216.69 11.7809 961.244 3947.98 32.9354 4196.74 +EDGE_SE3:QUAT 1179 1230 -1.42276 12.2078 -6.54533 -0.163849 -0.083965 0.151518 0.971157 1 3.12964e-18 3.12964e-18 1.05778e-07 3.25635e-08 -4.17724e-10 1 3.12964e-18 1.05778e-07 3.25635e-08 -4.17724e-10 1 1.05778e-07 3.25635e-08 -4.17724e-10 3916.08 28.1087 -331.613 4000.48 -27.4884 3931.63 +EDGE_SE3:QUAT 1180 1229 -1.68686 -12.3184 -6.37657 -0.113529 -0.268421 -0.197537 0.93597 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5665.68 -250.172 -3133.34 3705.26 258.765 5561.15 +EDGE_SE3:QUAT 1181 1231 -0.529627 -0.289654 -6.24879 0.319271 -0.0636778 -0.0294909 0.945062 1 4.81482e-20 4.81482e-20 -4.52531e-10 4.51891e-09 1.31613e-08 1 4.81482e-20 -4.52531e-10 4.51891e-09 1.31613e-08 1 -4.52531e-10 4.51891e-09 1.31613e-08 3617.38 -44.9177 -328.03 4000.32 20.8914 4021.64 +EDGE_SE3:QUAT 1180 1231 -1.94377 12.1483 -6.58179 -0.0235756 -0.0449296 0.0316534 0.99821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.5 5.67953 -351.948 3992.56 -6.73836 4026.72 +EDGE_SE3:QUAT 1181 1230 -1.60581 -12.8596 -6.22839 -0.0278948 -0.0125645 -0.23349 0.971878 1 1.20371e-20 1.20371e-20 -6.74996e-09 1.61518e-09 1.65593e-10 1 1.20371e-20 -6.74996e-09 1.61518e-09 1.65593e-10 1 -6.74996e-09 1.61518e-09 1.65593e-10 4003.84 0.560472 -167.886 3998.03 22.1153 3788.88 +EDGE_SE3:QUAT 1182 1232 -0.993667 -0.209253 -6.00229 0.115432 0.0789319 -0.14965 0.9788 1 3.85186e-19 3.85186e-19 -3.13578e-08 -2.35649e-08 -5.91789e-10 1 3.85186e-19 -3.13578e-08 -2.35649e-08 -5.91789e-10 1 -3.13578e-08 -2.35649e-08 -5.91789e-10 4113.11 20.8368 833.932 3956.96 -45.4442 4076.82 +EDGE_SE3:QUAT 1181 1232 -1.89363 12.1616 -6.53604 -0.0584573 -0.0739814 0.319328 0.942942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.8 21.304 -290.756 4002.84 -33.3655 3609.59 +EDGE_SE3:QUAT 1182 1231 -1.63946 -12.1283 -6.10963 -0.0186264 0.304692 -0.0431272 0.951292 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5981.87 -222.369 3444.79 3653.14 -221.081 5975.82 +EDGE_SE3:QUAT 1183 1233 -0.826243 0.0553578 -6.58629 0.131279 0.0212815 0.0625618 0.98914 1 7.70372e-19 7.70372e-19 5.49142e-08 3.6624e-09 2.2854e-10 1 7.70372e-19 5.49142e-08 3.6624e-09 2.2854e-10 1 5.49142e-08 3.6624e-09 2.2854e-10 3931.9 2.3619 67.6509 3999.99 1.43334 3985.18 +EDGE_SE3:QUAT 1182 1233 -1.62153 12.2721 -6.5301 0.0577534 -0.0454478 0.190827 0.978869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.71 -0.404313 -477.601 3985.6 -46.0085 3910.39 +EDGE_SE3:QUAT 1183 1232 -1.40751 -12.5904 -6.31486 -0.105551 -0.0162331 -0.0278606 0.993891 1 2.0463e-19 2.0463e-19 -2.74583e-08 1.38857e-09 -6.29955e-09 1 2.0463e-19 -2.74583e-08 1.38857e-09 -6.29955e-09 1 -2.74583e-08 1.38857e-09 -6.29955e-09 3962.03 8.9507 -162.824 3998.18 1.46726 4003.49 +EDGE_SE3:QUAT 1184 1234 -0.874649 -0.107101 -6.1681 -0.0263974 -0.0547134 0.0809318 0.994867 1 1.20371e-20 1.20371e-20 6.93948e-09 5.87159e-10 -3.46166e-10 1 1.20371e-20 6.93948e-09 5.87159e-10 -3.46166e-10 1 6.93948e-09 5.87159e-10 -3.46166e-10 4038.96 10.7368 -410.936 3990.52 -18.4282 4015.55 +EDGE_SE3:QUAT 1183 1234 -1.77331 12.5176 -6.50734 0.00246515 -0.0374514 -0.00847942 0.999259 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.47 -0.663063 -300.797 3994.41 1.3771 4022.21 +EDGE_SE3:QUAT 1184 1233 -1.85993 -12.433 -6.35601 0.0111241 -0.132593 0.000732878 0.991108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4296.3 -7.12222 -1129.28 3929.73 4.62701 4296.79 +EDGE_SE3:QUAT 1185 1235 -0.911789 0.302484 -6.27963 0.0770285 -0.102877 -0.0350942 0.991086 1 1.92593e-19 1.92593e-19 -2.80466e-08 1.45584e-09 2.7122e-09 1 1.92593e-19 -2.80466e-08 1.45584e-09 2.7122e-09 1 -2.80466e-08 1.45584e-09 2.7122e-09 4133.08 -42.5326 -807.556 3964.95 34.4297 4151.89 +EDGE_SE3:QUAT 1184 1235 -1.67332 12.4698 -6.2409 -0.289261 0.0370983 0.0872258 0.952546 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3739.4 -86.905 552.568 3979.98 0.858716 4043.66 +EDGE_SE3:QUAT 1185 1234 -1.7769 -12.4153 -6.28824 0.0167569 -0.304026 0.0888252 0.948366 1 3.00927e-21 3.00927e-21 4.03434e-09 4.13352e-10 -1.28363e-09 1 3.00927e-21 4.03434e-09 4.13352e-10 -1.28363e-09 1 4.03434e-09 4.13352e-10 -1.28363e-09 5993.84 263.584 -3458.33 3659.17 -258.051 5963.41 +EDGE_SE3:QUAT 1186 1236 -1.02411 0.089919 -6.70036 0.0582016 0.076548 -0.0227215 0.995106 1 4.81482e-20 4.81482e-20 1.39811e-08 -1.94816e-10 1.10463e-09 1 4.81482e-20 1.39811e-08 -1.94816e-10 1.10463e-09 1 1.39811e-08 -1.94816e-10 1.10463e-09 4085.88 16.4791 638.448 3975.59 0.954027 4097.36 +EDGE_SE3:QUAT 1185 1236 -1.79576 12.4264 -6.08931 -0.1158 0.0790966 0.327227 0.934482 1 3.27408e-18 3.27408e-18 -6.59607e-09 -2.11256e-08 -1.08356e-07 1 3.27408e-18 -6.59607e-09 -2.11256e-08 -1.08356e-07 1 -6.59607e-09 -2.11256e-08 -1.08356e-07 4182.36 36.6899 1001.31 3949.51 164.783 3807.69 +EDGE_SE3:QUAT 1186 1235 -1.61584 -12.3219 -6.34016 -0.198037 0.0743151 -0.147723 0.966145 1 7.70372e-19 7.70372e-19 4.41365e-10 -1.17763e-08 5.36694e-08 1 7.70372e-19 4.41365e-10 -1.17763e-08 5.36694e-08 1 4.41365e-10 -1.17763e-08 5.36694e-08 3848.36 -11.3885 201.149 4001.85 -11.2122 3917.94 +EDGE_SE3:QUAT 1187 1237 -1.20054 0.0947023 -6.16199 0.061218 0.0253617 -0.0108644 0.997743 1 6.01853e-20 6.01853e-20 -1.3919e-08 -6.8165e-09 5.32366e-11 1 6.01853e-20 -1.3919e-08 -6.8165e-09 5.32366e-11 1 -1.3919e-08 -6.8165e-09 5.32366e-11 3996.02 6.37134 210.198 3997.23 -0.162078 4010.54 +EDGE_SE3:QUAT 1186 1237 -1.72695 12.5341 -6.36123 0.0723791 0.00453101 0.141066 0.98734 1 7.70372e-19 7.70372e-19 -8.80463e-10 3.92852e-09 5.48185e-08 1 7.70372e-19 -8.80463e-10 3.92852e-09 5.48185e-08 1 -8.80463e-10 3.92852e-09 5.48185e-08 3980.48 -4.417 -85.6069 3999.01 -8.86149 3921.84 +EDGE_SE3:QUAT 1187 1236 -1.89097 -12.0888 -6.03028 -0.129634 0.196985 0.0622765 0.969801 1 1.92593e-19 1.92593e-19 -2.94028e-08 -3.51429e-10 -6.2413e-09 1 1.92593e-19 -2.94028e-08 -3.51429e-10 -6.2413e-09 1 -2.94028e-08 -3.51429e-10 -6.2413e-09 4691.66 -103.559 1900.39 3839.76 -72.332 4743.37 +EDGE_SE3:QUAT 1188 1238 -0.999484 0.315355 -6.30117 0.0195581 0.0442105 -0.0636043 0.996804 1 1.20371e-20 1.20371e-20 -6.94596e-09 4.32598e-10 -3.22715e-10 1 1.20371e-20 -6.94596e-09 4.32598e-10 -3.22715e-10 1 -6.94596e-09 4.32598e-10 -3.22715e-10 4032.22 0.537125 369.004 3991.55 -11.1406 4017.57 +EDGE_SE3:QUAT 1187 1238 -1.80701 12.504 -6.45275 0.0884998 0.164883 -0.0804471 0.979035 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4492.12 24.5684 1538.83 3880.59 -9.76328 4497.57 +EDGE_SE3:QUAT 1188 1237 -1.15705 -12.5457 -5.97291 0.18377 0.0814561 0.153138 0.967545 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3878.09 20.4151 268.357 4001.79 19.657 3919.37 +EDGE_SE3:QUAT 1189 1239 -1.17574 -0.0585174 -6.11383 -0.0571413 -0.201788 0.0587584 0.975994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4664.59 138.123 -1780.66 3864.82 -138.351 4663.84 +EDGE_SE3:QUAT 1188 1239 -1.85967 12.5076 -6.11898 -0.0963022 0.194729 0.163038 0.962406 1 1.73334e-18 1.73334e-18 -2.38447e-08 4.75415e-08 5.40278e-08 1 1.73334e-18 -2.38447e-08 4.75415e-08 5.40278e-08 1 -2.38447e-08 4.75415e-08 5.40278e-08 4770.77 69.771 1970.9 3830.95 114.352 4701.54 +EDGE_SE3:QUAT 1189 1238 -1.48704 -12.4277 -6.52725 0.080154 -0.184579 -0.100195 0.974406 1 3.85186e-19 3.85186e-19 3.33999e-08 -7.62653e-09 -3.33999e-08 1 3.85186e-19 3.33999e-08 -7.62653e-09 -3.33999e-08 1 3.33999e-08 -7.62653e-09 -3.33999e-08 4458.19 -159.235 -1474.49 3915.46 162.123 4443.74 +EDGE_SE3:QUAT 1190 1240 -0.706012 -0.113119 -6.18328 0.038864 0.109985 0.0601084 0.991353 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4178.17 36.2892 878.078 3958.24 40.5076 4169.76 +EDGE_SE3:QUAT 1189 1240 -1.62768 12.3979 -6.11188 0.117771 0.133001 0.106781 0.978284 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4138.01 93.6253 904.441 3969.72 91.9436 4147.88 +EDGE_SE3:QUAT 1190 1239 -1.81665 -12.3342 -6.14918 -0.118841 -0.179833 -0.166866 0.962129 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4670.67 -31.2146 -1854.28 3842.56 87.8444 4615.78 +EDGE_SE3:QUAT 1191 1241 -0.92446 -0.101144 -5.91171 -0.0423736 -0.0317018 0.0397193 0.997809 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.31 5.66861 -232.811 3996.89 -5.42238 4007.18 +EDGE_SE3:QUAT 1190 1241 -1.48879 12.3128 -6.49131 0.0082045 0.0544411 0.281665 0.957932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.54 16.9864 360.484 3996.48 48.7153 3714.47 +EDGE_SE3:QUAT 1191 1240 -1.5688 -12.3282 -6.12395 0.0473723 -0.197801 0.0510338 0.977766 1 2.40741e-19 2.40741e-19 -2.64808e-08 -1.51376e-09 -8.68834e-09 1 2.40741e-19 -2.64808e-08 -1.51376e-09 -8.68834e-09 1 -2.64808e-08 -1.51376e-09 -8.68834e-09 4719.6 -3.26258 -1856.11 3839.61 -12.4538 4718.16 +EDGE_SE3:QUAT 1192 1242 -0.85462 0.078385 -6.25449 0.105694 -0.030782 -0.0507267 0.992627 1 4.81482e-20 4.81482e-20 2.67599e-10 -1.50609e-09 -1.37889e-08 1 4.81482e-20 2.67599e-10 -1.50609e-09 -1.37889e-08 1 2.67599e-10 -1.50609e-09 -1.37889e-08 3963.04 -8.9376 -177.605 3998.67 5.4294 3997.43 +EDGE_SE3:QUAT 1191 1242 -1.645 12.5529 -6.31441 -0.0838931 0.0711397 0.0197032 0.993737 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4058.12 -23.9184 593.765 3979.02 -4.66992 4084.72 +EDGE_SE3:QUAT 1192 1241 -1.34722 -12.3568 -6.2872 0.117516 -0.0839584 -0.126262 0.981427 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.7 -37.6226 -469.704 3993.26 38.594 3989.17 +EDGE_SE3:QUAT 1193 1243 -0.821781 -0.418569 -6.04091 0.108421 -0.0157748 0.021291 0.993752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3958.7 -8.5321 -151.582 3998.46 -0.838021 4003.91 +EDGE_SE3:QUAT 1192 1243 -1.8118 12.1284 -6.35335 0.0016089 0.0201089 0.0663186 0.997595 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.28 0.759331 158.75 3998.47 5.2755 3988.7 +EDGE_SE3:QUAT 1193 1242 -1.63711 -12.6436 -6.21794 0.113621 0.0261292 0.0051999 0.993167 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3958.17 11.2136 198.369 3997.78 2.23693 4009.7 +EDGE_SE3:QUAT 1194 1244 -0.865226 0.273492 -5.97563 0.00898111 0.0143197 -0.102281 0.994612 1 7.52316e-22 7.52316e-22 -1.72621e-09 1.7712e-10 -2.75019e-11 1 7.52316e-22 -1.72621e-09 1.7712e-10 -2.75019e-11 1 -1.72621e-09 1.7712e-10 -2.75019e-11 4003.5 -0.000459365 123.806 3999.03 -6.4533 3961.98 +EDGE_SE3:QUAT 1193 1244 -1.48901 12.6085 -6.30037 -0.0480775 0.0314468 -0.0347751 0.997743 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.02 -6.15377 230.845 3996.95 -4.92835 4008.43 +EDGE_SE3:QUAT 1194 1243 -1.4324 -12.3515 -6.34338 0.00968979 -0.01531 -0.123272 0.992207 1 1.95602e-19 1.95602e-19 -3.78985e-09 7.93971e-10 2.75923e-08 1 1.95602e-19 -3.78985e-09 7.93971e-10 2.75923e-08 1 -3.78985e-09 7.93971e-10 2.75923e-08 4002.4 -1.04081 -105.548 3999.43 6.21008 3941.99 +EDGE_SE3:QUAT 1195 1245 -1.0103 -0.318678 -6.38665 -0.0410502 0.0690528 -0.00605817 0.99675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4069.4 -12.6757 557.084 3981.48 -6.51785 4075.99 +EDGE_SE3:QUAT 1194 1245 -1.90434 12.6744 -6.03635 -0.0564731 -0.0264932 -0.0257185 0.997721 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.28 6.17618 -228.793 3996.63 1.96156 4010.39 +EDGE_SE3:QUAT 1195 1244 -1.71258 -12.1912 -6.3969 -0.0257821 -0.119755 0.0124054 0.992391 1 2.0463e-19 2.0463e-19 6.55834e-09 2.76776e-08 -2.84715e-11 1 2.0463e-19 6.55834e-09 2.76776e-08 -2.84715e-11 1 6.55834e-09 2.76776e-08 -2.84715e-11 4234.36 19.3999 -1002.12 3943.77 -16.5896 4236.4 +EDGE_SE3:QUAT 1196 1246 -1.05109 0.0568129 -5.97826 0.105836 -0.159202 0.100826 0.976364 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4467.4 -26.5601 -1520.41 3882.67 -17.5502 4471.54 +EDGE_SE3:QUAT 1195 1246 -1.83789 12.3418 -6.29345 0.112117 0.119796 -0.17861 0.970143 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4294.43 -5.295 1224.47 3918.7 -79.2822 4217.11 +EDGE_SE3:QUAT 1196 1245 -2.02015 -12.0369 -6.2015 0.0899814 0.0694907 -0.0182601 0.993348 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4049.72 25.3586 578.955 3980.11 5.51548 4080.78 +EDGE_SE3:QUAT 1197 1247 -1.05513 0.499658 -6.34658 0.119624 0.133713 -0.0585455 0.98203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4281.05 58.2853 1211.49 3921.65 18.6136 4324.58 +EDGE_SE3:QUAT 1196 1247 -1.87518 12.2808 -6.84044 -0.230266 0.0991792 0.207213 0.945624 1 7.70372e-19 7.70372e-19 -1.01639e-08 1.03565e-08 -5.5369e-08 1 7.70372e-19 -1.01639e-08 1.03565e-08 -5.5369e-08 1 -1.01639e-08 1.03565e-08 -5.5369e-08 4201.38 -87.2979 1355.02 3895.43 53.4762 4241.72 +EDGE_SE3:QUAT 1197 1246 -1.58878 -12.3323 -6.15783 0.109172 0.113263 -0.00099622 0.987548 1 3.85186e-19 3.85186e-19 2.7448e-08 2.80871e-08 4.93798e-11 1 3.85186e-19 2.7448e-08 2.80871e-08 4.93798e-11 1 2.7448e-08 2.80871e-08 4.93798e-11 4158.41 57.1199 931.08 3953.76 34.5182 4206.08 +EDGE_SE3:QUAT 1198 1248 -0.467864 0.424183 -6.35789 -0.0522257 -0.112476 0.0670517 0.990013 1 4.81482e-20 4.81482e-20 -1.40565e-08 -1.1399e-09 1.47109e-09 1 4.81482e-20 -1.40565e-08 -1.1399e-09 1.47109e-09 1 -1.40565e-08 -1.1399e-09 1.47109e-09 4174.37 45.1403 -880.859 3959.31 -48.0125 4167.29 +EDGE_SE3:QUAT 1197 1248 -1.54611 12.1397 -6.83428 0.0814974 0.0549003 -0.0114981 0.995094 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.63 18.1973 450.916 3987.77 3.46085 4049.67 +EDGE_SE3:QUAT 1198 1247 -1.92235 -12.3553 -5.98906 0.0170917 0.0612346 -0.00709497 0.997952 1 1.20371e-20 1.20371e-20 6.97728e-09 -3.52362e-11 4.29544e-10 1 1.20371e-20 6.97728e-09 -3.52362e-11 4.29544e-10 1 6.97728e-09 -3.52362e-11 4.29544e-10 4059.81 3.77187 497.641 3984.92 -0.263972 4060.78 +EDGE_SE3:QUAT 1199 1249 -0.86151 0.185839 -6.09636 0.116971 -0.216787 -0.0286067 0.968764 1 4.81482e-20 4.81482e-20 3.07365e-09 -2.15569e-09 -1.47148e-08 1 4.81482e-20 3.07365e-09 -2.15569e-09 -1.47148e-08 1 3.07365e-09 -2.15569e-09 -1.47148e-08 4721.81 -204.866 -1926.52 3859.69 194.781 4773.27 +EDGE_SE3:QUAT 1198 1249 -1.62836 12.042 -6.41213 0.122555 0.180849 -0.180713 0.958967 1 7.70372e-19 7.70372e-19 1.2731e-08 3.39939e-09 5.82131e-08 1 7.70372e-19 1.2731e-08 3.39939e-09 5.82131e-08 1 1.2731e-08 3.39939e-09 5.82131e-08 4692.51 -44.4285 1891.5 3839.13 -104.504 4621.96 +EDGE_SE3:QUAT 1199 1248 -2.13276 -11.8558 -5.93551 0.0255846 0.101449 -0.0154112 0.994392 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4168.91 7.98939 845.897 3958.43 -0.543982 4170.58 +EDGE_SE3:QUAT 1200 1250 -0.779184 -0.271357 -6.03459 0.0561916 0.238869 0.0411258 0.968552 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5020.24 175.692 2280.12 3801.22 174.409 5026.11 +EDGE_SE3:QUAT 1199 1250 -1.57122 12.3494 -6.68129 -0.0079837 -0.0998884 0.000848336 0.994966 1 1.95649e-19 1.95649e-19 3.49747e-09 2.76283e-08 -5.62918e-10 1 1.95649e-19 3.49747e-09 2.76283e-08 -5.62918e-10 1 3.49747e-09 2.76283e-08 -5.62918e-10 4164.23 3.86607 -827.64 3960.12 -2.39494 4164.48 +EDGE_SE3:QUAT 1200 1249 -1.63711 -12.0812 -5.67529 -0.00665298 0.108185 -0.0806654 0.99083 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4186.84 -26.6775 884.934 3956.85 -41.7948 4160.99 +EDGE_SE3:QUAT 1201 1251 -1.19642 -0.472499 -6.15775 0.30234 0.113914 0.0240587 0.946063 1 1.92593e-19 1.92593e-19 2.40346e-09 -2.61568e-08 8.70345e-09 1 1.92593e-19 2.40346e-09 -2.61568e-08 8.70345e-09 1 2.40346e-09 -2.61568e-08 8.70345e-09 3757.26 115.467 720.052 3993.59 77.8537 4120.58 +EDGE_SE3:QUAT 1200 1251 -1.21889 12.2492 -6.22408 -0.0370983 0.0528122 0.107258 0.992134 1 1.92593e-19 1.92593e-19 1.66015e-09 -7.02959e-10 2.77244e-08 1 1.92593e-19 1.66015e-09 -7.02959e-10 2.77244e-08 1 1.66015e-09 -7.02959e-10 2.77244e-08 4048.39 -0.756381 467.526 3986.46 23.6921 4007.87 +EDGE_SE3:QUAT 1201 1250 -1.40524 -12.7022 -5.96921 0.0614813 -0.0563604 -0.100396 0.991445 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.63 -16.539 -370.253 3993.47 21.1804 3993.43 +EDGE_SE3:QUAT 1202 1252 -0.953629 0.239222 -6.11849 -0.0387954 -0.135058 -0.0580054 0.988377 1 8.1852e-19 8.1852e-19 -1.69966e-08 -5.41809e-08 6.67187e-10 1 8.1852e-19 -1.69966e-08 -5.41809e-08 6.67187e-10 1 -1.69966e-08 -5.41809e-08 6.67187e-10 4315 -1.20423 -1177.78 3924.27 21.9565 4307.56 +EDGE_SE3:QUAT 1201 1252 -2.17779 12.2598 -6.6105 -0.0612459 -0.00434709 0.189168 0.980023 1 8.19273e-19 8.19273e-19 1.28924e-08 4.15965e-09 -5.42592e-08 1 8.19273e-19 1.28924e-08 4.15965e-09 -5.42592e-08 1 1.28924e-08 4.15965e-09 -5.42592e-08 3987.15 -4.21853 102.681 3998.63 14.0435 3859.01 +EDGE_SE3:QUAT 1202 1251 -1.7597 -12.4602 -6.30915 0.0690861 -0.085367 -0.150614 0.982474 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.16 -36.5494 -538.095 3988.86 47.6069 3979.52 +EDGE_SE3:QUAT 1203 1253 -0.891187 -0.25786 -6.62508 -0.0415185 0.0372963 -0.134302 0.989368 1 4.81482e-20 4.81482e-20 1.90365e-09 1.37248e-08 6.94312e-10 1 4.81482e-20 1.90365e-09 1.37248e-08 6.94312e-10 1 1.90365e-09 1.37248e-08 6.94312e-10 4005.41 -7.10734 223.91 3997.89 -14.4044 3940.16 +EDGE_SE3:QUAT 1202 1253 -1.74495 12.3245 -6.64554 0.0545762 -0.0992839 0.0443618 0.99257 1 2.40741e-19 2.40741e-19 1.31253e-08 2.8043e-08 -2.75621e-09 1 2.40741e-19 1.31253e-08 2.8043e-08 -2.75621e-09 1 1.31253e-08 2.8043e-08 -2.75621e-09 4160.8 -14.3117 -848.959 3957.9 -6.79652 4164.84 +EDGE_SE3:QUAT 1203 1252 -1.84614 -12.1794 -6.03537 0.00581754 -0.130892 -0.275046 0.952462 1 1.92593e-19 1.92593e-19 7.9174e-09 2.63527e-08 -2.10528e-09 1 1.92593e-19 7.9174e-09 2.63527e-08 -2.10528e-09 1 7.9174e-09 2.63527e-08 -2.10528e-09 4212.48 -104.37 -950.339 3976.82 148.337 3910.01 +EDGE_SE3:QUAT 1204 1254 -1.22749 -0.212816 -6.2774 0.0443534 -0.182881 -0.176044 0.966228 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4439.05 -176.414 -1412.59 3934.51 194.327 4322.95 +EDGE_SE3:QUAT 1203 1254 -1.96534 12.1375 -6.28374 0.0106274 0.0429977 0.0270945 0.998651 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.62 3.03857 342.234 3992.86 5.1753 4026.13 +EDGE_SE3:QUAT 1204 1253 -2.14044 -12.424 -5.97984 -0.0490284 0.111591 -0.154432 0.980456 1 9.62965e-19 9.62965e-19 3.28353e-08 -9.42205e-09 5.80168e-08 1 9.62965e-19 3.28353e-08 -9.42205e-09 5.80168e-08 1 3.28353e-08 -9.42205e-09 5.80168e-08 4140.04 -59.3124 789.966 3973.66 -76.9901 4054.25 +EDGE_SE3:QUAT 1205 1255 -0.894469 -0.115989 -5.8862 -0.144742 -0.0206255 -0.0225646 0.988997 1 1.20371e-20 1.20371e-20 1.82089e-10 9.99176e-10 -6.87116e-09 1 1.20371e-20 1.82089e-10 9.99176e-10 -6.87116e-09 1 1.82089e-10 9.99176e-10 -6.87116e-09 3926.04 14.9751 -198.834 3997.44 0.375515 4007.8 +EDGE_SE3:QUAT 1204 1255 -1.81223 12.3945 -6.53282 0.0251685 -0.106506 -0.0422362 0.993096 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4177.97 -23.949 -868.697 3957.59 27.4257 4173.37 +EDGE_SE3:QUAT 1205 1254 -1.41228 -12.2132 -6.22176 0.0183608 0.0414652 -0.0981891 0.994134 1 3.00927e-21 3.00927e-21 -3.46235e-09 3.37681e-10 -1.54073e-10 1 3.00927e-21 -3.46235e-09 3.37681e-10 -1.54073e-10 1 -3.46235e-09 3.37681e-10 -1.54073e-10 4029.16 -1.10306 350.683 3992.45 -16.9939 3991.94 +EDGE_SE3:QUAT 1206 1256 -1.26589 -0.177544 -6.26188 -0.164023 -0.0588189 -0.0520285 0.983326 1 7.70372e-19 7.70372e-19 -5.51235e-08 1.70964e-09 4.05221e-09 1 7.70372e-19 -5.51235e-08 1.70964e-09 4.05221e-09 1 -5.51235e-08 1.70964e-09 4.05221e-09 3969.36 44.5441 -560.55 3980.93 -2.2013 4066.15 +EDGE_SE3:QUAT 1205 1256 -1.5595 11.8917 -6.65661 -0.142526 -0.134288 0.0263894 0.980284 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4176.74 97.3984 -1048.87 3949.84 -75.8056 4255.2 +EDGE_SE3:QUAT 1206 1255 -2.06024 -12.3057 -6.17755 -0.0699758 -0.0508248 0.056297 0.994661 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.9 15.0314 -356.779 3993.25 -13.3501 4018.81 +EDGE_SE3:QUAT 1207 1257 -1.01535 0.223788 -6.52472 0.10464 -0.0690598 0.0654359 0.989949 1 2.40741e-19 2.40741e-19 2.89516e-08 6.52261e-11 -1.61766e-08 1 2.40741e-19 2.89516e-08 6.52261e-11 -1.61766e-08 1 2.89516e-08 6.52261e-11 -1.61766e-08 4054.74 -27.0855 -635.807 3974.99 -7.81847 4081.41 +EDGE_SE3:QUAT 1206 1257 -1.81189 12.0384 -6.56957 -0.175453 0.0272892 0.201184 0.963326 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3965.98 -45.9894 613.564 3969.53 58.6153 3927.21 +EDGE_SE3:QUAT 1207 1256 -1.99471 -12.3625 -5.96927 -0.104339 0.126576 0.0679789 0.984109 1 1.92593e-19 1.92593e-19 2.83555e-08 1.20799e-09 3.95323e-09 1 1.92593e-19 2.83555e-08 1.20799e-09 3.95323e-09 1 2.83555e-08 1.20799e-09 3.95323e-09 4262.97 -40.5836 1149.02 3927.4 -1.52009 4288.03 +EDGE_SE3:QUAT 1208 1258 -1.42066 -0.247591 -6.11213 0.080256 -0.0598379 -0.0867037 0.991192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.3 -20.2524 -388.338 3992.95 21.0349 4006.99 +EDGE_SE3:QUAT 1207 1258 -1.94864 12.6674 -6.17736 0.139082 -0.0903517 0.041184 0.98529 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4074.79 -52.2217 -794.917 3964.17 13.4931 4145.38 +EDGE_SE3:QUAT 1208 1257 -1.73986 -12.2028 -6.14719 0.101761 -0.160354 -0.0846116 0.978147 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4302.55 -124.215 -1224.05 3938.66 121.439 4315.34 +EDGE_SE3:QUAT 1209 1259 -1.12403 -0.0919438 -6.44246 -0.0503715 -0.163643 -0.0956002 0.980584 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4485.5 -25.1083 -1492.75 3887.94 54.3044 4459.09 +EDGE_SE3:QUAT 1208 1259 -1.79386 12.3085 -5.74386 0.160784 0.140767 -0.0536374 0.975426 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4271.78 97.2819 1281.22 3918.02 50.5932 4363.68 +EDGE_SE3:QUAT 1209 1258 -1.60994 -12.3026 -5.87273 -0.0253953 -0.106165 0.0486672 0.992832 1 2.0463e-19 2.0463e-19 -8.57253e-09 2.71558e-08 1.73869e-09 1 2.0463e-19 -8.57253e-09 2.71558e-08 1.73869e-09 1 -8.57253e-09 2.71558e-08 1.73869e-09 4175.42 25.5756 -862.409 3958.41 -30.2904 4168.53 +EDGE_SE3:QUAT 1210 1260 -0.918729 -0.151344 -6.05227 -0.0107975 0.142333 0.156787 0.977263 1 3.00927e-21 3.00927e-21 3.53152e-09 5.79352e-10 5.00586e-10 1 3.00927e-21 3.53152e-09 5.79352e-10 5.00586e-10 1 3.53152e-09 5.79352e-10 5.00586e-10 4330.37 74.8124 1197.2 3932.59 108.068 4232.51 +EDGE_SE3:QUAT 1209 1260 -1.86335 12.2791 -6.44396 0.0987567 -0.00161465 0.205483 0.973664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.99 -13.2619 -247.906 3993.65 -32.4171 3845.11 +EDGE_SE3:QUAT 1210 1259 -1.84845 -12.317 -6.01523 0.0153986 -0.0822807 0.137615 0.986942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4111.88 18.068 -681.219 3974.35 -47.8357 4037.08 +EDGE_SE3:QUAT 1211 1261 -1.13556 -0.144451 -5.90283 0.22059 0.0453186 -0.128143 0.96585 1 1.15556e-18 1.15556e-18 -5.44249e-08 -1.57156e-08 2.75408e-08 1 1.15556e-18 -5.44249e-08 -1.57156e-08 2.75408e-08 1 -5.44249e-08 -1.57156e-08 2.75408e-08 3913.56 71.1143 671.453 3968.37 -20.9287 4042.52 +EDGE_SE3:QUAT 1210 1261 -1.31088 12.1135 -6.43045 -0.0974724 0.0654658 0.211056 0.970396 1 7.70372e-19 7.70372e-19 -5.58446e-09 3.54035e-09 -5.48071e-08 1 7.70372e-19 -5.58446e-09 3.54035e-09 -5.48071e-08 1 -5.58446e-09 3.54035e-09 -5.48071e-08 4095.65 -3.28159 744.938 3965.67 73.4868 3955.47 +EDGE_SE3:QUAT 1211 1260 -1.83677 -12.2249 -6.01067 0.0472514 0.0548081 -0.299644 0.951303 1 1.20371e-20 1.20371e-20 6.66779e-09 -2.07216e-09 5.03811e-10 1 1.20371e-20 6.66779e-09 -2.07216e-09 5.03811e-10 1 6.66779e-09 -2.07216e-09 5.03811e-10 4065.08 -17.9579 549.177 3985.56 -86.2128 3714.86 +EDGE_SE3:QUAT 1212 1262 -1.0587 0.033491 -6.11324 0.244528 0.000162552 -0.090573 0.965403 1 9.62965e-19 9.62965e-19 5.25039e-08 -1.11193e-08 -2.44622e-08 1 9.62965e-19 5.25039e-08 -1.11193e-08 -2.44622e-08 1 5.25039e-08 -1.11193e-08 -2.44622e-08 3775.67 40.8208 255.885 3993.14 -11.8707 3982.03 +EDGE_SE3:QUAT 1211 1262 -1.7767 12.394 -6.25527 0.0628531 0.232821 0.0179817 0.97032 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4978.87 141.481 2228.97 3801.71 137.067 4993.37 +EDGE_SE3:QUAT 1212 1261 -1.8505 -12.5635 -6.26146 -0.0103304 -0.214327 -0.0919704 0.972368 1 3.00927e-21 3.00927e-21 3.71322e-09 -3.68723e-10 -8.11162e-10 1 3.00927e-21 3.71322e-09 -3.68723e-10 -8.11162e-10 1 3.71322e-09 -3.68723e-10 -8.11162e-10 4837.76 -111.72 -2013.81 3828.42 125.036 4804.35 +EDGE_SE3:QUAT 1213 1263 -1.22675 -0.192288 -6.22286 0.0494848 0.0503731 -0.0565935 0.995897 1 9.62965e-20 9.62965e-20 -1.46195e-08 -1.31038e-08 -1.66756e-10 1 9.62965e-20 -1.46195e-08 -1.31038e-08 -1.66756e-10 1 -1.46195e-08 -1.31038e-08 -1.66756e-10 4037.54 7.47315 437.784 3987.91 -9.60382 4034.52 +EDGE_SE3:QUAT 1212 1263 -1.87687 12.0338 -6.39717 0.0237504 -0.0891546 -0.083784 0.992203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4116.12 -24.3124 -698.371 3973.15 35.5446 4090.3 +EDGE_SE3:QUAT 1213 1262 -1.90387 -12.1775 -6.35045 -0.0495383 0.174892 -0.022776 0.983077 1 1.92593e-19 1.92593e-19 -2.90134e-08 1.24743e-09 -5.05696e-09 1 1.92593e-19 -2.90134e-08 1.24743e-09 -5.05696e-09 1 -2.90134e-08 1.24743e-09 -5.05696e-09 4510.67 -69.2213 1533.93 3885.62 -64.4169 4518.41 +EDGE_SE3:QUAT 1214 1264 -1.23078 -0.175441 -6.54497 0.0115808 -0.0997315 -0.0354263 0.994316 1 1.95602e-19 1.95602e-19 -2.45085e-09 2.77308e-08 -1.77048e-10 1 1.95602e-19 -2.45085e-09 2.77308e-08 -1.77048e-10 1 -2.45085e-09 2.77308e-08 -1.77048e-10 4160.64 -13.988 -818.952 3961.41 18.8479 4156.15 +EDGE_SE3:QUAT 1213 1264 -1.94555 12.2283 -6.37476 0.00027597 0.121953 0.0710201 0.989992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4244.88 27.1497 1019.56 3943.21 41.9317 4224.7 +EDGE_SE3:QUAT 1214 1263 -1.61498 -12.0581 -6.00536 -0.0958668 -0.00909566 0.023293 0.99508 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3963.72 1.73979 -45.0834 3999.93 -0.511515 3998.32 +EDGE_SE3:QUAT 1215 1265 -0.771858 0.152551 -6.2891 -0.0495857 -0.127939 -0.0267666 0.99018 1 4.81482e-20 4.81482e-20 1.42189e-08 -2.08982e-10 -1.86482e-09 1 4.81482e-20 1.42189e-08 -2.08982e-10 -1.86482e-09 1 1.42189e-08 -2.08982e-10 -1.86482e-09 4272.15 20.5347 -1098.84 3933.12 -4.19047 4279.12 +EDGE_SE3:QUAT 1214 1265 -1.52663 12.2529 -6.39094 0.132314 0.103307 -0.0154878 0.985688 1 1.88079e-22 1.88079e-22 9.19855e-11 1.17024e-10 8.74059e-10 1 1.88079e-22 9.19855e-11 1.17024e-10 8.74059e-10 1 9.19855e-11 1.17024e-10 8.74059e-10 4107.6 59.4162 861.444 3960.12 28.7941 4176.66 +EDGE_SE3:QUAT 1215 1264 -1.80395 -12.3273 -6.23173 -0.0488487 -0.0431997 -0.00597201 0.997854 1 4.81482e-20 4.81482e-20 -1.39007e-08 2.42197e-11 6.07028e-10 1 4.81482e-20 -1.39007e-08 2.42197e-11 6.07028e-10 1 -1.39007e-08 2.42197e-11 6.07028e-10 4020.88 8.46757 -350.168 3992.48 -1.16457 4030.28 +EDGE_SE3:QUAT 1216 1266 -0.857121 -0.0927063 -6.39958 -0.184093 -0.0848657 -0.072431 0.976556 1 9.62965e-19 9.62965e-19 5.4306e-08 -2.92925e-08 -1.07527e-08 1 9.62965e-19 5.4306e-08 -2.92925e-08 -1.07527e-08 1 5.4306e-08 -2.92925e-08 -1.07527e-08 4028.69 69.9552 -827.443 3960.74 -9.64552 4143.27 +EDGE_SE3:QUAT 1215 1266 -1.96894 11.8371 -6.1601 0.0817601 0.0064607 0.116514 0.989797 1 3.85374e-19 3.85374e-19 2.72238e-08 4.61039e-09 2.71935e-08 1 3.85374e-19 2.72238e-08 4.61039e-09 2.71935e-08 1 2.72238e-08 4.61039e-09 2.71935e-08 3973.89 -4.08555 -62.6552 3999.36 -5.86201 3946.33 +EDGE_SE3:QUAT 1216 1265 -2.01971 -12.458 -6.44485 0.0651103 0.106727 0.15016 0.980725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4107.64 56.1946 719.665 3979.29 69.4848 4034.41 +EDGE_SE3:QUAT 1217 1267 -0.92079 0.278471 -6.18418 0.0968012 0.0561121 0.0583105 0.992008 1 8.1852e-19 8.1852e-19 -5.43611e-08 -1.75706e-08 -9.86698e-10 1 8.1852e-19 -5.43611e-08 -1.75706e-08 -9.86698e-10 1 -5.43611e-08 -1.75706e-08 -9.86698e-10 3997.26 20.8043 375.432 3993.1 16.1028 4021.14 +EDGE_SE3:QUAT 1216 1267 -1.70228 11.7907 -6.28178 -0.0491895 0.0631528 0.0252408 0.996471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4058.24 -11.0264 525.626 3983.12 1.97347 4065.37 +EDGE_SE3:QUAT 1217 1266 -1.80623 -12.2548 -6.05033 0.186116 0.0181031 -0.063932 0.980278 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3880.16 28.6575 276.983 3994.08 -5.99893 4002.37 +EDGE_SE3:QUAT 1218 1268 -1.33449 0.336793 -6.16727 -0.0393491 -0.0238708 -0.0406605 0.998112 1 6.01853e-20 6.01853e-20 -1.05464e-10 6.40761e-09 1.41296e-08 1 6.01853e-20 -1.05464e-10 6.40761e-09 1.41296e-08 1 -1.05464e-10 6.40761e-09 1.41296e-08 4004.77 3.6293 -209.743 3997.13 3.79255 4004.35 +EDGE_SE3:QUAT 1217 1268 -2.13854 12.0994 -6.3053 0.032865 0.0549615 0.221383 0.973082 1 4.81482e-20 4.81482e-20 3.12785e-09 -1.34915e-08 7.43195e-10 1 4.81482e-20 3.12785e-09 -1.34915e-08 7.43195e-10 1 3.12785e-09 -1.34915e-08 7.43195e-10 4021.13 15.1359 323.722 3996.92 33.7229 3829.41 +EDGE_SE3:QUAT 1218 1267 -1.84485 -12.2682 -6.47123 -0.0358628 -0.0835449 -0.1217 0.988394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4122.07 -8.9376 -724.641 3969.57 41.5316 4067.97 +EDGE_SE3:QUAT 1219 1269 -0.952509 -0.216728 -6.38711 -0.0104695 -0.0260967 -0.101239 0.994465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.49 -0.618169 -218.761 3997.06 11.1328 3970.93 +EDGE_SE3:QUAT 1218 1269 -2.02738 12.2086 -6.46306 -0.0327774 -0.106013 0.277186 0.954387 1 3.12964e-18 3.12964e-18 -2.14474e-08 -1.37024e-08 1.08437e-07 1 3.12964e-18 -2.14474e-08 -1.37024e-08 1.08437e-07 1 -2.14474e-08 -1.37024e-08 1.08437e-07 4098.68 63.5637 -657.398 3992.53 -96.085 3795.65 +EDGE_SE3:QUAT 1219 1268 -2.14444 -11.8828 -5.89015 -0.0107444 0.0696894 -0.0931057 0.993156 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.88 -13.598 546.665 3983.09 -27.6274 4038.67 +EDGE_SE3:QUAT 1220 1270 -1.14269 -0.0822978 -5.99434 -0.0704637 -0.111377 -0.0650127 0.989143 1 4.81482e-20 4.81482e-20 -1.69389e-09 -8.13676e-10 1.41159e-08 1 4.81482e-20 -1.69389e-09 -8.13676e-10 1.41159e-08 1 -1.69389e-09 -8.13676e-10 1.41159e-08 4208.08 17.5775 -981.759 3944.83 12.6075 4211.03 +EDGE_SE3:QUAT 1219 1270 -2.23671 12.1473 -6.22007 0.0313245 0.0341452 -0.148816 0.987779 1 6.01853e-20 6.01853e-20 -8.91431e-09 -1.26903e-08 -1.40701e-11 1 6.01853e-20 -8.91431e-09 -1.26903e-08 -1.40701e-11 1 -8.91431e-09 -1.26903e-08 -1.40701e-11 4021.61 -0.0833978 320.799 3993.53 -24.2414 3936.95 +EDGE_SE3:QUAT 1220 1269 -1.88524 -12.2992 -5.82872 0.0717073 -0.112675 0.00727098 0.991014 1 1.93016e-19 1.93016e-19 -2.83756e-08 3.53722e-10 4.52857e-09 1 1.93016e-19 -2.83756e-08 3.53722e-10 4.52857e-09 1 -2.83756e-08 3.53722e-10 4.52857e-09 4190.24 -35.9898 -942.166 3950.45 19.3997 4210.6 +EDGE_SE3:QUAT 1221 1271 -1.11647 -0.237581 -6.13021 0.0377954 -0.0439294 0.0492456 0.997104 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.06 -4.8409 -374.635 3991.15 -7.6576 4025.08 +EDGE_SE3:QUAT 1220 1271 -2.008 12.0645 -6.31966 0.100048 0.144068 0.00652403 0.984476 1 1.92593e-19 1.92593e-19 -2.8465e-08 -1.04877e-09 -4.03862e-09 1 1.92593e-19 -2.8465e-08 -1.04877e-09 -4.03862e-09 1 -2.8465e-08 -1.04877e-09 -4.03862e-09 4297.04 76.7987 1209.21 3926.43 58.2032 4336.91 +EDGE_SE3:QUAT 1221 1270 -1.71182 -12.3081 -6.00249 -0.151964 0.162494 -0.143068 0.964383 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4133.84 -144.21 989.417 3982.52 -143.28 4144.34 +EDGE_SE3:QUAT 1222 1272 -1.01652 0.167133 -6.15554 -0.0388229 0.0144326 -0.126439 0.991109 1 4.81482e-20 4.81482e-20 1.37555e-08 -1.76544e-09 5.81893e-11 1 4.81482e-20 1.37555e-08 -1.76544e-09 5.81893e-11 1 1.37555e-08 -1.76544e-09 5.81893e-11 3994.6 -0.869324 54.2124 3999.95 -2.19131 3936.68 +EDGE_SE3:QUAT 1221 1272 -1.96618 12.1101 -6.34627 0.138918 0.121967 0.111615 0.976406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.02 81.8556 762.225 3981.66 78.1226 4088.38 +EDGE_SE3:QUAT 1222 1271 -1.92219 -12.5094 -6.1787 -0.022279 -0.0173409 -0.0929131 0.995274 1 1.20371e-20 1.20371e-20 6.39216e-10 6.90661e-09 1.29766e-10 1 1.20371e-20 6.39216e-10 6.90661e-09 1.29766e-10 1 6.39216e-10 6.90661e-09 1.29766e-10 4004.53 1.03557 -161.775 3998.26 7.69368 3971.99 +EDGE_SE3:QUAT 1223 1273 -1.40297 0.120076 -6.1619 0.0705713 -0.126142 -0.012167 0.989424 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4237.08 -47.741 -1046 3941.27 35.7226 4256.4 +EDGE_SE3:QUAT 1222 1273 -1.72563 12.4402 -6.68503 -0.0714573 -0.00491959 0.0361524 0.996776 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.56 -0.0810439 -8.11005 4000 0.0367271 3994.76 +EDGE_SE3:QUAT 1223 1272 -2.22502 -11.9772 -6.16349 -0.322487 0.0379061 0.0905958 0.941466 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3668.83 -105.22 591.848 3977.98 -3.28993 4051.99 +EDGE_SE3:QUAT 1224 1274 -0.853602 0.25013 -6.33315 -0.023691 0.0878883 -0.113596 0.989348 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4107.48 -28.0991 671.843 3976.3 -44.3047 4058.11 +EDGE_SE3:QUAT 1223 1274 -2.28439 12.0464 -6.21569 -0.0737465 0.046322 0.100238 0.991145 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.31 -11.0773 455.445 3986.33 19.5415 4010.88 +EDGE_SE3:QUAT 1224 1273 -1.72158 -12.2726 -6.05825 0.141762 0.0820951 -0.0501046 0.985218 1 7.70372e-19 7.70372e-19 5.56106e-08 -1.44123e-09 5.22855e-09 1 7.70372e-19 5.56106e-08 -1.44123e-09 5.22855e-09 1 5.56106e-08 -1.44123e-09 5.22855e-09 4052.45 48.4669 741.057 3968.03 7.24155 4122.79 +EDGE_SE3:QUAT 1225 1275 -1.30014 -0.174815 -6.22083 -0.150628 0.0525475 0.1931 0.968123 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.49 -34.1176 743.898 3961.69 60.4366 3983.1 +EDGE_SE3:QUAT 1224 1275 -1.88281 12.261 -6.45653 -0.0333784 -0.0469837 0.0382533 0.997605 1 4.81482e-20 4.81482e-20 -5.75509e-10 1.38428e-08 5.13769e-10 1 4.81482e-20 -5.75509e-10 1.38428e-08 5.13769e-10 1 -5.75509e-10 1.38428e-08 5.13769e-10 4027.95 7.9832 -361.57 3992.3 -8.62698 4026.56 +EDGE_SE3:QUAT 1225 1274 -1.84204 -12.3137 -6.10154 0.200757 -0.00884023 -0.169167 0.964884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3861.65 43.1511 327.109 3987.19 -35.087 3908.4 +EDGE_SE3:QUAT 1226 1276 -0.789495 0.0293192 -6.54895 0.166759 -0.0287659 0.0149654 0.985464 1 7.70372e-19 7.70372e-19 -5.48143e-08 -2.60709e-10 1.78449e-09 1 7.70372e-19 -5.48143e-08 -2.60709e-10 1.78449e-09 1 -5.48143e-08 -2.60709e-10 1.78449e-09 3904.43 -21.335 -250.829 3996.3 1.89811 4014.77 +EDGE_SE3:QUAT 1225 1276 -2.03861 12.3048 -6.4019 0.0555264 -0.0355413 0.00919157 0.997782 1 4.89006e-20 4.89006e-20 -9.10379e-12 1.37517e-08 -2.49881e-09 1 4.89006e-20 -9.10379e-12 1.37517e-08 -2.49881e-09 1 -9.10379e-12 1.37517e-08 -2.49881e-09 4008.65 -7.9291 -290.439 3994.78 0.381068 4020.64 +EDGE_SE3:QUAT 1226 1275 -2.01935 -12.3998 -5.60269 0.114814 0.0192682 0.00360488 0.993194 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3952.61 8.30832 146.346 3998.79 1.20996 4005.29 +EDGE_SE3:QUAT 1227 1277 -1.00556 0.118848 -6.21537 0.0373859 -0.0270797 0.130012 0.990437 1 8.1852e-19 8.1852e-19 -1.5765e-08 -1.53995e-10 5.56034e-08 1 8.1852e-19 -1.5765e-08 -1.53995e-10 5.56034e-08 1 -1.5765e-08 -1.53995e-10 5.56034e-08 4012.43 -2.15013 -269.536 3995.17 -17.8964 3950.41 +EDGE_SE3:QUAT 1226 1277 -1.63874 12.0493 -6.37912 -0.00636034 -0.0949845 0.00476733 0.995447 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4148.02 3.80858 -784.006 3963.98 -3.48476 4148.09 +EDGE_SE3:QUAT 1227 1276 -1.52238 -12.1094 -6.09482 -0.0714855 -0.0769463 -0.096696 0.989757 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4099.71 10.8361 -703.863 3969.71 25.0712 4082.75 +EDGE_SE3:QUAT 1228 1278 -1.14371 -0.0570427 -5.92056 0.0316896 0.0200647 -0.0865453 0.995542 1 1.20371e-20 1.20371e-20 -6.91591e-09 5.9176e-10 -1.75002e-10 1 1.20371e-20 -6.91591e-09 5.9176e-10 -1.75002e-10 1 -6.91591e-09 5.9176e-10 -1.75002e-10 4005.12 2.10412 191.627 3997.53 -8.37445 3979.18 +EDGE_SE3:QUAT 1227 1278 -2.02982 12.4764 -6.1083 0.21726 -0.274927 0.21683 0.911152 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 6094.01 -3.92121 -3787.46 3609.51 -0.420652 6094.76 +EDGE_SE3:QUAT 1228 1277 -1.61323 -12.367 -5.62049 0.000872896 0.0488295 0.0386289 0.998059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.17 2.40177 392.601 3990.61 7.81477 4032.2 +EDGE_SE3:QUAT 1229 1279 -1.02081 0.0778618 -5.97555 0.00544346 -0.0813776 0.079152 0.993521 1 4.70198e-23 4.70198e-23 4.36673e-10 3.48643e-11 -3.56948e-11 1 4.70198e-23 4.36673e-10 3.48643e-11 -3.56948e-11 1 4.36673e-10 3.48643e-11 -3.56948e-11 4107.66 11.0669 -665.383 3974.31 -27.2786 4082.72 +EDGE_SE3:QUAT 1228 1279 -2.17378 12.2317 -5.91973 0.0670129 -0.118578 -0.0101487 0.990629 1 1.92593e-19 1.92593e-19 7.36499e-10 2.74871e-08 -1.98056e-09 1 1.92593e-19 7.36499e-10 2.74871e-08 -1.98056e-09 1 7.36499e-10 2.74871e-08 -1.98056e-09 4209.12 -41.0908 -979.763 3947.5 29.336 4226.67 +EDGE_SE3:QUAT 1229 1278 -2.12203 -12.2665 -5.92749 -0.000707624 0.136841 0.133695 0.981529 1 1.20371e-20 1.20371e-20 7.06609e-09 9.9853e-10 9.49951e-10 1 1.20371e-20 7.06609e-09 9.9853e-10 9.49951e-10 1 7.06609e-09 9.9853e-10 9.49951e-10 4299.81 63.1532 1135.58 3936.85 89.9808 4228.31 +EDGE_SE3:QUAT 1230 1280 -1.46896 -0.337279 -6.25633 0.0404139 -0.0788443 -0.117593 0.989102 1 1.92593e-19 1.92593e-19 3.46552e-09 2.74284e-08 -1.61719e-09 1 1.92593e-19 3.46552e-09 2.74284e-08 -1.61719e-09 1 3.46552e-09 2.74284e-08 -1.61719e-09 4072.45 -26.7163 -568.329 3983.85 39.1143 4023.67 +EDGE_SE3:QUAT 1229 1280 -1.76283 12.3141 -6.56962 -0.0811509 -0.0119072 0.056692 0.995017 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.95 0.873434 -39.0041 3999.98 -0.65099 3987.43 +EDGE_SE3:QUAT 1230 1279 -1.83172 -11.958 -6.43245 -0.113027 -0.0963514 -0.0878105 0.985003 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4143.95 33.7169 -904.926 3951.73 13.3493 4164.21 +EDGE_SE3:QUAT 1231 1281 -1.07537 -0.160265 -6.18389 0.118491 0.0459486 -0.107412 0.986058 1 1.92593e-19 1.92593e-19 -1.92733e-09 -2.98295e-09 -2.75923e-08 1 1.92593e-19 -1.92733e-09 -2.98295e-09 -2.75923e-08 1 -1.92733e-09 -2.98295e-09 -2.75923e-08 4007.94 24.7651 511.986 3982.08 -20.612 4017.95 +EDGE_SE3:QUAT 1230 1281 -2.0642 12.3167 -6.48693 0.0787052 0.0726698 0.0184961 0.994074 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4054.18 25.4877 567.607 3981.72 15.0804 4077.59 +EDGE_SE3:QUAT 1231 1280 -1.96964 -12.1085 -6.1083 0.0115727 0.0171686 0.104782 0.99428 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.09 1.27894 120.706 3999.22 6.11392 3959.71 +EDGE_SE3:QUAT 1232 1282 -1.02712 -0.236611 -6.34624 0.0410402 0.0673943 0.108219 0.990991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.08 19.7901 480.737 3988.19 29.7156 4009.97 +EDGE_SE3:QUAT 1231 1282 -1.96216 12.1786 -6.15154 0.0766581 -0.0846435 0.00589195 0.993441 1 1.05794e-22 1.05794e-22 5.58015e-11 -5.06682e-11 -6.55689e-10 1 1.05794e-22 5.58015e-11 -5.06682e-11 -6.55689e-10 1 5.58015e-11 -5.06682e-11 -6.55689e-10 4093.44 -27.5638 -693.891 3972.11 11.4745 4116.81 +EDGE_SE3:QUAT 1232 1281 -1.80677 -11.9596 -5.92779 -0.0255315 0.0335037 -0.099245 0.994171 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.02 -5.05789 234.227 3997.09 -11.7294 3974.23 +EDGE_SE3:QUAT 1233 1283 -1.03837 0.245522 -6.10629 0.0505515 0.0825665 -0.0483464 0.994128 1 4.81482e-20 4.81482e-20 -1.40028e-08 5.68594e-10 -1.22134e-09 1 4.81482e-20 -1.40028e-08 5.68594e-10 -1.22134e-09 1 -1.40028e-08 5.68594e-10 -1.22134e-09 4109.87 10.6315 703.452 3970.31 -9.39129 4110.74 +EDGE_SE3:QUAT 1232 1283 -1.83395 12.105 -5.93985 -0.12022 0.0596718 0.0428792 0.990024 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.65 -30.1855 535.704 3982.41 -0.0310548 4063.11 +EDGE_SE3:QUAT 1233 1282 -2.08364 -12.0655 -6.17073 0.126592 -0.0219666 -0.119051 0.98454 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3934.96 4.56263 9.45178 3999.69 -4.28789 3942.37 +EDGE_SE3:QUAT 1234 1284 -1.19154 0.0109491 -6.35223 -0.037228 -0.0933542 0.0985978 0.990039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4115.87 32.9897 -707.801 3973.86 -44.1211 4082.53 +EDGE_SE3:QUAT 1233 1284 -2.19665 12.2556 -6.22502 0.146719 0.0726775 0.0863428 0.982719 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3954.19 33.3422 408.859 3994.58 26.9111 4010.48 +EDGE_SE3:QUAT 1234 1283 -1.91298 -12.3433 -5.85182 0.115423 -0.00277176 0.058444 0.991592 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3949.13 -7.26692 -101.731 3998.99 -3.452 3988.76 +EDGE_SE3:QUAT 1235 1285 -1.33165 -0.399291 -5.97447 -0.125145 0.018012 -0.0551319 0.990442 1 4.81482e-20 4.81482e-20 5.08113e-11 -1.75432e-09 1.37463e-08 1 4.81482e-20 5.08113e-11 -1.75432e-09 1.37463e-08 1 5.08113e-11 -1.75432e-09 1.37463e-08 3937.99 -1.96118 58.275 3999.98 -1.08773 3988.48 +EDGE_SE3:QUAT 1234 1285 -1.91374 12.1175 -6.09969 -0.0185423 -0.125527 0.0383277 0.991176 1 1.20371e-20 1.20371e-20 -7.09658e-09 -3.17203e-10 8.84796e-10 1 1.20371e-20 -7.09658e-09 -3.17203e-10 8.84796e-10 1 -7.09658e-09 -3.17203e-10 8.84796e-10 4256.75 26.6742 -1048.41 3939.67 -30.7922 4252.25 +EDGE_SE3:QUAT 1235 1284 -1.99075 -12.1018 -6.40261 -0.000340185 -0.0158718 -0.0736912 0.997155 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.99 -0.421768 -126.351 3999.03 4.6567 3982.27 +EDGE_SE3:QUAT 1236 1286 -1.4191 0.00444724 -6.36221 -0.196935 -0.282326 -0.108918 0.932548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5760.22 301.053 -3366.01 3685.51 -302.843 5867.9 +EDGE_SE3:QUAT 1235 1286 -1.91541 12.4298 -5.96411 0.194892 -0.0331141 -0.00178719 0.980264 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3863.19 -23.7043 -246.665 3997.06 4.8949 4015.11 +EDGE_SE3:QUAT 1236 1285 -2.05208 -12.3146 -5.91207 -0.0461114 0.0767038 -0.0311399 0.9955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4080.95 -18.9218 604.88 3978.89 -16.238 4085.58 +EDGE_SE3:QUAT 1237 1287 -1.16949 -0.300123 -5.92408 0.168284 -0.0521018 -0.0307994 0.983879 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3915.04 -28.4218 -339.272 3995.08 13.057 4024.53 +EDGE_SE3:QUAT 1236 1287 -1.98528 12.262 -6.77393 -0.0197219 0.0370608 0.220275 0.974534 1 3.00927e-21 3.00927e-21 3.39291e-09 7.63698e-10 1.45982e-10 1 3.00927e-21 3.39291e-09 7.63698e-10 1.45982e-10 1 3.39291e-09 7.63698e-10 1.45982e-10 4025.08 5.31728 327.516 3994.23 36.9987 3832.55 +EDGE_SE3:QUAT 1237 1286 -1.91914 -12.4059 -5.95106 0.00774717 0.195455 -0.166942 0.966368 1 7.70372e-19 7.70372e-19 -9.8434e-09 -5.35415e-08 -3.3462e-09 1 7.70372e-19 -9.8434e-09 -5.35415e-08 -3.3462e-09 1 -9.8434e-09 -5.35415e-08 -3.3462e-09 4638.27 -168.167 1721.5 3885.21 -193.649 4527.03 +EDGE_SE3:QUAT 1238 1288 -1.51052 -0.0941243 -6.25472 -0.0557687 -0.156902 0.0873118 0.982165 1 1.92593e-19 1.92593e-19 4.15132e-09 2.49331e-09 -2.84996e-08 1 1.92593e-19 4.15132e-09 2.49331e-09 -2.84996e-08 1 4.15132e-09 2.49331e-09 -2.84996e-08 4354.26 95.499 -1265.97 3926.01 -101.144 4336.21 +EDGE_SE3:QUAT 1237 1288 -2.07143 12.1252 -6.14673 -0.0625693 0.0696805 -0.0184628 0.995434 1 1.92593e-19 1.92593e-19 -2.78839e-08 7.63558e-10 -1.86974e-09 1 1.92593e-19 -2.78839e-08 7.63558e-10 -1.86974e-09 1 -2.78839e-08 7.63558e-10 -1.86974e-09 4058.2 -19.9282 548.57 3982.57 -12.3724 4072.49 +EDGE_SE3:QUAT 1238 1287 -2.20322 -11.9687 -5.78444 -0.0865222 0.0656488 -0.00110767 0.994084 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.01 -23.7856 525.806 3983.92 -9.28161 4067.95 +EDGE_SE3:QUAT 1239 1289 -1.18805 0.198623 -6.30521 -0.0792637 -0.0538147 -0.103539 0.99 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.61 12.8842 -525.542 3982.09 22.1912 4024.86 +EDGE_SE3:QUAT 1238 1289 -2.01451 12.3516 -6.16047 0.0471172 0.10382 -0.0294027 0.993044 1 4.81482e-20 4.81482e-20 -1.40957e-08 2.83797e-10 -1.50474e-09 1 4.81482e-20 -1.40957e-08 2.83797e-10 -1.50474e-09 1 -1.40957e-08 2.83797e-10 -1.50474e-09 4175.23 14.9538 877.69 3955.42 -1.26832 4180.65 +EDGE_SE3:QUAT 1239 1288 -2.06999 -11.9546 -5.92744 0.0802692 0.0949499 -0.0604995 0.990394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4142.3 22.5207 837.084 3958.71 -8.26614 4153.43 +EDGE_SE3:QUAT 1240 1290 -1.08384 0.0269234 -6.16884 -0.127918 -0.0289942 -0.174058 0.975961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.55 24.8487 -481.995 3981.96 41.3719 3934.82 +EDGE_SE3:QUAT 1239 1290 -1.93469 12.1089 -6.50626 0.0142039 0.00816719 0.105904 0.994241 1 3.00927e-21 3.00927e-21 3.4497e-09 3.68145e-10 1.73101e-11 1 3.00927e-21 3.4497e-09 3.68145e-10 1.73101e-11 1 3.4497e-09 3.68145e-10 1.73101e-11 3999.72 0.385379 46.3107 3999.91 2.12854 3955.66 +EDGE_SE3:QUAT 1240 1289 -2.06381 -12.1745 -6.07054 -0.0553503 -0.134226 -0.00489949 0.989392 1 4.83363e-20 4.83363e-20 1.41232e-08 9.63937e-11 -1.03793e-09 1 4.83363e-20 1.41232e-08 9.63937e-11 -1.03793e-09 1 1.41232e-08 9.63937e-11 -1.03793e-09 4291.37 35.4034 -1143.11 3929.24 -22.7958 4303.53 +EDGE_SE3:QUAT 1241 1291 -1.5979 -0.00122816 -6.01777 0.0890986 -0.189101 0.138969 0.967982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4705.29 42.5886 -1868.61 3841.18 -83.3527 4659.8 +EDGE_SE3:QUAT 1240 1291 -1.60058 12.1889 -6.34653 -0.0289293 -0.0825931 -0.0857817 0.992463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4115.79 -4.36664 -700.551 3971.04 27.4481 4089.7 +EDGE_SE3:QUAT 1241 1290 -1.96233 -12.4008 -5.73988 -0.0891976 -0.185931 -0.19284 0.959315 1 8.1852e-19 8.1852e-19 2.12059e-09 -3.49046e-09 5.50036e-08 1 8.1852e-19 2.12059e-09 -3.49046e-09 5.50036e-08 1 2.12059e-09 -3.49046e-09 5.50036e-08 4700.14 -104.916 -1861.11 3852.23 156.286 4583.21 +EDGE_SE3:QUAT 1242 1292 -1.22342 -0.237536 -5.99322 -0.0168428 0.0856458 0.0791149 0.993037 1 1.92593e-19 1.92593e-19 -2.45799e-09 9.08225e-11 -2.7987e-08 1 1.92593e-19 -2.45799e-09 9.08225e-11 -2.7987e-08 1 -2.45799e-09 9.08225e-11 -2.7987e-08 4122.28 8.29704 713.375 3970.3 27.431 4098.38 +EDGE_SE3:QUAT 1241 1292 -2.16881 12.0867 -6.25436 -0.00801524 0.0543721 -0.0243622 0.998191 1 6.31946e-20 6.31946e-20 -3.50758e-09 1.40157e-08 -7.00649e-09 1 6.31946e-20 -3.50758e-09 1.40157e-08 -7.00649e-09 1 -3.50758e-09 1.40157e-08 -7.00649e-09 4046.85 -3.53664 436.636 3988.41 -6.04311 4044.73 +EDGE_SE3:QUAT 1242 1291 -2.13489 -12.1728 -5.84132 -0.0190664 -0.0194055 -0.106719 0.993917 1 2.52778e-19 2.52778e-19 -1.39036e-08 -5.02118e-09 -2.73953e-08 1 2.52778e-19 -1.39036e-08 -5.02118e-09 -2.73953e-08 1 -1.39036e-08 -5.02118e-09 -2.73953e-08 4006.36 0.571255 -177.071 3997.97 9.6649 3962.26 +EDGE_SE3:QUAT 1243 1293 -1.2136 0.112691 -6.1767 0.0822752 0.0816634 -0.0401159 0.992448 1 4.81482e-20 4.81482e-20 -1.22498e-09 -1.07858e-09 -1.39796e-08 1 4.81482e-20 -1.22498e-09 -1.07858e-09 -1.39796e-08 1 -1.22498e-09 -1.07858e-09 -1.39796e-08 4092.92 24.3443 703.177 3970.49 -0.622991 4113.56 +EDGE_SE3:QUAT 1242 1293 -2.09124 12.1608 -6.28945 -0.065424 -0.349766 0.00712407 0.934523 1 8.1852e-19 8.1852e-19 7.46074e-08 6.5151e-09 -4.22566e-08 1 8.1852e-19 7.46074e-08 6.5151e-09 -4.22566e-08 1 7.46074e-08 6.5151e-09 -4.22566e-08 6897.87 403.703 -4489.73 3566.03 -413.698 6914.79 +EDGE_SE3:QUAT 1243 1292 -2.00822 -11.8522 -5.96346 0.0322802 -0.0870389 0.0322017 0.995161 1 1.20371e-20 1.20371e-20 -7.01504e-09 -1.90016e-10 6.25884e-10 1 1.20371e-20 -7.01504e-09 -1.90016e-10 6.25884e-10 1 -7.01504e-09 -1.90016e-10 6.25884e-10 4123.73 -6.51093 -726.596 3968.64 -6.46472 4123.75 +EDGE_SE3:QUAT 1244 1294 -1.183 -0.137417 -6.43926 -0.0744096 -0.0642599 0.0708595 0.992629 1 1.92593e-19 1.92593e-19 2.77219e-08 2.23911e-09 -1.46065e-09 1 1.92593e-19 2.77219e-08 2.23911e-09 -1.46065e-09 1 2.77219e-08 2.23911e-09 -1.46065e-09 4027.06 22.0647 -447.181 3989.82 -21.5696 4029.12 +EDGE_SE3:QUAT 1243 1294 -1.892 12.0468 -6.25068 0.0163305 -0.00917833 0.0968565 0.995122 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.01 -0.516739 -91.272 3999.43 -4.66756 3964.55 +EDGE_SE3:QUAT 1244 1293 -2.23496 -12.2113 -5.75628 -0.103741 0.0236078 0.00668244 0.994302 1 1.92593e-19 1.92593e-19 2.76303e-08 4.64133e-11 6.80208e-10 1 1.92593e-19 2.76303e-08 4.64133e-11 6.80208e-10 1 2.76303e-08 4.64133e-11 6.80208e-10 3966.38 -10.1461 194.48 3997.7 -0.800341 4009.25 +EDGE_SE3:QUAT 1245 1295 -1.50207 0.130543 -6.07892 0.116564 0.0572653 0.109728 0.985441 1 1.92593e-19 1.92593e-19 2.74217e-08 3.35348e-09 8.04003e-10 1 1.92593e-19 2.74217e-08 3.35348e-09 8.04003e-10 1 2.74217e-08 3.35348e-09 8.04003e-10 3965.64 18.3656 289.913 3997.61 17.8263 3971.82 +EDGE_SE3:QUAT 1244 1295 -2.08608 11.9677 -6.10585 -0.125053 0.0555815 0.159597 0.977651 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.53 -25.3921 668.89 3969.88 43.8298 4006.19 +EDGE_SE3:QUAT 1245 1294 -2.27865 -12.0033 -6.21942 0.0600514 -0.0287202 -0.00422452 0.997773 1 6.01853e-20 6.01853e-20 -1.38159e-08 7.02961e-09 -2.97742e-11 1 6.01853e-20 -1.38159e-08 7.02961e-09 -2.97742e-11 1 -1.38159e-08 7.02961e-09 -2.97742e-11 3998.31 -6.88515 -226.097 3996.91 1.6397 4012.67 +EDGE_SE3:QUAT 1246 1296 -1.27589 0.268186 -6.19187 -0.0771288 0.186389 0.00591499 0.979426 1 9.65974e-19 9.65974e-19 -2.85617e-08 5.53693e-08 -4.69452e-09 1 9.65974e-19 -2.85617e-08 5.53693e-08 -4.69452e-09 1 -2.85617e-08 5.53693e-08 -4.69452e-09 4588.46 -83.3359 1680.46 3867.57 -69.2892 4612.11 +EDGE_SE3:QUAT 1245 1296 -2.35969 12.2405 -6.28737 -0.104345 -0.0254181 -0.00924652 0.994173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.66 11.1312 -212.038 3997.25 -0.736092 4010.87 +EDGE_SE3:QUAT 1246 1295 -1.90908 -12.1712 -5.80021 0.0100203 -0.038075 0.0405878 0.9984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.53 -0.132161 -310.311 3994.03 -6.06395 4017.34 +EDGE_SE3:QUAT 1247 1297 -1.48387 -0.0650582 -5.89913 0.0597575 -0.0614911 -0.12188 0.988834 1 1.92593e-19 1.92593e-19 2.7579e-08 -3.60167e-09 -1.2454e-09 1 1.92593e-19 2.7579e-08 -3.60167e-09 -1.2454e-09 1 2.7579e-08 -3.60167e-09 -1.2454e-09 4023.9 -19.1279 -394.468 3993.06 26.6442 3978.76 +EDGE_SE3:QUAT 1246 1297 -2.14495 11.896 -6.13149 0.0701713 -0.0355593 -0.0441376 0.995923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.23 -9.30143 -245.225 3996.8 6.87921 4007.13 +EDGE_SE3:QUAT 1247 1296 -2.06773 -12.3339 -5.87164 0.0207343 0.00754753 0.0915374 0.995557 1 1.20371e-20 1.20371e-20 6.90835e-09 6.36865e-10 2.52235e-11 1 1.20371e-20 6.90835e-09 6.36865e-10 2.52235e-11 1 6.90835e-09 6.36865e-10 2.52235e-11 3998.61 0.362586 36.9423 3999.95 1.34548 3966.81 +EDGE_SE3:QUAT 1248 1298 -1.3016 0.00583224 -5.94636 0.033306 -0.284927 0.0120559 0.957895 1 4.83363e-20 4.83363e-20 1.55811e-08 -8.87017e-11 -3.7326e-09 1 4.83363e-20 1.55811e-08 -8.87017e-11 -3.7326e-09 1 1.55811e-08 -8.87017e-11 -3.7326e-09 5698.94 -63.8863 -3116.89 3676.73 64.0522 5702.79 +EDGE_SE3:QUAT 1247 1298 -1.86173 12.1149 -5.86519 -0.161601 -0.0475247 0.197716 0.965678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3891.1 -13.1821 23.8663 3998.52 16.1845 3839.2 +EDGE_SE3:QUAT 1248 1297 -2.0422 -12.6209 -6.2544 0.00658919 0.141314 -0.191283 0.971287 1 7.82409e-19 7.82409e-19 3.93975e-09 5.52757e-08 1.72055e-09 1 7.82409e-19 3.93975e-09 5.52757e-08 1.72055e-09 1 3.93975e-09 5.52757e-08 1.72055e-09 4309.48 -91.4243 1155.83 3942.98 -129.169 4163.3 +EDGE_SE3:QUAT 1249 1299 -1.17216 0.148847 -5.836 -0.114995 -0.0361927 0.0179743 0.992544 1 2.40741e-19 2.40741e-19 2.72489e-08 1.44902e-08 7.51687e-10 1 2.40741e-19 2.72489e-08 1.44902e-08 7.51687e-10 1 2.72489e-08 1.44902e-08 7.51687e-10 3963.89 15.0221 -259.954 3996.4 -5.35495 4015.5 +EDGE_SE3:QUAT 1248 1299 -2.11793 12.3241 -6.16137 -0.00445324 -0.0146345 0.121897 0.992425 1 3.76158e-21 3.76158e-21 1.29871e-09 3.65493e-09 4.51711e-12 1 3.76158e-21 1.29871e-09 3.65493e-09 4.51711e-12 1 1.29871e-09 3.65493e-09 4.51711e-12 4002.84 0.792237 -108.088 3999.36 -6.43585 3943.48 +EDGE_SE3:QUAT 1249 1298 -2.16342 -12.374 -6.29347 0.00618371 -0.0400173 -0.0605364 0.997344 1 4.81482e-20 4.81482e-20 -5.4249e-10 1.53205e-10 1.38838e-08 1 4.81482e-20 -5.4249e-10 1.53205e-10 1.38838e-08 1 -5.4249e-10 1.53205e-10 1.38838e-08 4024.59 -3.26271 -315.555 3994.02 9.87832 4010.08 +EDGE_SE3:QUAT 1250 1300 -1.55054 0.302846 -6.21056 -0.183864 0.103253 0.00312227 0.977509 1 7.70372e-19 7.70372e-19 -5.53815e-08 1.9803e-09 -5.51126e-09 1 7.70372e-19 -5.53815e-08 1.9803e-09 -5.51126e-09 1 -5.53815e-08 1.9803e-09 -5.51126e-09 4025.64 -81.7607 818.547 3968.43 -45.5975 4160.83 +EDGE_SE3:QUAT 1249 1300 -2.01983 12.0414 -6.24392 -0.0299862 -0.0308563 -0.0236412 0.998794 1 1.20371e-20 1.20371e-20 -6.94464e-09 1.51526e-10 2.23793e-10 1 1.20371e-20 -6.94464e-09 1.51526e-10 2.23793e-10 1 -6.94464e-09 1.51526e-10 2.23793e-10 4012.69 3.34322 -255.74 3995.88 2.36178 4014.05 +EDGE_SE3:QUAT 1250 1299 -2.29516 -12.4104 -5.88921 0.0879708 -0.0194011 0.0726197 0.993283 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.97 -9.97981 -228.948 3996.13 -7.76125 3991.84 +EDGE_SE3:QUAT 1251 1301 -1.38498 -0.00701265 -6.16998 -0.0391294 -0.0698159 -0.0805969 0.993528 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4082.31 2.03856 -601.369 3978.01 20.8589 4062.45 +EDGE_SE3:QUAT 1250 1301 -2.26411 12.0345 -6.16199 -0.149865 -0.00714503 -0.0296764 0.988235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3913 9.26449 -107.792 3999.07 1.32572 3999.32 +EDGE_SE3:QUAT 1251 1300 -2.33753 -12.1236 -6.04771 0.00414532 -0.0273031 0.112858 0.993227 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.04 1.59862 -220.416 3997.12 -12.4881 3961.16 +EDGE_SE3:QUAT 1252 1302 -1.78055 -0.0445061 -6.24471 0.00468173 0.0735636 0.0815942 0.993936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4084.74 12.0547 588.658 3980.01 25.8338 4058.19 +EDGE_SE3:QUAT 1251 1302 -1.79695 12.5572 -6.24007 0.109044 -0.120207 -0.0817471 0.98335 1 1.92593e-19 1.92593e-19 -3.00312e-09 -2.72224e-08 3.60981e-09 1 1.92593e-19 -3.00312e-09 -2.72224e-08 3.60981e-09 1 -3.00312e-09 -2.72224e-08 3.60981e-09 4127.3 -74.3394 -856.27 3968.04 69.7278 4148.13 +EDGE_SE3:QUAT 1252 1301 -1.81751 -12.4849 -6.14196 -0.101367 0.17082 -0.157197 0.967385 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4270.47 -158.298 1165.46 3963.35 -165.161 4212.73 +EDGE_SE3:QUAT 1253 1303 -1.66213 0.269253 -5.93858 0.100227 -0.0199259 0.144534 0.984209 1 7.70372e-19 7.70372e-19 2.63192e-09 -5.03999e-09 -5.48141e-08 1 7.70372e-19 2.63192e-09 -5.03999e-09 -5.48141e-08 1 2.63192e-09 -5.03999e-09 -5.48141e-08 3985.36 -14.6776 -324.529 3991.56 -24.5689 3941.98 +EDGE_SE3:QUAT 1252 1303 -2.06695 12.3032 -6.49347 0.0615615 0.200792 0.103063 0.97225 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4598.43 178.986 1683.55 3890.93 184.406 4571.1 +EDGE_SE3:QUAT 1253 1302 -2.45495 -11.8512 -5.84233 -0.0789341 0.0577938 0.116919 0.988311 1 3.85186e-19 3.85186e-19 2.97785e-08 1.21561e-09 2.97785e-08 1 3.85186e-19 2.97785e-08 1.21561e-09 2.97785e-08 1 2.97785e-08 1.21561e-09 2.97785e-08 4054.2 -11.6623 568.763 3979.21 27.8217 4024.44 +EDGE_SE3:QUAT 1254 1304 -1.5722 0.140716 -6.03722 -0.0213239 0.201621 0.0942875 0.974682 1 6.77085e-21 6.77085e-21 5.52716e-09 5.30215e-10 1.14531e-09 1 6.77085e-21 5.52716e-09 5.30215e-10 1.14531e-09 1 5.52716e-09 5.30215e-10 1.14531e-09 4740.62 85.0744 1876.43 3843.59 102.499 4706.88 +EDGE_SE3:QUAT 1253 1304 -2.04919 12.3577 -5.93572 -0.00647632 0.0191022 0.184236 0.982675 1 1.22251e-20 1.22251e-20 2.13065e-09 -6.65899e-09 2.36033e-11 1 1.22251e-20 2.13065e-09 -6.65899e-09 2.36033e-11 1 2.13065e-09 -6.65899e-09 2.36033e-11 4006.17 1.22683 159.32 3998.59 14.8703 3870.56 +EDGE_SE3:QUAT 1254 1303 -2.29992 -12.3775 -5.85446 0.147283 -0.054169 -0.155646 0.975268 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3915.18 -4.92979 -135.98 4000.67 4.95149 3905.05 +EDGE_SE3:QUAT 1255 1305 -1.64971 0.058355 -6.18311 0.00295347 -0.00787893 -0.110285 0.993864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.81 -0.228667 -58.0171 3999.81 3.11184 3952.19 +EDGE_SE3:QUAT 1254 1305 -2.42855 12.0981 -6.20386 0.0320068 -0.0998633 0.111721 0.988191 1 2.0463e-19 2.0463e-19 4.04674e-09 1.02693e-09 2.72931e-08 1 2.0463e-19 4.04674e-09 1.02693e-09 2.72931e-08 1 4.04674e-09 1.02693e-09 2.72931e-08 4172.24 14.47 -858.163 3958.39 -45.2351 4126.41 +EDGE_SE3:QUAT 1255 1304 -2.38246 -12.0637 -6.25436 0.173607 0.0487519 -0.127529 0.975305 1 7.70372e-19 7.70372e-19 5.48282e-08 -5.84973e-09 4.93545e-09 1 7.70372e-19 5.48282e-08 -5.84973e-09 4.93545e-09 1 5.48282e-08 -5.84973e-09 4.93545e-09 3977.36 48.43 636.836 3971.82 -25.2802 4032.86 +EDGE_SE3:QUAT 1256 1306 -1.50564 -0.231968 -6.35847 -0.219232 0.030995 -0.0100335 0.975129 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3818.14 -21.2073 205.092 3998.37 -4.83121 4009.99 +EDGE_SE3:QUAT 1255 1306 -2.3743 12.0026 -6.09162 -0.156042 -0.0166518 0.0100648 0.987559 1 6.01853e-21 6.01853e-21 9.52392e-11 -2.88318e-09 -3.97026e-09 1 6.01853e-21 9.52392e-11 -2.88318e-09 -3.97026e-09 1 9.52392e-11 -2.88318e-09 -3.97026e-09 3905.6 8.02418 -109.877 3999.44 -1.29721 4002.59 +EDGE_SE3:QUAT 1256 1305 -2.35 -11.9195 -5.98496 0.0866352 0.208996 -0.145577 0.963132 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4879.59 -74.3515 2113.3 3811.73 -108.695 4824.85 +EDGE_SE3:QUAT 1257 1307 -1.52866 -0.0136213 -5.95067 0.130232 -0.0294409 0.108191 0.985123 1 2.40741e-19 2.40741e-19 2.00209e-10 1.03061e-08 -2.91605e-08 1 2.40741e-19 2.00209e-10 1.03061e-08 -2.91605e-08 1 2.00209e-10 1.03061e-08 -2.91605e-08 3970.3 -24.353 -395.277 3988.33 -18.2524 3991.32 +EDGE_SE3:QUAT 1256 1307 -1.90201 11.9351 -6.08661 -0.141474 0.0428656 0.0179635 0.98885 1 8.1852e-19 8.1852e-19 5.51967e-08 -1.34313e-08 6.24948e-10 1 8.1852e-19 5.51967e-08 -1.34313e-08 6.24948e-10 1 5.51967e-08 -1.34313e-08 6.24948e-10 3953.04 -25.9796 365.368 3992.11 -3.54036 4031.81 +EDGE_SE3:QUAT 1257 1306 -2.0514 -12.1648 -5.91662 0.0469173 0.0147228 -0.0943394 0.994325 1 4.81482e-20 4.81482e-20 -1.38113e-08 1.28626e-09 -3.22317e-10 1 4.81482e-20 -1.38113e-08 1.28626e-09 -3.22317e-10 1 -1.38113e-08 1.28626e-09 -3.22317e-10 3998.25 3.4939 168.853 3997.91 -8.3595 3971.45 +EDGE_SE3:QUAT 1258 1308 -1.54466 0.0918143 -5.92499 -0.058685 0.259009 -0.0732995 0.9613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5180.5 -279.259 2491.18 3796.95 -279.856 5172.78 +EDGE_SE3:QUAT 1257 1308 -2.42199 11.7345 -6.00967 -0.0213888 -0.0667004 -0.0444136 0.996555 1 4.81482e-20 4.81482e-20 -9.56587e-10 -2.17675e-10 1.3959e-08 1 4.81482e-20 -9.56587e-10 -2.17675e-10 1.3959e-08 1 -9.56587e-10 -2.17675e-10 1.3959e-08 4072.96 1.23037 -552.054 3981.49 10.515 4066.9 +EDGE_SE3:QUAT 1258 1307 -2.33861 -11.8877 -5.98348 -0.0514535 -0.0947399 -0.0469037 0.993064 1 1.92593e-19 1.92593e-19 -1.04588e-09 -2.7574e-08 -1.19943e-09 1 1.92593e-19 -1.04588e-09 -2.7574e-08 -1.19943e-09 1 -1.04588e-09 -2.7574e-08 -1.19943e-09 4146.77 11.9405 -808.852 3961.49 8.81996 4148.56 +EDGE_SE3:QUAT 1259 1309 -1.46443 -0.0364431 -6.0709 -0.0564368 -0.0732148 -0.0276345 0.995335 1 4.81482e-20 4.81482e-20 -1.39714e-08 2.72961e-10 1.0638e-09 1 4.81482e-20 -1.39714e-08 2.72961e-10 1.0638e-09 1 -1.39714e-08 2.72961e-10 1.0638e-09 4079.17 14.6516 -613.261 3977.3 1.25565 4088.85 +EDGE_SE3:QUAT 1258 1309 -2.66274 11.8408 -6.19518 -0.0131836 0.143611 0.09929 0.984552 1 4.23178e-22 4.23178e-22 1.33648e-09 1.35306e-10 1.94592e-10 1 4.23178e-22 1.33648e-09 1.35306e-10 1.94592e-10 1 1.33648e-09 1.35306e-10 1.94592e-10 4350.1 44.6779 1235.43 3921.42 67.7404 4311.36 +EDGE_SE3:QUAT 1259 1308 -1.84088 -12.0269 -5.97299 -0.0221651 -0.0480693 -0.0600675 0.99679 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.97 1.04873 -401.704 3990 11.1923 4025.51 +EDGE_SE3:QUAT 1260 1310 -1.3801 -0.267005 -6.22679 0.0787155 0.143142 -0.116542 0.979659 1 9.62965e-19 9.62965e-19 3.39642e-08 5.16625e-08 2.00583e-09 1 9.62965e-19 3.39642e-08 5.16625e-08 2.00583e-09 1 3.39642e-08 5.16625e-08 2.00583e-09 4379.14 -5.86271 1333.86 3906.27 -49.4007 4349.6 +EDGE_SE3:QUAT 1259 1310 -2.47341 12.3764 -6.33768 -0.027247 0.0780146 0.192398 0.977831 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4105.22 21.777 666.673 3976.72 65.0538 3960.12 +EDGE_SE3:QUAT 1260 1309 -2.18638 -11.7885 -6.41875 0.0570294 -0.050111 -0.0513287 0.995792 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.93 -12.9583 -364.728 3992.64 12.2287 4022.4 +EDGE_SE3:QUAT 1261 1311 -1.50147 0.120156 -6.29603 -0.0756575 0.0572219 -0.0643717 0.993407 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.74 -18.6498 395.758 3991.96 -17.1875 4022.06 +EDGE_SE3:QUAT 1260 1311 -2.18392 12.1558 -6.02365 0.192979 -0.0749976 0.0762099 0.97536 1 9.62965e-19 9.62965e-19 5.63061e-08 -2.4705e-08 -4.57601e-10 1 9.62965e-19 5.63061e-08 -2.4705e-08 -4.57601e-10 1 5.63061e-08 -2.4705e-08 -4.57601e-10 3989.84 -68.369 -758.597 3966.13 5.35724 4115.57 +EDGE_SE3:QUAT 1261 1310 -2.78092 -12.3577 -5.99786 -0.0937137 -0.187682 -0.0618513 0.975791 1 9.62965e-19 9.62965e-19 -3.08839e-08 -5.33967e-08 1.64437e-09 1 9.62965e-19 -3.08839e-08 -5.33967e-08 1.64437e-09 1 -3.08839e-08 -5.33967e-08 1.64437e-09 4638.79 50.7259 -1774.81 3851.45 -23.4162 4658.62 +EDGE_SE3:QUAT 1262 1312 -1.20308 -0.220412 -5.77575 0.0241373 0.0985469 0.15733 0.98232 1 4.81482e-20 4.81482e-20 -1.38575e-08 -2.3262e-09 -1.21008e-09 1 4.81482e-20 -1.38575e-08 -2.3262e-09 -1.21008e-09 1 -1.38575e-08 -2.3262e-09 -1.21008e-09 4127.24 42.4593 732.353 3974.95 66.108 4030.56 +EDGE_SE3:QUAT 1261 1312 -2.15693 11.8745 -6.34486 -0.0736228 -0.000451404 0.261077 0.962506 1 3.27408e-18 3.27408e-18 2.26822e-08 1.42744e-08 -1.05995e-07 1 3.27408e-18 2.26822e-08 1.42744e-08 -1.05995e-07 1 2.26822e-08 1.42744e-08 -1.05995e-07 3988.94 -7.96481 216.721 3995.03 37.5925 3737.98 +EDGE_SE3:QUAT 1262 1311 -2.05008 -11.808 -5.65548 0.142712 0.10793 0.0339468 0.983276 1 2.40741e-19 2.40741e-19 -4.61066e-10 2.94143e-08 9.67337e-09 1 2.40741e-19 -4.61066e-10 2.94143e-08 9.67337e-09 1 -4.61066e-10 2.94143e-08 9.67337e-09 4073.11 70.1521 802.335 3969.97 50.6118 4149.97 +EDGE_SE3:QUAT 1263 1313 -1.53335 0.0203293 -5.89702 -0.0110007 -0.00495433 0.104749 0.994426 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.67 0.144163 -25.2517 3999.98 -1.07309 3956.26 +EDGE_SE3:QUAT 1262 1313 -2.35458 11.9126 -5.84283 -0.0685188 0.0253253 0.0892479 0.993327 1 2.40741e-19 2.40741e-19 -2.64531e-08 -1.61576e-08 -1.90056e-09 1 2.40741e-19 -2.64531e-08 -1.61576e-08 -1.90056e-09 1 -2.64531e-08 -1.61576e-08 -1.90056e-09 3999.63 -8.00854 272.796 3994.74 11.6207 3986.54 +EDGE_SE3:QUAT 1263 1312 -2.34461 -12.1155 -6.00574 0.182817 -0.0203728 -0.135697 0.973524 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3868.64 21.7706 137.004 3996.41 -16.0295 3928.68 +EDGE_SE3:QUAT 1264 1314 -1.50862 -0.116995 -5.9936 0.00617017 0.0899096 -0.0615921 0.994024 1 2.40929e-19 2.40929e-19 4.39317e-10 -2.77142e-08 1.39642e-08 1 2.40929e-19 4.39317e-10 -2.77142e-08 1.39642e-08 1 4.39317e-10 -2.77142e-08 1.39642e-08 4132.57 -9.98658 740.622 3968.12 -23.5244 4117.55 +EDGE_SE3:QUAT 1263 1314 -2.5522 11.9597 -6.19659 -0.128885 0.0374559 0.000569931 0.990952 1 8.1852e-19 8.1852e-19 5.50339e-08 -1.4255e-08 2.30561e-10 1 8.1852e-19 5.50339e-08 -1.4255e-08 2.30561e-10 1 5.50339e-08 -1.4255e-08 2.30561e-10 3955.11 -19.0911 294.454 3995.09 -4.17109 4021.55 +EDGE_SE3:QUAT 1264 1313 -2.20621 -12.281 -5.69693 -0.121598 0.0825391 -0.0640616 0.987065 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.41 -41.7132 556.664 3985.98 -33.1534 4059.14 +EDGE_SE3:QUAT 1265 1315 -1.5267 0.182006 -6.07943 0.0611508 0.0301833 0.0966601 0.992979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.79 5.57297 166.532 3998.89 7.6517 3969.38 +EDGE_SE3:QUAT 1264 1315 -2.35931 12.2367 -6.29978 -0.0857821 0.145482 0.131148 0.976871 1 1.92593e-19 1.92593e-19 2.85624e-08 3.21197e-09 4.72312e-09 1 1.92593e-19 2.85624e-08 3.21197e-09 4.72312e-09 1 2.85624e-08 3.21197e-09 4.72312e-09 4400.28 10.5895 1379.83 3901.06 59.295 4360.91 +EDGE_SE3:QUAT 1265 1314 -1.82738 -12.4598 -6.03036 -0.0174466 -0.206689 -0.0481701 0.977064 1 7.52316e-22 7.52316e-22 -1.85458e-09 8.53218e-11 3.9363e-10 1 7.52316e-22 -1.85458e-09 8.53218e-11 3.9363e-10 1 -1.85458e-09 8.53218e-11 3.9363e-10 4785.9 -36.8688 -1941.14 3829.52 46.4021 4777.83 +EDGE_SE3:QUAT 1266 1316 -1.64242 -0.0753395 -6.02337 0.17069 -0.080821 0.110465 0.975772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.74 -58.6163 -864.398 3954.44 -12.9952 4129.47 +EDGE_SE3:QUAT 1265 1316 -2.16656 12.0658 -6.49686 0.0800768 0.093659 0.121547 0.984907 1 7.70372e-19 7.70372e-19 3.93036e-09 5.71423e-09 5.53219e-08 1 7.70372e-19 3.93036e-09 5.71423e-09 5.53219e-08 1 3.93036e-09 5.71423e-09 5.53219e-08 4067.51 44.1929 619.983 3983.74 50.4098 4034.06 +EDGE_SE3:QUAT 1266 1315 -2.14903 -12.1578 -5.72898 -0.056137 0.0806037 -0.203418 0.974152 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.16 -32.5316 472.328 3993.61 -49.8702 3888.25 +EDGE_SE3:QUAT 1267 1317 -1.42286 -0.0553957 -6.36527 0.199104 0.13828 -0.0613443 0.968232 1 1.54074e-18 1.54074e-18 -5.64965e-08 -5.3663e-08 1.7378e-09 1 1.54074e-18 -5.64965e-08 -5.3663e-08 1.7378e-09 1 -5.64965e-08 -5.3663e-08 1.7378e-09 4216.44 124.108 1280.9 3921.91 66.4422 4359.96 +EDGE_SE3:QUAT 1266 1317 -2.3483 11.9335 -6.55984 -0.0568983 -0.0856772 0.110026 0.988593 1 7.70372e-19 7.70372e-19 -5.54977e-08 -6.76976e-09 3.95039e-09 1 7.70372e-19 -5.54977e-08 -6.76976e-09 3.95039e-09 1 -5.54977e-08 -6.76976e-09 3.95039e-09 4076.34 33.6451 -605.349 3982.27 -42.1976 4040.87 +EDGE_SE3:QUAT 1267 1316 -2.2869 -12.1974 -6.53513 0.0156708 -0.0594482 0.0797408 0.994918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4058.71 3.11085 -492.284 3985.4 -19.1162 4034.26 +EDGE_SE3:QUAT 1268 1318 -1.3648 -0.18689 -6.15854 0.00181625 0.0668717 0.0468252 0.996661 1 4.89006e-20 4.89006e-20 -2.67418e-09 -1.96852e-10 -1.40714e-08 1 4.89006e-20 -2.67418e-09 -1.96852e-10 -1.40714e-08 1 -2.67418e-09 -1.96852e-10 -1.40714e-08 4071.74 5.612 540.516 3982.53 13.4253 4062.98 +EDGE_SE3:QUAT 1267 1318 -2.63046 12.3056 -6.19504 -0.168727 -0.0974915 0.00954402 0.980783 1 1.20371e-20 1.20371e-20 6.25164e-10 1.22659e-09 -6.92309e-09 1 1.20371e-20 6.25164e-10 1.22659e-09 -6.92309e-09 1 6.25164e-10 1.22659e-09 -6.92309e-09 4021.33 69.74 -748.303 3973.36 -40.3552 4134.84 +EDGE_SE3:QUAT 1268 1317 -2.20583 -11.4779 -5.83008 -0.0828221 -0.0509855 -0.241176 0.965596 1 1.92593e-19 1.92593e-19 2.71244e-08 -6.50033e-09 -2.33922e-09 1 1.92593e-19 2.71244e-08 -6.50033e-09 -2.33922e-09 1 2.71244e-08 -6.50033e-09 -2.33922e-09 4063.76 -0.546213 -612.588 3976.53 75.1777 3858.54 +EDGE_SE3:QUAT 1269 1319 -1.25246 0.283537 -6.49518 -0.00243601 0.186613 0.146249 0.971484 1 7.70372e-19 7.70372e-19 8.6611e-09 -5.38437e-08 3.02055e-09 1 7.70372e-19 8.6611e-09 -5.38437e-08 3.02055e-09 1 8.6611e-09 -5.38437e-08 3.02055e-09 4579.76 136.808 1629.85 3889.13 160.455 4494.22 +EDGE_SE3:QUAT 1268 1319 -2.44336 12.0067 -6.47883 0.0303372 -0.00569438 -0.0738904 0.996789 1 1.22251e-20 1.22251e-20 -6.85239e-09 1.37875e-09 -1.87569e-11 1 1.22251e-20 -6.85239e-09 1.37875e-09 -1.87569e-11 1 -6.85239e-09 1.37875e-09 -1.87569e-11 3996.38 -0.156146 -18.3334 4000 0.347425 3978.22 +EDGE_SE3:QUAT 1269 1318 -1.92547 -12.0697 -5.79693 -0.0919034 0.00472777 -0.138998 0.986008 1 3.00927e-21 3.00927e-21 -4.77136e-10 -3.42162e-09 -3.1107e-10 1 3.00927e-21 -4.77136e-10 -3.42162e-09 -3.1107e-10 1 -4.77136e-10 -3.42162e-09 -3.1107e-10 3968.87 7.29335 -114.267 3998.31 11.3129 3925.37 +EDGE_SE3:QUAT 1270 1320 -1.59306 0.00404409 -6.24152 0.116406 -0.115724 -0.219848 0.961626 1 9.62965e-19 9.62965e-19 6.06177e-08 1.28183e-08 -7.14801e-09 1 9.62965e-19 6.06177e-08 1.28183e-08 -7.14801e-09 1 6.06177e-08 1.28183e-08 -7.14801e-09 4013.07 -60.2741 -544.795 4000.2 68.0694 3873.94 +EDGE_SE3:QUAT 1269 1320 -2.16131 12.4457 -6.39264 0.00335658 -0.0399859 -0.0754716 0.99634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.73 -3.38017 -315.807 3994.06 12.1682 4001.99 +EDGE_SE3:QUAT 1270 1319 -2.07376 -12.2118 -6.21916 -0.0153679 -0.167863 -0.0105033 0.985635 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4492.19 6.72873 -1488.53 3887.07 -1.78924 4492.69 +EDGE_SE3:QUAT 1271 1321 -1.48851 0.122731 -6.68772 -0.00719109 -0.160889 -0.0371797 0.986246 1 4.81953e-20 4.81953e-20 -1.90508e-09 5.46096e-11 1.43623e-08 1 4.81953e-20 -1.90508e-09 5.46096e-11 1.43623e-08 1 -1.90508e-09 5.46096e-11 1.43623e-08 4448.93 -19.8169 -1413.6 3896.97 28.5257 4443.61 +EDGE_SE3:QUAT 1270 1321 -2.17203 12.0209 -6.39872 -0.0447213 0.0650821 -0.0501139 0.995617 1 4.81482e-20 4.81482e-20 -8.38589e-10 7.18896e-10 -1.39219e-08 1 4.81482e-20 -8.38589e-10 7.18896e-10 -1.39219e-08 1 -8.38589e-10 7.18896e-10 -1.39219e-08 4052.67 -16.0756 496.493 3985.99 -16.9331 4050.63 +EDGE_SE3:QUAT 1271 1320 -2.3053 -11.9618 -6.03369 -0.049849 -0.0583009 -0.0979417 0.992232 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4057.6 4.39553 -524.311 3982.84 22.6516 4029.17 +EDGE_SE3:QUAT 1272 1322 -1.98119 -0.0961905 -6.13477 -0.0687235 -0.213212 -0.0774204 0.971506 1 8.1852e-19 8.1852e-19 -1.78756e-08 -5.32029e-08 1.18328e-09 1 8.1852e-19 -1.78756e-08 -5.32029e-08 1.18328e-09 1 -1.78756e-08 -5.32029e-08 1.18328e-09 4871.19 -3.08811 -2086.3 3809.42 23.3868 4866.1 +EDGE_SE3:QUAT 1271 1322 -2.1864 11.9918 -6.30742 0.0184585 0.00134989 -0.0796583 0.99665 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.83 0.297047 28.2583 3999.93 -1.35429 3974.81 +EDGE_SE3:QUAT 1272 1321 -2.37414 -11.9674 -5.92961 -0.0153967 -0.120526 -0.20003 0.972227 1 1.92593e-19 1.92593e-19 5.61396e-09 2.69719e-08 -9.35452e-10 1 1.92593e-19 5.61396e-09 2.69719e-08 -9.35452e-10 1 5.61396e-09 2.69719e-08 -9.35452e-10 4230.73 -64.9775 -990.521 3955.82 108.29 4071.63 +EDGE_SE3:QUAT 1273 1323 -1.27412 0.205293 -5.94761 -0.12796 0.110004 0.000414011 0.98566 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4125.41 -63.9447 894.574 3958.28 -38.0099 4190.9 +EDGE_SE3:QUAT 1272 1323 -2.40575 11.778 -6.59752 -0.128095 0.0240261 0.147292 0.980469 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.23 -23.8557 406.315 3986.83 29.4515 3953.09 +EDGE_SE3:QUAT 1273 1322 -2.41553 -11.7779 -5.94319 0.105003 -0.0232451 -0.0771344 0.991204 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3957.41 -3.02558 -85.0893 3999.9 2.43081 3977.71 +EDGE_SE3:QUAT 1274 1324 -1.27959 0.0163471 -5.9063 -0.120883 -0.00459547 0.0863465 0.988894 1 1.93345e-19 1.93345e-19 -2.76e-08 -6.41708e-10 -2.4318e-10 1 1.93345e-19 -2.76e-08 -6.41708e-10 -2.4318e-10 1 -2.76e-08 -6.41708e-10 -2.4318e-10 3943.07 -7.74732 87.887 3998.96 5.45599 3971.69 +EDGE_SE3:QUAT 1273 1324 -2.51959 11.6689 -6.57226 0.00477418 -0.0562417 -0.107618 0.992589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4047.83 -9.01411 -440.485 3988.98 24.5725 4001.59 +EDGE_SE3:QUAT 1274 1323 -2.08225 -11.8728 -6.04358 -0.0543033 -0.0276479 -0.00222359 0.998139 1 4.81482e-20 4.81482e-20 1.38733e-08 1.0951e-11 -3.85368e-10 1 4.81482e-20 1.38733e-08 1.0951e-11 -3.85368e-10 1 1.38733e-08 1.0951e-11 -3.85368e-10 4000.52 6.04627 -222.249 3996.96 -0.755461 4012.29 +EDGE_SE3:QUAT 1275 1325 -1.49013 0.122951 -6.10002 0.153636 0.0771191 0.077956 0.982024 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3954.88 38.8948 451.453 3993.03 30.0811 4024.98 +EDGE_SE3:QUAT 1274 1325 -2.50893 11.3879 -6.27256 0.0227841 -0.122569 -0.0254717 0.991871 1 1.20371e-20 1.20371e-20 -7.09196e-09 2.28375e-10 8.65651e-10 1 1.20371e-20 -7.09196e-09 2.28375e-10 8.65651e-10 1 -7.09196e-09 2.28375e-10 8.65651e-10 4244.76 -23.2228 -1023.85 3941.87 23.7846 4244.24 +EDGE_SE3:QUAT 1275 1324 -2.59204 -11.9997 -5.51877 0.00350328 0.0065328 -0.012122 0.999899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.65 0.0801579 52.7676 3999.83 -0.317332 4000.11 +EDGE_SE3:QUAT 1276 1326 -1.70256 0.0803254 -5.90999 0.0196937 -0.0744522 0.131136 0.988369 1 3.00927e-21 3.00927e-21 3.47028e-09 4.55122e-10 -2.70345e-10 1 3.00927e-21 3.47028e-09 4.55122e-10 -2.70345e-10 1 3.47028e-09 4.55122e-10 -2.70345e-10 4093.43 12.2703 -623.672 3977.87 -40.914 4026.2 +EDGE_SE3:QUAT 1275 1326 -2.40562 11.6412 -6.02248 -0.0429162 -0.170653 0.193836 0.965123 1 9.62965e-19 9.62965e-19 1.59371e-08 5.96619e-08 2.0148e-09 1 9.62965e-19 1.59371e-08 5.96619e-08 2.0148e-09 1 1.59371e-08 5.96619e-08 2.0148e-09 4360.38 157.608 -1270.93 3949.48 -179.024 4217.45 +EDGE_SE3:QUAT 1276 1325 -2.39279 -11.9757 -5.92363 -0.131584 -0.030014 -0.0137823 0.990755 1 3.00927e-21 3.00927e-21 -1.13217e-10 -4.55321e-10 3.44451e-09 1 3.00927e-21 -1.13217e-10 -4.55321e-10 3.44451e-09 1 -1.13217e-10 -4.55321e-10 3.44451e-09 3947.1 17.0435 -256.309 3996.03 -1.35706 4015.59 +EDGE_SE3:QUAT 1277 1327 -1.82244 0.000601651 -5.83544 -0.0528932 -0.0484577 0.0392057 0.996653 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.41 11.5663 -362.733 3992.48 -9.7871 4026.45 +EDGE_SE3:QUAT 1276 1327 -2.0156 11.7593 -6.21987 -0.00286959 -0.00162922 -0.00335059 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.01 0.0187051 -13.1489 3999.99 0.0219078 4000 +EDGE_SE3:QUAT 1277 1326 -2.60195 -12.0827 -5.78834 0.0282829 0.037107 0.0783641 0.995832 1 1.20371e-20 1.20371e-20 -6.92551e-09 -5.60097e-10 -2.23647e-10 1 1.20371e-20 -6.92551e-09 -5.60097e-10 -2.23647e-10 1 -6.92551e-09 -5.60097e-10 -2.23647e-10 4014.68 5.9246 268.24 3996.01 11.0595 3993.31 +EDGE_SE3:QUAT 1278 1328 -1.72626 0.300138 -5.88848 0.0730735 -0.0164999 -0.0330441 0.996642 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.21 -3.50948 -101.915 3999.49 1.84459 3998.2 +EDGE_SE3:QUAT 1277 1328 -1.91384 12.0163 -6.28205 -0.159661 0.166547 0.158803 0.959975 1 7.70372e-19 7.70372e-19 1.21669e-08 -6.48754e-09 5.77968e-08 1 7.70372e-19 1.21669e-08 -6.48754e-09 5.77968e-08 1 1.21669e-08 -6.48754e-09 5.77968e-08 4574.38 -36.4369 1779.04 3849.04 34.4637 4575.47 +EDGE_SE3:QUAT 1278 1327 -2.21213 -12.1372 -5.824 -0.174019 -0.119057 -0.192332 0.958411 1 7.70372e-19 7.70372e-19 -5.61426e-08 8.57214e-09 9.96152e-09 1 7.70372e-19 -5.61426e-08 8.57214e-09 9.96152e-09 1 -5.61426e-08 8.57214e-09 9.96152e-09 4307.41 37.7746 -1379.51 3896.47 65.5792 4280.57 +EDGE_SE3:QUAT 1279 1329 -1.37043 0.0283891 -6.12258 -0.221315 -0.0172337 -0.00538676 0.975035 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3809.1 15.8501 -141.862 3998.98 -1.30401 4004.91 +EDGE_SE3:QUAT 1278 1329 -2.61014 11.8943 -6.5368 -0.0284192 -0.10944 0.10367 0.988164 1 2.40741e-19 2.40741e-19 1.09013e-08 2.89935e-08 -3.67212e-12 1 2.40741e-19 1.09013e-08 2.89935e-08 -3.67212e-12 1 1.09013e-08 2.89935e-08 -3.67212e-12 4171.89 42.1737 -855.376 3962.24 -56.6781 4132.13 +EDGE_SE3:QUAT 1279 1328 -2.81499 -11.8039 -5.85858 -0.00647108 -0.051458 -0.247801 0.967422 1 3.08149e-18 3.08149e-18 -5.38194e-09 2.13143e-09 1.07959e-07 1 3.08149e-18 -5.38194e-09 2.13143e-09 1.07959e-07 1 -5.38194e-09 2.13143e-09 1.07959e-07 4038.59 -13.9836 -396.086 3993.35 49.221 3793.13 +EDGE_SE3:QUAT 1280 1330 -1.54961 -0.148468 -6.03742 0.156335 -0.139525 0.0833518 0.974241 1 3.12964e-18 3.12964e-18 -1.11338e-07 -6.48336e-09 4.15946e-09 1 3.12964e-18 -1.11338e-07 -6.48336e-09 4.15946e-09 1 -1.11338e-07 -6.48336e-09 4.15946e-09 4305.73 -80.8142 -1333.13 3908.25 25.7387 4375.7 +EDGE_SE3:QUAT 1279 1330 -2.25266 11.9767 -6.04117 0.186437 0.0550497 0.135111 0.971574 1 7.70372e-19 7.70372e-19 -5.3933e-08 -8.11181e-09 3.79138e-12 1 7.70372e-19 -5.3933e-08 -8.11181e-09 3.79138e-12 1 -5.3933e-08 -8.11181e-09 3.79138e-12 3860.93 1.76548 112.914 4000.76 2.38333 3926.95 +EDGE_SE3:QUAT 1280 1329 -2.63244 -12.3238 -5.89141 0.0391193 0.00554846 -0.0291449 0.998794 1 4.89006e-20 4.89006e-20 1.39122e-08 1.33537e-09 4.10637e-11 1 4.89006e-20 1.39122e-08 1.33537e-09 4.10637e-11 1 1.39122e-08 1.33537e-09 4.10637e-11 3994.71 1.18825 57.9013 3999.76 -0.865599 3997.44 +EDGE_SE3:QUAT 1281 1331 -1.90655 -0.159927 -6.22005 0.013445 -0.24804 0.0418911 0.96775 1 1.88079e-22 1.88079e-22 -9.57607e-10 -3.99812e-11 2.45668e-10 1 1.88079e-22 -9.57607e-10 -3.99812e-11 2.45668e-10 1 -9.57607e-10 -3.99812e-11 2.45668e-10 5203.09 57.0357 -2502.88 3755.45 -61.1573 5196.79 +EDGE_SE3:QUAT 1280 1331 -2.40804 11.8126 -6.20265 0.239981 0.010863 0.13117 0.961814 1 7.70372e-19 7.70372e-19 5.35114e-08 6.73301e-09 -2.85373e-09 1 7.70372e-19 5.35114e-08 6.73301e-09 -2.85373e-09 1 5.35114e-08 6.73301e-09 -2.85373e-09 3786.31 -47.4715 -282.696 3989.94 -23.3392 3947.85 +EDGE_SE3:QUAT 1281 1330 -2.50211 -11.7244 -5.89317 0.0193887 0.0611058 -0.159558 0.985105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.5 -10.376 514.026 3985.2 -41.3234 3963.16 +EDGE_SE3:QUAT 1282 1332 -1.70602 -0.00174444 -6.15579 0.0371117 0.0150897 -0.00196305 0.999195 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.17 2.25187 121.439 3999.08 0.0851225 4003.67 +EDGE_SE3:QUAT 1281 1332 -2.51715 11.9856 -6.46729 0.155123 0.0643318 -0.0858456 0.982053 1 1.92593e-19 1.92593e-19 -2.44164e-09 -4.03547e-09 -2.7631e-08 1 1.92593e-19 -2.44164e-09 -4.03547e-09 -2.7631e-08 1 -2.44164e-09 -4.03547e-09 -2.7631e-08 4010.93 45.2327 664.473 3972.13 -8.82942 4077.7 +EDGE_SE3:QUAT 1282 1331 -2.20601 -11.8703 -5.73044 -0.290997 -0.0260898 -0.102882 0.950818 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3727.64 86.1177 -525.657 3979.45 9.67768 4024.02 +EDGE_SE3:QUAT 1283 1333 -1.60154 0.293441 -6.64791 0.0652765 0.11219 -0.0474384 0.990405 1 4.81482e-20 4.81482e-20 1.4126e-08 -4.76266e-10 1.66972e-09 1 4.81482e-20 1.4126e-08 -4.76266e-10 1.66972e-09 1 1.4126e-08 -4.76266e-10 1.66972e-09 4206.75 20.3521 972.27 3946.05 -4.31452 4214.79 +EDGE_SE3:QUAT 1282 1333 -2.56832 11.9609 -6.32309 0.0311807 -0.00684054 0.0469137 0.998389 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.4 -1.1314 -72.0038 3999.63 -1.771 3992.48 +EDGE_SE3:QUAT 1283 1332 -2.23892 -12.1979 -6.09938 0.0354275 -0.00839135 -0.154608 0.987305 1 1.88079e-22 1.88079e-22 1.34275e-10 8.56323e-10 -3.14819e-11 1 1.88079e-22 1.34275e-10 8.56323e-10 -3.14819e-11 1 1.34275e-10 8.56323e-10 -3.14819e-11 3994.85 0.394186 0.0168166 3999.97 -1.75896 3904.26 +EDGE_SE3:QUAT 1284 1334 -2.03184 -0.204115 -5.93038 -0.102128 -0.0551111 0.0681089 0.990906 1 8.1852e-19 8.1852e-19 -5.41311e-08 -1.8102e-08 6.88994e-10 1 8.1852e-19 -5.41311e-08 -1.8102e-08 6.88994e-10 1 -5.41311e-08 -1.8102e-08 6.88994e-10 3988.38 20.242 -349.971 3994.42 -16.4335 4011.55 +EDGE_SE3:QUAT 1283 1334 -2.37283 12.1426 -6.33333 -0.150658 -0.134109 0.0717197 0.976818 1 7.70372e-19 7.70372e-19 5.56506e-08 6.35915e-09 -5.93328e-09 1 7.70372e-19 5.56506e-08 6.35915e-09 -5.93328e-09 1 5.56506e-08 6.35915e-09 -5.93328e-09 4115.28 102.732 -934.158 3967.32 -90.2704 4185.49 +EDGE_SE3:QUAT 1284 1333 -2.25782 -12.2067 -5.7777 -0.125094 -0.0752759 -0.207332 0.967315 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4126.06 12.8064 -891.235 3951.04 78.0356 4016.71 +EDGE_SE3:QUAT 1285 1335 -1.60988 0.190916 -5.79288 0.148632 0.121895 -0.057538 0.979663 1 7.70372e-19 7.70372e-19 -1.11964e-09 -5.44644e-08 7.68935e-09 1 7.70372e-19 -1.11964e-09 -5.44644e-08 7.68935e-09 1 -1.11964e-09 -5.44644e-08 7.68935e-09 4198.14 73.4721 1108.25 3934.44 26.5994 4273.26 +EDGE_SE3:QUAT 1284 1335 -2.68273 12.1196 -6.24512 -0.176211 0.0988707 0.118944 0.972125 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4131.99 -67.4301 1045.35 3936.73 10.2222 4199.6 +EDGE_SE3:QUAT 1285 1334 -2.11136 -12.1917 -6.03739 -0.0756939 0.211731 0.0419255 0.97349 1 1.20371e-20 1.20371e-20 1.64688e-09 -4.89167e-10 7.4443e-09 1 1.20371e-20 1.64688e-09 -4.89167e-10 7.4443e-09 1 1.64688e-09 -4.89167e-10 7.4443e-09 4829.74 -57.5904 2034.13 3817.75 -41.2178 4845.63 +EDGE_SE3:QUAT 1286 1336 -1.47147 -0.0842947 -5.77054 0.0644639 -0.0119121 0.067644 0.995554 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.65 -4.81252 -146.274 3998.37 -5.09456 3986.97 +EDGE_SE3:QUAT 1285 1336 -2.6473 11.678 -6.15237 -0.146212 -0.0449962 -0.00162141 0.988228 1 7.70372e-19 7.70372e-19 -5.50746e-08 -6.40778e-10 2.42627e-09 1 7.70372e-19 -5.50746e-08 -6.40778e-10 2.42627e-09 1 -5.50746e-08 -6.40778e-10 2.42627e-09 3945.51 26.109 -353.657 3993.12 -6.68914 4031.01 +EDGE_SE3:QUAT 1286 1335 -2.42906 -12.3263 -5.94831 -0.155259 -0.138654 -0.312711 0.926759 1 1.92593e-19 1.92593e-19 -2.78523e-08 8.1791e-09 6.01409e-09 1 1.92593e-19 -2.78523e-08 8.1791e-09 6.01409e-09 1 -2.78523e-08 8.1791e-09 6.01409e-09 4519.53 -104.187 -1687 3880.6 229.785 4224.8 +EDGE_SE3:QUAT 1287 1337 -1.86662 0.743201 -5.77899 0.0160466 -0.00997581 0.122246 0.99232 1 2.0463e-19 2.0463e-19 -6.51116e-09 -1.21119e-09 -2.74572e-08 1 2.0463e-19 -6.51116e-09 -1.21119e-09 -2.74572e-08 1 -6.51116e-09 -1.21119e-09 -2.74572e-08 4001.53 -0.441637 -101.36 3999.3 -6.58985 3942.78 +EDGE_SE3:QUAT 1286 1337 -2.43223 12.3596 -6.256 -0.0137823 -0.0132426 0.1703 0.985207 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.56 0.855042 -73.7275 3999.81 -5.38619 3885.31 +EDGE_SE3:QUAT 1287 1336 -2.29973 -12.1247 -5.65397 -0.160649 -0.0221651 -0.0876096 0.982866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3924.26 28.5964 -336.073 3991.23 11.7116 3996.79 +EDGE_SE3:QUAT 1288 1338 -1.74623 -0.120221 -6.37904 -0.0573818 0.101028 -0.0540281 0.991757 1 1.92593e-19 1.92593e-19 1.84396e-09 2.75059e-08 1.92043e-09 1 1.92593e-19 1.84396e-09 2.75059e-08 1.92043e-09 1 1.84396e-09 2.75059e-08 1.92043e-09 4136.16 -37.1647 787.368 3966.59 -36.5238 4137.65 +EDGE_SE3:QUAT 1287 1338 -2.48164 11.7991 -6.29204 -0.0956817 -0.10262 -0.0737627 0.987357 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4168.65 28.5097 -929.269 3949.81 10.0986 4183.51 +EDGE_SE3:QUAT 1288 1337 -2.4214 -12.1388 -5.9697 -0.0641909 -0.0737277 0.047836 0.99406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4059.28 24.0356 -555.944 3982.97 -21.316 4066.61 +EDGE_SE3:QUAT 1289 1339 -1.75106 -0.119874 -6.3504 -0.123017 0.00722858 -0.131685 0.983602 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.06 11.9546 -135.259 3997.52 12.8531 3934.23 +EDGE_SE3:QUAT 1288 1339 -2.56814 12.3125 -5.79532 0.0244401 -0.0621078 0.0910205 0.99361 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.29 2.41923 -524.714 3983.38 -22.7463 4034.54 +EDGE_SE3:QUAT 1289 1338 -2.37635 -12.2551 -5.70847 0.00229773 0.0487616 0.0300043 0.998357 1 4.83363e-20 4.83363e-20 -4.48559e-10 -1.38813e-08 3.04191e-11 1 4.83363e-20 -4.48559e-10 -1.38813e-08 3.04191e-11 1 -4.48559e-10 -1.38813e-08 3.04191e-11 4038.03 2.18434 391.963 3990.61 6.15212 4034.45 +EDGE_SE3:QUAT 1290 1340 -1.3869 -0.153355 -5.82642 0.0591422 -0.0339714 0.0625285 0.99571 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.59 -7.66251 -314.757 3993.46 -8.34508 4008.94 +EDGE_SE3:QUAT 1289 1340 -2.52626 12.079 -6.3919 0.0758145 0.105509 0.0176442 0.991367 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4150.44 40.4211 850.842 3960.24 28.7623 4172.19 +EDGE_SE3:QUAT 1290 1339 -2.22648 -11.9905 -6.04181 -0.142155 -0.018531 0.13218 0.980804 1 7.70384e-19 7.70384e-19 -5.44183e-08 -7.54047e-09 -1.12641e-09 1 7.70384e-19 -5.44183e-08 -7.54047e-09 -1.12641e-09 1 -5.44183e-08 -7.54047e-09 -1.12641e-09 3919.36 -11.2092 79.8936 3998.44 10.4207 3930.3 +EDGE_SE3:QUAT 1291 1341 -1.70403 0.267934 -5.78099 0.0110873 0.115407 0.0276782 0.992871 1 3.00927e-21 3.00927e-21 3.53802e-09 1.10597e-10 4.08232e-10 1 3.00927e-21 3.53802e-09 1.10597e-10 4.08232e-10 1 3.53802e-09 1.10597e-10 4.08232e-10 4218.9 15.4398 962.143 3947.8 18.9183 4216.33 +EDGE_SE3:QUAT 1290 1341 -1.96355 11.828 -6.21045 0.0813503 0.171456 -0.0499733 0.980555 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4516.73 42.5391 1570.96 3877.42 17.2986 4533.21 +EDGE_SE3:QUAT 1291 1340 -2.18813 -11.8944 -5.75629 -0.13419 -0.0198751 -0.169447 0.976159 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3969.56 25.915 -417.01 3985.45 36.6667 3926.73 +EDGE_SE3:QUAT 1292 1342 -1.60658 0.267953 -6.05487 -0.00122256 -0.103055 0.081189 0.991356 1 1.20371e-20 1.20371e-20 -7.0257e-09 -5.89664e-10 7.19064e-10 1 1.20371e-20 -7.0257e-09 -5.89664e-10 7.19064e-10 1 -7.0257e-09 -5.89664e-10 7.19064e-10 4171.34 22.0384 -845.444 3960.1 -38.3588 4144.98 +EDGE_SE3:QUAT 1291 1342 -2.47812 11.8859 -6.10356 -0.245903 0.0585045 0.0117982 0.967455 1 3.13039e-18 3.13039e-18 1.07824e-07 -1.49616e-08 1.26954e-09 1 3.13039e-18 1.07824e-07 -1.49616e-08 1.26954e-09 1 1.07824e-07 -1.49616e-08 1.26954e-09 3811.41 -57.9601 465.027 3990.49 -17.7583 4052.72 +EDGE_SE3:QUAT 1292 1341 -2.5108 -12.1083 -5.88174 -0.0346848 -0.0590105 0.0125356 0.997576 1 3.00927e-21 3.00927e-21 2.02507e-10 1.27156e-10 -3.4847e-09 1 3.00927e-21 2.02507e-10 1.27156e-10 -3.4847e-09 1 2.02507e-10 1.27156e-10 -3.4847e-09 4050 9.47977 -471.435 3986.65 -5.93777 4054.18 +EDGE_SE3:QUAT 1293 1343 -1.51382 0.293765 -5.97724 -0.0270122 -0.00293491 0.0259516 0.999294 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.14 0.167628 -15.0256 3999.99 -0.161269 3997.36 +EDGE_SE3:QUAT 1292 1343 -2.80505 12.1323 -6.33435 -0.0895624 0.0206026 0.132236 0.986949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.87 -11.9461 300.004 3992.98 20.5551 3952.01 +EDGE_SE3:QUAT 1293 1342 -2.43258 -11.6564 -6.20322 0.0280608 -0.0234752 -0.245444 0.96872 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.63 -2.00091 -91.5313 4000.04 7.28802 3760.81 +EDGE_SE3:QUAT 1294 1344 -1.58865 0.0262817 -5.99977 0.182626 -0.250332 0.0654222 0.948526 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5164.1 -274.145 -2621.84 3776.56 258.404 5280.39 +EDGE_SE3:QUAT 1293 1344 -2.65499 11.7545 -6.10537 -0.0552168 0.0250716 0.134219 0.989094 1 9.62965e-20 9.62965e-20 -1.55782e-08 1.19117e-08 1.09108e-10 1 9.62965e-20 -1.55782e-08 1.19117e-08 1.09108e-10 1 -1.55782e-08 1.19117e-08 1.09108e-10 4007.63 -5.09933 283.394 3994.32 19.5964 3947.77 +EDGE_SE3:QUAT 1294 1343 -2.46206 -11.8798 -6.02465 0.00656287 0.0172294 -0.101752 0.994639 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.99 -0.298729 143.817 3998.73 -7.39012 3963.75 +EDGE_SE3:QUAT 1295 1345 -1.7991 -0.0783637 -6.44024 -0.00971752 -0.0699617 -0.134762 0.988357 1 2.93874e-22 2.93874e-22 -1.08238e-09 1.47555e-10 7.66697e-11 1 2.93874e-22 -1.08238e-09 1.47555e-10 7.66697e-11 1 -1.08238e-09 1.47555e-10 7.66697e-11 4079.21 -13.4673 -569.821 3981.87 39.2462 4006.94 +EDGE_SE3:QUAT 1294 1345 -2.53467 12.1336 -6.38308 0.0895006 -0.0311414 0.113944 0.988957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.71 -13.3652 -365.063 3990.44 -19.4317 3980.82 +EDGE_SE3:QUAT 1295 1344 -2.27293 -12.1943 -6.12476 -0.0434641 0.031359 -0.155362 0.986403 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.7 -4.80577 161.558 3999.19 -10.8141 3909.71 +EDGE_SE3:QUAT 1296 1346 -1.67949 0.189333 -6.15942 -0.056559 0.121708 -0.0267897 0.990591 1 4.81482e-20 4.81482e-20 -1.67931e-09 9.25924e-10 -1.4147e-08 1 4.81482e-20 -1.67931e-09 9.25924e-10 -1.4147e-08 1 -1.67931e-09 9.25924e-10 -1.4147e-08 4222.17 -42.1591 997.584 3946.17 -36.079 4232.09 +EDGE_SE3:QUAT 1295 1346 -2.66736 12.2481 -6.33294 0.0115165 -0.0662537 -0.0245092 0.997435 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4069.55 -5.81591 -534.074 3982.86 8.05401 4067.68 +EDGE_SE3:QUAT 1296 1345 -2.27039 -11.8999 -6.20166 0.0699636 -0.0493433 -0.047501 0.995195 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.26 -14.4523 -352.927 3993.25 11.6735 4021.81 +EDGE_SE3:QUAT 1297 1347 -1.64566 -0.142716 -5.94774 0.0450029 -0.0939513 0.146797 0.983666 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4158.96 15.6537 -834.415 3960.92 -57.6497 4080.87 +EDGE_SE3:QUAT 1296 1347 -2.49106 11.5892 -6.37811 0.0250928 0.010058 -0.0177611 0.999477 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.32 1.05109 85.7304 3999.52 -0.710397 4000.57 +EDGE_SE3:QUAT 1297 1346 -2.60222 -11.7483 -5.9108 0.0260583 0.0482128 -0.133997 0.989465 1 6.01853e-20 6.01853e-20 -8.73611e-09 -1.28143e-08 -2.00244e-10 1 6.01853e-20 -8.73611e-09 -1.28143e-08 -2.00244e-10 1 -8.73611e-09 -1.28143e-08 -2.00244e-10 4041.02 -2.86143 420.601 3989.35 -27.9692 3971.92 +EDGE_SE3:QUAT 1298 1348 -1.84807 0.105227 -5.95446 0.0929294 -0.0318385 -0.0716112 0.992584 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3972.49 -7.61755 -170.426 3998.9 6.37832 3986.52 +EDGE_SE3:QUAT 1297 1348 -2.42647 11.872 -5.88536 0.0389949 0.0465186 0.149125 0.986954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4014.77 10.6373 291.212 3996.39 21.4344 3931.9 +EDGE_SE3:QUAT 1298 1347 -2.40822 -12.2974 -5.89093 -0.077052 -0.0200433 -0.251687 0.964528 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.26 6.99066 -369.273 3989.52 53.0283 3779.62 +EDGE_SE3:QUAT 1299 1349 -1.78205 0.184346 -6.02221 -0.237124 0.27399 0.0996604 0.926698 1 1.92593e-19 1.92593e-19 -9.6437e-09 7.2932e-09 -3.1074e-08 1 1.92593e-19 -9.6437e-09 7.2932e-09 -3.1074e-08 1 -9.6437e-09 7.2932e-09 -3.1074e-08 5502.45 -428.931 3145.53 3753.62 -426.762 5687.64 +EDGE_SE3:QUAT 1298 1349 -2.57244 11.8235 -6.31804 -0.00951979 -0.131325 -0.00352822 0.991287 1 7.73381e-19 7.73381e-19 -3.62247e-09 -5.50239e-08 -2.24491e-11 1 7.73381e-19 -3.62247e-09 -5.50239e-08 -2.24491e-11 1 -3.62247e-09 -5.50239e-08 -2.24491e-11 4290.69 4.70821 -1117.55 3930.99 -1.95757 4291 +EDGE_SE3:QUAT 1299 1348 -2.25894 -12.1147 -6.24963 0.180924 -0.00514875 0.224303 0.957564 1 4.81482e-20 4.81482e-20 2.8963e-09 -1.33377e-08 2.23676e-09 1 4.81482e-20 2.8963e-09 -1.33377e-08 2.23676e-09 1 2.8963e-09 -1.33377e-08 2.23676e-09 3927.18 -46.8346 -503.935 3975.19 -64.1473 3856.87 +EDGE_SE3:QUAT 1300 1350 -1.77356 0.258538 -6.05916 0.0326559 -0.0140794 0.0660652 0.997181 1 4.81482e-20 4.81482e-20 1.38469e-08 9.03106e-10 -2.53169e-10 1 4.81482e-20 1.38469e-08 9.03106e-10 -2.53169e-10 1 1.38469e-08 9.03106e-10 -2.53169e-10 4000.45 -1.95655 -137.673 3998.69 -4.62069 3987.26 +EDGE_SE3:QUAT 1299 1350 -2.54246 11.7001 -6.38077 -0.193774 -0.0603518 -0.0242687 0.978887 1 3.00927e-21 3.00927e-21 2.27536e-10 6.72489e-10 -3.42522e-09 1 3.00927e-21 2.27536e-10 6.72489e-10 -3.42522e-09 1 2.27536e-10 6.72489e-10 -3.42522e-09 3915.88 50.8774 -518.322 3985.52 -12.5748 4063.72 +EDGE_SE3:QUAT 1300 1349 -2.7324 -11.9541 -5.91684 -0.023572 -0.231539 -0.0860761 0.968723 1 7.71124e-19 7.71124e-19 -2.80949e-09 -5.39468e-08 5.06601e-10 1 7.71124e-19 -2.80949e-09 -5.39468e-08 5.06601e-10 1 -2.80949e-09 -5.39468e-08 5.06601e-10 5021.91 -104.607 -2268.35 3792.21 115.978 4994.49 +EDGE_SE3:QUAT 1301 1351 -2.18956 -0.133036 -5.63318 0.0331505 -0.161815 0.136866 0.976721 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4463.9 70.4709 -1446.56 3899.92 -103.798 4393.37 +EDGE_SE3:QUAT 1300 1351 -2.67101 11.9371 -6.03321 0.0940728 0.040295 -0.117863 0.987742 1 4.33334e-19 4.33334e-19 -2.74086e-08 -8.38302e-09 2.70429e-08 1 4.33334e-19 -2.74086e-08 -8.38302e-09 2.70429e-08 1 -2.74086e-08 -8.38302e-09 2.70429e-08 4013.86 15.6854 448.047 3986.12 -23.2243 3993.69 +EDGE_SE3:QUAT 1301 1350 -2.43073 -11.5214 -5.69074 0.158206 -0.0401204 0.102871 0.981213 1 1.92593e-19 1.92593e-19 1.94117e-09 -4.12444e-09 -2.74501e-08 1 1.92593e-19 1.94117e-09 -4.12444e-09 -2.74501e-08 1 1.94117e-09 -4.12444e-09 -2.74501e-08 3961.46 -37.3412 -502.666 3982.14 -16.8724 4019.25 +EDGE_SE3:QUAT 1302 1352 -1.97326 -0.397847 -5.92383 -0.0446978 -0.106887 -0.0711803 0.990712 1 1.92593e-19 1.92593e-19 -3.18348e-09 -8.50078e-10 2.81923e-08 1 1.92593e-19 -3.18348e-09 -8.50078e-10 2.81923e-08 1 -3.18348e-09 -8.50078e-10 2.81923e-08 4195.33 1.58021 -924.486 3950.85 23.6693 4183.05 +EDGE_SE3:QUAT 1301 1352 -2.22831 11.869 -6.25246 -0.207927 -0.074037 0.085754 0.971561 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3853.61 32.6545 -340.513 3998.91 -23.8167 3997.13 +EDGE_SE3:QUAT 1302 1351 -2.16269 -12.2341 -5.86737 -0.0257682 -0.055278 -0.0873093 0.994313 1 4.81482e-20 4.81482e-20 -1.17848e-09 -1.38017e-08 -2.20407e-10 1 4.81482e-20 -1.17848e-09 -1.38017e-08 -2.20407e-10 1 -1.17848e-09 -1.38017e-08 -2.20407e-10 4051.66 -0.691375 -469.318 3986.53 19.4288 4023.83 +EDGE_SE3:QUAT 1303 1353 -1.75168 -0.0144167 -6.05488 -0.0305619 -0.0127922 0.162174 0.986206 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.54 0.456782 -39.7752 4000 -1.53753 3895.08 +EDGE_SE3:QUAT 1302 1353 -2.61301 11.8414 -5.73841 -0.0684856 -0.0635176 0.107772 0.989778 1 2.40741e-19 2.40741e-19 -3.09313e-10 1.59835e-08 -2.6493e-08 1 2.40741e-19 -3.09313e-10 1.59835e-08 -2.6493e-08 1 -3.09313e-10 1.59835e-08 -2.6493e-08 4022.67 21.0054 -410.91 3992.31 -25.9062 3994.97 +EDGE_SE3:QUAT 1303 1352 -2.41624 -11.8042 -5.76893 -0.0950474 -0.0248829 -0.189033 0.977043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.49 13.4026 -399.149 3987.7 40.1659 3895.69 +EDGE_SE3:QUAT 1304 1354 -2.10693 0.0846691 -5.85472 -0.0487439 0.065057 -0.187553 0.978885 1 9.62965e-20 9.62965e-20 -1.0956e-08 1.62761e-08 3.80162e-10 1 9.62965e-20 -1.0956e-08 1.62761e-08 3.80162e-10 1 -1.0956e-08 1.62761e-08 3.80162e-10 4026.74 -20.966 386.252 3995 -36.2462 3895.53 +EDGE_SE3:QUAT 1303 1354 -2.45008 11.7429 -6.07038 -0.0493271 0.125339 -0.0026576 0.990883 1 5.11575e-20 5.11575e-20 1.37479e-08 -3.54998e-11 -1.76596e-09 1 5.11575e-20 1.37479e-08 -3.54998e-11 -1.76596e-09 1 1.37479e-08 -3.54998e-11 -1.76596e-09 4251.02 -31.3638 1054.05 3938.84 -21.5721 4260.73 +EDGE_SE3:QUAT 1304 1353 -2.9641 -11.8282 -5.46106 0.152857 -0.0407849 -0.224721 0.961495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3904.19 19.4141 101.411 3996.08 -28.3888 3795.65 +EDGE_SE3:QUAT 1305 1355 -2.04343 0.00107296 -6.1093 0.0821412 0.016394 0.144868 0.985899 1 7.52316e-22 7.52316e-22 -2.5253e-10 1.71008e-09 -1.4464e-10 1 7.52316e-22 -2.5253e-10 1.71008e-09 -1.4464e-10 1 -2.5253e-10 1.71008e-09 -1.4464e-10 3972.47 -2.62261 -14.4499 3999.75 -4.62782 3915.52 +EDGE_SE3:QUAT 1304 1355 -2.76232 11.897 -5.86975 -0.0961173 0.128548 0.285569 0.944821 1 1.92593e-19 1.92593e-19 2.76102e-08 7.82569e-09 4.65457e-09 1 1.92593e-19 2.76102e-08 7.82569e-09 4.65457e-09 1 2.76102e-08 7.82569e-09 4.65457e-09 4360.49 91.3487 1322.07 3925.74 184.843 4071.24 +EDGE_SE3:QUAT 1305 1354 -2.56735 -11.6473 -6.21249 0.0292886 0.16626 0.0355374 0.985006 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4464.44 53.7828 1445.85 3895.43 54.9579 4462.82 +EDGE_SE3:QUAT 1306 1356 -1.60883 -0.077306 -6.0014 0.153364 -0.120236 0.133691 0.971674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4259.77 -49.7032 -1242.07 3914.72 -24.1851 4282.36 +EDGE_SE3:QUAT 1305 1356 -2.67116 11.9075 -5.95105 0.0966641 -0.0383084 0.010027 0.994529 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.35 -15.2365 -315.431 3993.98 1.95558 4024.32 +EDGE_SE3:QUAT 1306 1355 -2.56658 -11.6085 -5.9152 0.0403067 -0.0937921 -0.0186378 0.994601 1 1.20371e-20 1.20371e-20 6.48643e-10 -3.14386e-10 -7.02147e-09 1 1.20371e-20 6.48643e-10 -3.14386e-10 -7.02147e-09 1 6.48643e-10 -3.14386e-10 -7.02147e-09 4133.55 -20.6876 -761.465 3966.62 16.3854 4138.66 +EDGE_SE3:QUAT 1307 1357 -1.86935 -0.132988 -6.10002 -0.105134 0.127594 0.00542072 0.986224 1 1.92593e-19 1.92593e-19 -2.82857e-08 6.27358e-10 -3.60953e-09 1 1.92593e-19 -2.82857e-08 6.27358e-10 -3.60953e-09 1 -2.82857e-08 6.27358e-10 -3.60953e-09 4223.83 -63.5508 1069.63 3939.95 -40.6379 4267.93 +EDGE_SE3:QUAT 1306 1357 -2.5252 11.8327 -6.2946 0.0133542 -0.109257 0.194413 0.974725 1 3.00927e-21 3.00927e-21 -3.46395e-09 -6.97606e-10 3.76715e-10 1 3.00927e-21 -3.46395e-09 -6.97606e-10 3.76715e-10 1 -3.46395e-09 -6.97606e-10 3.76715e-10 4188.51 51.4806 -890.645 3962.96 -93.1315 4038.04 +EDGE_SE3:QUAT 1307 1356 -2.83308 -11.8654 -6.00511 -0.0445554 -0.0158051 -0.00582254 0.998865 1 4.81482e-20 4.81482e-20 -1.38693e-08 6.10226e-11 2.25769e-10 1 4.81482e-20 -1.38693e-08 6.10226e-11 2.25769e-10 1 -1.38693e-08 6.10226e-11 2.25769e-10 3996.23 2.87209 -129.287 3998.95 0.103268 4004.04 +EDGE_SE3:QUAT 1308 1358 -1.73873 0.0525921 -6.24318 -0.0434304 0.213571 0.0139951 0.975861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4838.78 -46.6928 2025.24 3818.32 -38.9505 4845.55 +EDGE_SE3:QUAT 1307 1358 -2.46275 11.824 -5.96834 0.0595034 0.0437149 0.0628558 0.995288 1 4.81482e-20 4.81482e-20 1.38518e-08 9.43951e-10 4.95069e-10 1 4.81482e-20 1.38518e-08 9.43951e-10 4.95069e-10 1 1.38518e-08 9.43951e-10 4.95069e-10 4008.49 10.9807 302.402 3995.17 11.3454 4006.85 +EDGE_SE3:QUAT 1308 1357 -2.6245 -12.0246 -6.1199 -0.0107016 -0.018889 0.110851 0.9936 1 3.00927e-21 3.00927e-21 3.4492e-09 3.86376e-10 -5.5752e-11 1 3.00927e-21 3.4492e-09 3.86376e-10 -5.5752e-11 1 3.4492e-09 3.86376e-10 -5.5752e-11 4004.04 1.48717 -134.309 3999.03 -7.23018 3955.34 +EDGE_SE3:QUAT 1309 1359 -1.60039 0.147872 -6.1181 0.0645066 0.124092 0.0658483 0.98798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4206.97 59.0226 972.22 3952.21 59.2804 4206.27 +EDGE_SE3:QUAT 1308 1359 -2.53343 11.8955 -6.39824 -0.225993 -0.0367235 -0.163283 0.959644 1 7.70372e-19 7.70372e-19 5.76769e-09 1.14763e-08 -5.41031e-08 1 7.70372e-19 5.76769e-09 1.14763e-08 -5.41031e-08 1 5.76769e-09 1.14763e-08 -5.41031e-08 3912.6 75.0904 -702.066 3962.76 38.6853 4010.24 +EDGE_SE3:QUAT 1309 1358 -2.57198 -11.9693 -5.91604 -0.227529 -0.13742 0.0498803 0.962735 1 1.92593e-19 1.92593e-19 2.81437e-09 7.06341e-09 -2.74021e-08 1 1.92593e-19 2.81437e-09 7.06341e-09 -2.74021e-08 1 2.81437e-09 7.06341e-09 -2.74021e-08 3986.65 128.97 -907.658 3979.35 -104.006 4183.77 +EDGE_SE3:QUAT 1310 1360 -1.76706 0.380925 -5.76958 -0.0464038 -0.205591 -0.0956471 0.972847 1 1.92593e-19 1.92593e-19 -6.40559e-09 -2.43105e-10 2.96211e-08 1 1.92593e-19 -6.40559e-09 -2.43105e-10 2.96211e-08 1 -6.40559e-09 -2.43105e-10 2.96211e-08 4797.06 -57.624 -1967.69 3828.29 78.7384 4769.08 +EDGE_SE3:QUAT 1309 1360 -2.68931 11.7257 -6.20744 -0.201893 0.0974815 0.136694 0.96491 1 1.15556e-18 1.15556e-18 5.39897e-08 -1.67907e-08 -2.44916e-08 1 1.15556e-18 5.39897e-08 -1.67907e-08 -2.44916e-08 1 5.39897e-08 -1.67907e-08 -2.44916e-08 4121.15 -82.5821 1105.2 3929.51 11.8705 4209.45 +EDGE_SE3:QUAT 1310 1359 -2.65196 -11.7787 -5.96986 -0.0466192 0.0456444 0.186518 0.980283 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.77 1.82109 452.511 3987.43 42.716 3911.3 +EDGE_SE3:QUAT 1311 1361 -1.78178 -0.126363 -5.71499 -0.0168191 0.0840128 0.00580967 0.996306 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4114.54 -5.2176 689.983 3971.7 -0.800511 4115.54 +EDGE_SE3:QUAT 1310 1361 -2.65202 12.0052 -6.40458 0.0844422 -0.0703877 0.0780061 0.990873 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.98 -18.3633 -645.497 3974.14 -15.1366 4077.16 +EDGE_SE3:QUAT 1311 1360 -2.25281 -11.8989 -5.84932 -0.0391681 0.119046 -0.122011 0.984585 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4189.5 -58.3638 906.742 3960.7 -73.7282 4136.09 +EDGE_SE3:QUAT 1312 1362 -1.91405 -0.104768 -6.25682 -0.0689628 -0.105175 0.0258015 0.991724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4151.24 38.878 -842.729 3961.05 -30.2953 4167.6 +EDGE_SE3:QUAT 1311 1362 -2.83516 11.707 -6.19392 0.0206955 0.0181433 0.0548991 0.998113 1 1.20371e-20 1.20371e-20 -6.92951e-09 -3.86259e-10 -1.09333e-10 1 1.20371e-20 -6.92951e-09 -3.86259e-10 -1.09333e-10 1 -6.92951e-09 -3.86259e-10 -1.09333e-10 4002.56 1.67969 130.905 3999.02 3.61237 3992.22 +EDGE_SE3:QUAT 1312 1361 -2.5929 -12.0434 -5.71117 -0.0750332 -0.0203139 -0.0815443 0.993634 1 1.92593e-19 1.92593e-19 -8.89458e-10 -1.96898e-09 2.76257e-08 1 1.92593e-19 -8.89458e-10 -1.96898e-09 2.76257e-08 1 -8.89458e-10 -1.96898e-09 2.76257e-08 3990.9 8.23605 -233.15 3996.03 9.19274 3986.83 +EDGE_SE3:QUAT 1313 1363 -1.99928 0.157866 -6.13045 0.132052 0.0997247 -0.132918 0.977216 1 1.92593e-19 1.92593e-19 2.79661e-08 -3.00518e-09 3.66453e-09 1 1.92593e-19 2.79661e-08 -3.00518e-09 3.66453e-09 1 2.79661e-08 -3.00518e-09 3.66453e-09 4175.03 33.5001 1020.29 3938.87 -34.3344 4174.12 +EDGE_SE3:QUAT 1312 1363 -2.59218 12.1419 -5.94935 0.0424436 -0.0272881 -0.0338576 0.998152 1 6.01853e-20 6.01853e-20 1.36191e-08 -7.42713e-09 -2.99435e-11 1 6.01853e-20 1.36191e-08 -7.42713e-09 -2.99435e-11 1 1.36191e-08 -7.42713e-09 -2.99435e-11 4002.81 -4.68843 -200.533 3997.68 3.9823 4005.43 +EDGE_SE3:QUAT 1313 1362 -2.59025 -11.9082 -5.65106 0.110715 -0.122971 0.0633429 0.984179 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4239.44 -45.8519 -1112.33 3931.75 6.35653 4272.42 +EDGE_SE3:QUAT 1314 1364 -2.02589 0.143387 -5.57664 0.00701461 -0.110095 0.212666 0.970877 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4181.25 58.6506 -871.738 3967.27 -100.979 4000.54 +EDGE_SE3:QUAT 1313 1364 -2.40388 12.0238 -6.18811 -0.0822268 -0.133187 0.0541375 0.986189 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4231.64 72.3786 -1050.04 3945.74 -67.038 4246.96 +EDGE_SE3:QUAT 1314 1363 -2.1106 -11.7469 -5.64133 0.0906221 -0.0166313 -0.147555 0.984753 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3966.64 3.89985 30.1676 3999.55 -6.33269 3912.4 +EDGE_SE3:QUAT 1315 1365 -1.80205 -0.123254 -5.8942 0.0365537 0.0638911 -0.115287 0.990601 1 2.40741e-19 2.40741e-19 -1.69718e-08 -2.59473e-08 -3.99412e-10 1 2.40741e-19 -1.69718e-08 -2.59473e-08 -3.99412e-10 1 -1.69718e-08 -2.59473e-08 -3.99412e-10 4071.51 -2.11285 559.851 3981.08 -30.4286 4023.69 +EDGE_SE3:QUAT 1314 1365 -3.0953 12.0107 -5.94738 -0.115812 -0.0373422 -0.00264658 0.992565 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.4 17.3652 -297.822 3994.84 -3.48148 4022.02 +EDGE_SE3:QUAT 1315 1364 -2.49544 -11.999 -5.65031 0.14983 -0.131662 -0.127333 0.971598 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4054.69 -93.9908 -782.962 3985.16 91.2632 4079.63 +EDGE_SE3:QUAT 1316 1366 -2.02132 -0.0564474 -6.33819 0.00233251 -0.0244985 0.114761 0.993088 1 1.20841e-20 1.20841e-20 -3.65278e-10 6.94076e-09 1.24284e-11 1 1.20841e-20 -3.65278e-10 6.94076e-09 1.24284e-11 1 -3.65278e-10 6.94076e-09 1.24284e-11 4009.53 1.43044 -195.722 3997.75 -11.2551 3956.87 +EDGE_SE3:QUAT 1315 1366 -2.58412 11.9458 -5.68189 0.0713009 -0.0439943 0.190927 0.978022 1 8.1852e-19 8.1852e-19 -9.92296e-09 -5.36376e-09 -5.37776e-08 1 8.1852e-19 -9.92296e-09 -5.36376e-09 -5.37776e-08 1 -9.92296e-09 -5.36376e-09 -5.37776e-08 4040.11 -4.24753 -496.775 3983.81 -47.5881 3914.63 +EDGE_SE3:QUAT 1316 1365 -2.29915 -11.6512 -5.32669 -0.0613119 -0.0468488 0.113791 0.990504 1 4.81482e-20 4.81482e-20 1.65141e-09 -1.37375e-08 -9.78444e-10 1 4.81482e-20 1.65141e-09 -1.37375e-08 -9.78444e-10 1 1.65141e-09 -1.37375e-08 -9.78444e-10 4004.67 11.8459 -283.412 3996.55 -16.7643 3967.91 +EDGE_SE3:QUAT 1317 1367 -2.03437 0.286997 -6.31522 0.00130917 0.0872865 0.000451222 0.996182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4124.74 0.592989 717.311 3969.53 0.42331 4124.74 +EDGE_SE3:QUAT 1316 1367 -2.61718 11.9134 -6.12771 0.0258299 -0.00955446 0.0494037 0.998399 1 6.31946e-20 6.31946e-20 6.93191e-09 -2.7811e-09 1.38615e-08 1 6.31946e-20 6.93191e-09 -2.7811e-09 1.38615e-08 1 6.93191e-09 -2.7811e-09 1.38615e-08 3999.41 -1.10243 -91.4072 3999.43 -2.30856 3992.32 +EDGE_SE3:QUAT 1317 1366 -2.7373 -11.969 -5.80787 -0.0193289 0.0261538 -0.136014 0.990173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.87 -3.23178 172.403 3998.58 -11.1799 3933.37 +EDGE_SE3:QUAT 1318 1368 -1.6263 0.14718 -6.01385 -0.148778 0.136314 -0.0574898 0.977742 1 9.62965e-19 9.62965e-19 -5.90485e-08 1.04279e-08 -3.43007e-08 1 9.62965e-19 -5.90485e-08 1.04279e-08 -3.43007e-08 1 -5.90485e-08 1.04279e-08 -3.43007e-08 4141.87 -105.093 989.468 3960.69 -89.8657 4217.19 +EDGE_SE3:QUAT 1317 1368 -2.39514 11.9427 -6.50644 -0.187273 0.110674 0.3202 0.922037 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4399.08 42.1258 1567.72 3880.86 204.937 4129.25 +EDGE_SE3:QUAT 1318 1367 -2.81942 -11.8312 -5.69008 -0.0369115 0.0939532 -0.0296363 0.994451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4133.34 -21.5084 757.936 3967.14 -20.0747 4135.28 +EDGE_SE3:QUAT 1319 1369 -2.37246 0.0852605 -6.01451 -0.0320014 0.00544926 -0.0375214 0.998768 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.11 -0.401852 29.05 3999.96 -0.466489 3994.57 +EDGE_SE3:QUAT 1318 1369 -2.6761 11.8732 -6.14232 -0.136137 0.214378 0.0594931 0.965386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4834.36 -132.795 2111.72 3815.63 -106.402 4894.34 +EDGE_SE3:QUAT 1319 1368 -2.53112 -11.7963 -5.82434 0.0912504 -0.0434308 0.00405938 0.994872 1 1.92611e-19 1.92611e-19 2.77069e-08 -8.40737e-11 -9.39745e-10 1 1.92611e-19 2.77069e-08 -8.40737e-11 -9.39745e-10 1 2.77069e-08 -8.40737e-11 -9.39745e-10 3997.06 -16.0966 -349.848 3992.71 3.4638 4030.3 +EDGE_SE3:QUAT 1320 1370 -1.94296 -0.198792 -6.03849 -0.109995 0.0329216 0.084142 0.989817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.05 -18.7431 368.609 3990.43 12.2852 4005.13 +EDGE_SE3:QUAT 1319 1370 -2.78545 11.46 -6.13431 -0.0618248 -0.170715 0.0340509 0.982789 1 1.92593e-19 1.92593e-19 2.88784e-08 1.70036e-09 -4.83037e-09 1 1.92593e-19 2.88784e-08 1.70036e-09 -4.83037e-09 1 2.88784e-08 1.70036e-09 -4.83037e-09 4464.69 85.1604 -1466.5 3896.76 -80.1701 4475.34 +EDGE_SE3:QUAT 1320 1369 -2.38707 -11.794 -5.51889 0.0451887 -0.0766705 -0.187508 0.978223 1 4.81482e-20 4.81482e-20 1.36761e-08 -2.73404e-09 -7.55662e-10 1 4.81482e-20 1.36761e-08 -2.73404e-09 -7.55662e-10 1 1.36761e-08 -2.73404e-09 -7.55662e-10 4048.95 -29.3 -484.55 3991.46 47.8921 3916.48 +EDGE_SE3:QUAT 1321 1371 -1.58969 0.0140535 -6.16594 0.00167317 -0.0557822 -0.0119238 0.99837 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.17 -1.29239 -450.81 3987.59 2.90172 4049.61 +EDGE_SE3:QUAT 1320 1371 -2.71309 11.8065 -6.19335 0.0206899 -0.0724233 0.0642183 0.995089 1 1.92593e-19 1.92593e-19 1.71671e-09 -2.76234e-08 3.16039e-10 1 1.92593e-19 1.71671e-09 -2.76234e-08 3.16039e-10 1 1.71671e-09 -2.76234e-08 3.16039e-10 4087.22 1.95675 -603.043 3978.17 -17.8279 4072.44 +EDGE_SE3:QUAT 1321 1370 -2.37459 -11.7007 -5.79764 0.00842663 -0.111911 -0.0789608 0.99054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4199.82 -28.8917 -916.815 3953.97 43.3424 4175.17 +EDGE_SE3:QUAT 1322 1372 -1.69179 -0.0498526 -6.16078 -0.225399 -0.0225828 0.126685 0.965731 1 7.71124e-19 7.71124e-19 5.385e-08 5.1889e-09 1.58914e-09 1 7.71124e-19 5.385e-08 5.1889e-09 1.58914e-09 1 5.385e-08 5.1889e-09 1.58914e-09 3800.5 -31.7887 164.667 3994.97 17.4618 3939.52 +EDGE_SE3:QUAT 1321 1372 -2.82638 11.613 -5.82997 0.0743187 -0.000423939 0.12528 0.989334 1 1.92593e-19 1.92593e-19 2.74697e-08 3.43839e-09 -5.22798e-10 1 1.92593e-19 2.74697e-08 3.43839e-09 -5.22798e-10 1 2.74697e-08 3.43839e-09 -5.22798e-10 3980.81 -5.23206 -113.516 3998.61 -9.22578 3940.12 +EDGE_SE3:QUAT 1322 1371 -2.79772 -11.803 -6.02228 -0.0650202 0.00737517 -0.050793 0.996563 1 4.81482e-20 4.81482e-20 -9.59727e-12 9.08102e-10 -1.38302e-08 1 4.81482e-20 -9.59727e-12 9.08102e-10 -1.38302e-08 1 -9.59727e-12 9.08102e-10 -1.38302e-08 3983.13 -0.194414 18.9459 4000 -0.159061 3989.72 +EDGE_SE3:QUAT 1323 1373 -1.82792 0.362314 -5.99987 -0.0482538 0.106937 0.284815 0.951376 1 1.20371e-20 1.20371e-20 6.79245e-09 2.00597e-09 8.2677e-10 1 1.20371e-20 6.79245e-09 2.00597e-09 8.2677e-10 1 6.79245e-09 2.00597e-09 8.2677e-10 4206.19 69.2068 953.352 3964.15 141.648 3891.03 +EDGE_SE3:QUAT 1322 1373 -2.68612 12.107 -6.43183 0.102659 0.00148761 0.122962 0.987086 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3961.99 -9.16762 -137.582 3997.84 -11.1622 3943.67 +EDGE_SE3:QUAT 1323 1372 -2.6285 -12.1112 -5.79282 0.0387748 0.0367234 0.0596209 0.996791 1 9.62965e-20 9.62965e-20 4.25128e-10 -1.44285e-08 -1.32673e-08 1 9.62965e-20 4.25128e-10 -1.44285e-08 -1.32673e-08 1 4.25128e-10 -1.44285e-08 -1.32673e-08 4011.41 6.65323 264.817 3996.08 8.76746 4003.21 +EDGE_SE3:QUAT 1324 1374 -1.50198 0.0112228 -5.86031 -0.00559897 -0.0743788 -0.073806 0.994479 1 2.51446e-22 2.51446e-22 -1.00857e-09 7.484e-11 7.54447e-11 1 2.51446e-22 -1.00857e-09 7.484e-11 7.54447e-11 1 -1.00857e-09 7.484e-11 7.54447e-11 4089.91 -8.29906 -606.839 3978.36 22.9451 4068.25 +EDGE_SE3:QUAT 1323 1374 -2.92987 12.0512 -6.20043 -0.0328804 -0.0447318 0.0160237 0.998329 1 9.62965e-20 9.62965e-20 -1.36445e-08 -1.41186e-08 1.28961e-10 1 9.62965e-20 -1.36445e-08 -1.41186e-08 1.28961e-10 1 -1.36445e-08 -1.41186e-08 1.28961e-10 4026.61 6.64043 -353.156 3992.46 -4.4152 4029.91 +EDGE_SE3:QUAT 1324 1373 -3.18497 -12.0928 -5.82369 -0.0418145 0.107084 -0.287516 0.950852 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4084.03 -63.2846 620.778 3996.43 -92.2439 3760.36 +EDGE_SE3:QUAT 1325 1375 -2.18257 -0.208997 -5.88049 0.116307 0.011121 0.0478137 0.991999 1 2.40741e-19 2.40741e-19 -2.75297e-08 -2.98412e-09 -1.37593e-08 1 2.40741e-19 -2.75297e-08 -2.98412e-09 -1.37593e-08 1 -2.75297e-08 -2.98412e-09 -1.37593e-08 3945.87 -0.101315 20.8255 4000.01 0.00314231 3990.83 +EDGE_SE3:QUAT 1324 1375 -2.65591 11.7507 -6.22395 0.0093064 0.0971242 0.251006 0.963056 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4115.58 52.5355 693.143 3984 92.3607 3863.91 +EDGE_SE3:QUAT 1325 1374 -2.69626 -11.9062 -6.0075 -0.064466 0.0111653 -0.0950039 0.993325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.27 0.302475 14.7022 4000 0.471473 3963.79 +EDGE_SE3:QUAT 1326 1376 -2.01877 0.123924 -6.14701 -0.118379 0.0362147 0.043064 0.991373 1 2.40741e-19 2.40741e-19 -2.80839e-08 1.28311e-08 3.39573e-10 1 2.40741e-19 -2.80839e-08 1.28311e-08 3.39573e-10 1 -2.80839e-08 1.28311e-08 3.39573e-10 3973.57 -20.0909 345.858 3992.21 3.00177 4022.21 +EDGE_SE3:QUAT 1325 1376 -2.49735 11.6503 -5.9762 0.0311902 -0.0720379 -0.080509 0.993658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4069.8 -18.0918 -548.105 3983.36 26.3004 4047.77 +EDGE_SE3:QUAT 1326 1375 -2.44297 -11.8362 -5.86052 0.0689046 0.0510499 -0.163715 0.982773 1 8.66668e-19 8.66668e-19 -1.2e-08 -8.71809e-09 5.47375e-08 1 8.66668e-19 -1.2e-08 -8.71809e-09 5.47375e-08 1 -1.2e-08 -8.71809e-09 5.47375e-08 4050.03 4.58569 530.852 3981.9 -41.6759 3961.81 +EDGE_SE3:QUAT 1327 1377 -1.84422 -0.0713573 -5.99354 -0.0643017 -0.0322126 -0.0749004 0.994594 1 1.92593e-19 1.92593e-19 2.76901e-08 -1.95799e-09 -1.14694e-09 1 1.92593e-19 2.76901e-08 -1.95799e-09 -1.14694e-09 1 2.76901e-08 -1.95799e-09 -1.14694e-09 4007.77 8.23957 -313.216 3993.39 10.3789 4001.87 +EDGE_SE3:QUAT 1326 1377 -2.69059 12.1568 -6.20414 -0.0836734 0.0935245 -0.0243847 0.991795 1 1.92593e-19 1.92593e-19 2.79778e-08 -1.13555e-09 2.48029e-09 1 1.92593e-19 2.79778e-08 -1.13555e-09 2.48029e-09 1 2.79778e-08 -1.13555e-09 2.48029e-09 4102.74 -37.9924 735.038 3970.42 -26.7151 4128.37 +EDGE_SE3:QUAT 1327 1376 -2.61796 -11.8177 -6.17813 -0.0360533 -0.171684 -0.133121 0.97545 1 2.70834e-20 2.70834e-20 1.08218e-08 -1.42549e-09 -1.94156e-09 1 2.70834e-20 1.08218e-08 -1.42549e-09 -1.94156e-09 1 1.08218e-08 -1.42549e-09 -1.94156e-09 4529.38 -75.9207 -1556.96 3886.3 107.687 4463.69 +EDGE_SE3:QUAT 1328 1378 -1.96047 0.0669688 -6.03464 0.069343 0.00560238 0.115305 0.990891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.17 -2.86321 -51.1857 3999.57 -4.7976 3947.22 +EDGE_SE3:QUAT 1327 1378 -2.79699 11.824 -6.04877 -0.0374376 -0.0056294 -0.0745216 0.996501 1 4.81482e-20 4.81482e-20 1.38318e-08 -1.02576e-09 -1.5424e-10 1 4.81482e-20 1.38318e-08 -1.02576e-09 -1.5424e-10 1 1.38318e-08 -1.02576e-09 -1.5424e-10 3995.88 1.52599 -77.9203 3999.51 3.24522 3979.27 +EDGE_SE3:QUAT 1328 1377 -3.02783 -11.657 -5.91181 0.117924 -0.0419998 0.0486137 0.990942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.85 -22.5785 -399.682 3989.67 -3.82153 4030.02 +EDGE_SE3:QUAT 1329 1379 -1.96776 0.117535 -6.00694 -0.0681407 0.0655784 -0.161955 0.982256 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4014.91 -21.4347 372.111 3995.43 -31.0961 3928.56 +EDGE_SE3:QUAT 1328 1379 -2.78783 11.6973 -6.00638 -0.0351728 0.0436614 0.0394356 0.997648 1 4.81482e-20 4.81482e-20 6.43841e-10 -4.42501e-10 1.3903e-08 1 4.81482e-20 6.43841e-10 -4.42501e-10 1.3903e-08 1 6.43841e-10 -4.42501e-10 1.3903e-08 4028.48 -4.733 367.197 3991.54 5.75386 4027.2 +EDGE_SE3:QUAT 1329 1378 -2.316 -11.4805 -5.44339 0.160975 0.0164056 -0.0985955 0.981884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3919.82 27.511 312.193 3991.88 -14.0188 3984.59 +EDGE_SE3:QUAT 1330 1380 -1.9149 -0.00468883 -6.11176 0.0235356 0.00095979 0.0464579 0.998642 1 1.20371e-20 1.20371e-20 6.92948e-09 3.22323e-10 -8.52984e-12 1 1.20371e-20 6.92948e-09 3.22323e-10 -8.52984e-12 1 6.92948e-09 3.22323e-10 -8.52984e-12 3997.79 -0.115652 -5.45016 3999.99 -0.228401 3991.37 +EDGE_SE3:QUAT 1329 1380 -3.00688 11.8259 -5.99765 0.0558313 -0.00374733 0.0674821 0.99615 1 4.81482e-20 4.81482e-20 -1.38267e-08 -9.25088e-10 1.5541e-10 1 4.81482e-20 -1.38267e-08 -9.25088e-10 1.5541e-10 1 -1.38267e-08 -9.25088e-10 1.5541e-10 3988.87 -2.39633 -74.6411 3999.51 -2.93677 3983.12 +EDGE_SE3:QUAT 1330 1379 -2.64635 -12.236 -6.01221 -0.00802768 0.0252971 -0.0772489 0.996659 1 1.95602e-19 1.95602e-19 -4.12197e-09 5.991e-10 -2.77778e-08 1 1.95602e-19 -4.12197e-09 5.991e-10 -2.77778e-08 1 -4.12197e-09 5.991e-10 -2.77778e-08 4009.08 -1.87929 193.517 3997.8 -7.51815 3985.47 +EDGE_SE3:QUAT 1331 1381 -1.79173 -0.0857943 -5.85336 -0.0953727 0.10789 0.11115 0.983316 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4206.92 -17.0186 1016.42 3940.55 32.1493 4193.89 +EDGE_SE3:QUAT 1330 1381 -2.8431 11.9963 -6.09255 0.0468805 -0.0835772 0.259685 0.960927 1 1.20371e-20 1.20371e-20 6.79291e-09 1.80346e-09 -6.76563e-10 1 1.20371e-20 6.79291e-09 1.80346e-09 -6.76563e-10 1 6.79291e-09 1.80346e-09 -6.76563e-10 4132.46 35.2879 -764.814 3972.52 -101.527 3871.5 +EDGE_SE3:QUAT 1331 1380 -3.04751 -11.5904 -5.93852 0.0336443 0.00989094 -0.0984537 0.994524 1 4.81482e-20 4.81482e-20 -1.38077e-08 1.35498e-09 -2.25856e-10 1 4.81482e-20 -1.38077e-08 1.35498e-09 -2.25856e-10 1 -1.38077e-08 1.35498e-09 -2.25856e-10 3998.88 1.75431 117.412 3998.97 -6.27046 3964.63 +EDGE_SE3:QUAT 1332 1382 -1.96346 -0.104251 -5.66839 -0.000269081 -0.00172975 -0.11201 0.993706 1 4.72034e-23 4.72034e-23 -2.16418e-11 -4.33987e-10 5.89376e-15 1 4.72034e-23 -2.16418e-11 -4.33987e-10 5.89376e-15 1 -2.16418e-11 -4.33987e-10 5.89376e-15 4000.05 -0.00630509 -13.9372 3999.99 0.782403 3949.86 +EDGE_SE3:QUAT 1331 1382 -3.21451 11.9877 -5.71258 -0.0434631 -0.0369492 0.0833081 0.99489 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.83 7.24707 -249.175 3996.8 -10.9451 3987.63 +EDGE_SE3:QUAT 1332 1381 -2.72583 -11.5498 -5.91588 -0.0531749 -0.0222806 0.0885834 0.994399 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.14 3.23955 -119.304 3999.44 -4.77494 3972.06 +EDGE_SE3:QUAT 1333 1383 -2.03314 -0.300664 -5.97957 -0.0495833 -0.141502 -0.0430491 0.987758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4343.49 14.0803 -1240.22 3917 5.54028 4345.91 +EDGE_SE3:QUAT 1332 1383 -2.81206 11.5321 -6.06758 0.15735 -0.147274 -0.01207 0.976425 1 8.1852e-19 8.1852e-19 5.8387e-08 -5.85148e-09 -2.19458e-08 1 8.1852e-19 5.8387e-08 -5.85148e-09 -2.19458e-08 1 5.8387e-08 -5.85148e-09 -2.19458e-08 4226.87 -118.976 -1188.04 3937.74 92.1158 4325.33 +EDGE_SE3:QUAT 1333 1382 -2.59209 -11.6441 -5.77776 -0.0256083 -0.0609539 -0.0946624 0.993312 1 2.0463e-19 2.0463e-19 9.50771e-09 2.69317e-08 -6.934e-11 1 2.0463e-19 9.50771e-09 2.69317e-08 -6.934e-11 1 9.50771e-09 2.69317e-08 -6.934e-11 4063.15 -2.27787 -517.132 3983.84 23.3394 4029.92 +EDGE_SE3:QUAT 1334 1384 -1.99245 -0.130857 -6.03293 -0.0531167 0.137051 -0.0571279 0.987488 1 9.62965e-19 9.62965e-19 -2.4292e-08 5.68796e-08 2.19661e-10 1 9.62965e-19 -2.4292e-08 5.68796e-08 2.19661e-10 1 -2.4292e-08 5.68796e-08 2.19661e-10 4277.97 -61.1335 1114.06 3936.76 -61.9199 4276.2 +EDGE_SE3:QUAT 1333 1384 -2.44817 11.4178 -6.08913 -0.0469705 -0.0526648 0.0298164 0.997061 1 4.81482e-20 4.81482e-20 -1.39076e-08 -4.85489e-10 6.90753e-10 1 4.81482e-20 -1.39076e-08 -4.85489e-10 6.90753e-10 1 -1.39076e-08 -4.85489e-10 6.90753e-10 4031.97 11.5289 -406.047 3990.35 -9.08214 4037.23 +EDGE_SE3:QUAT 1334 1383 -3.25759 -11.8521 -5.73889 -0.10683 -0.0490347 -0.00252949 0.993064 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.41 21.2623 -392.031 3991.06 -5.67883 4038.03 +EDGE_SE3:QUAT 1335 1385 -2.16605 -0.0160735 -6.02917 -0.0161708 0.0674664 0.102202 0.992341 1 3.00927e-21 3.00927e-21 -3.4762e-09 -3.53544e-10 -2.4288e-10 1 3.00927e-21 -3.4762e-09 -3.53544e-10 -2.4288e-10 1 -3.4762e-09 -3.53544e-10 -2.4288e-10 4075.94 7.07516 560.258 3981.55 28.3696 4035.21 +EDGE_SE3:QUAT 1334 1385 -2.43593 11.7352 -6.04743 0.137435 0.0786774 -0.0210967 0.987156 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.88 45.5381 661.102 3975.43 14.6531 4104.65 +EDGE_SE3:QUAT 1335 1384 -2.9917 -11.9564 -5.85261 0.081093 -0.0298978 0.00862554 0.996221 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.77 -9.95832 -245.983 3996.28 0.742576 4014.77 +EDGE_SE3:QUAT 1336 1386 -1.8373 0.303813 -5.78221 0.071629 -0.0636133 -0.10701 0.989632 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.3 -21.3381 -407.979 3992.51 25.6991 3995.01 +EDGE_SE3:QUAT 1335 1386 -2.883 11.7704 -6.45784 -0.144602 0.130445 -0.0140571 0.980753 1 8.1852e-19 8.1852e-19 -1.16845e-09 -5.65664e-08 5.54806e-09 1 8.1852e-19 -1.16845e-09 -5.65664e-08 5.54806e-09 1 -1.16845e-09 -5.65664e-08 5.54806e-09 4169.98 -92.5373 1039.15 3949.11 -67.4133 4252.83 +EDGE_SE3:QUAT 1336 1385 -2.75084 -11.7501 -5.80818 -0.144008 0.0834952 -0.0557225 0.984472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.49 -46.7294 556.576 3986.68 -33.788 4063.03 +EDGE_SE3:QUAT 1337 1387 -2.33762 -0.446403 -5.72529 -0.0432937 -0.0419165 -0.0965598 0.993501 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.76 3.75396 -382.784 3990.59 17.3436 3998.97 +EDGE_SE3:QUAT 1336 1387 -2.91304 11.8358 -6.0167 0.13837 0.255099 0.0393763 0.956153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4995.29 345.668 2333.19 3845.56 341.814 5065.68 +EDGE_SE3:QUAT 1337 1386 -2.69546 -11.6676 -5.78803 -0.0989718 0.12994 0.0749521 0.983719 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4286.12 -34.3192 1186.29 3922.91 5.11227 4302.83 +EDGE_SE3:QUAT 1338 1388 -2.02372 -0.0236103 -6.07244 0.0688713 0.0146483 -0.0494706 0.996291 1 4.81482e-20 4.81482e-20 -2.94873e-10 -9.32273e-10 -1.38369e-08 1 4.81482e-20 -2.94873e-10 -9.32273e-10 -1.38369e-08 1 -2.94873e-10 -9.32273e-10 -1.38369e-08 3987.13 5.46626 156.855 3998.23 -3.65175 3996.31 +EDGE_SE3:QUAT 1337 1388 -3.00288 11.7212 -5.88988 -0.0783403 -0.0121438 -0.000288203 0.996853 1 1.17549e-23 1.17549e-23 -2.61146e-12 -1.69958e-11 2.16221e-10 1 1.17549e-23 -2.61146e-12 -1.69958e-11 2.16221e-10 1 -2.61146e-12 -1.69958e-11 2.16221e-10 3977.78 3.77954 -96.576 3999.43 -0.261638 4002.33 +EDGE_SE3:QUAT 1338 1387 -2.52626 -11.732 -6.11396 0.0135975 0.0336166 -0.141436 0.989283 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.45 -2.24259 284.916 3995.19 -20.3523 3940.17 +EDGE_SE3:QUAT 1339 1389 -2.03672 -0.0759294 -5.72216 -0.09316 -0.0784636 -0.158213 0.979864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4118.48 8.18474 -798.542 3961.16 52.1987 4053.07 +EDGE_SE3:QUAT 1338 1389 -2.66994 11.7883 -5.98399 -0.0876727 -0.0527941 0.153677 0.982807 1 7.70372e-19 7.70372e-19 -1.26821e-09 -5.55499e-09 5.46542e-08 1 7.70372e-19 -1.26821e-09 -5.55499e-09 5.46542e-08 1 -1.26821e-09 -5.55499e-09 5.46542e-08 3983.08 12.8957 -244.157 3998.78 -17.0723 3919.36 +EDGE_SE3:QUAT 1339 1388 -2.58928 -11.664 -5.98131 0.110759 0.109065 -0.204081 0.966534 1 9.62965e-19 9.62965e-19 -1.77884e-08 5.91194e-08 -7.47077e-09 1 9.62965e-19 -1.77884e-08 5.91194e-08 -7.47077e-09 1 -1.77884e-08 5.91194e-08 -7.47077e-09 4255.66 -12.4359 1146.18 3928.3 -94.9201 4138.14 +EDGE_SE3:QUAT 1340 1390 -1.88647 0.105642 -5.97952 -0.197557 0.0467361 0.101059 0.973948 1 9.62965e-19 9.62965e-19 -5.25578e-08 -3.13424e-08 -9.72502e-09 1 9.62965e-19 -5.25578e-08 -3.13424e-08 -9.72502e-09 1 -5.25578e-08 -3.13424e-08 -9.72502e-09 3928.72 -56.5161 591.378 3976.23 12.4911 4043.99 +EDGE_SE3:QUAT 1339 1390 -2.87632 12.0192 -5.95894 0.0649487 -0.0738713 0.194517 0.975955 1 1.92593e-19 1.92593e-19 2.75313e-08 5.24404e-09 -2.61504e-09 1 1.92593e-19 2.75313e-08 5.24404e-09 -2.61504e-09 1 2.75313e-08 5.24404e-09 -2.61504e-09 4109.82 9.11546 -723.472 3969.74 -67.4519 3975.35 +EDGE_SE3:QUAT 1340 1389 -2.62296 -11.7673 -5.49652 -0.217454 0.109907 -0.037654 0.969132 1 4.81482e-20 4.81482e-20 -1.16464e-09 3.24608e-09 -1.36784e-08 1 4.81482e-20 -1.16464e-09 3.24608e-09 -1.36784e-08 1 -1.16464e-09 3.24608e-09 -1.36784e-08 3940.98 -91.2721 736.962 3982.46 -63.7434 4124.46 +EDGE_SE3:QUAT 1341 1391 -2.17876 0.250225 -5.7486 0.0402359 0.0493507 0.0833775 0.994482 1 9.62965e-20 9.62965e-20 1.26412e-08 1.50147e-08 -8.49228e-11 1 9.62965e-20 1.26412e-08 1.50147e-08 -8.49228e-11 1 1.26412e-08 1.50147e-08 -8.49228e-11 4024.16 11.029 351.783 3993.36 16.3405 4002.83 +EDGE_SE3:QUAT 1340 1391 -2.681 11.6217 -6.04568 0.0781238 0.0810041 0.158708 0.980891 1 3.85186e-19 3.85186e-19 2.26781e-08 3.1951e-08 -1.35563e-09 1 3.85186e-19 2.26781e-08 3.1951e-08 -1.35563e-09 1 2.26781e-08 3.1951e-08 -1.35563e-09 4030.14 33.0866 475.269 3992.47 42.6666 3953.8 +EDGE_SE3:QUAT 1341 1390 -2.79364 -11.652 -6.07923 -0.0313426 -0.00660656 -0.226499 0.973485 1 1.20371e-20 1.20371e-20 -6.75862e-09 1.56691e-09 1.37052e-10 1 1.20371e-20 -6.75862e-09 1.56691e-09 1.37052e-10 1 -6.75862e-09 1.56691e-09 1.37052e-10 4000.24 1.34918 -131.131 3998.59 17.7686 3798.96 +EDGE_SE3:QUAT 1342 1392 -2.12213 0.116917 -5.81421 0.0337823 0.12402 -0.0265205 0.99135 1 1.20371e-20 1.20371e-20 -8.98355e-10 -2.01173e-10 -7.10138e-09 1 1.20371e-20 -8.98355e-10 -2.01173e-10 -7.10138e-09 1 -8.98355e-10 -2.01173e-10 -7.10138e-09 4257.98 10.1571 1057.88 3937.36 -2.7342 4259.73 +EDGE_SE3:QUAT 1341 1392 -2.61191 12.0458 -5.85074 0.0156379 -0.0576592 0.117412 0.991285 1 6.01853e-20 6.01853e-20 8.54274e-09 -1.29453e-08 -3.92325e-10 1 6.01853e-20 8.54274e-09 -1.29453e-08 -3.92325e-10 1 8.54274e-09 -1.29453e-08 -3.92325e-10 4055.69 6.07985 -479.465 3986.5 -28.0902 4001.53 +EDGE_SE3:QUAT 1342 1391 -2.58309 -11.4076 -5.75159 0.0929041 0.146608 -0.0628916 0.982812 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4368.2 38.6775 1331.61 3906.51 5.13096 4386.9 +EDGE_SE3:QUAT 1343 1393 -1.84459 -0.0655586 -5.93357 0.13249 -0.0821415 -0.140436 0.977741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.74 -33.3379 -402.924 3996.93 34.0212 3959.06 +EDGE_SE3:QUAT 1342 1393 -2.84802 11.5011 -6.28317 -0.0241472 0.195907 0.151545 0.968541 1 7.70372e-19 7.70372e-19 8.56027e-09 -5.37415e-08 2.07508e-09 1 7.70372e-19 8.56027e-09 -5.37415e-08 2.07508e-09 1 8.56027e-09 -5.37415e-08 2.07508e-09 4680.47 139.148 1788.28 3867.46 166.058 4590.94 +EDGE_SE3:QUAT 1343 1392 -2.7229 -11.6765 -5.97386 -0.0702576 -0.0885177 -0.134494 0.984449 1 7.70372e-19 7.70372e-19 5.86197e-09 2.55308e-09 -5.57803e-08 1 7.70372e-19 5.86197e-09 2.55308e-09 -5.57803e-08 1 5.86197e-09 2.55308e-09 -5.57803e-08 4144.25 0.585827 -826.649 3959.73 46.1584 4091.64 +EDGE_SE3:QUAT 1344 1394 -2.29308 -0.200537 -5.87356 0.135441 -0.180036 0.143527 0.963661 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4657.52 -17.6985 -1859.83 3839.21 -37.8054 4648.49 +EDGE_SE3:QUAT 1343 1394 -3.15013 11.4463 -6.13329 0.00676387 -0.0196778 0.018235 0.999617 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.13 -0.369463 -159.034 3998.42 -1.39632 4004.98 +EDGE_SE3:QUAT 1344 1393 -2.73003 -11.656 -5.70015 -0.0951016 -0.0119608 0.0583677 0.993683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3963.89 0.278834 -27.8346 4000.01 -0.210842 3986.44 +EDGE_SE3:QUAT 1345 1395 -2.26805 -0.0724926 -5.73538 -0.232442 0.0164106 0.0314672 0.971963 1 7.82409e-19 7.82409e-19 -5.41728e-08 5.59746e-09 1.47904e-12 1 7.82409e-19 -5.41728e-08 5.59746e-09 1.47904e-12 1 -5.41728e-08 5.59746e-09 1.47904e-12 3794.35 -26.5631 205.727 3997.14 0.439521 4006.5 +EDGE_SE3:QUAT 1344 1395 -2.4189 11.5047 -5.94377 -0.0225244 0.0334558 -0.0161616 0.999056 1 1.20371e-20 1.20371e-20 6.94736e-09 -1.23016e-10 2.27216e-10 1 1.20371e-20 6.94736e-09 -1.23016e-10 2.27216e-10 1 6.94736e-09 -1.23016e-10 2.27216e-10 4015.31 -3.41421 263.955 3995.75 -2.73699 4016.3 +EDGE_SE3:QUAT 1345 1394 -2.7487 -11.5279 -5.79204 0.283307 -0.027112 -0.023391 0.95836 1 1.20371e-20 1.20371e-20 -6.94125e-11 1.97508e-09 6.65265e-09 1 1.20371e-20 -6.94125e-11 1.97508e-09 6.65265e-09 1 -6.94125e-11 1.97508e-09 6.65265e-09 3681.92 -11.5872 -115.845 4000.09 3.01278 4000.78 +EDGE_SE3:QUAT 1346 1396 -2.01584 0.0163716 -5.81273 0.00494649 0.235545 -0.0857193 0.968063 1 1.92593e-19 1.92593e-19 7.25265e-09 -1.20031e-09 3.01828e-08 1 1.92593e-19 7.25265e-09 -1.20031e-09 3.01828e-08 1 7.25265e-09 -1.20031e-09 3.01828e-08 5038.53 -140.978 2287.68 3794.75 -149.516 5009.24 +EDGE_SE3:QUAT 1345 1396 -2.8752 11.9163 -6.19917 -0.00183943 -0.0417752 -0.00200389 0.999123 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.06 0.230325 -336.295 3993.02 0.265436 4028.06 +EDGE_SE3:QUAT 1346 1395 -3.5777 -11.363 -5.5636 -0.0609145 -0.0472694 -0.145745 0.986313 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4040.72 4.52338 -475.351 3985.4 33.2367 3970.59 +EDGE_SE3:QUAT 1347 1397 -2.02166 0.0926061 -6.25568 -0.0329493 0.130485 -0.235237 0.962575 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4185.54 -94.6243 896.589 3977.3 -125.566 3968.54 +EDGE_SE3:QUAT 1346 1397 -2.97133 11.5416 -5.75452 0.0492906 -0.15863 0.138151 0.976382 1 7.70372e-19 7.70372e-19 9.74046e-09 -2.86064e-10 -5.735e-08 1 7.70372e-19 9.74046e-09 -2.86064e-10 -5.735e-08 1 9.74046e-09 -2.86064e-10 -5.735e-08 4459.27 55.368 -1447.73 3897.53 -93.5681 4392.65 +EDGE_SE3:QUAT 1347 1396 -2.94904 -11.4868 -5.82226 0.128546 -0.0199804 -0.14372 0.981031 1 7.70372e-19 7.70372e-19 -5.44559e-08 7.99418e-09 -9.86422e-10 1 7.70372e-19 -5.44559e-08 7.99418e-09 -9.86422e-10 1 -5.44559e-08 7.99418e-09 -9.86422e-10 3933.59 9.15718 65.2215 3998.74 -10.2336 3917.06 +EDGE_SE3:QUAT 1348 1398 -2.28173 -0.288218 -5.49421 -0.0614765 0.147738 0.0780885 0.98402 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4388.1 -2.73587 1332.5 3906.11 27.016 4378.83 +EDGE_SE3:QUAT 1347 1398 -2.70222 11.7414 -6.19564 -0.113236 -0.107903 0.0547413 0.986173 1 1.92593e-19 1.92593e-19 -2.59534e-09 -3.59173e-09 2.7892e-08 1 1.92593e-19 -2.59534e-09 -3.59173e-09 2.7892e-08 1 -2.59534e-09 -3.59173e-09 2.7892e-08 4099.38 61.4284 -791.815 3970.17 -51.0709 4138.68 +EDGE_SE3:QUAT 1348 1397 -2.80551 -12.0708 -5.77854 -0.0588 -0.0620255 -0.0787866 0.993221 1 4.33334e-19 4.33334e-19 -1.3937e-08 -2.52133e-08 -2.81995e-08 1 4.33334e-19 -1.3937e-08 -2.52133e-08 -2.81995e-08 1 -1.3937e-08 -2.52133e-08 -2.81995e-08 4061.39 8.85374 -553.847 3980.84 16.9992 4050.39 +EDGE_SE3:QUAT 1349 1399 -2.27017 0.128857 -5.59148 0.0490236 0.0199968 0.0713673 0.996044 1 1.92593e-19 1.92593e-19 -3.53192e-10 -1.42726e-09 -2.76574e-08 1 1.92593e-19 -3.53192e-10 -1.42726e-09 -2.76574e-08 1 -3.53192e-10 -1.42726e-09 -2.76574e-08 3993.72 2.93143 116.451 3999.39 3.93959 3982.96 +EDGE_SE3:QUAT 1348 1399 -3.1134 11.282 -5.78303 -0.105785 0.0692089 0.1342 0.982858 1 1.92593e-19 1.92593e-19 -2.77133e-08 -3.3321e-09 -2.63618e-09 1 1.92593e-19 -2.77133e-08 -3.3321e-09 -2.63618e-09 1 -2.77133e-08 -3.3321e-09 -2.63618e-09 4079.99 -19.7243 718.467 3967.25 36.3169 4052.71 +EDGE_SE3:QUAT 1349 1398 -2.80002 -11.6357 -5.97387 0.0404095 -0.019852 -0.169685 0.984469 1 4.81482e-20 4.81482e-20 1.36641e-08 -2.37061e-09 -7.12042e-11 1 4.81482e-20 1.36641e-08 -2.37061e-09 -7.12042e-11 1 1.36641e-08 -2.37061e-09 -7.12042e-11 3994.49 -1.35142 -70.9673 3999.98 3.61924 3885.85 +EDGE_SE3:QUAT 1350 1400 -1.82025 -0.109217 -6.19434 0.000428104 0.0481471 0.0444576 0.99785 1 1.88079e-22 1.88079e-22 -8.69508e-10 -3.89559e-11 -4.17545e-11 1 1.88079e-22 -8.69508e-10 -3.89559e-11 -4.17545e-11 1 -8.69508e-10 -3.89559e-11 -4.17545e-11 4037.08 2.57457 386.914 3990.89 8.82381 4029.18 +EDGE_SE3:QUAT 1349 1400 -3.33171 11.6407 -5.92972 -0.128553 0.0489691 0.0544097 0.988997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.13 -28.4833 469.337 3985.94 3.91711 4042.39 +EDGE_SE3:QUAT 1350 1399 -2.25016 -11.5315 -5.63482 0.0595853 0.0558524 -0.127048 0.988529 1 4.81482e-20 4.81482e-20 1.38395e-08 -1.68589e-09 9.62627e-10 1 4.81482e-20 1.38395e-08 -1.68589e-09 9.62627e-10 1 1.38395e-08 -1.68589e-09 9.62627e-10 4055.28 4.66011 532.182 3982.11 -30.918 4004.92 +EDGE_SE3:QUAT 1351 1401 -2.17 0.186444 -5.99478 -0.00238036 -0.0857954 0.22359 0.970897 1 1.20371e-20 1.20371e-20 -6.82543e-09 -1.59799e-09 5.34506e-10 1 1.20371e-20 -6.82543e-09 -1.59799e-09 5.34506e-10 1 -6.82543e-09 -1.59799e-09 5.34506e-10 4100.32 37.3078 -642.453 3982.91 -75.3251 3900.37 +EDGE_SE3:QUAT 1350 1401 -3.07174 11.4747 -6.19153 0.143556 0.0653297 0.211951 0.964469 1 7.70372e-19 7.70372e-19 1.38334e-10 -8.77288e-09 -5.35298e-08 1 7.70372e-19 1.38334e-10 -8.77288e-09 -5.35298e-08 1 1.38334e-10 -8.77288e-09 -5.35298e-08 3916.31 2.06487 120.674 4001.24 0.373112 3819.06 +EDGE_SE3:QUAT 1351 1400 -3.06063 -11.6575 -5.92713 -0.0701181 -0.0210749 0.061523 0.995417 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.55 3.78397 -114.968 3999.45 -3.41769 3988.08 +EDGE_SE3:QUAT 1352 1402 -2.15186 0.0174521 -6.49886 0.0162322 -0.0168794 0.0263862 0.999377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.85 -0.963035 -140.131 3998.75 -1.75866 4002.12 +EDGE_SE3:QUAT 1351 1402 -2.98343 11.6197 -5.89152 0.103564 0.0570248 0.0411172 0.992135 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.58 22.9307 400.012 3991.79 14.7021 4032.72 +EDGE_SE3:QUAT 1352 1401 -2.7277 -11.9106 -5.98215 -0.0169562 -0.085264 -0.246127 0.965331 1 1.93345e-19 1.93345e-19 8.55313e-09 2.63528e-08 -8.67928e-10 1 1.93345e-19 8.55313e-09 2.63528e-08 -8.67928e-10 1 8.55313e-09 2.63528e-08 -8.67928e-10 4113.05 -38.2914 -685.917 3980.08 87.5517 3871.88 +EDGE_SE3:QUAT 1353 1403 -1.64262 -0.188031 -5.53417 -0.128573 0.0856477 -0.110456 0.981801 1 7.70372e-19 7.70372e-19 5.49091e-08 -7.27118e-09 2.92051e-09 1 7.70372e-19 5.49091e-08 -7.27118e-09 2.92051e-09 1 5.49091e-08 -7.27118e-09 2.92051e-09 3992.07 -41.0357 491.779 3992.17 -38.9193 4009.39 +EDGE_SE3:QUAT 1352 1403 -2.93323 11.8311 -5.8275 0.0140829 0.121338 0.0420396 0.991621 1 1.20371e-20 1.20371e-20 -7.08542e-09 -3.34275e-10 -8.54712e-10 1 1.20371e-20 -7.08542e-09 -3.34275e-10 -8.54712e-10 1 -7.08542e-09 -3.34275e-10 -8.54712e-10 4240.16 23.9051 1010.88 3943.47 29.7358 4233.88 +EDGE_SE3:QUAT 1353 1402 -3.17862 -11.805 -5.74611 0.106978 -0.108656 -0.15979 0.975303 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4048.03 -60.4047 -627.716 3989.48 66.7954 3991.68 +EDGE_SE3:QUAT 1354 1404 -2.57664 0.00180856 -5.49633 0.00942198 -0.0412572 0.122395 0.991579 1 1.93345e-19 1.93345e-19 2.90483e-09 2.36897e-10 -2.76946e-08 1 1.93345e-19 2.90483e-09 2.36897e-10 -2.76946e-08 1 2.90483e-09 2.36897e-10 -2.76946e-08 4028.08 3.59972 -338.467 3993.26 -20.8253 3968.52 +EDGE_SE3:QUAT 1353 1404 -2.80698 11.8201 -6.0721 -0.230626 0.0138793 -0.0928372 0.968504 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3790.87 26.7951 -145.551 3996.62 10.2346 3969.15 +EDGE_SE3:QUAT 1354 1403 -3.12435 -11.7849 -5.91063 0.00641456 -0.0170977 -0.0839877 0.996299 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.99 -0.946549 -129.005 3999.04 5.3633 3975.94 +EDGE_SE3:QUAT 1355 1405 -1.89519 -0.294436 -5.96869 0.0488126 0.134259 0.136978 0.980219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4228.59 81.9085 1005.98 3956.06 97.4207 4163.07 +EDGE_SE3:QUAT 1354 1405 -3.02116 11.8948 -6.11872 0.0284445 0.225039 0.0606062 0.972047 1 8.1852e-19 8.1852e-19 1.04559e-08 5.51245e-08 -7.17588e-12 1 8.1852e-19 1.04559e-08 5.51245e-08 -7.17588e-12 1 1.04559e-08 5.51245e-08 -7.17588e-12 4904.23 138.434 2110.4 3818.49 141.987 4892.78 +EDGE_SE3:QUAT 1355 1404 -3.11687 -11.6392 -6.05183 0.15797 0.0400737 -0.128779 0.97819 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.1 38.6126 548.669 3978.2 -26.4824 4006.58 +EDGE_SE3:QUAT 1356 1406 -2.3475 0.252308 -5.9534 0.077494 -0.0857896 0.040184 0.992482 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4107.43 -23.3813 -736.976 3967.75 -0.961784 4124.99 +EDGE_SE3:QUAT 1355 1406 -2.7914 11.736 -6.33652 -0.0465416 0.0779485 0.00320518 0.995865 1 2.64486e-23 2.64486e-23 -2.56525e-11 1.53473e-11 -3.27906e-10 1 2.64486e-23 -2.56525e-11 1.53473e-11 -3.27906e-10 1 -2.56525e-11 1.53473e-11 -3.27906e-10 4090.28 -15.2887 636.832 3975.94 -5.90816 4098.9 +EDGE_SE3:QUAT 1356 1405 -2.49937 -11.4266 -5.75786 -0.102908 -0.00316452 -0.0746862 0.991878 1 1.92593e-19 1.92593e-19 2.75412e-08 -2.01206e-09 -5.08411e-10 1 1.92593e-19 2.75412e-08 -2.01206e-09 -5.08411e-10 1 2.75412e-08 -2.01206e-09 -5.08411e-10 3960.79 7.29018 -116.036 3998.69 5.12297 3980.84 +EDGE_SE3:QUAT 1357 1407 -2.17976 0.268504 -6.1603 -0.0513802 -0.00233068 0.101607 0.993494 1 4.83363e-20 4.83363e-20 1.3876e-08 5.44245e-10 6.84026e-11 1 4.83363e-20 1.3876e-08 5.44245e-10 6.84026e-11 1 1.3876e-08 5.44245e-10 6.84026e-11 3989.81 -1.63274 43.8255 3999.74 3.27706 3959.08 +EDGE_SE3:QUAT 1356 1407 -2.59174 11.3306 -6.41442 0.0317134 0.114496 0.197683 0.97304 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4153.45 66.4619 811.56 3975.14 94.0979 4001.16 +EDGE_SE3:QUAT 1357 1406 -2.79375 -11.6601 -5.64485 -0.0842017 0.114557 0.0483927 0.988658 1 1.92593e-19 1.92593e-19 -8.17571e-10 2.74615e-08 2.07995e-09 1 1.92593e-19 -8.17571e-10 2.74615e-08 2.07995e-09 1 -8.17571e-10 2.74615e-08 2.07995e-09 4209.13 -31.5329 1003.22 3943.12 -2.21828 4228.12 +EDGE_SE3:QUAT 1358 1408 -2.21547 -0.0456104 -5.80517 -0.0362716 -0.138333 0.118582 0.982592 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4271.55 76.2975 -1088.69 3944.48 -91.6331 4220.56 +EDGE_SE3:QUAT 1357 1408 -3.19907 11.9074 -6.35969 0.0765397 -0.0369743 0.139301 0.986595 1 9.62965e-19 9.62965e-19 2.43926e-08 7.25028e-09 5.34935e-08 1 9.62965e-19 2.43926e-08 7.25028e-09 5.34935e-08 1 2.43926e-08 7.25028e-09 5.34935e-08 4018.87 -9.76983 -414.915 3988.1 -27.8869 3964.69 +EDGE_SE3:QUAT 1358 1407 -3.03508 -11.542 -5.99629 -0.0367203 0.0726628 -0.0712828 0.994128 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4069.56 -18.8213 552.849 3983.01 -24.5981 4054.63 +EDGE_SE3:QUAT 1359 1409 -2.30196 -0.248643 -5.70819 -0.177465 0.092207 0.0830787 0.976269 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4071.16 -70.2471 910.137 3952.52 -6.86112 4169.53 +EDGE_SE3:QUAT 1358 1409 -2.79617 11.8456 -6.19633 -0.022401 -0.00489877 0.0600218 0.997934 1 1.20371e-20 1.20371e-20 -6.92466e-09 -4.17607e-10 1.50914e-11 1 1.20371e-20 -6.92466e-09 -4.17607e-10 1.50914e-11 1 -6.92466e-09 -4.17607e-10 1.50914e-11 3998.12 0.210661 -22.8586 3999.98 -0.528151 3985.71 +EDGE_SE3:QUAT 1359 1408 -2.92784 -11.7919 -6.00071 -0.184555 0.0285268 0.0292804 0.981972 1 1.20371e-20 1.20371e-20 2.58595e-10 -1.27272e-09 6.83108e-09 1 1.20371e-20 2.58595e-10 -1.27272e-09 6.83108e-09 1 2.58595e-10 -1.27272e-09 6.83108e-09 3883.37 -27.0427 281.075 3995.08 -0.688629 4016.19 +EDGE_SE3:QUAT 1360 1410 -2.03045 -0.113245 -5.69916 -0.143106 -0.0770503 -0.0308527 0.986221 1 9.62965e-19 9.62965e-19 -5.5714e-08 -2.69389e-08 7.61778e-10 1 9.62965e-19 -5.5714e-08 -2.69389e-08 7.61778e-10 1 -5.5714e-08 -2.69389e-08 7.61778e-10 4025.73 46.65 -664.989 3974.78 -11.9691 4103.84 +EDGE_SE3:QUAT 1359 1410 -2.78516 11.8096 -6.07359 -0.143198 -0.169348 -0.00240662 0.975095 1 1.54074e-18 1.54074e-18 -5.46463e-08 -5.68684e-08 1.18336e-09 1 1.54074e-18 -5.46463e-08 -5.68684e-08 1.18336e-09 1 -5.46463e-08 -5.68684e-08 1.18336e-09 4388.59 133.008 -1450.77 3906.67 -107.111 4470.59 +EDGE_SE3:QUAT 1360 1409 -2.71329 -11.5801 -5.79386 0.0890256 0.205326 -0.135006 0.96524 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4842.71 -51.2871 2064.58 3815.74 -85.8705 4801.51 +EDGE_SE3:QUAT 1361 1411 -2.62661 0.380748 -5.9551 -0.0278155 -0.146049 -0.0415391 0.988013 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4368.17 -2.15964 -1273.94 3913.22 16.5637 4364.37 +EDGE_SE3:QUAT 1360 1411 -3.1832 11.2523 -6.1887 0.0652269 0.101982 0.0387309 0.99189 1 1.92593e-19 1.92593e-19 2.80641e-08 1.49009e-09 2.70527e-09 1 1.92593e-19 2.80641e-08 1.49009e-09 2.70527e-09 1 2.80641e-08 1.49009e-09 2.70527e-09 4138.5 38.0075 804.057 3964.82 32.8621 4149.52 +EDGE_SE3:QUAT 1361 1410 -2.91867 -11.7635 -5.59339 0.167173 0.0401376 -0.105139 0.979483 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3953.16 40.9781 516.681 3981.07 -17.1696 4020.74 +EDGE_SE3:QUAT 1362 1412 -2.30831 -0.389979 -5.98936 0.0728412 -0.104701 -0.0760323 0.988914 1 1.92593e-19 1.92593e-19 -2.79521e-08 2.60674e-09 2.57271e-09 1 1.92593e-19 -2.79521e-08 2.60674e-09 2.57271e-09 1 -2.79521e-08 2.60674e-09 2.57271e-09 4125.15 -48.3669 -779.746 3969.59 48.9432 4123.25 +EDGE_SE3:QUAT 1361 1412 -3.42402 11.655 -6.00863 0.0540672 -0.0456166 0.0514624 0.996166 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.65 -8.35962 -398.757 3989.89 -7.66487 4028.75 +EDGE_SE3:QUAT 1362 1411 -3.19189 -11.8817 -5.61544 -0.033868 0.0724664 -0.144133 0.98632 1 7.70372e-19 7.70372e-19 3.32858e-09 -2.99888e-09 5.51951e-08 1 7.70372e-19 3.32858e-09 -2.99888e-09 5.51951e-08 1 3.32858e-09 -2.99888e-09 5.51951e-08 4058.94 -23.6338 509.088 3987.71 -40.1074 3980.43 +EDGE_SE3:QUAT 1363 1413 -2.14003 -0.0115394 -5.65193 -0.132602 -0.0835527 -0.149657 0.976237 1 1.92593e-19 1.92593e-19 2.7768e-08 -3.55351e-09 -3.31296e-09 1 1.92593e-19 2.7768e-08 -3.55351e-09 -3.31296e-09 1 2.7768e-08 -3.55351e-09 -3.31296e-09 4123.43 29.8357 -902.958 3949.92 43.5724 4104.17 +EDGE_SE3:QUAT 1362 1413 -2.59644 11.2467 -6.28562 0.0221241 0.0650533 0.0586919 0.995909 1 2.0463e-19 2.0463e-19 -5.24456e-09 -2.80702e-08 3.94554e-10 1 2.0463e-19 -5.24456e-09 -2.80702e-08 3.94554e-10 1 -5.24456e-09 -2.80702e-08 3.94554e-10 4061.68 11.5514 508.595 3984.98 17.5511 4049.86 +EDGE_SE3:QUAT 1363 1412 -3.10517 -11.4739 -6.38992 0.0119989 0.0858551 -0.00937549 0.996191 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4120.43 2.84564 706.165 3970.4 -1.3641 4120.65 +EDGE_SE3:QUAT 1364 1414 -2.15681 -0.162444 -5.8704 0.0513016 -0.0541933 0.0461422 0.996144 1 9.62965e-20 9.62965e-20 -1.448e-08 1.32603e-08 1.72437e-10 1 9.62965e-20 -1.448e-08 1.32603e-08 1.72437e-10 1 -1.448e-08 1.32603e-08 1.72437e-10 4042.66 -8.9039 -464.344 3986.53 -7.23949 4044.67 +EDGE_SE3:QUAT 1363 1414 -2.99463 11.33 -5.69308 -0.12765 -0.00291101 0.205205 0.970355 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3952.41 -21.1953 282.074 3991.13 37.6279 3849.16 +EDGE_SE3:QUAT 1364 1413 -2.69198 -11.3372 -5.54166 0.0186723 0.0410882 -0.0472962 0.997861 1 1.20371e-20 1.20371e-20 6.94893e-09 -3.19573e-10 2.96983e-10 1 1.20371e-20 6.94893e-09 -3.19573e-10 2.96983e-10 1 6.94893e-09 -3.19573e-10 2.96983e-10 4027.33 1.24168 340.184 3992.79 -7.46823 4019.78 +EDGE_SE3:QUAT 1365 1415 -2.0106 0.105573 -5.96543 0.182657 -0.136799 0.118424 0.966384 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4312.08 -87.9773 -1407.92 3897.82 13.6856 4389.44 +EDGE_SE3:QUAT 1364 1415 -2.90927 11.3211 -6.31914 0.0818368 0.00266575 0.0394197 0.995862 1 4.81482e-20 4.81482e-20 5.27849e-11 -1.13509e-09 -1.38204e-08 1 4.81482e-20 5.27849e-11 -1.13509e-09 -1.38204e-08 1 5.27849e-11 -1.13509e-09 -1.38204e-08 3973.25 -1.24419 -17.4364 3999.94 -0.597892 3993.82 +EDGE_SE3:QUAT 1365 1414 -3.20632 -11.7207 -5.64209 -0.1382 -0.0357349 -0.36074 0.921678 1 3.08149e-18 3.08149e-18 1.33418e-08 8.95733e-09 -1.04536e-07 1 3.08149e-18 1.33418e-08 8.95733e-09 -1.04536e-07 1 1.33418e-08 8.95733e-09 -1.04536e-07 4073.49 2.91126 -796.175 3957.77 158.651 3629.35 +EDGE_SE3:QUAT 1366 1416 -2.67921 -0.0883957 -5.55424 0.179172 0.137944 -0.0607002 0.972206 1 7.70372e-19 7.70372e-19 5.64984e-08 -5.30036e-10 8.7255e-09 1 7.70372e-19 5.64984e-08 -5.30036e-10 8.7255e-09 1 5.64984e-08 -5.30036e-10 8.7255e-09 4242.71 107.643 1273.67 3919.98 54.3822 4356.38 +EDGE_SE3:QUAT 1365 1416 -2.98235 11.4115 -5.79728 0.070032 0.0530632 0.0491728 0.994918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.35 15.9927 381.384 3992.12 13.2708 4026.3 +EDGE_SE3:QUAT 1366 1415 -2.79813 -11.3173 -5.86439 -0.0567277 -0.13467 -0.0184687 0.989093 1 8.21529e-19 8.21529e-19 -1.39492e-08 -5.4673e-08 -4.58859e-09 1 8.21529e-19 -1.39492e-08 -5.4673e-08 -4.58859e-09 1 -1.39492e-08 -5.4673e-08 -4.58859e-09 4298.31 30.4482 -1158.27 3927.04 -14.5532 4309.82 +EDGE_SE3:QUAT 1367 1417 -2.06848 0.0603305 -6.12457 -0.0905167 -0.0931271 0.0635458 0.989493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.53 43.3629 -677.267 3977.11 -38.7369 4095.15 +EDGE_SE3:QUAT 1366 1417 -3.14446 11.7202 -6.19222 0.0637763 -0.0619557 -0.0497561 0.994796 1 4.81482e-20 4.81482e-20 -7.64793e-10 9.79193e-10 1.3895e-08 1 4.81482e-20 -7.64793e-10 9.79193e-10 1.3895e-08 1 -7.64793e-10 9.79193e-10 1.3895e-08 4035.34 -18.7294 -457.567 3988.47 16.6496 4041.71 +EDGE_SE3:QUAT 1367 1416 -3.091 -11.625 -5.89014 0.0836139 0.00468069 -0.144754 0.985917 1 7.70372e-19 7.70372e-19 -1.57188e-09 -4.37772e-09 -5.4782e-08 1 7.70372e-19 -1.57188e-09 -4.37772e-09 -5.4782e-08 1 -1.57188e-09 -4.37772e-09 -5.4782e-08 3979.51 8.3052 178.776 3996.91 -15.7491 3923.66 +EDGE_SE3:QUAT 1368 1418 -2.39219 -0.191266 -5.93669 -0.00178055 -0.0456252 -0.0122609 0.998882 1 5.12045e-20 5.12045e-20 -4.44552e-10 -1.38547e-08 -3.46942e-09 1 5.12045e-20 -4.44552e-10 -1.38547e-08 -3.46942e-09 1 -4.44552e-10 -1.38547e-08 -3.46942e-09 4033.54 -0.284561 -367.86 3991.67 2.215 4032.95 +EDGE_SE3:QUAT 1367 1418 -3.22881 11.6911 -5.87954 -0.039995 -0.0200046 -0.0783399 0.995923 1 4.81482e-20 4.81482e-20 1.38378e-08 -1.06385e-09 -3.60477e-10 1 4.81482e-20 1.38378e-08 -1.06385e-09 -3.60477e-10 1 1.38378e-08 -1.06385e-09 -3.60477e-10 4003.16 3.13808 -196.047 3997.37 7.65565 3985.01 +EDGE_SE3:QUAT 1368 1417 -3.01064 -11.6541 -5.35473 0.0730708 0.0722407 -0.142895 0.98439 1 7.70372e-19 7.70372e-19 5.03686e-09 2.83792e-09 5.54662e-08 1 7.70372e-19 5.03686e-09 2.83792e-09 5.54662e-08 1 5.03686e-09 2.83792e-09 5.54662e-08 4096.95 4.24728 698.516 3970.15 -43.4005 4036.63 +EDGE_SE3:QUAT 1369 1419 -2.29133 -0.107018 -6.24269 0.148428 -0.0841332 0.027275 0.98496 1 3.00927e-21 3.00927e-21 3.11551e-10 -5.14048e-10 -3.47142e-09 1 3.00927e-21 3.11551e-10 -5.14048e-10 -3.47142e-09 1 3.11551e-10 -5.14048e-10 -3.47142e-09 4036.83 -53.0359 -717.923 3971.37 17.3732 4121.97 +EDGE_SE3:QUAT 1368 1419 -3.4416 11.4202 -5.58779 -0.120533 0.0292301 -0.00271582 0.992275 1 2.0463e-19 2.0463e-19 2.75185e-08 -7.15313e-09 -6.7997e-11 1 2.0463e-19 2.75185e-08 -7.15313e-09 -6.7997e-11 1 2.75185e-08 -7.15313e-09 -6.7997e-11 3954.55 -13.5777 225.478 3997.12 -2.65667 4012.64 +EDGE_SE3:QUAT 1369 1418 -3.21495 -11.6868 -5.77893 -0.090804 -0.15934 -0.110893 0.976764 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4475.18 3.45777 -1513.69 3883.83 39.3538 4458.97 +EDGE_SE3:QUAT 1370 1420 -2.1746 -0.36571 -5.72655 -0.0591605 -0.0311689 -0.092151 0.993497 1 2.40741e-19 2.40741e-19 -2.88811e-08 -1.13416e-08 4.19631e-10 1 2.40741e-19 -2.88811e-08 -1.13416e-08 4.19631e-10 1 -2.88811e-08 -1.13416e-08 4.19631e-10 4010.05 6.86711 -311.621 3993.4 13.5138 3990.08 +EDGE_SE3:QUAT 1369 1420 -3.18283 11.4324 -5.68666 -0.221105 -0.00768414 0.0909175 0.970973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3810.79 -28.0348 176.018 3995.98 10.4714 3973.28 +EDGE_SE3:QUAT 1370 1419 -2.66556 -11.449 -5.73105 -0.0655758 0.034391 -0.213379 0.974159 1 1.92593e-19 1.92593e-19 2.70423e-08 -6.00261e-09 1.00638e-10 1 1.92593e-19 2.70423e-08 -6.00261e-09 1.00638e-10 1 2.70423e-08 -6.00261e-09 1.00638e-10 3983.9 -2.35671 92.1914 4000.27 -3.57578 3818.98 +EDGE_SE3:QUAT 1371 1421 -2.34657 0.221933 -5.79064 -0.0387253 -0.0337476 -0.124749 0.990858 1 4.81482e-20 4.81482e-20 1.37959e-08 -1.70007e-09 -5.87595e-10 1 4.81482e-20 1.37959e-08 -1.70007e-09 -5.87595e-10 1 1.37959e-08 -1.70007e-09 -5.87595e-10 4019.77 2.1169 -322.43 3993.24 20.0637 3963.52 +EDGE_SE3:QUAT 1370 1421 -3.14754 11.3739 -6.31165 -0.0332164 0.0504796 0.0822832 0.994775 1 1.20371e-20 1.20371e-20 -6.94341e-09 -5.52745e-10 -3.85021e-10 1 1.20371e-20 -6.94341e-09 -5.52745e-10 -3.85021e-10 1 -6.94341e-09 -5.52745e-10 -3.85021e-10 4042.63 -1.92442 436.381 3988.13 16.5679 4019.96 +EDGE_SE3:QUAT 1371 1420 -3.16293 -11.4391 -5.5265 0.0433088 0.0255152 -0.104245 0.993281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.63 3.60126 254.965 3995.58 -13.3147 3972.66 +EDGE_SE3:QUAT 1372 1422 -2.41881 0.112878 -5.95619 0.0331293 0.00736249 0.0617708 0.997513 1 4.81482e-20 4.81482e-20 -1.38437e-08 -8.6221e-10 -4.45064e-11 1 4.81482e-20 -1.38437e-08 -8.6221e-10 -4.45064e-11 1 -1.38437e-08 -8.6221e-10 -4.45064e-11 3995.88 0.461263 33.9891 3999.96 0.81213 3985.01 +EDGE_SE3:QUAT 1371 1422 -3.11345 11.4273 -5.98308 0.205294 0.0257516 0.14173 0.968041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3833.6 -27.5791 -147.687 3995.44 -18.8898 3921.83 +EDGE_SE3:QUAT 1372 1421 -3.25425 -11.6105 -5.62011 -0.0146286 0.0370889 0.076886 0.996242 1 3.00927e-21 3.00927e-21 -3.46671e-09 -2.6442e-10 -1.35307e-10 1 3.00927e-21 -3.46671e-09 -2.6442e-10 -1.35307e-10 1 -3.46671e-09 -2.6442e-10 -1.35307e-10 4022.88 0.389651 309.077 3994.09 11.6847 4000.09 +EDGE_SE3:QUAT 1373 1423 -2.4424 0.0493965 -5.86951 -0.11606 -0.0143699 0.0435151 0.992185 1 1.92593e-19 1.92593e-19 -2.75406e-08 -1.26754e-09 1.08303e-10 1 1.92593e-19 -2.75406e-08 -1.26754e-09 1.08303e-10 1 -2.75406e-08 -1.26754e-09 1.08303e-10 3946.69 1.88606 -52.3216 3999.96 -0.870122 3993 +EDGE_SE3:QUAT 1372 1423 -3.13255 11.4707 -6.36849 0.0623073 0.0909074 -0.156312 0.98154 1 2.40741e-19 2.40741e-19 1.7994e-08 2.5204e-08 6.04934e-10 1 2.40741e-19 1.7994e-08 2.5204e-08 6.04934e-10 1 1.7994e-08 2.5204e-08 6.04934e-10 4155.32 -9.50067 844.368 3959.2 -59.3593 4073.12 +EDGE_SE3:QUAT 1373 1422 -2.4153 -11.4518 -5.89902 0.0555746 0.0294037 -0.0507467 0.99673 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.51 6.52769 268.083 3995.26 -5.72466 4007.56 +EDGE_SE3:QUAT 1374 1424 -2.53844 -0.116974 -5.85911 -0.0360183 -0.0142796 -0.05649 0.997651 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.55 2.25981 -137.971 3998.69 3.89198 3991.97 +EDGE_SE3:QUAT 1373 1424 -3.14407 11.6533 -6.20188 -0.10925 0.109288 -0.10484 0.98241 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4078.15 -63.3388 723.864 3979.14 -62.666 4081.92 +EDGE_SE3:QUAT 1374 1423 -2.78952 -11.711 -5.82209 -0.0474562 -0.117518 -0.188362 0.973888 1 1.20371e-20 1.20371e-20 6.98164e-09 -1.30525e-09 -9.07463e-10 1 1.20371e-20 6.98164e-09 -1.30525e-09 -9.07463e-10 1 6.98164e-09 -1.30525e-09 -9.07463e-10 4250.77 -45.5622 -1051.95 3944.37 98.1476 4117.86 +EDGE_SE3:QUAT 1375 1425 -2.32164 0.00164642 -5.92965 0.101956 0.0528381 -0.119789 0.986136 1 1.92593e-19 1.92593e-19 2.08892e-09 2.44257e-09 2.76395e-08 1 1.92593e-19 2.08892e-09 2.44257e-09 2.76395e-08 1 2.08892e-09 2.44257e-09 2.76395e-08 4035.55 19.3433 562.022 3979.01 -26.8533 4019.73 +EDGE_SE3:QUAT 1374 1425 -3.37831 11.5687 -6.10518 -0.0733373 0.0400314 0.206259 0.974924 1 7.70372e-19 7.70372e-19 3.68255e-09 -2.86454e-09 5.4518e-08 1 7.70372e-19 3.68255e-09 -2.86454e-09 5.4518e-08 1 3.68255e-09 -2.86454e-09 5.4518e-08 4034.94 -4.44565 480.282 3984.62 50.871 3886.28 +EDGE_SE3:QUAT 1375 1424 -2.7778 -11.4366 -5.46992 -0.0988828 0.0162814 0.038454 0.994223 1 7.70372e-19 7.70372e-19 5.52426e-08 1.91824e-09 1.30477e-09 1 7.70372e-19 5.52426e-08 1.91824e-09 1.30477e-09 1 5.52426e-08 1.91824e-09 1.30477e-09 3968.37 -8.94708 173.672 3997.86 2.62855 4001.57 +EDGE_SE3:QUAT 1376 1426 -2.4591 0.18041 -6.06814 -0.287814 0.0714181 -0.143792 0.944133 1 7.70372e-19 7.70372e-19 -1.23806e-09 -1.64372e-08 5.23454e-08 1 7.70372e-19 -1.23806e-09 -1.64372e-08 5.23454e-08 1 -1.23806e-09 -1.64372e-08 5.23454e-08 3659.89 24.7871 19.8185 3999.24 11.1739 3908.53 +EDGE_SE3:QUAT 1375 1426 -3.01917 11.273 -6.23939 0.00904846 -0.0815588 0.0827396 0.993187 1 1.88079e-22 1.88079e-22 8.7323e-10 7.24179e-11 -7.20353e-11 1 1.88079e-22 8.7323e-10 7.24179e-11 -7.20353e-11 1 8.7323e-10 7.24179e-11 -7.20353e-11 4109.04 10.5176 -670.4 3973.9 -28.232 4081.98 +EDGE_SE3:QUAT 1376 1425 -3.03458 -11.3687 -5.46929 0.0143522 -0.038171 -0.103398 0.993804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.2 -5.25751 -283.87 3995.52 14.9402 3977.26 +EDGE_SE3:QUAT 1377 1427 -2.36972 0.360491 -5.54991 0.179585 0.0203453 0.0509608 0.982211 1 3.00927e-21 3.00927e-21 1.90348e-10 -3.407e-09 6.27037e-10 1 3.00927e-21 1.90348e-10 -3.407e-09 6.27037e-10 1 1.90348e-10 -3.407e-09 6.27037e-10 3871.16 0.775799 46.9936 4000.06 0.538106 3989.77 +EDGE_SE3:QUAT 1376 1427 -3.10816 11.1037 -5.68949 -0.0115849 0.0309095 0.0247353 0.999149 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.19 -0.895164 251.307 3996.06 2.88049 4013.28 +EDGE_SE3:QUAT 1377 1426 -3.28772 -11.262 -5.88315 0.152246 0.0850532 -0.0832318 0.981152 1 9.62965e-19 9.62965e-19 5.71388e-08 2.41771e-08 2.11632e-09 1 9.62965e-19 5.71388e-08 2.41771e-08 2.11632e-09 1 5.71388e-08 2.41771e-08 2.11632e-09 4072.98 52.5585 831.366 3958.87 -3.15176 4137.99 +EDGE_SE3:QUAT 1378 1428 -1.95442 -0.0857576 -6.02939 -0.135248 0.0279337 0.0389477 0.989652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3946.36 -19.4019 280.599 3994.76 2.21947 4013.46 +EDGE_SE3:QUAT 1377 1428 -3.2533 11.4027 -5.77562 0.0868848 0.106651 -0.135326 0.981205 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4212.3 3.4792 1014.64 3941.23 -49.8417 4169.24 +EDGE_SE3:QUAT 1378 1427 -2.79139 -11.4005 -5.48908 0.156967 0.0923093 -0.0874211 0.979387 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4096.62 57.7579 905.432 3952.09 -1.45383 4164.61 +EDGE_SE3:QUAT 1379 1429 -2.72279 0.0821308 -5.93193 0.00818943 -0.162036 0.0255528 0.98642 1 7.52316e-22 7.52316e-22 1.80626e-09 4.43207e-11 -2.97076e-10 1 7.52316e-22 1.80626e-09 4.43207e-11 -2.97076e-10 1 1.80626e-09 4.43207e-11 -2.97076e-10 4456.35 10.8947 -1426.52 3894.98 -17.4966 4454 +EDGE_SE3:QUAT 1378 1429 -2.97902 11.5895 -5.79581 -0.0294448 0.190403 0.156249 0.968744 1 7.52316e-22 7.52316e-22 1.81511e-09 2.93729e-10 3.56007e-10 1 7.52316e-22 1.81511e-09 2.93729e-10 3.56007e-10 1 1.81511e-09 2.93729e-10 3.56007e-10 4646.07 129.7 1737.94 3872.7 159.686 4551.88 +EDGE_SE3:QUAT 1379 1428 -3.233 -11.4378 -5.93492 0.0113483 -0.0455517 -0.0199144 0.998699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.34 -3.09338 -363.995 3991.9 4.25639 4031.27 +EDGE_SE3:QUAT 1380 1430 -2.71309 0.356957 -6.16022 -0.22965 -0.0243925 -0.00659359 0.972945 1 1.05794e-22 1.05794e-22 1.61317e-11 1.49557e-10 -6.33736e-10 1 1.05794e-22 1.61317e-11 1.49557e-10 -6.33736e-10 1 1.61317e-11 1.49557e-10 -6.33736e-10 3798.8 22.8546 -197.867 3998.09 -2.7816 4009.58 +EDGE_SE3:QUAT 1379 1430 -3.19595 11.5085 -6.01294 -0.0738402 0.0350997 0.113231 0.990199 1 1.92593e-19 1.92593e-19 -1.40624e-09 1.79179e-09 -2.76048e-08 1 1.92593e-19 -1.40624e-09 1.79179e-09 -2.76048e-08 1 -1.40624e-09 1.79179e-09 -2.76048e-08 4012.95 -9.89795 375.526 3990.28 19.9095 3983.48 +EDGE_SE3:QUAT 1380 1429 -2.98574 -11.2717 -5.60236 -0.0110919 0.116598 -0.214894 0.969589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4180.6 -69.8711 871.812 3970.58 -106.208 3996.38 +EDGE_SE3:QUAT 1381 1431 -2.39766 0.259996 -5.71082 -0.0938455 -0.109565 -0.0465201 0.988445 1 4.33334e-19 4.33334e-19 -2.72489e-08 -2.5495e-08 -1.31562e-08 1 4.33334e-19 -2.72489e-08 -2.5495e-08 -1.31562e-08 1 -2.72489e-08 -2.5495e-08 -1.31562e-08 4182.96 36.3665 -959.399 3947.75 -5.36232 4209.53 +EDGE_SE3:QUAT 1380 1431 -3.17406 11.4243 -5.52155 0.149398 -0.0182625 0.117665 0.981581 1 7.70372e-19 7.70372e-19 5.46925e-08 5.97291e-09 -2.86994e-09 1 7.70372e-19 5.46925e-08 5.97291e-09 -2.86994e-09 1 5.46925e-08 5.97291e-09 -2.86994e-09 3939.66 -27.1774 -346.799 3990 -19.4344 3973.56 +EDGE_SE3:QUAT 1381 1430 -3.22269 -11.3977 -5.90905 -0.0465659 -0.03277 -0.0105322 0.998322 1 9.62965e-20 9.62965e-20 -1.3989e-08 -1.37512e-08 -1.70558e-10 1 9.62965e-20 -1.3989e-08 -1.37512e-08 -1.70558e-10 1 -1.3989e-08 -1.37512e-08 -1.70558e-10 4009.23 6.07423 -268.203 3995.52 0.193455 4017.46 +EDGE_SE3:QUAT 1382 1432 -2.56727 0.0336524 -5.97367 0.0846739 0.00215961 0.145082 0.985788 1 1.92593e-19 1.92593e-19 -2.73736e-08 -3.98073e-09 6.15938e-10 1 1.92593e-19 -2.73736e-08 -3.98073e-09 6.15938e-10 1 -2.73736e-08 -3.98073e-09 6.15938e-10 3974.88 -7.02417 -128.203 3998.08 -12.5978 3919.36 +EDGE_SE3:QUAT 1381 1432 -3.16956 11.7688 -6.00591 -0.121571 0.203113 0.170101 0.956572 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4877.51 53.2806 2150.48 3805.44 100.802 4820.89 +EDGE_SE3:QUAT 1382 1431 -2.8096 -11.8483 -5.96881 0.0343652 0.235631 -0.107362 0.965283 1 3.00927e-21 3.00927e-21 3.77857e-09 -4.03627e-10 9.29249e-10 1 3.00927e-21 3.77857e-09 -4.03627e-10 9.29249e-10 1 3.77857e-09 -4.03627e-10 9.29249e-10 5074.06 -129.108 2340.72 3786.27 -142.714 5032.68 +EDGE_SE3:QUAT 1383 1433 -2.35757 0.0743759 -6.2031 -0.162375 0.067609 -0.0790375 0.981232 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3926.45 -30.5508 364.819 3996.15 -22.5572 4006.92 +EDGE_SE3:QUAT 1382 1433 -3.22512 11.2411 -6.02651 -0.0598032 -0.000813257 -0.0606409 0.996366 1 4.81482e-20 4.81482e-20 1.38283e-08 -8.34263e-10 -1.11422e-10 1 4.81482e-20 1.38283e-08 -8.34263e-10 -1.11422e-10 1 1.38283e-08 -8.34263e-10 -1.11422e-10 3986.26 1.88459 -49.7505 3999.74 1.912 3985.86 +EDGE_SE3:QUAT 1383 1432 -2.95671 -11.3807 -5.60203 -0.404564 -0.0734803 0.230793 0.881852 1 3.85186e-18 3.85186e-18 -9.17949e-08 -4.49289e-08 3.55492e-08 1 3.85186e-18 -9.17949e-08 -4.49289e-08 3.55492e-08 1 -9.17949e-08 -4.49289e-08 3.55492e-08 3395.82 -192.776 557.64 3941 99.0167 3837.44 +EDGE_SE3:QUAT 1384 1434 -2.60904 0.0301331 -5.77808 -0.0827012 -0.0863581 -0.109259 0.986795 1 1.92593e-19 1.92593e-19 -2.86804e-09 -1.78727e-09 2.79297e-08 1 1.92593e-19 -2.86804e-09 -1.78727e-09 2.79297e-08 1 -2.86804e-09 -1.78727e-09 2.79297e-08 4129.45 12.7242 -807.716 3960.74 30.9323 4109.06 +EDGE_SE3:QUAT 1383 1434 -3.25055 11.391 -5.94837 -0.073411 -0.0475712 0.117809 0.989176 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.86 12.3891 -267.64 3997.28 -16.1381 3961.9 +EDGE_SE3:QUAT 1384 1433 -2.77197 -11.52 -5.81871 -0.130838 -0.0656659 -0.122441 0.98162 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.2 32.5045 -709.68 3967.46 27.6762 4061.71 +EDGE_SE3:QUAT 1385 1435 -1.98017 0.0321508 -5.72489 -0.235245 0.0223968 0.292596 0.926577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.36 -80.4372 942.217 3927.94 130.458 3860.27 +EDGE_SE3:QUAT 1384 1435 -3.17687 11.5671 -5.65819 0.0905173 -0.17452 0.118966 0.97324 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4583.2 9.67633 -1686.32 3862.49 -50.9334 4559.36 +EDGE_SE3:QUAT 1385 1434 -3.01085 -11.5823 -5.77687 -0.0345797 0.00100939 0.0828513 0.995961 1 1.92593e-19 1.92593e-19 1.85971e-10 -9.42036e-10 2.76449e-08 1 1.92593e-19 1.85971e-10 -9.42036e-10 2.76449e-08 1 1.85971e-10 -9.42036e-10 2.76449e-08 3995.63 -0.889932 42.1771 3999.82 2.20538 3972.96 +EDGE_SE3:QUAT 1386 1436 -2.53064 0.0643286 -5.57069 -0.0227167 0.0709479 0.0200415 0.99702 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4081.1 -4.47661 582.738 3979.47 3.31743 4081.56 +EDGE_SE3:QUAT 1385 1436 -3.08033 11.1863 -5.86273 0.154059 -0.118698 0.231252 0.953257 1 7.70372e-19 7.70372e-19 -1.00457e-08 5.19196e-09 5.59055e-08 1 7.70372e-19 -1.00457e-08 5.19196e-09 5.59055e-08 1 -1.00457e-08 5.19196e-09 5.59055e-08 4338.9 4.84973 -1388.66 3898.35 -113.893 4219.93 +EDGE_SE3:QUAT 1386 1435 -3.07096 -10.9985 -5.67365 0.145865 -0.216748 0.0808948 0.961873 1 4.81482e-20 4.81482e-20 3.56496e-09 -1.89811e-09 -1.49193e-08 1 4.81482e-20 3.56496e-09 -1.89811e-09 -1.49193e-08 1 3.56496e-09 -1.89811e-09 -1.49193e-08 4888.23 -123.314 -2200.19 3802.13 92.9544 4947.16 +EDGE_SE3:QUAT 1387 1437 -2.38805 0.16389 -5.59637 -0.0628413 -0.158309 0.0114856 0.985321 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4404.81 61.7516 -1363.61 3906.02 -51.7961 4420.08 +EDGE_SE3:QUAT 1386 1437 -3.17287 11.2953 -5.9016 0.0759426 -0.00957057 0.246379 0.966146 1 1.92593e-19 1.92593e-19 2.68851e-08 6.7416e-09 -1.23763e-09 1 1.92593e-19 2.68851e-08 6.7416e-09 -1.23763e-09 1 2.68851e-08 6.7416e-09 -1.23763e-09 3996.25 -8.1806 -285.137 3992.86 -42.5671 3776.51 +EDGE_SE3:QUAT 1387 1436 -3.27077 -11.367 -5.6703 0.123982 0.178121 -0.114085 0.969477 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4609.88 34.7862 1771.11 3850.83 -11.9991 4619.3 +EDGE_SE3:QUAT 1388 1438 -2.49598 -0.177296 -5.48595 -0.053211 0.28522 0.0234803 0.956696 1 1.20371e-20 1.20371e-20 -2.37378e-09 4.00184e-10 -7.9398e-09 1 1.20371e-20 -2.37378e-09 4.00184e-10 -7.9398e-09 1 -2.37378e-09 4.00184e-10 -7.9398e-09 5705.5 -90.1137 3132.86 3676.66 -90.4744 5714.62 +EDGE_SE3:QUAT 1387 1438 -3.26956 11.37 -5.64727 0.00221404 0.0937734 0.0467488 0.994493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4142.99 11.1569 769.737 3965.65 20.1165 4134.27 +EDGE_SE3:QUAT 1388 1437 -3.38342 -11.4042 -6.07124 0.0324592 -0.0212045 -0.0932045 0.994892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.04 -2.61123 -131.177 3999.18 5.7704 3969.5 +EDGE_SE3:QUAT 1389 1439 -2.0639 -0.028812 -6.06326 0.0537537 0.0886875 -0.22154 0.969621 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4151.62 -28.7815 824.273 3964.83 -90.6978 3966.86 +EDGE_SE3:QUAT 1388 1439 -2.97793 11.3185 -5.71384 7.85789e-06 -0.0102456 0.145952 0.989239 1 3.05629e-21 3.05629e-21 -7.7376e-11 3.49542e-09 5.98469e-12 1 3.05629e-21 -7.7376e-11 3.49542e-09 5.98469e-12 1 -7.7376e-11 3.49542e-09 5.98469e-12 4001.57 0.353386 -79.4 3999.65 -5.73618 3916.37 +EDGE_SE3:QUAT 1389 1438 -3.29993 -11.4061 -5.66229 -0.064408 0.0181636 0.0187383 0.997582 1 1.20371e-20 1.20371e-20 -1.12832e-10 6.92242e-09 4.42225e-10 1 1.20371e-20 -1.12832e-10 6.92242e-09 4.42225e-10 1 -1.12832e-10 6.92242e-09 4.42225e-10 3989.71 -5.11406 159.001 3998.36 0.949071 4004.9 +EDGE_SE3:QUAT 1390 1440 -2.42625 0.050682 -5.67762 0.0121458 -0.0753593 0.00877611 0.997044 1 1.95602e-19 1.95602e-19 7.00324e-11 2.76355e-08 -3.803e-09 1 1.95602e-19 7.00324e-11 2.76355e-08 -3.803e-09 1 7.00324e-11 2.76355e-08 -3.803e-09 4092.19 -2.73585 -616.214 3977.19 -1.16109 4092.47 +EDGE_SE3:QUAT 1389 1440 -3.21815 11.5688 -5.68531 -0.291853 -0.025977 -0.199388 0.935089 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3825.81 124.223 -848.378 3942.68 54.2816 4007.5 +EDGE_SE3:QUAT 1390 1439 -3.33462 -11.49 -5.77532 -0.0933197 0.080227 -0.194516 0.973149 1 2.40741e-19 2.40741e-19 2.42577e-08 -1.92613e-08 -6.05406e-10 1 2.40741e-19 2.42577e-08 -1.92613e-08 -6.05406e-10 1 2.42577e-08 -1.92613e-08 -6.05406e-10 3999.77 -29.1985 386.151 3997.93 -37.4713 3883.26 +EDGE_SE3:QUAT 1391 1441 -2.4882 0.244878 -5.80751 -0.0510681 -0.184664 0.0200814 0.981269 1 9.62965e-20 9.62965e-20 1.18943e-08 -3.16113e-10 1.18943e-08 1 9.62965e-20 1.18943e-08 -3.16113e-10 1.18943e-08 1 1.18943e-08 -3.16113e-10 1.18943e-08 4577.98 76.1893 -1643.16 3872.14 -70.937 4586.8 +EDGE_SE3:QUAT 1390 1441 -3.07348 11.5741 -5.42979 -0.0240759 -0.155664 -0.0132333 0.987428 1 1.20371e-20 1.20371e-20 -7.20239e-09 4.4593e-11 1.13857e-09 1 1.20371e-20 -7.20239e-09 4.4593e-11 1.13857e-09 1 -7.20239e-09 4.4593e-11 1.13857e-09 4417.41 11.9706 -1362.01 3902.73 -4.48779 4419.03 +EDGE_SE3:QUAT 1391 1440 -2.93255 -11.2269 -5.27982 0.185902 -0.118552 -0.0395671 0.974587 1 1.92593e-19 1.92593e-19 -2.26836e-09 -2.69773e-08 5.52839e-09 1 1.92593e-19 -2.26836e-09 -2.69773e-08 5.52839e-09 1 -2.26836e-09 -2.69773e-08 5.52839e-09 4028.66 -94.6411 -836.466 3973.34 70.4623 4160.63 +EDGE_SE3:QUAT 1392 1442 -2.22641 0.190525 -5.68619 -0.173331 0.0408744 -0.0397145 0.983213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3892.8 -18.3824 231.058 3998.17 -8.18192 4006.67 +EDGE_SE3:QUAT 1391 1442 -3.51717 11.0591 -6.21322 0.0638289 0.0769021 0.101789 0.989773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4052.78 28.5022 531.353 3986.34 34.2012 4027.64 +EDGE_SE3:QUAT 1392 1441 -2.9889 -11.3697 -5.83508 0.0555495 -0.0723565 -0.184945 0.978506 1 8.1852e-19 8.1852e-19 8.27089e-11 1.79484e-08 5.35428e-08 1 8.1852e-19 8.27089e-11 1.79484e-08 5.35428e-08 1 8.27089e-11 1.79484e-08 5.35428e-08 4032.25 -26.0233 -428.977 3993.96 40.9636 3907.77 +EDGE_SE3:QUAT 1393 1443 -2.65272 0.272485 -5.48675 -0.0761288 0.0286033 0.0163271 0.996554 1 2.0463e-19 2.0463e-19 -2.77928e-08 6.58681e-09 -3.32329e-10 1 2.0463e-19 -2.77928e-08 6.58681e-09 -3.32329e-10 1 -2.77928e-08 6.58681e-09 -3.32329e-10 3991.45 -9.12374 242.412 3996.3 0.392264 4013.57 +EDGE_SE3:QUAT 1392 1443 -3.398 11.3019 -5.8325 0.0178014 -0.0205261 0.0830052 0.996179 1 1.20371e-20 1.20371e-20 6.91944e-09 5.71647e-10 -1.60993e-10 1 1.20371e-20 6.91944e-09 5.71647e-10 -1.60993e-10 1 6.91944e-09 5.71647e-10 -1.60993e-10 4006.85 -0.684941 -180.425 3997.9 -7.53682 3980.56 +EDGE_SE3:QUAT 1393 1442 -3.02772 -11.3599 -5.88577 0.0307927 0.106648 -0.251353 0.961509 1 9.21588e-21 9.21588e-21 5.98624e-09 -1.56079e-09 6.72841e-10 1 9.21588e-21 5.98624e-09 -1.56079e-09 6.72841e-10 1 5.98624e-09 -1.56079e-09 6.72841e-10 4189 -60.8057 899.441 3966.26 -118.922 3940.08 +EDGE_SE3:QUAT 1394 1444 -2.5289 -0.141128 -5.74854 0.031374 -0.149791 -0.0114849 0.988153 1 4.81482e-20 4.81482e-20 1.4351e-08 -3.15477e-10 -2.15927e-09 1 4.81482e-20 1.4351e-08 -3.15477e-10 -2.15927e-09 1 1.4351e-08 -3.15477e-10 -2.15927e-09 4376.18 -31.9047 -1290.35 3912.3 27.8874 4379.59 +EDGE_SE3:QUAT 1393 1444 -3.19429 11.1646 -6.2331 -0.0355637 0.0680826 -0.00106404 0.997045 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4069.73 -10.407 552.039 3981.7 -4.33913 4074.78 +EDGE_SE3:QUAT 1394 1443 -2.79853 -11.5701 -5.88063 -0.0182494 -0.0856354 0.00461218 0.996149 1 7.52316e-22 7.52316e-22 1.50346e-10 3.40093e-11 -1.75367e-09 1 7.52316e-22 1.50346e-10 3.40093e-11 -1.75367e-09 1 1.50346e-10 3.40093e-11 -1.75367e-09 4118.13 7.73092 -701.528 3970.88 -5.0604 4119.38 +EDGE_SE3:QUAT 1395 1445 -2.42972 -0.229553 -5.72619 0.0515652 -0.0602331 -0.00201412 0.99685 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4047.27 -13.1227 -484.734 3985.91 5.03379 4057.89 +EDGE_SE3:QUAT 1394 1445 -2.97247 11.3048 -5.87735 -0.0122799 -0.0723924 0.042536 0.996393 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4082.19 9.1205 -581.405 3980.01 -14.5336 4075.55 +EDGE_SE3:QUAT 1395 1444 -3.36019 -11.5037 -5.77272 0.185337 -0.00246224 -0.152116 0.970827 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3883.78 36.0334 308.987 3989.47 -28.2857 3928.62 +EDGE_SE3:QUAT 1396 1446 -2.46711 -0.0291559 -5.7581 -0.145425 0.134612 0.0352772 0.979534 1 3.85186e-18 3.85186e-18 -1.12885e-07 5.49577e-08 -8.21897e-09 1 3.85186e-18 -1.12885e-07 5.49577e-08 -8.21897e-09 1 -1.12885e-07 5.49577e-08 -8.21897e-09 4238.43 -86.4125 1181.72 3929.11 -47.7692 4318.05 +EDGE_SE3:QUAT 1395 1446 -3.33372 11.1767 -6.08379 -0.200689 -0.0450937 -0.0200325 0.978411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3876.43 39.7515 -389.308 3991.76 -7.17185 4035.93 +EDGE_SE3:QUAT 1396 1445 -3.09805 -11.3643 -5.52746 -0.0922123 0.198536 -0.117218 0.96868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4494.88 -203.976 1550.5 3920.57 -206.93 4473.93 +EDGE_SE3:QUAT 1397 1447 -2.94768 -0.0984651 -5.85961 0.0700741 -0.0381078 0.0836769 0.993295 1 2.40741e-19 2.40741e-19 -2.8769e-08 1.16223e-08 4.88873e-10 1 2.40741e-19 -2.8769e-08 1.16223e-08 4.88873e-10 1 -2.8769e-08 1.16223e-08 4.88873e-10 4014.63 -10.0402 -372.341 3990.73 -13.4232 4006.26 +EDGE_SE3:QUAT 1396 1447 -3.31067 11.6292 -5.88322 -0.0475328 -0.0504603 0.180023 0.981217 1 9.62965e-20 9.62965e-20 1.10904e-08 1.61751e-08 4.49285e-10 1 9.62965e-20 1.10904e-08 1.61751e-08 4.49285e-10 1 1.10904e-08 1.61751e-08 4.49285e-10 4010.37 12.4407 -283.108 3997.42 -23.9588 3889.78 +EDGE_SE3:QUAT 1397 1446 -3.08015 -11.4596 -5.54843 0.258784 0.0307379 -0.0709311 0.962837 1 4.81482e-20 4.81482e-20 -6.4291e-10 -1.33828e-08 3.51313e-09 1 4.81482e-20 -6.4291e-10 -1.33828e-08 3.51313e-09 1 -6.4291e-10 -1.33828e-08 3.51313e-09 3778.34 61.5882 434.953 3987.14 -2.50997 4026.09 +EDGE_SE3:QUAT 1398 1448 -2.39556 0.455126 -5.72746 0.00488701 -0.0865942 0.175623 0.980629 1 1.95602e-19 1.95602e-19 -1.47194e-09 2.78338e-08 4.19315e-10 1 1.95602e-19 -1.47194e-09 2.78338e-08 4.19315e-10 1 -1.47194e-09 2.78338e-08 4.19315e-10 4114.76 29.8438 -687.723 3976.43 -63.6326 3991.49 +EDGE_SE3:QUAT 1397 1448 -3.10378 11.306 -5.8919 0.125869 0.0101069 0.13166 0.983219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3939.05 -11.4094 -117.658 3997.88 -11.957 3933.08 +EDGE_SE3:QUAT 1398 1447 -3.20561 -11.2274 -5.7729 -0.103191 -0.219734 -0.119634 0.962682 1 1.92593e-19 1.92593e-19 -7.33591e-09 -1.72273e-09 3.00045e-08 1 1.92593e-19 -7.33591e-09 -1.72273e-09 3.00045e-08 1 -7.33591e-09 -1.72273e-09 3.00045e-08 4980.87 -14.0013 -2267.53 3786.45 43.2887 4966.22 +EDGE_SE3:QUAT 1399 1449 -2.65761 -0.426838 -5.44328 0.0857763 -0.110851 0.204838 0.968708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4251.45 28.3926 -1096.88 3936.42 -100.278 4113.04 +EDGE_SE3:QUAT 1398 1449 -3.44046 11.392 -5.76539 -0.0344702 0.112656 -0.0177251 0.992878 1 1.20371e-20 1.20371e-20 7.90214e-10 -2.8043e-10 7.06528e-09 1 1.20371e-20 7.90214e-10 -2.8043e-10 7.06528e-09 1 7.90214e-10 -2.8043e-10 7.06528e-09 4201.64 -23.796 931.755 3951.16 -20.3179 4205.13 +EDGE_SE3:QUAT 1399 1448 -3.05043 -11.6886 -5.62821 0.202314 0.00316009 -0.102391 0.973948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3852.36 33.4399 264.536 3992.96 -14.3478 3974.15 +EDGE_SE3:QUAT 1400 1450 -2.81931 -0.0819555 -5.82579 0.00814494 0.0687733 0.0790243 0.994464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.85 11.179 545.743 3982.78 23.3594 4048.13 +EDGE_SE3:QUAT 1399 1450 -3.21 11.5478 -5.78099 -0.0553099 0.00427337 0.0503428 0.99719 1 4.81482e-20 4.81482e-20 1.38407e-08 6.87967e-10 1.35733e-10 1 4.81482e-20 1.38407e-08 6.87967e-10 1.35733e-10 1 1.38407e-08 6.87967e-10 1.35733e-10 3988.86 -2.09726 67.2089 3999.62 1.89616 3990.96 +EDGE_SE3:QUAT 1400 1449 -3.20018 -11.4994 -5.70567 -0.0224516 -0.164102 -0.169952 0.971433 1 7.82409e-19 7.82409e-19 -2.42192e-09 -5.51679e-08 7.51319e-10 1 7.82409e-19 -2.42192e-09 -5.51679e-08 7.51319e-10 1 -2.42192e-09 -5.51679e-08 7.51319e-10 4457.57 -105.05 -1431.83 3909.86 140.904 4344.05 +EDGE_SE3:QUAT 1401 1451 -2.16269 -0.249076 -5.88384 0.148473 -0.0613415 -0.0202778 0.986804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.15 -34.3181 -442.892 3990.27 16.0416 4046.68 +EDGE_SE3:QUAT 1400 1451 -3.27516 11.2074 -5.84624 -0.0136266 -0.0715143 0.0247054 0.99704 1 1.20371e-20 1.20371e-20 4.95692e-10 1.21329e-10 -6.98871e-09 1 1.20371e-20 4.95692e-10 1.21329e-10 -6.98871e-09 1 4.95692e-10 1.21329e-10 -6.98871e-09 4080.95 7.20281 -577.46 3980.08 -9.1877 4079.25 +EDGE_SE3:QUAT 1401 1450 -3.42641 -11.7506 -5.49677 -0.0106294 0.135564 -0.187668 0.972774 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4261.95 -87.4011 1058.69 3953.51 -119.869 4121.53 +EDGE_SE3:QUAT 1402 1452 -2.23873 -0.315809 -5.85493 0.066956 -0.00832876 -0.0691053 0.995325 1 1.88079e-22 1.88079e-22 -6.03664e-11 -8.63277e-10 5.85157e-11 1 1.88079e-22 -6.03664e-11 -8.63277e-10 5.85157e-11 1 -6.03664e-11 -8.63277e-10 5.85157e-11 3982.01 0.265099 -10.5207 4000 -0.274409 3980.84 +EDGE_SE3:QUAT 1401 1452 -3.40251 11.4085 -6.15392 0.114161 0.130571 0.0683526 0.98247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4167.22 86.3844 963.506 3959.01 78.3982 4200.66 +EDGE_SE3:QUAT 1402 1451 -3.06348 -11.7845 -5.79447 0.085831 -0.0691862 -0.0312489 0.993413 1 3.85186e-19 3.85186e-19 -2.66118e-08 2.87636e-08 -7.66384e-10 1 3.85186e-19 -2.66118e-08 2.87636e-08 -7.66384e-10 1 -2.66118e-08 2.87636e-08 -7.66384e-10 4037.38 -26.1549 -521.621 3985.05 17.3488 4062.94 +EDGE_SE3:QUAT 1403 1453 -2.69083 -0.118974 -5.48537 0.0761395 0.0646727 -0.0591988 0.993235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4057.66 16.5449 574.567 3979.48 -9.29879 4066.83 +EDGE_SE3:QUAT 1402 1453 -3.49036 11.0013 -5.91708 0.0948039 -0.0194797 0.0200098 0.995104 1 1.92593e-19 1.92593e-19 -2.76468e-08 -4.44193e-10 6.36049e-10 1 1.92593e-19 -2.76468e-08 -4.44193e-10 6.36049e-10 1 -2.76468e-08 -4.44193e-10 6.36049e-10 3971.82 -8.51219 -176.596 3997.97 -0.787603 4006.17 +EDGE_SE3:QUAT 1403 1452 -3.29853 -11.0161 -5.56992 0.128188 0.0324072 -0.294485 0.946465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.28 15.1606 660.825 3968.13 -105.281 3757.12 +EDGE_SE3:QUAT 1404 1454 -2.36735 -0.120766 -5.4562 0.0179702 0.103143 0.00704447 0.994479 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4173.62 10.4236 854.543 3957.82 8.16116 4174.71 +EDGE_SE3:QUAT 1403 1454 -3.57326 11.1655 -5.80695 0.112594 -0.0435652 -0.069938 0.990219 1 1.92593e-19 1.92593e-19 -7.32891e-10 3.27834e-09 2.75358e-08 1 1.92593e-19 -7.32891e-10 3.27834e-09 2.75358e-08 1 -7.32891e-10 3.27834e-09 2.75358e-08 3964.07 -14.0204 -246.363 3997.62 10.5983 3995.22 +EDGE_SE3:QUAT 1404 1453 -2.92645 -11.1317 -5.50835 0.0267175 -0.0732207 -0.0755045 0.994095 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4075.42 -17.0226 -565.143 3982.05 25.3572 4055.47 +EDGE_SE3:QUAT 1405 1455 -2.45273 0.0131323 -5.95657 -0.15293 0.00209742 -0.191052 0.969591 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3929.71 29.3302 -323.236 3988.59 38.6588 3877.25 +EDGE_SE3:QUAT 1404 1455 -3.39473 11.2916 -5.94322 0.085024 0.0266371 0.128346 0.987719 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3972 1.83898 76.5533 4000.04 2.31751 3935.03 +EDGE_SE3:QUAT 1405 1454 -3.20038 -11.0869 -5.6755 -0.105272 0.0101521 -0.133455 0.985396 1 7.70372e-19 7.70372e-19 -1.00616e-09 -5.78419e-09 5.47086e-08 1 7.70372e-19 -1.00616e-09 -5.78419e-09 5.47086e-08 1 -1.00616e-09 -5.78419e-09 5.47086e-08 3956.83 7.52036 -87.6387 3998.69 9.58767 3929.92 +EDGE_SE3:QUAT 1406 1456 -2.45697 0.0550879 -5.82092 -0.0113093 0.0525235 0.126802 0.990472 1 7.71124e-19 7.71124e-19 4.72521e-09 3.46599e-10 5.53963e-08 1 7.71124e-19 4.72521e-09 3.46599e-10 5.53963e-08 1 4.72521e-09 3.46599e-10 5.53963e-08 4045.49 6.27803 431.433 3989.21 27.5398 3981.69 +EDGE_SE3:QUAT 1405 1456 -3.47092 11.3207 -5.87377 -0.00394636 0.0650268 0.146351 0.987085 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.85 13.8105 517.748 3985.43 38.9334 3980.24 +EDGE_SE3:QUAT 1406 1455 -2.93176 -11.366 -5.40469 -0.196231 -0.0999068 0.209295 0.952737 1 7.70372e-19 7.70372e-19 -1.80163e-10 -1.22944e-08 5.2907e-08 1 7.70372e-19 -1.80163e-10 -1.22944e-08 5.2907e-08 1 -1.80163e-10 -1.22944e-08 5.2907e-08 3848.65 13.2921 -228.977 4004.81 -12.9187 3827.46 +EDGE_SE3:QUAT 1407 1457 -2.71961 0.0229907 -5.95479 0.0214458 0.320466 0.0149798 0.946899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 6312.36 154.819 3822.62 3599.56 155.405 6313.31 +EDGE_SE3:QUAT 1406 1457 -3.57117 11.1472 -5.68418 0.0447888 -0.189517 0.0433033 0.979899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4650.79 -9.18574 -1751.95 3853.26 -5.79551 4651.32 +EDGE_SE3:QUAT 1407 1456 -3.31546 -11.0217 -5.51197 -0.0543862 -0.10021 0.0111561 0.993416 1 6.01853e-20 6.01853e-20 1.47579e-08 7.2528e-10 -8.42291e-09 1 6.01853e-20 1.47579e-08 7.2528e-10 -8.42291e-09 1 1.47579e-08 7.2528e-10 -8.42291e-09 4149.06 27.2519 -818.224 3961.96 -18.5006 4160.4 +EDGE_SE3:QUAT 1408 1458 -2.8483 -0.00238151 -5.59642 -0.0412614 0.045722 -0.0426209 0.997191 1 1.44445e-19 1.44445e-19 1.3829e-08 -1.51124e-08 1.38463e-08 1 1.44445e-19 1.3829e-08 -1.51124e-08 1.38463e-08 1 1.3829e-08 -1.51124e-08 1.38463e-08 4022.69 -9.05651 344.879 3993.12 -9.22816 4022.23 +EDGE_SE3:QUAT 1407 1458 -3.4362 11.2617 -5.79454 -0.0408255 -0.0541798 -0.164308 0.984074 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4055.15 -3.69079 -501.271 3984.93 40.7586 3953.83 +EDGE_SE3:QUAT 1408 1457 -3.56039 -11.0934 -5.55337 0.0286163 -0.0217272 -0.12618 0.991357 1 2.40741e-20 2.40741e-20 -5.99912e-09 7.76174e-09 -1.34089e-10 1 2.40741e-20 -5.99912e-09 7.76174e-09 -1.34089e-10 1 -5.99912e-09 7.76174e-09 -1.34089e-10 4000.66 -2.48647 -126.686 3999.32 7.21937 3940.25 +EDGE_SE3:QUAT 1409 1459 -2.51107 0.0910686 -5.72419 -0.00406626 0.117078 -0.0262379 0.992768 1 1.93345e-19 1.93345e-19 -9.94838e-10 2.76034e-08 8.18229e-11 1 1.93345e-19 -9.94838e-10 2.76034e-08 8.18229e-11 1 -9.94838e-10 2.76034e-08 8.18229e-11 4227.42 -11.4804 980.665 3945.74 -16.152 4224.73 +EDGE_SE3:QUAT 1408 1459 -3.1386 10.9913 -5.76393 -0.0511031 -0.0533228 0.216448 0.973497 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.38 13.0937 -267.05 3998.68 -25.2446 3829.43 +EDGE_SE3:QUAT 1409 1458 -3.52762 -11.6251 -5.60931 0.019197 0.162959 0.046782 0.985336 1 8.30557e-19 8.30557e-19 -6.45629e-09 -5.56074e-08 -1.35954e-08 1 8.30557e-19 -6.45629e-09 -5.56074e-08 -1.35954e-08 1 -6.45629e-09 -5.56074e-08 -1.35954e-08 4447.04 50.6648 1412.55 3899.5 55.9289 4439.76 +EDGE_SE3:QUAT 1410 1460 -2.34017 -0.0674219 -5.58368 -0.163052 -0.0838347 0.0981925 0.978133 1 9.62965e-19 9.62965e-19 -5.79868e-08 2.03152e-08 7.48547e-09 1 9.62965e-19 -5.79868e-08 2.03152e-08 7.48547e-09 1 -5.79868e-08 2.03152e-08 7.48547e-09 3941.52 41.3609 -448.467 3994.93 -34.7328 4009.3 +EDGE_SE3:QUAT 1409 1460 -3.6336 11.3178 -6.00675 0.114729 -0.0416244 -0.00306131 0.99252 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.42 -18.8354 -324.061 3994.02 5.09935 4026.04 +EDGE_SE3:QUAT 1410 1459 -3.57389 -11.5159 -5.58704 -0.256509 0.00348102 0.187768 0.948121 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3811.84 -84.5852 574.172 3967.76 52.3201 3934 +EDGE_SE3:QUAT 1411 1461 -2.29396 -0.189374 -5.51921 0.0641692 -0.0261453 0.0847763 0.993988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.8 -7.34307 -271.653 3994.86 -10.8977 3989.53 +EDGE_SE3:QUAT 1410 1461 -3.35305 11.2632 -5.99292 0.125491 -0.0172077 0.00165938 0.991944 1 7.70384e-19 7.70384e-19 -5.51004e-08 1.76008e-10 1.16385e-09 1 7.70384e-19 -5.51004e-08 1.76008e-10 1.16385e-09 1 -5.51004e-08 1.76008e-10 1.16385e-09 3941.7 -8.59708 -137.036 3998.91 0.778522 4004.68 +EDGE_SE3:QUAT 1411 1460 -3.38782 -11.4052 -5.92864 0.0358963 0.10382 0.107673 0.988099 1 2.40741e-19 2.40741e-19 -1.07236e-08 -2.90528e-08 3.00242e-10 1 2.40741e-19 -1.07236e-08 -2.90528e-08 3.00242e-10 1 -1.07236e-08 -2.90528e-08 3.00242e-10 4145.88 41.3407 792.272 3968.1 54.7012 4104.66 +EDGE_SE3:QUAT 1412 1462 -2.40345 -0.00810346 -5.83396 -0.0357121 0.0482524 0.0249468 0.997885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4034.32 -5.8962 399.078 3990.12 3.04342 4036.94 +EDGE_SE3:QUAT 1411 1462 -3.29906 11.3162 -5.97602 -0.0487085 -0.0418488 0.172682 0.982882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.14 8.41949 -220.136 3998.57 -16.9623 3892.36 +EDGE_SE3:QUAT 1412 1461 -3.27468 -11.5718 -5.71135 0.20613 0.0905354 -0.113206 0.967728 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.18 85.5523 990.256 3943.23 0.29501 4179.87 +EDGE_SE3:QUAT 1413 1463 -2.39794 -0.0696236 -5.7569 -0.0358724 0.0994966 -0.0111637 0.994328 1 4.81482e-20 4.81482e-20 -1.40735e-08 2.63255e-10 -1.39258e-09 1 4.81482e-20 -1.40735e-08 2.63255e-10 -1.39258e-09 1 -1.40735e-08 2.63255e-10 -1.39258e-09 4155.28 -18.8873 816.981 3961.59 -13.8538 4159.93 +EDGE_SE3:QUAT 1412 1463 -3.34997 11.1467 -5.81058 0.105936 -0.0368841 0.161446 0.980486 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.65 -17.7272 -486.178 3982.94 -37.4983 3953.28 +EDGE_SE3:QUAT 1413 1462 -3.17217 -11.6623 -5.36629 0.111816 0.0335186 0.0141425 0.993063 1 1.20371e-20 1.20371e-20 2.05182e-10 7.85257e-10 6.90377e-09 1 1.20371e-20 2.05182e-10 7.85257e-10 6.90377e-09 1 2.05182e-10 7.85257e-10 6.90377e-09 3964.91 13.7265 244.973 3996.73 4.3324 4014.12 +EDGE_SE3:QUAT 1414 1464 -2.37608 0.230357 -5.84179 -0.0451521 0.0893341 -0.0751738 0.992134 1 4.81482e-20 4.81482e-20 -1.39631e-08 1.18449e-09 -1.14058e-09 1 4.81482e-20 -1.39631e-08 1.18449e-09 -1.14058e-09 1 -1.39631e-08 1.18449e-09 -1.14058e-09 4104.62 -29.6099 681.332 3975.03 -35.0422 4090.17 +EDGE_SE3:QUAT 1413 1464 -3.07203 11.3452 -5.71896 -0.00223594 -0.034042 0.118235 0.992399 1 7.52316e-22 7.52316e-22 1.72533e-09 2.06292e-10 -5.66092e-11 1 7.52316e-22 1.72533e-09 2.06292e-10 -5.66092e-11 1 1.72533e-09 2.06292e-10 -5.66092e-11 4017.39 3.45863 -264.485 3996.02 -15.7053 3961.49 +EDGE_SE3:QUAT 1414 1463 -2.89873 -11.3586 -6.06079 0.115 0.215578 -0.188145 0.951264 1 7.70372e-19 7.70372e-19 5.96411e-08 -9.50341e-09 1.50753e-08 1 7.70372e-19 5.96411e-08 -9.50341e-09 1.50753e-08 1 5.96411e-08 -9.50341e-09 1.50753e-08 5005.47 -110.658 2313.88 3790.89 -152.948 4916.78 +EDGE_SE3:QUAT 1415 1465 -2.46545 0.293951 -5.73072 0.00422659 -0.0760085 -0.0506018 0.995813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4092.43 -8.5074 -615.286 3977.66 17.0644 4082.26 +EDGE_SE3:QUAT 1414 1465 -3.39289 11.7762 -5.76293 -0.112776 -0.149698 -0.167368 0.967915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4454.68 -15.8591 -1509.62 3885.51 80.8678 4393.5 +EDGE_SE3:QUAT 1415 1464 -3.32802 -11.3187 -5.65108 0.0797524 0.0567661 -0.0483273 0.994023 1 2.40741e-19 2.40741e-19 2.8345e-08 1.27102e-08 7.43047e-10 1 2.40741e-19 2.8345e-08 1.27102e-08 7.43047e-10 1 2.8345e-08 1.27102e-08 7.43047e-10 4036.4 16.9179 501.32 3984.27 -5.6883 4052.5 +EDGE_SE3:QUAT 1416 1466 -2.51871 0.0611807 -5.43612 0.0704853 -0.292581 0.0453786 0.952559 1 1.08334e-19 1.08334e-19 -7.46054e-09 1.37025e-09 2.40354e-08 1 1.08334e-19 -7.46054e-09 1.37025e-09 2.40354e-08 1 -7.46054e-09 1.37025e-09 2.40354e-08 5846.56 -82.2275 -3308.97 3655.13 84.7838 5858.19 +EDGE_SE3:QUAT 1415 1466 -3.59607 11.0487 -6.14021 -0.00446735 0.0391474 0.20202 0.978588 1 1.88079e-22 1.88079e-22 8.51363e-10 1.76003e-10 3.28118e-11 1 1.88079e-22 8.51363e-10 1.76003e-10 3.28118e-11 1 8.51363e-10 1.76003e-10 3.28118e-11 4023.22 6.63188 306.287 3995.33 30.9815 3860.05 +EDGE_SE3:QUAT 1416 1465 -3.01943 -11.2303 -5.4837 0.176497 -0.0870472 0.07635 0.977467 1 1.01111e-18 1.01111e-18 -5.51143e-08 2.2456e-08 -1.23355e-08 1 1.01111e-18 -5.51143e-08 2.2456e-08 -1.23355e-08 1 -5.51143e-08 2.2456e-08 -1.23355e-08 4048.56 -67.1292 -850.548 3958.24 7.07683 4149.85 +EDGE_SE3:QUAT 1417 1467 -2.56366 0.0873892 -5.82885 -0.0635471 -0.0771814 0.00437213 0.99498 1 1.95602e-19 1.95602e-19 2.82096e-08 6.28788e-10 -5.62679e-09 1 1.95602e-19 2.82096e-08 6.28788e-10 -5.62679e-09 1 2.82096e-08 6.28788e-10 -5.62679e-09 4078.61 21.5835 -622.923 3977.33 -10.6405 4094.68 +EDGE_SE3:QUAT 1416 1467 -3.62893 11.558 -5.92766 -0.253628 0.177055 0.0988673 0.945806 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4440.17 -221.577 1810.08 3873.5 -153.435 4658.38 +EDGE_SE3:QUAT 1417 1466 -3.32787 -11.4061 -5.56933 -0.12282 -0.0846579 -0.0460994 0.987736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4075.62 41.6539 -749.973 3967.11 -5.70596 4127.46 +EDGE_SE3:QUAT 1418 1468 -2.43625 0.0129376 -5.87197 -0.0796886 -0.0286492 0.184115 0.97925 1 1.92593e-19 1.92593e-19 2.71778e-08 5.17314e-09 6.7742e-11 1 1.92593e-19 2.71778e-08 5.17314e-09 6.7742e-11 1 2.71778e-08 5.17314e-09 6.7742e-11 3974.09 -0.303694 -43.9651 4000.1 1.58198 3863.89 +EDGE_SE3:QUAT 1417 1468 -3.17448 11.2424 -6.10025 0.0448233 0.0957636 0.100302 0.989323 1 4.81482e-20 4.81482e-20 1.3944e-08 1.5549e-09 1.18777e-09 1 4.81482e-20 1.3944e-08 1.5549e-09 1.18777e-09 1 1.3944e-08 1.5549e-09 1.18777e-09 4116.14 36.9381 716.171 3973.84 46.8742 4083.93 +EDGE_SE3:QUAT 1418 1467 -3.27192 -11.526 -5.57933 0.0160161 -0.0739911 0.126013 0.989136 1 1.93345e-19 1.93345e-19 -5.20601e-09 2.72381e-08 2.15208e-10 1 1.93345e-19 -5.20601e-09 2.72381e-08 2.15208e-10 1 -5.20601e-09 2.72381e-08 2.15208e-10 4091.11 12.3716 -614.016 3978.56 -38.9789 4028.61 +EDGE_SE3:QUAT 1419 1469 -2.32251 0.0524529 -5.65767 -0.00577231 0.148107 -0.0695341 0.986507 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4365.92 -44.5873 1264.23 3917.42 -57.3778 4346.71 +EDGE_SE3:QUAT 1418 1469 -3.39158 11.0035 -5.75677 0.0208132 -0.0887937 0.0083925 0.995797 1 2.0463e-19 2.0463e-19 -7.15367e-09 2.76059e-08 8.28919e-11 1 2.0463e-19 -7.15367e-09 2.76059e-08 8.28919e-11 1 -7.15367e-09 2.76059e-08 8.28919e-11 4128.06 -6.60507 -732.136 3968.33 0.77726 4129.51 +EDGE_SE3:QUAT 1419 1468 -3.36603 -11.0336 -5.88922 0.102166 -0.112895 -0.142545 0.978007 1 9.62965e-19 9.62965e-19 2.86689e-10 3.45085e-08 5.14523e-08 1 9.62965e-19 2.86689e-10 3.45085e-08 5.14523e-08 1 2.86689e-10 3.45085e-08 5.14523e-08 4076.15 -66.2009 -702.208 3983.72 71.7506 4036.62 +EDGE_SE3:QUAT 1420 1470 -2.55487 0.160798 -5.6755 0.0320337 -0.0238927 0.0648654 0.997094 1 2.40741e-20 2.40741e-20 7.3679e-09 -6.47967e-09 6.09544e-12 1 2.40741e-20 7.3679e-09 -6.47967e-09 6.09544e-12 1 7.3679e-09 -6.47967e-09 6.09544e-12 4007.41 -2.52168 -215.074 3996.96 -6.7478 3994.69 +EDGE_SE3:QUAT 1419 1470 -3.64571 11.0162 -5.83158 0.0142258 -0.0757362 0.159852 0.984129 1 7.71547e-19 7.71547e-19 2.12936e-09 2.37147e-10 -5.51214e-08 1 7.71547e-19 2.12936e-09 2.37147e-10 -5.51214e-08 1 2.12936e-09 2.37147e-10 -5.51214e-08 4093.76 18.4509 -622.321 3979.16 -50.901 3992.36 +EDGE_SE3:QUAT 1420 1469 -3.44411 -11.2136 -5.72949 0.0175726 0.0461174 -0.199191 0.978717 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4036.69 -7.78226 391.341 3991.78 -39.5855 3879.22 +EDGE_SE3:QUAT 1421 1471 -2.84154 -0.0586479 -5.82624 -0.0680171 -0.114639 0.0110414 0.991015 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4192.49 39.91 -942.642 3951.16 -28.1791 4210.51 +EDGE_SE3:QUAT 1420 1471 -3.19922 11.1723 -5.98974 0.0235919 -0.0518592 0.00650027 0.998355 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.47 -4.67745 -420.331 3989.16 0.145279 4043.52 +EDGE_SE3:QUAT 1421 1470 -3.70865 -11.1369 -5.56809 0.0486237 0.13829 -0.0141862 0.989096 1 8.19273e-19 8.19273e-19 -1.40745e-08 -5.48153e-08 2.36039e-09 1 8.19273e-19 -1.40745e-08 -5.48153e-08 2.36039e-09 1 -1.40745e-08 -5.48153e-08 2.36039e-09 4317.74 27.7055 1189.9 3923.41 14.5398 4326.39 +EDGE_SE3:QUAT 1422 1472 -2.44612 0.145098 -5.58377 -0.0467581 0.221507 -0.0154662 0.973914 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4888.85 -98.2373 2096.7 3813.58 -94.4989 4896.64 +EDGE_SE3:QUAT 1421 1472 -3.40921 11.0958 -5.61991 -0.111209 0.295014 0.118389 0.941586 1 7.70372e-19 7.70372e-19 -6.46191e-08 -4.5051e-09 -2.12249e-08 1 7.70372e-19 -6.46191e-08 -4.5051e-09 -2.12249e-08 1 -6.46191e-08 -4.5051e-09 -2.12249e-08 6022.48 30.0948 3546.97 3627.69 23.2429 6015.89 +EDGE_SE3:QUAT 1422 1471 -3.26039 -11.4551 -5.92188 0.0246421 0.00191322 -0.0435543 0.998745 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.76 0.388594 28.1074 3999.93 -0.699337 3992.61 +EDGE_SE3:QUAT 1423 1473 -2.43493 0.129437 -5.74836 0.067969 0.0741276 0.0853917 0.991259 1 1.92593e-19 1.92593e-19 2.64982e-09 -2.74874e-08 2.22782e-09 1 1.92593e-19 2.64982e-09 -2.74874e-08 2.22782e-09 1 2.64982e-09 -2.74874e-08 2.22782e-09 4047.72 26.8766 519.713 3986.47 29.5068 4037.03 +EDGE_SE3:QUAT 1422 1473 -3.57143 10.8082 -6.03999 -0.171139 -0.199816 0.013752 0.964674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4503.27 217.343 -1694.37 3898.31 -196.716 4619.67 +EDGE_SE3:QUAT 1423 1472 -3.33314 -11.5112 -5.16892 0.246702 0.103078 0.0385065 0.962824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3857.52 86.2952 649.311 3989.69 57.6106 4095.04 +EDGE_SE3:QUAT 1424 1474 -2.44302 -0.529315 -5.44818 0.154118 0.00762142 0.0412774 0.98716 1 8.1852e-19 8.1852e-19 5.47238e-08 4.45142e-09 1.34037e-08 1 8.1852e-19 5.47238e-08 4.45142e-09 1.34037e-08 1 5.47238e-08 4.45142e-09 1.34037e-08 3904.89 -3.28536 -16.3879 3999.89 -0.883948 3993.09 +EDGE_SE3:QUAT 1423 1474 -3.82401 11.4176 -6.01371 0.00230315 0.0044644 -0.00198396 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.3 0.0402723 35.772 3999.92 -0.0344061 4000.3 +EDGE_SE3:QUAT 1424 1473 -3.27155 -11.3818 -5.05164 0.0786626 0.0740032 -0.156654 0.981731 1 1.15556e-18 1.15556e-18 2.64282e-08 2.02266e-08 -5.42112e-08 1 1.15556e-18 2.64282e-08 2.02266e-08 -5.42112e-08 1 2.64282e-08 2.02266e-08 -5.42112e-08 4104.96 3.48055 732.55 3967.34 -50.2441 4031.55 +EDGE_SE3:QUAT 1425 1475 -2.62968 -0.270913 -5.44955 0.00786288 -0.0472093 0.0463018 0.99778 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4036.26 0.990146 -383.852 3990.96 -8.69043 4027.93 +EDGE_SE3:QUAT 1424 1475 -3.25788 10.9717 -5.74402 0.0457037 -0.220908 0.204784 0.952457 1 7.78318e-19 7.78318e-19 1.95812e-08 4.33894e-09 -6.0233e-08 1 7.78318e-19 1.95812e-08 4.33894e-09 -6.0233e-08 1 1.95812e-08 4.33894e-09 -6.0233e-08 4905.22 241.372 -2119.09 3849 -269.393 4745.83 +EDGE_SE3:QUAT 1425 1474 -2.97593 -11.3664 -5.30102 -0.0825663 0.139888 -0.0839769 0.983139 1 1.92593e-19 1.92593e-19 -3.48218e-09 3.11283e-09 -2.81971e-08 1 1.92593e-19 -3.48218e-09 3.11283e-09 -2.81971e-08 1 -3.48218e-09 3.11283e-09 -2.81971e-08 4239.05 -87.683 1066.98 3948.27 -87.9342 4238.11 +EDGE_SE3:QUAT 1426 1476 -2.36471 -0.00684903 -5.74044 0.0277437 0.0830601 -0.10778 0.99031 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4118.07 -8.99685 706.596 3971.01 -36.3791 4074.68 +EDGE_SE3:QUAT 1425 1476 -3.55676 11.3033 -5.53819 -0.0977988 0.0830635 0.101783 0.986497 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4112.02 -21.5127 790.231 3961.96 24.1611 4108.84 +EDGE_SE3:QUAT 1426 1475 -3.43081 -11.044 -5.61088 -0.0459813 -0.0187066 -0.130115 0.990256 1 4.81482e-20 4.81482e-20 1.37629e-08 -1.7787e-09 -4.14972e-10 1 4.81482e-20 1.37629e-08 -1.7787e-09 -4.14972e-10 1 1.37629e-08 -1.7787e-09 -4.14972e-10 4003.17 3.52687 -216.931 3996.61 14.9516 3943.91 +EDGE_SE3:QUAT 1427 1477 -2.48209 0.0910489 -5.49152 0.183916 -0.0180791 -0.0025748 0.982772 1 7.52316e-22 7.52316e-22 -2.7638e-11 3.19579e-10 1.70579e-09 1 7.52316e-22 -2.7638e-11 3.19579e-10 1.70579e-09 1 -2.7638e-11 3.19579e-10 1.70579e-09 3869.04 -11.7826 -131.917 3999.15 1.43705 4004.31 +EDGE_SE3:QUAT 1426 1477 -3.66827 11.0452 -6.16433 0.0253536 0.0828218 0.0694183 0.99382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4100.36 19.7901 649.953 3976.21 27.8687 4083.66 +EDGE_SE3:QUAT 1427 1476 -3.57172 -10.9981 -4.98869 -0.113116 -0.0330099 -0.0297745 0.992587 1 2.52778e-19 2.52778e-19 2.76583e-08 1.24011e-08 7.3706e-09 1 2.52778e-19 2.76583e-08 1.24011e-08 7.3706e-09 1 2.76583e-08 1.24011e-08 7.3706e-09 3971.22 16.916 -300.322 3994.24 1.06122 4018.85 +EDGE_SE3:QUAT 1428 1478 -2.61662 0.19639 -5.83006 -0.0400965 0.107286 0.122951 0.985781 1 2.0463e-19 2.0463e-19 -3.78135e-09 -1.20819e-09 2.72683e-08 1 2.0463e-19 -3.78135e-09 -1.20819e-09 2.72683e-08 1 -3.78135e-09 -1.20819e-09 2.72683e-08 4202.59 17.4692 937.974 3951.08 53.2918 4148.55 +EDGE_SE3:QUAT 1427 1478 -3.42584 11.1163 -5.74558 -0.189551 -0.0382794 0.0175199 0.980968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3871.9 22.8062 -251.531 3997.35 -7.08751 4014.39 +EDGE_SE3:QUAT 1428 1477 -3.16624 -11.2668 -5.20849 -0.0729518 -0.102876 -0.248598 0.960361 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4217.33 -45.0039 -1005.78 3950.49 122.758 3991.41 +EDGE_SE3:QUAT 1429 1479 -2.81684 -0.301937 -5.81487 -0.0538682 -0.0210173 0.11603 0.991561 1 4.81482e-20 4.81482e-20 -1.37639e-08 -1.63344e-09 1.09946e-10 1 4.81482e-20 -1.37639e-08 -1.63344e-09 1.09946e-10 1 -1.37639e-08 -1.63344e-09 1.09946e-10 3990.23 2.21348 -89.815 3999.81 -3.92351 3947.98 +EDGE_SE3:QUAT 1428 1479 -3.24164 11.3504 -6.03619 -0.116448 -0.00288141 0.229973 0.966201 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3964.12 -18.8557 287.678 3990.84 43.4663 3806.81 +EDGE_SE3:QUAT 1429 1478 -3.35374 -11.1871 -5.79082 0.143901 0.127929 -0.217913 0.956787 1 1.54074e-18 1.54074e-18 6.64433e-08 -5.93304e-09 6.64433e-08 1 1.54074e-18 6.64433e-08 -5.93304e-09 6.64433e-08 1 6.64433e-08 -5.93304e-09 6.64433e-08 4375.02 -11.1262 1429.85 3894.47 -108.361 4267.9 +EDGE_SE3:QUAT 1430 1480 -2.77145 -0.120851 -5.59007 -0.0465395 0.043472 -0.0816302 0.994626 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.49 -9.63711 299.073 3995.33 -13.4095 3995.5 +EDGE_SE3:QUAT 1429 1480 -3.38409 11.2201 -5.7706 0.0278882 -0.063569 0.1353 0.98837 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4070.58 6.70035 -547.926 3982.4 -36.4325 4000.47 +EDGE_SE3:QUAT 1430 1479 -3.16966 -11.3944 -5.89306 0.0137667 -0.0295435 0.127489 0.991304 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.09 1.19196 -252.293 3996.14 -16.2449 3950.83 +EDGE_SE3:QUAT 1431 1481 -3.0462 -0.075061 -5.70636 -0.0186974 0.0645417 0.136119 0.988411 1 3.00927e-21 3.00927e-21 3.46045e-09 4.7196e-10 2.352e-10 1 3.00927e-21 3.46045e-09 4.7196e-10 2.352e-10 1 3.46045e-09 4.7196e-10 2.352e-10 4070.37 9.37776 540.579 3983.24 36.8421 3997.66 +EDGE_SE3:QUAT 1430 1481 -3.43257 11.147 -5.79227 0.0364263 0.119209 0.147439 0.981185 1 4.81482e-20 4.81482e-20 1.39419e-08 2.27214e-09 1.45736e-09 1 4.81482e-20 1.39419e-08 2.27214e-09 1.45736e-09 1 1.39419e-08 2.27214e-09 1.45736e-09 4183.06 63.425 889.401 3964.49 83.3803 4101.42 +EDGE_SE3:QUAT 1431 1480 -3.54365 -11.3602 -5.9261 -0.111924 0.0154769 -0.173747 0.978287 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3951.5 10.5088 -110.785 3997.73 16.4892 3880.86 +EDGE_SE3:QUAT 1432 1482 -2.86357 -0.317655 -5.68074 -0.00976987 -0.076518 -0.0138898 0.996924 1 1.92593e-19 1.92593e-19 -3.48165e-10 -2.76707e-08 -2.1477e-10 1 1.92593e-19 -3.48165e-10 -2.76707e-08 -2.1477e-10 1 -3.48165e-10 -2.76707e-08 -2.1477e-10 4095.41 1.23594 -626.375 3976.46 3.20508 4095.02 +EDGE_SE3:QUAT 1431 1482 -3.83693 11.2715 -5.75535 -0.0894375 0.121617 -0.0124705 0.988461 1 1.92593e-19 1.92593e-19 -2.82331e-08 9.93808e-10 -3.34948e-09 1 1.92593e-19 -2.82331e-08 9.93808e-10 -3.34948e-09 1 -2.82331e-08 9.93808e-10 -3.34948e-09 4201.92 -55.5553 995.267 3947.52 -39.8997 4233.29 +EDGE_SE3:QUAT 1432 1481 -3.68572 -11.3553 -5.25097 -0.112684 -0.0705753 -0.0284814 0.990712 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.24 32.6371 -603.378 3978.49 -5.78037 4085.78 +EDGE_SE3:QUAT 1433 1483 -2.73788 -0.23407 -5.69032 -0.109178 -0.0101547 -0.0709914 0.991432 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3959.45 10.4288 -171.462 3997.54 6.2364 3986.97 +EDGE_SE3:QUAT 1432 1483 -3.36713 11.7855 -6.01714 -0.0891224 0.0986381 0.0820064 0.987726 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4160.15 -22.3209 897.154 3952.73 16.6459 4165.02 +EDGE_SE3:QUAT 1433 1482 -3.27096 -10.8029 -5.62034 -0.0433893 0.137261 -0.171962 0.974529 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4228.49 -93.2256 1002.19 3961.26 -114.688 4117.73 +EDGE_SE3:QUAT 1434 1484 -2.614 -0.155727 -5.70229 -0.0356449 -0.139801 0.0409118 0.988692 1 4.81482e-20 4.81482e-20 -1.95945e-09 -7.0253e-10 1.42568e-08 1 4.81482e-20 -1.95945e-09 -7.0253e-10 1.42568e-08 1 -1.95945e-09 -7.0253e-10 1.42568e-08 4312.31 45.4249 -1170.65 3927.89 -46.4892 4310.7 +EDGE_SE3:QUAT 1433 1484 -3.28914 11.1649 -5.85074 -0.10514 0.0461064 0.131241 0.98468 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.02 -19.2736 524.733 3981.13 29.3871 3998.34 +EDGE_SE3:QUAT 1434 1483 -3.4222 -10.9312 -5.64518 0.0322858 -0.0138717 -0.1848 0.982148 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.97 -0.335236 -35.23 4000.03 0.900093 3863.54 +EDGE_SE3:QUAT 1435 1485 -2.75778 -0.251475 -5.74868 0.0200278 0.178146 -0.0230343 0.98353 1 1.20371e-20 1.20371e-20 7.29024e-09 -1.26638e-10 1.32527e-09 1 1.20371e-20 7.29024e-09 -1.26638e-10 1.32527e-09 1 7.29024e-09 -1.26638e-10 1.32527e-09 4562.41 0.933772 1604.43 3872.36 -6.87925 4561.9 +EDGE_SE3:QUAT 1434 1485 -3.46292 11.2647 -5.81418 0.0882189 0.0284447 0.0551325 0.994167 1 2.0463e-19 2.0463e-19 2.72056e-08 8.54526e-09 -1.26927e-10 1 2.0463e-19 2.72056e-08 8.54526e-09 -1.26927e-10 1 2.72056e-08 8.54526e-09 -1.26927e-10 3975.64 7.12582 166.065 3998.79 5.10681 3994.61 +EDGE_SE3:QUAT 1435 1484 -3.4692 -11.0749 -5.07831 -0.0260278 -0.0669308 -0.100846 0.992307 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4076.39 -4.05138 -568.047 3980.73 27.3922 4038.42 +EDGE_SE3:QUAT 1436 1486 -2.72684 0.264517 -5.91596 0.0488821 -0.0641627 0.0475896 0.995605 1 2.40741e-19 2.40741e-19 -1.50947e-08 2.70604e-08 -2.36488e-10 1 2.40741e-19 -1.50947e-08 2.70604e-08 -2.36488e-10 1 -1.50947e-08 2.70604e-08 -2.36488e-10 4063.75 -8.99161 -546.491 3981.61 -8.4762 4064.25 +EDGE_SE3:QUAT 1435 1486 -3.49446 11.3544 -5.74342 0.165273 -0.0725419 0.1535 0.971525 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4070.68 -48.1027 -869.978 3951.6 -39.0982 4085.69 +EDGE_SE3:QUAT 1436 1485 -3.33568 -11.2982 -5.7494 -0.0665063 -0.127398 -0.0690878 0.987205 1 4.81482e-20 4.81482e-20 -1.42049e-08 7.70526e-10 1.93557e-09 1 4.81482e-20 -1.42049e-08 7.70526e-10 1.93557e-09 1 -1.42049e-08 7.70526e-10 1.93557e-09 4280.08 13.5742 -1131.31 3929.05 16.4943 4278.68 +EDGE_SE3:QUAT 1437 1487 -2.74016 -0.123227 -5.87986 0.0244514 0.0052386 0.0198851 0.99949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.93 0.426808 36.0177 3999.93 0.351427 3998.74 +EDGE_SE3:QUAT 1436 1487 -3.2009 11.5238 -5.77243 -0.0208452 0.120736 -0.10491 0.986905 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4219.4 -48.1616 966.391 3952.13 -64.788 4177.12 +EDGE_SE3:QUAT 1437 1486 -3.58259 -10.6225 -5.38238 -0.119802 0.161461 -0.0481234 0.978398 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4317.48 -124.486 1281.64 3929.37 -112.309 4365.62 +EDGE_SE3:QUAT 1438 1488 -2.88913 0.0327922 -5.70725 0.0627196 -0.0355841 -0.0191422 0.997213 1 1.20371e-20 1.20371e-20 2.28626e-10 -4.46411e-10 -6.93523e-09 1 1.20371e-20 2.28626e-10 -4.46411e-10 -6.93523e-09 1 2.28626e-10 -4.46411e-10 -6.93523e-09 4002.33 -8.92162 -269.481 3995.77 4.31349 4016.6 +EDGE_SE3:QUAT 1437 1488 -3.45623 11.0456 -5.63142 0.181612 0.103711 0.0435812 0.976915 1 7.70372e-19 7.70372e-19 -5.50761e-08 -4.45806e-09 -4.53129e-09 1 7.70372e-19 -5.50761e-08 -4.45806e-09 -4.53129e-09 1 -5.50761e-08 -4.45806e-09 -4.53129e-09 3989.1 75.319 708.866 3980.57 53.4507 4113.43 +EDGE_SE3:QUAT 1438 1487 -3.32539 -11.1594 -5.42614 0.0658607 0.00728842 -0.021805 0.997564 1 1.95602e-19 1.95602e-19 -2.76212e-08 4.03463e-09 -5.07153e-10 1 1.95602e-19 -2.76212e-08 4.03463e-09 -5.07153e-10 1 -2.76212e-08 4.03463e-09 -5.07153e-10 3984.05 2.61749 75.091 3999.6 -0.754394 3999.5 +EDGE_SE3:QUAT 1439 1489 -2.57791 0.123393 -6.18773 -0.0943566 -0.102855 -0.0498847 0.988954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4158.87 33.8294 -903.256 3953.02 -2.02298 4184.53 +EDGE_SE3:QUAT 1438 1489 -3.92062 11.1008 -5.30971 0.0425809 -0.0348243 0.171074 0.983721 1 9.62965e-20 9.62965e-20 1.60394e-08 -1.13178e-08 -2.60446e-10 1 9.62965e-20 1.60394e-08 -1.13178e-08 -2.60446e-10 1 1.60394e-08 -1.13178e-08 -2.60446e-10 4023.75 -0.796223 -354.053 3991.95 -31.094 3913.94 +EDGE_SE3:QUAT 1439 1488 -3.5861 -11.3579 -5.6591 -0.0133145 0.0276192 -0.218058 0.975454 1 1.20371e-20 1.20371e-20 -6.77502e-09 1.52104e-09 -1.34068e-10 1 1.20371e-20 -6.77502e-09 1.52104e-09 -1.34068e-10 1 -6.77502e-09 1.52104e-09 -1.34068e-10 4006.55 -3.8222 171.786 3998.96 -17.1566 3817.06 +EDGE_SE3:QUAT 1440 1490 -2.51332 -0.171349 -6.06753 -0.0352587 -0.0913816 0.0620954 0.993252 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4119.85 25.6138 -717.661 3971.37 -30.6894 4109.4 +EDGE_SE3:QUAT 1439 1490 -3.69903 10.8577 -5.7209 0.278435 0.0127397 0.111011 0.953933 1 1.92593e-19 1.92593e-19 1.34873e-09 -7.62325e-09 -2.65276e-08 1 1.92593e-19 1.34873e-09 -7.62325e-09 -2.65276e-08 1 1.34873e-09 -7.62325e-09 -2.65276e-08 3703.83 -52.8439 -261.061 3991.05 -18.0973 3964.64 +EDGE_SE3:QUAT 1440 1489 -3.44867 -10.8406 -5.39635 0.0455905 0.0481417 0.0457449 0.99675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.82 10.4815 360.12 3992.59 10.5015 4023.77 +EDGE_SE3:QUAT 1441 1491 -2.717 -0.0370165 -6.2227 0.0309881 0.039936 -0.075574 0.995858 1 1.20371e-20 1.20371e-20 6.93602e-09 -5.09907e-10 3.07074e-10 1 1.20371e-20 6.93602e-09 -5.09907e-10 3.07074e-10 1 6.93602e-09 -5.09907e-10 3.07074e-10 4025.96 2.30548 346.648 3992.39 -12.3047 4006.96 +EDGE_SE3:QUAT 1440 1491 -3.39172 10.9648 -5.90643 0.163762 -0.00612 0.231495 0.958934 1 7.70372e-19 7.70372e-19 -4.35447e-09 8.02697e-09 5.36128e-08 1 7.70372e-19 -4.35447e-09 8.02697e-09 5.36128e-08 1 -4.35447e-09 8.02697e-09 5.36128e-08 3945.8 -38.8907 -480.48 3977.69 -64.3815 3838.71 +EDGE_SE3:QUAT 1441 1490 -3.31661 -10.9082 -5.53341 0.173114 0.0314562 0.0543198 0.982899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3883.8 8.08475 128.846 3999.79 3.9678 3991.87 +EDGE_SE3:QUAT 1442 1492 -2.77539 0.19198 -5.93905 0.0312811 -0.134772 -0.016604 0.990244 1 7.70372e-19 7.70372e-19 -1.43503e-09 -5.49586e-08 2.05549e-09 1 7.70372e-19 -1.43503e-09 -5.49586e-08 2.05549e-09 1 -1.43503e-09 -5.49586e-08 2.05549e-09 4298.16 -29.0339 -1139.98 3929.54 25.9875 4300.97 +EDGE_SE3:QUAT 1441 1492 -3.59339 11.2632 -5.72345 0.050434 0.0303087 -0.0747282 0.995466 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.11 5.50644 285.897 3994.55 -9.88874 3997.95 +EDGE_SE3:QUAT 1442 1491 -3.36095 -11.1523 -5.59606 -0.0222948 -0.00388866 -0.169087 0.985341 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.34 0.721689 -74.1482 3999.53 7.47202 3886.97 +EDGE_SE3:QUAT 1443 1493 -3.03337 0.0506011 -5.50346 0.0192021 -0.0887611 -0.155666 0.983626 1 4.81482e-20 4.81482e-20 1.38363e-08 -2.26979e-09 -1.10151e-09 1 4.81482e-20 1.38363e-08 -2.26979e-09 -1.10151e-09 1 1.38363e-08 -2.26979e-09 -1.10151e-09 4105.29 -33.4029 -662.816 3978.81 57.2331 4009.83 +EDGE_SE3:QUAT 1442 1493 -3.38774 11.2022 -5.41938 0.0364707 0.100867 -0.0160075 0.994102 1 2.40741e-19 2.40741e-19 1.43319e-08 2.74692e-08 4.99641e-10 1 2.40741e-19 1.43319e-08 2.74692e-08 4.99641e-10 1 1.43319e-08 2.74692e-08 4.99641e-10 4164.84 12.9089 842.368 3958.8 1.97729 4169.13 +EDGE_SE3:QUAT 1443 1492 -3.35198 -11.0445 -5.40735 0.062252 -0.125292 -0.0170374 0.990018 1 1.20371e-20 1.20371e-20 -8.73095e-10 4.90725e-10 7.08438e-09 1 1.20371e-20 -8.73095e-10 4.90725e-10 7.08438e-09 1 -8.73095e-10 4.90725e-10 7.08438e-09 4237.28 -44.101 -1036.87 3942 34.8022 4251.62 +EDGE_SE3:QUAT 1444 1494 -2.96342 -0.123203 -5.3361 -0.0999507 0.0213489 0.0563257 0.993167 1 2.40741e-19 2.40741e-19 2.7169e-08 2.76759e-09 -1.29175e-08 1 2.40741e-19 2.7169e-08 2.76759e-09 -1.29175e-08 1 2.7169e-08 2.76759e-09 -1.29175e-08 3973.73 -11.8733 235.212 3996.04 5.43649 4001 +EDGE_SE3:QUAT 1443 1494 -3.94332 10.9738 -5.63835 0.00877485 -0.0392544 0.278007 0.959737 1 4.81482e-20 4.81482e-20 3.8608e-09 -1.33182e-08 -1.88356e-10 1 4.81482e-20 3.8608e-09 -1.33182e-08 -1.88356e-10 1 3.8608e-09 -1.33182e-08 -1.88356e-10 4023.16 8.98704 -307.686 3996.28 -42.7456 3714.32 +EDGE_SE3:QUAT 1444 1493 -3.58622 -11.177 -5.40836 0.136074 -0.0551826 -0.151062 0.977558 1 7.70372e-19 7.70372e-19 5.62933e-10 -8.14996e-09 -5.43029e-08 1 7.70372e-19 5.62933e-10 -8.14996e-09 -5.43029e-08 1 5.62933e-10 -8.14996e-09 -5.43029e-08 3931.23 -8.76226 -173.411 4000.44 9.08702 3914.02 +EDGE_SE3:QUAT 1445 1495 -2.48463 -0.168264 -5.73328 0.0834627 0.0108789 -0.0559034 0.994882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.06 6.32768 141.513 3998.44 -3.94834 3992.42 +EDGE_SE3:QUAT 1444 1495 -3.65782 10.9891 -5.39229 0.0159174 0.0229037 0.0903425 0.99552 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.68 2.22213 163.977 3998.52 7.31778 3974.05 +EDGE_SE3:QUAT 1445 1494 -3.30519 -11.0463 -5.4241 -0.0210283 -0.0299962 0.120734 0.992009 1 1.20371e-20 1.20371e-20 -6.89254e-09 -8.48215e-10 1.67057e-10 1 1.20371e-20 -6.89254e-09 -8.48215e-10 1.67057e-10 1 -6.89254e-09 -8.48215e-10 1.67057e-10 4008.65 4.10509 -204.812 3997.87 -12.0979 3952.11 +EDGE_SE3:QUAT 1446 1496 -2.78532 -0.18742 -5.86897 0.00127274 -0.169618 0.000673002 0.985509 1 2.93874e-24 2.93874e-24 1.95129e-11 -1.27891e-13 -1.13373e-10 1 2.93874e-24 1.95129e-11 -1.27891e-13 -1.13373e-10 1 1.95129e-11 -1.27891e-13 -1.13373e-10 4503.34 -0.71892 -1505.56 3884.92 0.350871 4503.34 +EDGE_SE3:QUAT 1445 1496 -3.52981 11.0514 -5.84837 0.0618684 0.0975261 0.0102886 0.993255 1 1.92593e-19 1.92593e-19 -2.80878e-08 -6.39761e-10 -2.69899e-09 1 1.92593e-19 -2.80878e-08 -6.39761e-10 -2.69899e-09 1 -2.80878e-08 -6.39761e-10 -2.69899e-09 4136.2 29.2463 793.129 3964.31 18.9074 4151.09 +EDGE_SE3:QUAT 1446 1495 -3.49716 -11.1307 -4.99231 0.0344647 -0.0711269 -0.0946279 0.99237 1 3.85186e-19 3.85186e-19 1.01406e-09 2.88631e-08 2.64594e-08 1 3.85186e-19 1.01406e-09 2.88631e-08 2.64594e-08 1 1.01406e-09 2.88631e-08 2.64594e-08 4063.87 -19.5782 -528.732 3985 29.2283 4032.8 +EDGE_SE3:QUAT 1447 1497 -2.805 -0.0721846 -5.76897 0.0383665 0.0218782 0.114618 0.992427 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.55 2.67298 118.981 3999.45 6.0083 3950.89 +EDGE_SE3:QUAT 1446 1497 -3.58248 11.04 -5.77251 0.156529 0.152705 -0.0482587 0.974603 1 1.20371e-20 1.20371e-20 1.16994e-09 1.08782e-09 7.12858e-09 1 1.20371e-20 1.16994e-09 1.08782e-09 7.12858e-09 1 1.16994e-09 1.08782e-09 7.12858e-09 4335.39 106.041 1386.16 3907.03 63.5397 4424.08 +EDGE_SE3:QUAT 1447 1496 -3.53432 -10.7533 -5.24611 0.00310535 -0.0813239 -0.0732301 0.993989 1 3.00927e-21 3.00927e-21 -3.49391e-09 2.62631e-10 2.81123e-10 1 3.00927e-21 -3.49391e-09 2.62631e-10 2.81123e-10 1 -3.49391e-09 2.62631e-10 2.81123e-10 4105.2 -12.8871 -657.313 3975.04 26.1375 4083.79 +EDGE_SE3:QUAT 1448 1498 -2.38825 -0.142829 -5.41755 -0.0795415 -0.0773854 -0.218884 0.96942 1 4.81482e-20 4.81482e-20 -1.37239e-08 2.93382e-09 1.46303e-09 1 4.81482e-20 -1.37239e-08 2.93382e-09 1.46303e-09 1 -1.37239e-08 2.93382e-09 1.46303e-09 4128.87 -11.5141 -800.981 3963.4 83.6778 3962.54 +EDGE_SE3:QUAT 1447 1498 -3.65128 10.7294 -5.45513 0.030038 -0.0472406 0.271986 0.960671 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4043.02 11.8538 -434.402 3990.86 -61.1864 3750.73 +EDGE_SE3:QUAT 1448 1497 -3.354 -10.7044 -5.90423 0.0350499 -0.101506 -0.00567314 0.994201 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4163.45 -17.7192 -837.738 3959.59 11.6791 4168.24 +EDGE_SE3:QUAT 1449 1499 -2.86383 0.125133 -5.7749 -0.167509 -0.0837706 -0.0325082 0.981767 1 1.20371e-20 1.20371e-20 -6.32928e-10 -1.1584e-09 6.92338e-09 1 1.20371e-20 -6.32928e-10 -1.1584e-09 6.92338e-09 1 -6.32928e-10 -1.1584e-09 6.92338e-09 4015.45 60.5139 -725.994 3971.17 -19.3143 4123.46 +EDGE_SE3:QUAT 1448 1499 -3.91801 11.2861 -5.76327 0.0882151 -0.161241 0.0378514 0.982236 1 2.0463e-19 2.0463e-19 3.00434e-08 -2.99856e-10 -1.20573e-08 1 2.0463e-19 3.00434e-08 -2.99856e-10 -1.20573e-08 1 3.00434e-08 -2.99856e-10 -1.20573e-08 4438.47 -54.7756 -1448.77 3893.72 29.6043 4463.87 +EDGE_SE3:QUAT 1449 1498 -3.36892 -11.1034 -5.412 0.0910992 0.143199 -0.161556 0.97216 1 1.92593e-19 1.92593e-19 2.84563e-08 -4.09363e-09 4.78597e-09 1 1.92593e-19 2.84563e-08 -4.09363e-09 4.78597e-09 1 2.84563e-08 -4.09363e-09 4.78597e-09 4402.21 -25.81 1389.89 3901.38 -83.9673 4331 +EDGE_SE3:QUAT 1450 1500 -2.79702 0.08658 -5.83685 0.0901906 -0.11916 0.208331 0.966574 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4292.57 35.0568 -1186.11 3927.46 -108.839 4151.5 +EDGE_SE3:QUAT 1449 1500 -3.48167 11.1558 -5.27001 0.000457155 0.134486 0.0449721 0.989894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4303.71 21.5589 1143.29 3929.04 30.8549 4295.62 +EDGE_SE3:QUAT 1450 1499 -3.57524 -10.9615 -5.13842 0.0504999 -0.170004 -0.0436211 0.983181 1 1.92593e-19 1.92593e-19 2.88744e-08 -1.87742e-09 -4.80663e-09 1 1.92593e-19 2.88744e-08 -1.87742e-09 -4.80663e-09 1 2.88744e-08 -1.87742e-09 -4.80663e-09 4465.25 -81.0691 -1458.82 3897.39 79.8284 4467.84 +EDGE_SE3:QUAT 1451 1501 -2.77332 0.10537 -5.80981 -0.181935 0.00965961 0.0199484 0.983061 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3870.94 -11.6915 116.107 3999.05 0.489156 4001.75 +EDGE_SE3:QUAT 1450 1501 -3.42647 10.8245 -5.75596 0.0442975 0.0425175 0.0663173 0.995908 1 4.81482e-20 4.81482e-20 9.7181e-10 -1.38175e-08 6.89429e-10 1 4.81482e-20 9.7181e-10 -1.38175e-08 6.89429e-10 1 9.7181e-10 -1.38175e-08 6.89429e-10 4014.94 8.95826 303.127 3994.98 11.407 4005.2 +EDGE_SE3:QUAT 1451 1500 -3.88635 -10.9166 -5.79592 -0.117044 -0.109165 -0.268387 0.949922 1 3.08149e-18 3.08149e-18 1.76688e-08 5.33201e-09 -1.10237e-07 1 3.08149e-18 1.76688e-08 5.33201e-09 -1.10237e-07 1 1.76688e-08 5.33201e-09 -1.10237e-07 4286.81 -43.4995 -1218.68 3925.81 148.661 4053.48 +EDGE_SE3:QUAT 1452 1502 -2.9797 0.290412 -5.30562 0.0973391 0.107617 0.191215 0.970763 1 7.70372e-19 7.70372e-19 5.44684e-08 1.18931e-08 3.37914e-09 1 7.70372e-19 5.44684e-08 1.18931e-08 3.37914e-09 1 5.44684e-08 1.18931e-08 3.37914e-09 4044.15 57.4541 589.396 3993.15 67.6902 3935.8 +EDGE_SE3:QUAT 1451 1502 -3.71662 11.127 -5.98341 -0.319312 -0.119862 -0.104183 0.934248 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3969.97 204.846 -1286.16 3933.38 -96.4166 4334.4 +EDGE_SE3:QUAT 1452 1501 -3.37482 -10.9692 -5.18998 -0.133483 -0.0731647 -0.0964934 0.983625 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4059.77 37.8012 -736.629 3966.14 15.4682 4093.8 +EDGE_SE3:QUAT 1453 1503 -3.11485 0.10925 -5.64095 0.00299346 -0.0609856 0.0478653 0.996986 1 2.93874e-24 2.93874e-24 -1.08906e-10 -5.22768e-12 6.66243e-12 1 2.93874e-24 -1.08906e-10 -5.22768e-12 6.66243e-12 1 -1.08906e-10 -5.22768e-12 6.66243e-12 4060.15 3.58711 -494.349 3985.26 -12.0239 4051.03 +EDGE_SE3:QUAT 1452 1503 -3.36064 10.9695 -5.76896 0.127725 -0.0345667 0.171015 0.976343 1 1.92593e-19 1.92593e-19 -2.73301e-08 -4.40696e-09 2.07925e-09 1 1.92593e-19 -2.73301e-08 -4.40696e-09 2.07925e-09 1 -2.73301e-08 -4.40696e-09 2.07925e-09 4000.36 -25.2521 -521.072 3979.68 -42.2185 3948.63 +EDGE_SE3:QUAT 1453 1502 -3.45591 -10.9444 -5.53253 0.0863158 0.108016 -0.110555 0.984205 1 1.92593e-19 1.92593e-19 2.81329e-08 -2.656e-09 3.52049e-09 1 1.92593e-19 2.81329e-08 -2.656e-09 3.52049e-09 1 2.81329e-08 -2.656e-09 3.52049e-09 4208.51 11.7143 1005.27 3941.95 -34.5881 4189.42 +EDGE_SE3:QUAT 1454 1504 -3.16383 0.102096 -5.56638 0.0559241 0.0707051 -0.00192132 0.995927 1 1.88079e-22 1.88079e-22 6.17437e-11 4.92512e-11 8.72537e-10 1 1.88079e-22 6.17437e-11 4.92512e-11 8.72537e-10 1 6.17437e-11 4.92512e-11 8.72537e-10 4068.29 16.6558 574.238 3980.39 6.27916 4080.79 +EDGE_SE3:QUAT 1453 1504 -3.9102 11.1187 -6.01416 0.21791 0.0517492 -0.149643 0.963039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3952.48 74.9573 773.395 3958.66 -30.2533 4052.85 +EDGE_SE3:QUAT 1454 1503 -3.5341 -10.7524 -5.34038 0.0551358 -0.103887 -0.0458397 0.992001 1 9.62965e-20 9.62965e-20 -1.54267e-08 1.75397e-09 1.54267e-08 1 9.62965e-20 -1.54267e-08 1.75397e-09 1.54267e-08 1 -1.54267e-08 1.75397e-09 1.54267e-08 4149.95 -36.4226 -821.556 3963.23 34.606 4153.71 +EDGE_SE3:QUAT 1455 1505 -3.05624 0.00590663 -5.57801 0.0419886 -0.0297013 -0.0504325 0.997402 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.04 -5.17359 -211.19 3997.52 5.88503 4000.92 +EDGE_SE3:QUAT 1454 1505 -3.79267 11.1764 -5.82985 -0.00154639 -0.0325527 -0.0533106 0.998046 1 7.34684e-25 7.34684e-25 5.42193e-11 -2.8968e-12 -1.76733e-12 1 7.34684e-25 5.42193e-11 -2.8968e-12 -1.76733e-12 1 5.42193e-11 -2.8968e-12 -1.76733e-12 4016.98 -1.1595 -261.267 3995.82 7.00128 4005.62 +EDGE_SE3:QUAT 1455 1504 -3.65869 -10.7107 -5.40326 -0.00987817 0.164997 -0.259913 0.95138 1 3.08149e-18 3.08149e-18 1.58075e-08 -1.1063e-08 1.10506e-07 1 3.08149e-18 1.58075e-08 -1.1063e-08 1.10506e-07 1 1.58075e-08 -1.1063e-08 1.10506e-07 4349.73 -167.122 1238.57 3962.66 -203.388 4079.9 +EDGE_SE3:QUAT 1456 1506 -2.70192 -0.0739736 -5.50409 -0.0882104 0.0112524 -0.0836382 0.992521 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.65 1.30583 0.359333 3999.95 1.23712 3971.79 +EDGE_SE3:QUAT 1455 1506 -3.48141 10.9196 -5.93089 -0.100836 0.26915 0.156521 0.944929 1 1.92593e-19 1.92593e-19 3.13366e-08 3.99963e-09 9.45831e-09 1 1.92593e-19 3.13366e-08 3.99963e-09 9.45831e-09 1 3.13366e-08 3.99963e-09 9.45831e-09 5622.08 158.586 3068.52 3695.92 166.124 5564.75 +EDGE_SE3:QUAT 1456 1505 -3.40699 -10.648 -5.45946 -0.0234894 -0.0730075 -0.00389577 0.997047 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4084.64 6.88131 -595.771 3978.67 -1.8635 4086.79 +EDGE_SE3:QUAT 1457 1507 -2.9289 0.123967 -5.44035 -0.0565157 -0.159998 -0.234319 0.957236 1 7.70372e-19 7.70372e-19 9.89859e-09 -1.33996e-09 -5.64315e-08 1 7.70372e-19 9.89859e-09 -1.33996e-09 -5.64315e-08 1 9.89859e-09 -1.33996e-09 -5.64315e-08 4469.84 -126.364 -1471 3913.18 183.733 4263 +EDGE_SE3:QUAT 1456 1507 -3.7603 10.7787 -5.49438 0.0320106 0.102299 0.197896 0.974344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4117.79 52.7099 711.215 3980.68 79.5347 3965.24 +EDGE_SE3:QUAT 1457 1506 -3.46272 -10.8456 -5.5747 -0.000841028 0.0783123 -0.122339 0.989394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4095 -18.246 623.808 3978.62 -40.4083 4035.14 +EDGE_SE3:QUAT 1458 1508 -2.64948 0.180825 -5.31881 0.081505 -0.0233317 0.104728 0.990881 1 3.85186e-19 3.85186e-19 2.6474e-08 4.86123e-09 2.6474e-08 1 3.85186e-19 2.6474e-08 4.86123e-09 2.6474e-08 1 2.6474e-08 4.86123e-09 2.6474e-08 3993.33 -10.3034 -284.438 3994.02 -14.6213 3976.03 +EDGE_SE3:QUAT 1457 1508 -3.78504 11.3668 -5.3508 0.0370223 -0.0511016 -0.0447584 0.997003 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.16 -9.87829 -389.94 3991.17 10.9462 4029.63 +EDGE_SE3:QUAT 1458 1507 -3.67088 -11.1418 -5.53993 0.124953 0.233009 -0.0236923 0.964122 1 7.71124e-19 7.71124e-19 -6.05324e-08 -2.57374e-09 -1.62934e-08 1 7.71124e-19 -6.05324e-08 -2.57374e-09 -1.62934e-08 1 -6.05324e-08 -2.57374e-09 -1.62934e-08 4961.16 187.152 2267.73 3804.78 172.686 5021.37 +EDGE_SE3:QUAT 1459 1509 -2.81736 -0.209 -5.75554 -0.0931812 0.166467 0.0242326 0.981335 1 3.00927e-21 3.00927e-21 6.18014e-10 -3.31848e-10 3.6094e-09 1 3.00927e-21 6.18014e-10 -3.31848e-10 3.6094e-09 1 6.18014e-10 -3.31848e-10 3.6094e-09 4456.33 -71.5532 1485.06 3891.04 -48.9787 4488.72 +EDGE_SE3:QUAT 1458 1509 -3.79342 10.7954 -5.76028 -0.0324589 0.138913 0.00510188 0.989759 1 4.70198e-23 4.70198e-23 6.26822e-11 -1.45722e-11 4.46497e-10 1 4.70198e-23 6.26822e-11 -1.45722e-11 4.46497e-10 1 6.26822e-11 -1.45722e-11 4.46497e-10 4323.53 -20.7213 1190.97 3923.12 -12.8872 4327.64 +EDGE_SE3:QUAT 1459 1508 -3.57543 -10.9661 -5.43551 -0.0429476 0.077269 -0.076732 0.993125 1 4.81482e-20 4.81482e-20 1.39253e-08 -1.17783e-09 9.73091e-10 1 4.81482e-20 1.39253e-08 -1.17783e-09 9.73091e-10 1 1.39253e-08 -1.17783e-09 9.73091e-10 4075.3 -22.8917 581.276 3981.64 -28.6029 4059.13 +EDGE_SE3:QUAT 1460 1510 -2.78538 -0.12106 -5.43572 -0.0203198 0.155849 0.0451644 0.986539 1 1.20371e-20 1.20371e-20 -7.19992e-09 -2.98322e-10 -1.14579e-09 1 1.20371e-20 -7.19992e-09 -2.98322e-10 -1.14579e-09 1 -7.19992e-09 -2.98322e-10 -1.14579e-09 4422.35 12.4378 1369.6 3902.1 25.6084 4415.85 +EDGE_SE3:QUAT 1459 1510 -3.57005 11.0442 -5.99661 0.221986 -0.0105848 0.113032 0.968418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3834.87 -48.1305 -368.738 3987.65 -18.5782 3980.88 +EDGE_SE3:QUAT 1460 1509 -3.68685 -10.9646 -5.59526 -0.0558532 -0.0467636 -0.164466 0.983689 1 9.62965e-20 9.62965e-20 1.59577e-08 1.14393e-08 -3.41946e-10 1 9.62965e-20 1.59577e-08 1.14393e-08 -3.41946e-10 1 1.59577e-08 1.14393e-08 -3.41946e-10 4042.25 1.81671 -471.702 3985.85 38.2674 3946.53 +EDGE_SE3:QUAT 1461 1511 -2.92984 -0.0171854 -5.86015 0.0302495 0.0428616 -0.0465996 0.997535 1 4.81482e-20 4.81482e-20 6.32934e-10 3.65524e-10 1.38995e-08 1 4.81482e-20 6.32934e-10 3.65524e-10 1.38995e-08 1 6.32934e-10 3.65524e-10 1.38995e-08 4028.62 3.42111 360.804 3991.83 -7.25346 4023.59 +EDGE_SE3:QUAT 1460 1511 -3.77494 10.879 -5.5585 -0.250895 -0.0310182 -0.106683 0.961618 1 8.1852e-19 8.1852e-19 5.49693e-08 8.9803e-09 -1.04052e-09 1 8.1852e-19 5.49693e-08 8.9803e-09 -1.04052e-09 1 5.49693e-08 8.9803e-09 -1.04052e-09 3817.49 72.3428 -536.348 3978.78 12.9748 4023.76 +EDGE_SE3:QUAT 1461 1510 -3.38323 -11.2513 -5.20688 0.00636277 0.0833747 -0.000173876 0.996498 1 7.52316e-22 7.52316e-22 -1.75302e-09 -1.57599e-12 -1.46663e-10 1 7.52316e-22 -1.75302e-09 -1.57599e-12 -1.46663e-10 1 -1.75302e-09 -1.57599e-12 -1.46663e-10 4113.41 2.30422 683.52 3972.2 1.03424 4113.57 +EDGE_SE3:QUAT 1462 1512 -2.92403 -0.193074 -5.27892 0.0461344 0.0598584 0.040854 0.996303 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4043.34 14.0429 458.487 3987.9 13.2365 4045.18 +EDGE_SE3:QUAT 1461 1512 -3.8063 10.8387 -5.59466 -0.106444 0.195353 0.013829 0.974841 1 1.54375e-18 1.54375e-18 5.62303e-08 -5.54436e-08 1.8997e-09 1 1.54375e-18 5.62303e-08 -5.54436e-08 1.8997e-09 1 5.62303e-08 -5.54436e-08 1.8997e-09 4634.22 -119.203 1783.29 3858.89 -100.348 4678.78 +EDGE_SE3:QUAT 1462 1511 -3.24778 -10.858 -5.74681 -0.106282 -0.00109221 -0.224942 0.968558 1 9.62965e-19 9.62965e-19 -2.9579e-08 8.21769e-10 5.52123e-08 1 9.62965e-19 -2.9579e-08 8.21769e-10 5.52123e-08 1 -2.9579e-08 8.21769e-10 5.52123e-08 3973.19 15.9296 -284.354 3991.61 40.8124 3815.98 +EDGE_SE3:QUAT 1463 1513 -3.48312 -0.223651 -5.52247 -0.114367 0.0598803 -0.00518254 0.991619 1 1.95602e-19 1.95602e-19 -2.79101e-08 9.28794e-10 -5.05979e-09 1 1.95602e-19 -2.79101e-08 9.28794e-10 -5.05979e-09 1 -2.79101e-08 9.28794e-10 -5.05979e-09 4001.68 -27.8581 467.947 3987.73 -10.7806 4053.89 +EDGE_SE3:QUAT 1462 1513 -3.80134 10.6707 -5.48205 -0.0556064 0.0999727 0.0351595 0.992813 1 4.81482e-20 4.81482e-20 1.40739e-08 3.45904e-10 1.46141e-09 1 4.81482e-20 1.40739e-08 3.45904e-10 1.46141e-09 1 1.40739e-08 3.45904e-10 1.46141e-09 4160.57 -17.1548 849.514 3957.98 2.09529 4167.99 +EDGE_SE3:QUAT 1463 1512 -3.74976 -11.0538 -5.39317 -0.0786892 -0.125174 -0.0522112 0.98763 1 4.81482e-20 4.81482e-20 -1.88752e-09 -9.70248e-10 1.41883e-08 1 4.81482e-20 -1.88752e-09 -9.70248e-10 1.41883e-08 1 -1.88752e-09 -9.70248e-10 1.41883e-08 4259.42 28.8679 -1103.45 3932.42 0.0284428 4273.29 +EDGE_SE3:QUAT 1464 1514 -2.60569 -0.313414 -5.27576 0.00959744 0.15598 -0.0476737 0.986562 1 1.88079e-22 1.88079e-22 -8.9967e-10 4.28651e-11 -1.42422e-10 1 1.88079e-22 -8.9967e-10 4.28651e-11 -1.42422e-10 1 -8.9967e-10 4.28651e-11 -1.42422e-10 4420.23 -23.2538 1363.55 3903.37 -34.6962 4411.5 +EDGE_SE3:QUAT 1463 1514 -3.54724 10.8386 -5.68164 0.0119151 0.0830322 0.0813121 0.993153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4105.71 17.5223 660.671 3975.31 30.4729 4079.83 +EDGE_SE3:QUAT 1464 1513 -3.8421 -11.0242 -5.48972 0.114767 0.0493537 -0.108619 0.986202 1 2.40741e-19 2.40741e-19 2.89406e-08 1.10403e-08 5.88175e-10 1 2.40741e-19 2.89406e-08 1.10403e-08 5.88175e-10 1 2.89406e-08 1.10403e-08 5.88175e-10 4017.71 24.0881 536.695 3980.58 -21.645 4023.2 +EDGE_SE3:QUAT 1465 1515 -3.01319 0.451981 -5.65071 0.0712869 -0.0310905 0.0984671 0.992097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.38 -9.23678 -328.836 3992.49 -15.1185 3987.93 +EDGE_SE3:QUAT 1464 1515 -3.53724 10.6347 -5.47148 -0.0646206 -0.0917074 0.0510564 0.992375 1 4.33334e-19 4.33334e-19 2.73782e-08 3.03644e-08 -1.42634e-08 1 4.33334e-19 2.73782e-08 3.03644e-08 -1.42634e-08 1 2.73782e-08 3.03644e-08 -1.42634e-08 4103.43 33.7877 -703.799 3973.22 -31.2954 4109.71 +EDGE_SE3:QUAT 1465 1514 -3.61558 -10.7411 -5.85414 0.168721 -0.123727 -0.0550607 0.976316 1 7.70372e-19 7.70372e-19 -5.54211e-08 5.4145e-09 5.49143e-09 1 7.70372e-19 -5.54211e-08 5.4145e-09 5.49143e-09 1 -5.54211e-08 5.4145e-09 5.49143e-09 4062.34 -94.7432 -860.733 3971.91 76.4275 4164.08 +EDGE_SE3:QUAT 1466 1516 -2.88953 0.376998 -5.68074 -0.151547 -0.0443753 -0.143068 0.977034 1 7.70372e-19 7.70372e-19 4.67051e-09 7.5065e-09 -5.48438e-08 1 7.70372e-19 4.67051e-09 7.5065e-09 -5.48438e-08 1 4.67051e-09 7.5065e-09 -5.48438e-08 3994.63 37.1193 -598.276 3974.47 33.1875 4004.63 +EDGE_SE3:QUAT 1465 1516 -3.55446 11.0476 -5.74114 0.104483 -0.148977 -0.135898 0.973869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4195.41 -116.625 -1011.48 3966.41 121.104 4165.2 +EDGE_SE3:QUAT 1466 1515 -3.51636 -10.6888 -5.25998 0.122058 0.254029 -0.269755 0.920762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5495.73 -398.427 2939.55 3779.27 -418.038 5264.26 +EDGE_SE3:QUAT 1467 1517 -2.89032 -0.226587 -5.98145 -0.124352 -0.168197 0.109823 0.971692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4265.58 151.98 -1194.69 3953.73 -150.005 4279.19 +EDGE_SE3:QUAT 1466 1517 -3.60894 11.0065 -5.27863 -0.00193063 -0.0722188 0.0428164 0.996467 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4083.98 6.05843 -585.701 3979.56 -13.4544 4076.66 +EDGE_SE3:QUAT 1467 1516 -3.52404 -10.8718 -5.33812 -0.0592819 -0.0388981 -0.127043 0.98936 1 7.70372e-19 7.70372e-19 2.91985e-09 2.66434e-09 -5.51892e-08 1 7.70372e-19 2.91985e-09 2.66434e-09 -5.51892e-08 1 2.91985e-09 2.66434e-09 -5.51892e-08 4024.44 5.96801 -395.011 3989.61 24.1834 3973.94 +EDGE_SE3:QUAT 1468 1518 -3.03193 -0.140676 -5.72869 0.0366647 0.0993476 -0.127487 0.986171 1 1.20371e-20 1.20371e-20 -6.99628e-09 8.69012e-10 -7.46945e-10 1 1.20371e-20 -6.99628e-09 8.69012e-10 -7.46945e-10 1 -6.99628e-09 8.69012e-10 -7.46945e-10 4172.88 -16.5713 863.035 3958.27 -52.0635 4113.25 +EDGE_SE3:QUAT 1467 1518 -3.97631 10.733 -6.04128 -0.0988566 -0.0982852 -0.12741 0.982005 1 7.70372e-19 7.70372e-19 5.59879e-08 -6.1689e-09 -6.76196e-09 1 7.70372e-19 5.59879e-08 -6.1689e-09 -6.76196e-09 1 5.59879e-08 -6.1689e-09 -6.76196e-09 4175.39 15.0012 -951.285 3946.89 39.8143 4149.55 +EDGE_SE3:QUAT 1468 1517 -3.84115 -10.9455 -5.62593 0.0198429 -0.0355372 -0.335441 0.941182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.46 -5.91647 -163.602 4000.43 20.572 3555.95 +EDGE_SE3:QUAT 1469 1519 -2.98009 0.0338142 -5.44806 0.0313107 -0.0401893 -0.122121 0.991207 1 2.40741e-19 2.40741e-19 -1.46576e-08 2.85404e-09 2.80095e-08 1 2.40741e-19 -1.46576e-08 2.85404e-09 2.80095e-08 1 -1.46576e-08 2.85404e-09 2.80095e-08 4014.03 -7.63521 -269.334 3996.44 16.5164 3958.3 +EDGE_SE3:QUAT 1468 1519 -3.6571 10.9184 -5.83289 0.0665182 0.123597 -0.0706493 0.987577 1 8.1852e-19 8.1852e-19 1.72686e-08 5.40772e-08 -9.09157e-10 1 8.1852e-19 1.72686e-08 5.40772e-08 -9.09157e-10 1 1.72686e-08 5.40772e-08 -9.09157e-10 4263.11 13.0494 1096.45 3932.84 -17.5026 4260.84 +EDGE_SE3:QUAT 1469 1518 -3.57974 -10.7121 -5.61007 0.00656216 0.0830784 0.0790101 0.993384 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4108.25 15.5023 667.439 3974.56 29.1895 4083.45 +EDGE_SE3:QUAT 1470 1520 -2.8735 -0.115884 -5.65365 -0.00340639 0.00918056 0.0916544 0.995743 1 1.88079e-22 1.88079e-22 8.63827e-10 7.94701e-11 8.36984e-12 1 1.88079e-22 8.63827e-10 7.94701e-11 8.36984e-12 1 8.63827e-10 7.94701e-11 8.36984e-12 4001.41 0.065866 76.2703 3999.64 3.53417 3967.85 +EDGE_SE3:QUAT 1469 1520 -3.69241 10.9583 -5.74902 0.0523101 -0.101425 0.195682 0.974005 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4192.15 32.0568 -923.946 3955.44 -88.2315 4049.93 +EDGE_SE3:QUAT 1470 1519 -3.44723 -10.7738 -5.5373 -0.0360801 -0.0412376 0.0484796 0.99732 1 9.62965e-20 9.62965e-20 -1.44026e-08 -1.27382e-09 1.44026e-08 1 9.62965e-20 -1.44026e-08 -1.27382e-09 1.44026e-08 1 -1.44026e-08 -1.27382e-09 1.44026e-08 4018.45 7.31008 -308.645 3994.5 -8.75081 4014.26 +EDGE_SE3:QUAT 1471 1521 -3.03692 -0.183357 -5.56451 -0.0422319 -0.126956 0.0646552 0.988898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4240 50.165 -1024.67 3945.23 -54.6222 4230.41 +EDGE_SE3:QUAT 1470 1521 -3.87062 10.8947 -5.49337 0.08166 -0.131951 -0.0520344 0.986516 1 1.92593e-19 1.92593e-19 2.82508e-08 -2.15152e-09 -3.45246e-09 1 1.92593e-19 2.82508e-08 -2.15152e-09 -3.45246e-09 1 2.82508e-08 -2.15152e-09 -3.45246e-09 4228.41 -70.3607 -1042.24 3946.16 64.697 4244.25 +EDGE_SE3:QUAT 1471 1520 -3.48683 -11.225 -5.65823 0.0316892 0.112633 -0.182651 0.976191 1 3.00927e-21 3.00927e-21 3.48301e-09 -6.42684e-10 4.15469e-10 1 3.00927e-21 3.48301e-09 -6.42684e-10 4.15469e-10 1 3.48301e-09 -6.42684e-10 4.15469e-10 4218.61 -45.2178 969.599 3953.09 -91.1387 4089.18 +EDGE_SE3:QUAT 1472 1522 -2.99244 -0.0344846 -5.66623 0.0417178 0.0194947 0.135215 0.989746 1 4.81482e-20 4.81482e-20 1.37383e-08 1.89371e-09 1.04621e-10 1 4.81482e-20 1.37383e-08 1.89371e-09 1.04621e-10 1 1.37383e-08 1.89371e-09 1.04621e-10 3994.67 1.7733 84.4897 3999.83 4.24901 3928.5 +EDGE_SE3:QUAT 1471 1522 -3.52533 10.6845 -5.77815 -0.200209 -0.0987739 0.121123 0.967207 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3883.98 47.5425 -443.697 3999.66 -41.9616 3985.63 +EDGE_SE3:QUAT 1472 1521 -3.6285 -10.4475 -5.26929 -0.107545 0.0749151 0.170956 0.976522 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4110.55 -13.0087 808.777 3959.47 56.746 4039.91 +EDGE_SE3:QUAT 1473 1523 -2.90328 0.133764 -5.49687 0.098775 0.0580344 0.170259 0.978717 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.74 13.7068 240.269 3999.5 17.4372 3896.81 +EDGE_SE3:QUAT 1472 1523 -3.96134 10.5657 -5.82643 -0.257597 -0.0851897 -0.00493264 0.962477 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3834.93 85.8111 -642.716 3984.71 -40.6355 4100.25 +EDGE_SE3:QUAT 1473 1522 -3.48653 -10.6517 -5.3853 -0.0765418 -0.129215 -0.0594842 0.986867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4282.41 24.8986 -1147.63 3927.38 5.16958 4291.7 +EDGE_SE3:QUAT 1474 1524 -2.91713 0.0236907 -5.48413 -0.0554121 0.150785 -0.137073 0.977448 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4289.24 -106.544 1140.56 3946.69 -120.218 4226.37 +EDGE_SE3:QUAT 1473 1524 -3.56761 10.5597 -5.62578 0.015642 -0.112262 0.0633752 0.991532 1 3.00927e-21 3.00927e-21 -3.5307e-09 -2.18722e-10 4.03528e-10 1 3.00927e-21 -3.5307e-09 -2.18722e-10 4.03528e-10 1 -3.5307e-09 -2.18722e-10 4.03528e-10 4211.7 12.2563 -946.545 3949.42 -29.0251 4196.61 +EDGE_SE3:QUAT 1474 1523 -3.79626 -11.092 -5.39285 0.067654 0.144471 -0.00260127 0.98719 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4333.89 49.7333 1238.08 3919.54 35.3792 4352.17 +EDGE_SE3:QUAT 1475 1525 -3.05237 -0.546496 -5.74743 -0.0131948 0.0635202 0.0407743 0.99706 1 3.00927e-21 3.00927e-21 3.48801e-09 1.37866e-10 2.25189e-10 1 3.00927e-21 3.48801e-09 1.37866e-10 2.25189e-10 1 3.48801e-09 1.37866e-10 2.25189e-10 4065.99 0.499825 520.76 3983.53 9.78401 4060.04 +EDGE_SE3:QUAT 1474 1525 -4.24215 10.658 -5.83798 -0.00601057 0.032558 0.136686 0.990061 1 4.70198e-23 4.70198e-23 -4.30318e-10 -5.93652e-11 -1.43293e-11 1 4.70198e-23 -4.30318e-10 -5.93652e-11 -1.43293e-11 1 -4.30318e-10 -5.93652e-11 -1.43293e-11 4017.2 2.77633 263.937 3995.98 18.1443 3942.61 +EDGE_SE3:QUAT 1475 1524 -3.43255 -10.8405 -5.3223 0.0951625 0.034583 -0.232696 0.967265 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.88 9.88379 514.218 3981.18 -63.0768 3847.52 +EDGE_SE3:QUAT 1476 1526 -3.04777 0.244068 -5.54117 0.0612898 -0.0116119 -0.00593941 0.998035 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.91 -2.66943 -88.0457 3999.54 0.43985 4001.8 +EDGE_SE3:QUAT 1475 1526 -3.69438 10.8442 -5.43352 0.0393553 -0.142395 0.171857 0.973982 1 3.00927e-21 3.00927e-21 3.53458e-09 6.07979e-10 -5.34201e-10 1 3.00927e-21 3.53458e-09 6.07979e-10 -5.34201e-10 1 3.53458e-09 6.07979e-10 -5.34201e-10 4358.87 67.591 -1262.37 3923.64 -111.936 4246.92 +EDGE_SE3:QUAT 1476 1525 -3.88463 -10.9807 -5.36471 0.0245067 -0.0152212 -0.13003 0.99109 1 3.00927e-21 3.00927e-21 4.53283e-10 3.43825e-09 -9.5788e-11 1 3.00927e-21 4.53283e-10 3.43825e-09 -9.5788e-11 1 4.53283e-10 3.43825e-09 -9.5788e-11 3999.18 -1.21803 -80.8009 3999.76 4.43714 3933.95 +EDGE_SE3:QUAT 1477 1527 -2.85988 0.0824847 -5.66063 0.156175 0.0144534 0.101072 0.982438 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3902.88 -10.9487 -75.3862 3998.77 -7.06189 3959.58 +EDGE_SE3:QUAT 1476 1527 -3.63607 10.9727 -5.38555 -0.0815007 -0.0632038 0.0591929 0.992904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.08 22.5546 -444.497 3989.8 -19.4254 4034.64 +EDGE_SE3:QUAT 1477 1526 -3.68779 -10.6703 -5.30139 -0.123852 0.0377595 -0.019343 0.991393 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3956.4 -16.5907 267.451 3996.28 -6.04599 4016.26 +EDGE_SE3:QUAT 1478 1528 -2.82022 -0.091843 -5.16128 -0.0307671 -0.0566999 0.0686808 0.995551 1 2.40741e-19 2.40741e-19 -1.24485e-08 6.23105e-11 -2.70662e-08 1 2.40741e-19 -1.24485e-08 6.23105e-11 -2.70662e-08 1 -1.24485e-08 6.23105e-11 -2.70662e-08 4041.56 11.5095 -428.458 3989.59 -17.0191 4026.48 +EDGE_SE3:QUAT 1477 1528 -3.93837 10.7277 -5.50536 -0.0320067 0.176978 0.0274948 0.98331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4554.94 -9.87286 1596.45 3873.39 1.02532 4556.01 +EDGE_SE3:QUAT 1478 1527 -3.95592 -11.1227 -5.24898 -0.133084 -0.00712152 -0.0365592 0.990405 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3932.27 8.65382 -113.09 3998.95 1.9064 3997.77 +EDGE_SE3:QUAT 1479 1529 -3.08583 -0.378963 -5.24674 -0.0772635 0.0444122 0.060075 0.994208 1 1.92593e-19 1.92593e-19 2.77387e-08 1.47215e-09 1.47442e-09 1 1.92593e-19 2.77387e-08 1.47215e-09 1.47442e-09 1 2.77387e-08 1.47215e-09 1.47442e-09 4017.57 -13.2981 409.565 3989.13 8.52555 4027.01 +EDGE_SE3:QUAT 1478 1529 -4.01554 10.7845 -5.40585 0.0337455 -0.00255953 -0.0529154 0.998025 1 4.81482e-20 4.81482e-20 1.42238e-11 4.69444e-10 1.38504e-08 1 4.81482e-20 1.42238e-11 4.69444e-10 1.38504e-08 1 1.42238e-11 4.69444e-10 1.38504e-08 3995.43 0.138181 1.01635 4000 -0.216832 3988.79 +EDGE_SE3:QUAT 1479 1528 -3.70528 -10.9655 -5.09684 -0.046785 -0.140694 0.153667 0.976935 1 7.70372e-19 7.70372e-19 -6.77812e-09 -5.17028e-09 5.59966e-08 1 7.70372e-19 -6.77812e-09 -5.17028e-09 5.59966e-08 1 -6.77812e-09 -5.17028e-09 5.59966e-08 4247.95 94.2182 -1047.16 3955.36 -112.411 4162.25 +EDGE_SE3:QUAT 1480 1530 -3.17488 0.000175887 -5.41825 -0.150155 0.137924 -0.128539 0.97052 1 7.70372e-19 7.70372e-19 5.5008e-08 -9.5462e-09 4.94679e-09 1 7.70372e-19 5.5008e-08 -9.5462e-09 4.94679e-09 1 5.5008e-08 -9.5462e-09 4.94679e-09 4071.67 -103.349 829.992 3983.66 -100.74 4095.77 +EDGE_SE3:QUAT 1479 1530 -3.81128 10.5638 -5.21663 0.0186599 -0.110531 0.0917725 0.989451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4205.97 19.3053 -934.053 3951.43 -42.7483 4173.68 +EDGE_SE3:QUAT 1480 1529 -3.85674 -11.039 -5.56999 -0.0559024 -0.0433908 -0.0536861 0.996047 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.83 8.41796 -383.093 3990.61 7.85477 4024.81 +EDGE_SE3:QUAT 1481 1531 -2.96548 -0.169662 -5.44164 -0.00537794 0.131681 -0.012441 0.991199 1 3.76158e-21 3.76158e-21 -1.30855e-09 -6.33576e-12 3.32593e-09 1 3.76158e-21 -1.30855e-09 -6.33576e-12 3.32593e-09 1 -1.30855e-09 -6.33576e-12 3.32593e-09 4291.78 -9.19495 1119.29 3930.93 -10.6807 4291.28 +EDGE_SE3:QUAT 1480 1531 -3.77638 10.5184 -5.37929 0.00333908 -0.00560047 0.12521 0.992109 1 1.88079e-22 1.88079e-22 -8.60582e-10 -1.08583e-10 5.42522e-12 1 1.88079e-22 -8.60582e-10 -1.08583e-10 5.42522e-12 1 -8.60582e-10 -1.08583e-10 5.42522e-12 4000.55 0.0248173 -48.7248 3999.85 -3.13108 3937.88 +EDGE_SE3:QUAT 1481 1530 -3.60408 -10.6731 -5.50421 -0.0594836 -0.0018521 -0.14172 0.988116 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.84 3.93892 -113.951 3998.68 10.2688 3922.65 +EDGE_SE3:QUAT 1482 1532 -2.98681 -0.210347 -5.4755 0.259726 -0.0278872 0.0498786 0.96399 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3760.54 -49.9643 -351.169 3992.07 0.542035 4020.42 +EDGE_SE3:QUAT 1481 1532 -3.67764 10.8114 -5.60013 0.0403707 -0.0962564 -0.0203846 0.994329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4140.89 -21.8471 -781.927 3964.97 17.8538 4145.75 +EDGE_SE3:QUAT 1482 1531 -3.99677 -10.5799 -5.51616 0.137047 0.128353 -0.0289736 0.981786 1 1.20371e-20 1.20371e-20 -9.44254e-10 -9.63832e-10 -7.05799e-09 1 1.20371e-20 -9.44254e-10 -9.63832e-10 -7.05799e-09 1 -9.44254e-10 -9.63832e-10 -7.05799e-09 4212.75 77.571 1111.03 3936.16 42.081 4284.52 +EDGE_SE3:QUAT 1483 1533 -2.93653 0.32943 -5.21849 0.0625029 0.0701489 0.0985867 0.990683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.24 24.0764 481.402 3988.68 29.2303 4017.99 +EDGE_SE3:QUAT 1482 1533 -4.08332 10.7175 -5.57998 -0.168383 -0.0267968 -0.0159979 0.985227 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3900.67 20.5073 -237.744 3996.64 -1.48377 4013.05 +EDGE_SE3:QUAT 1483 1532 -3.59278 -10.8274 -5.41 0.0305991 -0.124641 -0.0733408 0.989014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4236.67 -45.5174 -1009.83 3946.39 54.0821 4218.9 +EDGE_SE3:QUAT 1484 1534 -3.373 -0.265549 -5.6107 -0.0214248 -0.128142 -0.00718089 0.991498 1 1.27894e-20 1.27894e-20 7.34435e-09 2.35134e-11 -2.69931e-09 1 1.27894e-20 7.34435e-09 2.35134e-11 -2.69931e-09 1 7.34435e-09 2.35134e-11 -2.69931e-09 4275.06 10.6311 -1088.24 3934.24 -4.58021 4276.69 +EDGE_SE3:QUAT 1483 1534 -3.88791 10.8421 -5.54076 -0.0674794 -0.000161697 0.0258457 0.997386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.87 -0.893757 19.5727 3999.96 0.337601 3997.41 +EDGE_SE3:QUAT 1484 1533 -3.61582 -10.7456 -4.96203 0.0335246 -0.0931972 -0.0818411 0.991712 1 2.40741e-19 2.40741e-19 -1.6409e-08 2.64215e-09 2.91753e-08 1 2.40741e-19 -1.6409e-08 2.64215e-09 2.91753e-08 1 -1.6409e-08 2.64215e-09 2.91753e-08 4121.98 -29.1984 -722.63 3971.74 38.2252 4099.68 +EDGE_SE3:QUAT 1485 1535 -3.46529 -0.0673075 -5.39739 -0.0206891 0.0135729 -0.0224953 0.999441 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.93 -1.13823 102.906 3999.37 -1.22226 4000.62 +EDGE_SE3:QUAT 1484 1535 -4.04855 10.5916 -5.73416 -0.0781705 0.081169 0.0410001 0.992784 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4093.95 -22.4743 698.334 3970.82 1.76376 4111.67 +EDGE_SE3:QUAT 1485 1534 -3.63852 -10.9244 -5.03694 -0.0269737 -0.167562 0.0452002 0.984455 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4470.16 59.4937 -1454.71 3895.11 -62.8855 4464.9 +EDGE_SE3:QUAT 1486 1536 -2.80612 0.0965737 -5.76264 0.0675455 -0.0253276 0.00121229 0.997394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.99 -6.86762 -202.668 3997.49 0.918674 4010.24 +EDGE_SE3:QUAT 1485 1536 -3.68177 10.2489 -5.57705 0.0629383 -0.087774 0.0268239 0.993788 1 1.20371e-20 1.20371e-20 -6.3741e-10 4.16804e-10 7.00914e-09 1 1.20371e-20 -6.3741e-10 4.16804e-10 7.00914e-09 1 -6.3741e-10 4.16804e-10 7.00914e-09 4116.17 -20.0088 -738.568 3967.8 1.74433 4129.13 +EDGE_SE3:QUAT 1486 1535 -3.3415 -10.6881 -5.36645 0.0653441 0.0666243 -0.0619041 0.99371 1 4.81482e-20 4.81482e-20 -1.39357e-08 7.46417e-10 -1.03337e-09 1 4.81482e-20 -1.39357e-08 7.46417e-10 -1.03337e-09 1 -1.39357e-08 7.46417e-10 -1.03337e-09 4066.97 12.9473 585.998 3978.75 -11.4378 4068.72 +EDGE_SE3:QUAT 1487 1537 -2.93763 0.0112267 -5.35169 0.0381988 0.0835408 0.159858 0.982857 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4075.58 32.8169 577.999 3985.28 51.6021 3979.2 +EDGE_SE3:QUAT 1486 1537 -3.87932 10.9444 -5.58953 -0.0949783 0.0792407 0.0215453 0.992087 1 1.92593e-19 1.92593e-19 2.79074e-08 1.7735e-10 2.30265e-09 1 1.92593e-19 2.79074e-08 1.7735e-10 2.30265e-09 1 2.79074e-08 1.7735e-10 2.30265e-09 4071.57 -30.5074 664.985 3974.11 -7.71271 4105.8 +EDGE_SE3:QUAT 1487 1536 -3.51433 -10.9009 -5.00257 -0.0612425 -0.126462 -0.0459211 0.989014 1 8.1852e-19 8.1852e-19 -1.59432e-08 -5.44837e-08 -9.63788e-10 1 8.1852e-19 -1.59432e-08 -5.44837e-08 -9.63788e-10 1 -1.59432e-08 -5.44837e-08 -9.63788e-10 4268.5 20.0023 -1102 3932.52 3.34187 4275.07 +EDGE_SE3:QUAT 1488 1538 -2.76664 0.0681417 -5.67788 0.17964 0.161213 -0.141397 0.960076 1 7.70372e-19 7.70372e-19 -5.75423e-08 4.89074e-09 -1.17865e-08 1 7.70372e-19 -5.75423e-08 4.89074e-09 -1.17865e-08 1 -5.75423e-08 4.89074e-09 -1.17865e-08 4505.42 78.1678 1715.42 3858.48 4.80174 4554.53 +EDGE_SE3:QUAT 1487 1538 -3.7911 10.5737 -5.7343 -0.106069 0.0935543 0.0984932 0.985036 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4142.62 -27.0362 886.821 3953.2 21.0955 4148.82 +EDGE_SE3:QUAT 1488 1537 -3.67676 -10.6555 -5.16172 -0.121962 -0.119343 -0.027951 0.984937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4188.74 62.215 -1026.92 3943.42 -29.9189 4245.11 +EDGE_SE3:QUAT 1489 1539 -3.39148 -0.0544972 -5.46455 -0.0315836 0.089989 -0.208652 0.973329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4084.71 -41.3598 604.945 3986.71 -67.9801 3914.56 +EDGE_SE3:QUAT 1488 1539 -3.78836 10.393 -5.28767 0.0237493 -0.250304 -0.032912 0.967316 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5201.21 -117.875 -2502.45 3760.94 118.499 5199.13 +EDGE_SE3:QUAT 1489 1538 -3.94385 -10.6223 -5.67726 0.0744695 0.0779458 -0.142327 0.983932 1 1.92593e-19 1.92593e-19 2.77786e-08 -3.70237e-09 2.68629e-09 1 1.92593e-19 2.77786e-08 -3.70237e-09 2.68629e-09 1 2.77786e-08 -3.70237e-09 2.68629e-09 4113.1 3.53751 748.434 3966.16 -45.3955 4054.26 +EDGE_SE3:QUAT 1490 1540 -3.3451 0.0203148 -5.3739 0.0717089 0.200303 -0.0780706 0.973982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4756.69 3.41515 1926.99 3830.44 -20.3701 4752.88 +EDGE_SE3:QUAT 1489 1540 -4.13776 10.2657 -5.46366 0.131703 0.0664244 -0.00801001 0.989029 1 9.63388e-19 9.63388e-19 5.50422e-08 2.78186e-08 -1.24865e-09 1 9.63388e-19 5.50422e-08 2.78186e-08 -1.24865e-09 1 5.50422e-08 2.78186e-08 -1.24865e-09 4001.82 36.2337 538.417 3983.74 12.0668 4070.94 +EDGE_SE3:QUAT 1490 1539 -4.01755 -10.6444 -5.35455 -0.0118488 -0.0760755 -0.120383 0.989737 1 7.52316e-22 7.52316e-22 -1.73758e-09 2.10637e-10 1.34649e-10 1 7.52316e-22 -1.73758e-09 2.10637e-10 1.34649e-10 1 -1.73758e-09 2.10637e-10 1.34649e-10 4094.88 -13.5602 -625.197 3977.86 38.3393 4037.47 +EDGE_SE3:QUAT 1491 1541 -3.11943 0.0324931 -5.02095 0.208665 0.132675 -0.0596584 0.967108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4170.6 126.046 1223.9 3929.12 66.1043 4330.53 +EDGE_SE3:QUAT 1490 1541 -3.99867 10.4387 -5.53448 -0.0130424 -0.21874 0.100561 0.9705 1 1.92593e-19 1.92593e-19 -6.44165e-09 -1.87324e-09 2.96548e-08 1 1.92593e-19 -6.44165e-09 -1.87324e-09 2.96548e-08 1 -6.44165e-09 -1.87324e-09 2.96548e-08 4836.36 160.841 -2012.36 3838.01 -171.146 4796.59 +EDGE_SE3:QUAT 1491 1540 -3.75493 -10.6287 -5.24244 -0.170474 0.0654526 -0.219693 0.958327 1 7.70372e-19 7.70372e-19 -5.315e-08 1.27062e-08 9.46823e-10 1 7.70372e-19 -5.315e-08 1.27062e-08 9.46823e-10 1 -5.315e-08 1.27062e-08 9.46823e-10 3877.15 10.1803 35.6017 3999.71 13.8352 3800.34 +EDGE_SE3:QUAT 1492 1542 -3.37194 0.0416357 -5.29739 -0.127355 -0.0265897 -0.0246059 0.991195 1 1.20371e-20 1.20371e-20 -2.21911e-10 -8.7668e-10 6.89089e-09 1 1.20371e-20 -2.21911e-10 -8.7668e-10 6.89089e-09 1 -2.21911e-10 -8.7668e-10 6.89089e-09 3950.11 15.9252 -245.437 3996.15 0.448683 4012.56 +EDGE_SE3:QUAT 1491 1542 -3.75617 10.6275 -5.66712 -0.145391 -0.121846 0.207612 0.959642 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.26 62.3996 -530.477 4002.93 -65.9842 3889.4 +EDGE_SE3:QUAT 1492 1541 -4.09789 -11.0019 -5.5338 0.00233975 -0.120113 -0.207687 0.97079 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4206.15 -71.1328 -932.306 3964.15 109.523 4033.64 +EDGE_SE3:QUAT 1493 1543 -3.38903 0.160224 -5.75703 0.0187267 0.0681689 -0.0194025 0.997309 1 1.92593e-19 1.92593e-19 -4.71905e-10 -2.76821e-08 4.50383e-10 1 1.92593e-19 -4.71905e-10 -2.76821e-08 4.50383e-10 1 -4.71905e-10 -2.76821e-08 4.50383e-10 4075.07 3.25949 558.348 3981.1 -3.53588 4074.97 +EDGE_SE3:QUAT 1492 1543 -3.87485 10.5677 -5.36894 -0.101277 -0.0600308 -0.114471 0.986426 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.89 20.048 -614.257 3975.54 26.2767 4039.5 +EDGE_SE3:QUAT 1493 1542 -3.5363 -10.5328 -4.74832 -0.0727525 -0.118047 -0.0385696 0.989588 1 1.20371e-20 1.20371e-20 8.73726e-10 4.67554e-10 -7.07568e-09 1 1.20371e-20 8.73726e-10 4.67554e-10 -7.07568e-09 1 8.73726e-10 4.67554e-10 -7.07568e-09 4224.58 28.6969 -1021.49 3941.36 -4.42498 4239.8 +EDGE_SE3:QUAT 1494 1544 -3.10671 0.0389998 -5.317 0.167425 0.159269 -0.0487836 0.971711 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4360.22 122.221 1453.45 3901.39 78.6506 4462.83 +EDGE_SE3:QUAT 1493 1544 -3.55198 10.5783 -5.60528 0.0631183 -0.0689041 0.050727 0.994331 1 4.81482e-20 4.81482e-20 1.04447e-09 -7.91248e-10 -1.39489e-08 1 4.81482e-20 1.04447e-09 -7.91248e-10 -1.39489e-08 1 1.04447e-09 -7.91248e-10 -1.39489e-08 4070.87 -13.645 -595.677 3978.23 -8.0935 4076.51 +EDGE_SE3:QUAT 1494 1543 -3.69658 -10.8037 -5.33855 0.101011 -0.13347 0.149103 0.974552 1 7.70372e-19 7.70372e-19 5.67275e-08 7.26106e-09 -9.05713e-09 1 7.70372e-19 5.67275e-08 7.26106e-09 -9.05713e-09 1 5.67275e-08 7.26106e-09 -9.05713e-09 4346.37 3.9057 -1303.66 3909.59 -63.6546 4298.25 +EDGE_SE3:QUAT 1495 1545 -3.52825 -0.0768064 -5.31624 0.0600196 -0.108981 0.0368646 0.991545 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4192.49 -20.2424 -932.964 3950.1 -0.66307 4201.46 +EDGE_SE3:QUAT 1494 1545 -3.9797 10.2989 -5.53085 -0.0118919 0.146848 -0.0338878 0.988507 1 1.20371e-20 1.20371e-20 7.16467e-09 -2.82732e-10 1.05532e-09 1 1.20371e-20 7.16467e-09 -2.82732e-10 1.05532e-09 1 7.16467e-09 -2.82732e-10 1.05532e-09 4363.15 -28.5165 1259.82 3915.98 -32.9883 4359.12 +EDGE_SE3:QUAT 1495 1544 -3.85044 -10.6946 -5.12477 0.185594 -0.095335 -0.163984 0.964145 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3884.65 -30.7966 -338.511 4002.63 30.1073 3914.87 +EDGE_SE3:QUAT 1496 1546 -2.94966 0.0665317 -5.41086 0.198516 0.0681642 -0.144366 0.967007 1 7.70372e-19 7.70372e-19 -5.49292e-08 6.14955e-09 -6.60591e-09 1 7.70372e-19 -5.49292e-08 6.14955e-09 -6.60591e-09 1 -5.49292e-08 6.14955e-09 -6.60591e-09 4020.55 68.8332 866.164 3951.65 -27.5878 4094.82 +EDGE_SE3:QUAT 1495 1546 -3.94154 10.579 -5.44586 0.0729455 -0.180661 0.144389 0.970151 1 4.81482e-20 4.81482e-20 1.45396e-08 1.88839e-09 -2.89578e-09 1 4.81482e-20 1.45396e-08 1.88839e-09 -2.89578e-09 1 1.45396e-08 1.88839e-09 -2.89578e-09 4628.61 60.0644 -1738.41 3860.39 -100.622 4566.51 +EDGE_SE3:QUAT 1496 1545 -3.75003 -10.5532 -5.36745 -0.0104816 0.201558 -0.0612402 0.977504 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4719.25 -85.8709 1843.04 3847.41 -93.4188 4704.68 +EDGE_SE3:QUAT 1497 1547 -3.54254 -0.0386287 -5.68711 0.0288186 0.0624359 0.0911754 0.993458 1 1.92593e-19 1.92593e-19 -1.56493e-09 -1.11627e-09 -2.77599e-08 1 1.92593e-19 -1.56493e-09 -1.11627e-09 -2.77599e-08 1 -1.56493e-09 -1.11627e-09 -2.77599e-08 4050.27 14.4881 466.348 3988.07 23.9111 4020.34 +EDGE_SE3:QUAT 1496 1547 -4.13517 10.6333 -5.19126 0.0134856 -0.107858 0.00326698 0.994069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4192.25 -5.84889 -899.52 3953.46 2.3376 4192.93 +EDGE_SE3:QUAT 1497 1546 -3.99035 -10.1642 -5.50299 0.0501708 0.0130254 -0.10856 0.992738 1 1.92593e-19 1.92593e-19 6.52095e-10 1.28351e-09 2.7578e-08 1 1.92593e-19 6.52095e-10 1.28351e-09 2.7578e-08 1 6.52095e-10 1.28351e-09 2.7578e-08 3996.8 3.77204 167.011 3997.87 -9.79415 3959.72 +EDGE_SE3:QUAT 1498 1548 -3.45454 -0.0165001 -5.4336 0.0272011 0.104105 0.0873591 0.990349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4158.95 34.4425 821.068 3963.93 46.1455 4131.38 +EDGE_SE3:QUAT 1497 1548 -3.94596 10.9484 -5.54672 -0.128935 -0.112639 -0.0338567 0.984653 1 9.62965e-19 9.62965e-19 -5.6323e-08 -2.71034e-08 3.25035e-09 1 9.62965e-19 -5.6323e-08 -2.71034e-08 3.25035e-09 1 -5.6323e-08 -2.71034e-08 3.25035e-09 4159.08 60.8737 -976.326 3948.22 -25.432 4221 +EDGE_SE3:QUAT 1498 1547 -3.8833 -10.7764 -5.11142 -0.0783165 -0.00214236 -0.121766 0.989462 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.33 6.06586 -129.57 3998.29 9.88703 3944.56 +EDGE_SE3:QUAT 1499 1549 -3.3595 0.152009 -5.21597 -0.0846965 -0.0629577 0.0148191 0.994305 1 1.20371e-20 1.20371e-20 -4.15875e-10 -6.0949e-10 6.9504e-09 1 1.20371e-20 -4.15875e-10 -6.0949e-10 6.9504e-09 1 -4.15875e-10 -6.0949e-10 6.9504e-09 4030.23 22.6013 -489.124 3986.35 -11.4336 4058.04 +EDGE_SE3:QUAT 1498 1549 -3.79522 10.1663 -5.35213 -0.116059 -0.0725946 -0.0389343 0.98982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4044.67 34.2618 -635.612 3975.93 -3.55471 4092.49 +EDGE_SE3:QUAT 1499 1548 -3.52326 -10.6121 -5.37873 -0.00898553 -0.0522484 0.0808497 0.995315 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.01 6.99525 -408.745 3990.26 -17.3804 4015.19 +EDGE_SE3:QUAT 1500 1550 -3.24092 0.0858503 -5.61955 -0.0660325 0.0528952 0.0151487 0.996299 1 8.21529e-19 8.21529e-19 5.55546e-08 -1.3149e-08 -1.33743e-09 1 8.21529e-19 5.55546e-08 -1.3149e-08 -1.33743e-09 1 5.55546e-08 -1.3149e-08 -1.33743e-09 4029.69 -13.8894 436.76 3988.35 -1.22814 4046.22 +EDGE_SE3:QUAT 1499 1550 -3.78811 10.4034 -5.63368 0.0306483 0.140698 -0.00616064 0.989559 1 4.70198e-23 4.70198e-23 6.35889e-11 1.36043e-11 4.46884e-10 1 4.70198e-23 6.35889e-11 1.36043e-11 4.46884e-10 1 6.35889e-11 1.36043e-11 4.46884e-10 4333.28 19.2271 1209.02 3921 11.5696 4336.88 +EDGE_SE3:QUAT 1500 1549 -3.66014 -10.6661 -4.79939 -0.0111245 -0.0255983 -0.0567081 0.998001 1 3.00927e-21 3.00927e-21 3.46736e-09 -1.9526e-10 -9.27252e-11 1 3.00927e-21 3.46736e-09 -1.9526e-10 -9.27252e-11 1 3.46736e-09 -1.9526e-10 -9.27252e-11 4010.69 0.257545 -211.846 3997.19 5.92699 3998.32 +EDGE_SE3:QUAT 1501 1551 -3.29328 0.113 -5.482 -0.0462505 -0.0611539 -0.0148654 0.996945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.62 10.7493 -502.557 3984.63 -0.421462 4061.29 +EDGE_SE3:QUAT 1500 1551 -3.42592 10.9142 -5.70747 -0.122445 -0.00134669 0.00214476 0.992472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3940.04 0.384546 -7.41218 4000 -0.00980315 3999.99 +EDGE_SE3:QUAT 1501 1550 -3.76516 -10.4739 -5.07102 0.0429411 0.0704223 -0.265212 0.960656 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4095.49 -25.4525 649.66 3979.81 -88.4512 3821.52 +EDGE_SE3:QUAT 1502 1552 -2.99155 -0.438669 -5.46198 0.172211 0.14049 -0.153582 0.962818 1 7.70372e-19 7.70372e-19 -5.68742e-08 6.06843e-09 -1.0596e-08 1 7.70372e-19 -5.68742e-08 6.06843e-09 -1.0596e-08 1 -5.68742e-08 6.06843e-09 -1.0596e-08 4387.39 57.6262 1510.96 3882.34 -24.7985 4411.67 +EDGE_SE3:QUAT 1501 1552 -4.21854 10.5276 -5.28812 0.216286 0.00599866 0.262663 0.940315 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3893.31 -69.4168 -601.747 3961.76 -92.8249 3804.46 +EDGE_SE3:QUAT 1502 1551 -3.77099 -10.3216 -5.58232 -0.131027 -0.00828432 0.0283446 0.990939 1 7.70372e-19 7.70372e-19 -5.50085e-08 -1.63897e-09 3.46927e-11 1 7.70372e-19 -5.50085e-08 -1.63897e-09 3.46927e-11 1 -5.50085e-08 -1.63897e-09 3.46927e-11 3931.37 0.337674 -20.4588 4000 -0.115875 3996.83 +EDGE_SE3:QUAT 1503 1553 -2.78214 0.0317896 -5.57978 0.119811 -0.277667 0.0697789 0.950619 1 4.81482e-20 4.81482e-20 -4.73665e-09 1.61408e-09 1.57722e-08 1 4.81482e-20 -4.73665e-09 1.61408e-09 1.57722e-08 1 -4.73665e-09 1.61408e-09 1.57722e-08 5632.7 -150.111 -3101.12 3688.34 148.051 5670.64 +EDGE_SE3:QUAT 1502 1553 -4.31288 10.5171 -5.30621 0.0644067 -0.098624 0.160739 0.979943 1 4.81482e-20 4.81482e-20 -1.39452e-08 -2.1373e-09 1.61554e-09 1 4.81482e-20 -1.39452e-08 -2.1373e-09 1.61554e-09 1 -1.39452e-08 -2.1373e-09 1.61554e-09 4183.67 13.7038 -917.33 3952.8 -65.925 4096.91 +EDGE_SE3:QUAT 1503 1552 -4.3079 -10.3096 -4.94742 0.0847556 0.0265304 -0.0471924 0.99493 1 2.52778e-19 2.52778e-19 2.74917e-08 4.5935e-09 -1.34596e-08 1 2.52778e-19 2.74917e-08 4.5935e-09 -1.34596e-08 1 2.74917e-08 4.5935e-09 -1.34596e-08 3987.79 10.5819 257.992 3995.5 -4.54061 4007.62 +EDGE_SE3:QUAT 1504 1554 -3.51343 -0.037956 -5.09393 0.00772592 -0.135956 0.0478037 0.989531 1 7.70795e-19 7.70795e-19 3.9727e-09 -5.48667e-08 -4.81993e-10 1 7.70795e-19 3.9727e-09 -5.48667e-08 -4.81993e-10 1 3.9727e-09 -5.48667e-08 -4.81993e-10 4313.2 17.9073 -1162.76 3926.66 -29.5401 4304.3 +EDGE_SE3:QUAT 1503 1554 -4.03896 10.9237 -5.26791 -0.0612447 -0.0973634 -0.0223625 0.993111 1 2.40741e-19 2.40741e-19 -1.43509e-08 -2.74204e-08 -2.03493e-10 1 2.40741e-19 -1.43509e-08 -2.74204e-08 -2.03493e-10 1 -1.43509e-08 -2.74204e-08 -2.03493e-10 4146.01 22.2846 -818.525 3961.08 -4.85405 4159.01 +EDGE_SE3:QUAT 1504 1553 -3.81352 -10.0088 -5.31454 -0.0561908 -0.136328 -0.233883 0.961018 1 7.70372e-19 7.70372e-19 1.26197e-08 5.34344e-08 -6.51646e-10 1 7.70372e-19 1.26197e-08 5.34344e-08 -6.51646e-10 1 1.26197e-08 5.34344e-08 -6.51646e-10 4343.29 -86.8841 -1245.19 3932.37 149.877 4137.12 +EDGE_SE3:QUAT 1505 1555 -3.23252 -0.0379291 -5.35239 0.108983 -0.00401342 -0.133343 0.985051 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3956.64 10.3325 140.387 3997.58 -12.8517 3933.03 +EDGE_SE3:QUAT 1504 1555 -3.62171 10.7809 -5.19969 0.073964 -0.0124328 0.109066 0.991201 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.19 -7.10752 -193.032 3996.97 -11.453 3961.49 +EDGE_SE3:QUAT 1505 1554 -3.91104 -10.6628 -5.17013 -0.0979288 -0.0879948 -0.0628915 0.989299 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4111.82 29.2105 -789.638 3962.87 5.966 4134.36 +EDGE_SE3:QUAT 1506 1556 -3.23249 0.68661 -5.45721 0.0494134 -0.12801 -0.066191 0.988327 1 4.81482e-20 4.81482e-20 -1.41368e-08 1.15797e-09 1.70809e-09 1 4.81482e-20 -1.41368e-08 1.15797e-09 1.70809e-09 1 -1.41368e-08 1.15797e-09 1.70809e-09 4237.47 -55.1102 -1024.96 3945.97 58.4046 4229.71 +EDGE_SE3:QUAT 1505 1556 -4.09381 10.5053 -5.53274 -0.0774029 0.0677619 0.185873 0.977174 1 7.70372e-19 7.70372e-19 5.11579e-09 -2.70368e-09 5.50687e-08 1 7.70372e-19 5.11579e-09 -2.70368e-09 5.50687e-08 1 5.11579e-09 -2.70368e-09 5.50687e-08 4093.94 0.403192 697.605 3970.45 60.6018 3979.71 +EDGE_SE3:QUAT 1506 1555 -3.86554 -10.9066 -5.32409 0.0216224 -0.0350298 -0.0749489 0.996337 1 1.20371e-20 1.20371e-20 6.92799e-09 -5.32408e-10 -2.18072e-10 1 1.20371e-20 6.92799e-09 -5.32408e-10 -2.18072e-10 1 6.92799e-09 -5.32408e-10 -2.18072e-10 4014.84 -4.71781 -259.192 3996.18 10.1184 3994.24 +EDGE_SE3:QUAT 1507 1557 -3.03205 -0.148295 -5.46838 -0.0718161 -0.0328087 0.0550087 0.995359 1 1.92593e-19 1.92593e-19 -2.76657e-08 -1.64666e-09 6.77715e-10 1 1.92593e-19 -2.76657e-08 -1.64666e-09 6.77715e-10 1 -2.76657e-08 -1.64666e-09 6.77715e-10 3990.55 8.12654 -212.497 3997.74 -6.783 3999.07 +EDGE_SE3:QUAT 1506 1557 -3.96591 10.2496 -5.58313 0.00450024 0.0172862 0.159192 0.987086 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.79 1.25643 124.707 3999.21 9.61209 3902.51 +EDGE_SE3:QUAT 1507 1556 -3.99359 -10.6258 -5.61454 -0.171784 -0.0905809 -0.140136 0.9709 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4121.69 57.5096 -1009.95 3938.83 27.511 4161.18 +EDGE_SE3:QUAT 1508 1558 -3.39681 -0.495889 -5.32756 0.0829045 -0.0318147 -0.135699 0.986763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.04 -3.70788 -112.021 3999.92 4.99689 3928.87 +EDGE_SE3:QUAT 1507 1558 -3.43182 10.3345 -5.6151 -0.135738 0.0776201 0.0553908 0.986145 1 9.62965e-19 9.62965e-19 -5.6506e-08 2.55383e-08 -1.47753e-09 1 9.62965e-19 -5.6506e-08 2.55383e-08 -1.47753e-09 1 -5.6506e-08 2.55383e-08 -1.47753e-09 4048.52 -43.4282 710.005 3970.04 -2.56517 4109.95 +EDGE_SE3:QUAT 1508 1557 -3.69353 -10.5756 -5.40724 0.0887216 0.0690731 -0.0539012 0.992196 1 1.92593e-19 1.92593e-19 2.78568e-08 -1.15991e-09 2.16755e-09 1 1.92593e-19 2.78568e-08 -1.15991e-09 2.16755e-09 1 2.78568e-08 -1.15991e-09 2.16755e-09 4060.46 22.1931 613.521 3976.87 -5.92496 4080.32 +EDGE_SE3:QUAT 1509 1559 -3.07028 -0.195133 -5.21085 0.0906821 0.00268146 0.0540114 0.994411 1 2.40741e-19 2.40741e-19 2.77001e-08 2.32769e-10 -1.39983e-08 1 2.40741e-19 2.77001e-08 2.32769e-10 -1.39983e-08 1 2.77001e-08 2.32769e-10 -1.39983e-08 3967.36 -2.57136 -37.2456 3999.8 -1.51947 3988.58 +EDGE_SE3:QUAT 1508 1559 -4.15636 10.5638 -5.47705 -0.21225 -0.00538212 0.151329 0.965412 1 1.20371e-20 1.20371e-20 -9.72164e-10 6.71064e-09 1.41829e-09 1 1.20371e-20 -9.72164e-10 6.71064e-09 1.41829e-09 1 -9.72164e-10 6.71064e-09 1.41829e-09 3843.8 -45.5314 331.229 3987.51 29.9903 3932.4 +EDGE_SE3:QUAT 1509 1558 -3.78567 -10.4652 -5.03544 0.0053099 -0.101447 -0.158819 0.982068 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4152.32 -40.7152 -795.978 3968.87 70.076 4051.54 +EDGE_SE3:QUAT 1510 1560 -3.30468 -0.161703 -5.7993 -0.167049 0.0353129 -0.056472 0.983696 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3894.16 -10.5407 158.483 3999.5 -5.49493 3993.03 +EDGE_SE3:QUAT 1509 1560 -3.78382 10.2899 -5.4204 -0.0190407 -0.0678672 0.027432 0.997135 1 1.20371e-20 1.20371e-20 -6.9817e-09 -2.11914e-10 4.66725e-10 1 1.20371e-20 -6.9817e-09 -2.11914e-10 4.66725e-10 1 -6.9817e-09 -2.11914e-10 4.66725e-10 4071.26 8.44335 -544.193 3982.34 -9.89669 4069.7 +EDGE_SE3:QUAT 1510 1559 -3.96166 -10.7547 -5.06518 -0.0358166 -0.0877325 -0.163543 0.981975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4136.48 -19.7175 -765.847 3967.8 61.7269 4034.63 +EDGE_SE3:QUAT 1511 1561 -2.98324 -0.0188177 -5.42847 0.0825893 -0.111111 -0.01775 0.990211 1 1.20371e-20 1.20371e-20 -7.56458e-10 6.29493e-10 7.03521e-09 1 1.20371e-20 -7.56458e-10 6.29493e-10 7.03521e-09 1 -7.56458e-10 6.29493e-10 7.03521e-09 4164.7 -46.7186 -897.19 3956.52 33.6722 4190.72 +EDGE_SE3:QUAT 1510 1561 -4.3875 10.5413 -5.42995 -0.00336386 0.0876589 0.0766582 0.993191 1 1.88079e-22 1.88079e-22 8.7486e-10 6.80565e-11 7.67534e-11 1 1.88079e-22 8.7486e-10 6.80565e-11 7.67534e-11 1 8.7486e-10 6.80565e-11 7.67534e-11 4124.66 13.3147 717.191 3970.4 29.0455 4101.19 +EDGE_SE3:QUAT 1511 1560 -4.18452 -10.7351 -4.89144 0.0959149 0.0450287 -0.065671 0.9922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.37 18.1106 432.673 3987.74 -9.07268 4028.92 +EDGE_SE3:QUAT 1512 1562 -3.34239 -0.409346 -5.24464 -0.0582965 0.0734264 -0.0159358 0.995468 1 1.20371e-20 1.20371e-20 4.97818e-10 -4.29418e-10 6.9793e-09 1 1.20371e-20 4.97818e-10 -4.29418e-10 6.9793e-09 1 4.97818e-10 -4.29418e-10 6.9793e-09 4069.73 -19.8436 583.314 3980.21 -12.3229 4082.3 +EDGE_SE3:QUAT 1511 1562 -3.88463 10.5886 -5.66145 0.054164 0.119876 0.186967 0.973519 1 3.85186e-19 3.85186e-19 2.19243e-08 3.27023e-08 -1.2289e-10 1 3.85186e-19 2.19243e-08 3.27023e-08 -1.2289e-10 1 2.19243e-08 3.27023e-08 -1.2289e-10 4143.72 73.6968 807.525 3977.45 94.1375 4015.63 +EDGE_SE3:QUAT 1512 1561 -3.79045 -10.4096 -5.44202 0.0932621 -0.0217652 -0.0659073 0.993219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.42 -3.68677 -97.5863 3999.73 2.83511 3984.83 +EDGE_SE3:QUAT 1513 1563 -2.9753 -0.053846 -5.38879 -0.0639927 -0.0347417 -0.00840166 0.99731 1 1.93345e-19 1.93345e-19 2.76887e-08 -2.19272e-10 7.4583e-10 1 1.93345e-19 2.76887e-08 -2.19272e-10 7.4583e-10 1 2.76887e-08 -2.19272e-10 7.4583e-10 4003.67 9.00008 -283.892 3995.03 -0.703761 4019.77 +EDGE_SE3:QUAT 1512 1563 -3.99671 10.5745 -5.31528 -0.0808034 -0.0665999 0.0476891 0.993358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.82 24.1176 -485.295 3987.41 -19.1065 4048.84 +EDGE_SE3:QUAT 1513 1562 -3.89212 -10.2931 -5.39494 0.0410549 0.0419105 -0.0458417 0.997224 1 4.81482e-20 4.81482e-20 -1.38945e-08 5.90922e-10 -6.32091e-10 1 4.81482e-20 -1.38945e-08 5.90922e-10 -6.32091e-10 1 -1.38945e-08 5.90922e-10 -6.32091e-10 4025.13 5.50087 358.504 3991.86 -6.61672 4023.46 +EDGE_SE3:QUAT 1514 1564 -3.47606 -0.16701 -5.32166 0.0244164 -0.0327369 0.0664075 0.996956 1 1.92593e-19 1.92593e-19 -9.91977e-10 5.54004e-10 2.77391e-08 1 1.92593e-19 -9.91977e-10 5.54004e-10 2.77391e-08 1 -9.91977e-10 5.54004e-10 2.77391e-08 4017.19 -1.63285 -280.579 3995 -8.92344 4001.94 +EDGE_SE3:QUAT 1513 1564 -3.90077 10.2523 -5.434 0.127184 0.0417948 0.0642644 0.988912 1 4.81482e-20 4.81482e-20 -1.01112e-09 1.37156e-08 -1.82819e-09 1 4.81482e-20 -1.01112e-09 1.37156e-08 -1.82819e-09 1 -1.01112e-09 1.37156e-08 -1.82819e-09 3947.85 13.8892 227.704 3998.13 9.2785 3996.03 +EDGE_SE3:QUAT 1514 1563 -3.83036 -10.5455 -5.33724 -0.0374249 -0.0736908 0.102943 0.991248 1 3.85186e-19 3.85186e-19 -2.47311e-08 -3.05537e-08 3.48365e-10 1 3.85186e-19 -2.47311e-08 -3.05537e-08 3.48365e-10 1 -2.47311e-08 -3.05537e-08 3.48365e-10 4066.07 22.0845 -540.681 3984.71 -32.5751 4029.28 +EDGE_SE3:QUAT 1515 1565 -3.32609 -0.0145886 -5.17093 -0.0438504 0.117322 -0.0560839 0.990539 1 4.81482e-20 4.81482e-20 -1.41062e-08 9.66808e-10 -1.58106e-09 1 4.81482e-20 -1.41062e-08 9.66808e-10 -1.58106e-09 1 -1.41062e-08 9.66808e-10 -1.58106e-09 4203.07 -41.8664 942.196 3952.51 -44.3108 4198.18 +EDGE_SE3:QUAT 1514 1565 -3.67709 10.4573 -5.70084 0.0200221 0.00183883 0.0434581 0.998853 1 1.17549e-23 1.17549e-23 9.43188e-12 -2.16591e-10 4.35983e-12 1 1.17549e-23 9.43188e-12 -2.16591e-10 4.35983e-12 1 9.43188e-12 -2.16591e-10 4.35983e-12 3998.4 0.00806021 4.23454 4000 0.0163323 3992.45 +EDGE_SE3:QUAT 1515 1564 -3.89004 -10.3887 -5.06028 -0.0118976 0.0132223 0.0287978 0.999427 1 6.01853e-21 6.01853e-21 -3.56759e-09 3.36862e-09 -9.59727e-12 1 6.01853e-21 -3.56759e-09 3.36862e-09 -9.59727e-12 1 -3.56759e-09 3.36862e-09 -9.59727e-12 4002.45 -0.534184 109.808 3999.23 1.5502 3999.69 +EDGE_SE3:QUAT 1516 1566 -3.57882 0.0918904 -5.23044 -0.00893322 -0.156308 0.0833147 0.984148 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4404.59 61.1076 -1335.58 3911.11 -75.495 4377.15 +EDGE_SE3:QUAT 1515 1566 -3.7418 10.5951 -4.97674 -0.192208 -0.181842 0.17887 0.947626 1 3.08149e-18 3.08149e-18 -9.56359e-09 -2.9027e-08 1.07846e-07 1 3.08149e-18 -9.56359e-09 -2.9027e-08 1.07846e-07 1 -9.56359e-09 -2.9027e-08 1.07846e-07 4036.9 164.313 -911.933 4012.57 -163.802 4056.7 +EDGE_SE3:QUAT 1516 1565 -3.59558 -10.3251 -5.23241 0.177071 0.110584 -0.0794556 0.974733 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4139.8 81.2961 1063.85 3938.47 19.301 4239.96 +EDGE_SE3:QUAT 1517 1567 -3.1529 -0.213594 -5.51402 -0.184218 -0.00633541 0.0170572 0.982717 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3864.24 -0.199801 -11.2549 4000 -0.00757065 3998.82 +EDGE_SE3:QUAT 1516 1567 -3.92511 10.4716 -6.07663 -0.184261 -0.102694 -0.02092 0.977274 1 9.6414e-19 9.6414e-19 5.47461e-08 2.77334e-08 1.41101e-09 1 9.6414e-19 5.47461e-08 2.77334e-08 1.41101e-09 1 5.47461e-08 2.77334e-08 1.41101e-09 4040.12 82.6053 -857.238 3963.55 -40.3787 4174.18 +EDGE_SE3:QUAT 1517 1566 -4.11106 -10.6405 -5.17251 -0.00676797 -0.0396822 -0.00581697 0.999172 1 4.89006e-20 4.89006e-20 -1.81228e-09 -1.38571e-08 -1.86113e-11 1 4.89006e-20 -1.81228e-09 -1.38571e-08 -1.86113e-11 1 -1.81228e-09 -1.38571e-08 -1.86113e-11 4025.2 0.878148 -319.659 3993.68 0.687265 4025.25 +EDGE_SE3:QUAT 1518 1568 -3.24026 0.158276 -4.97686 0.031192 0.0740737 0.0637874 0.994722 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4076.78 17.2896 573.866 3981.34 22.9156 4064.4 +EDGE_SE3:QUAT 1517 1568 -3.6729 10.1222 -5.54441 0.0176026 0.112897 0.0043748 0.993441 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4210.08 10.8425 943.353 3949.32 8.05976 4211.24 +EDGE_SE3:QUAT 1518 1567 -3.69794 -10.2334 -5.46571 -0.180777 0.0458275 -0.0807439 0.979132 1 7.82409e-19 7.82409e-19 -5.37608e-08 1.18958e-08 5.40864e-10 1 7.82409e-19 -5.37608e-08 1.18958e-08 5.40864e-10 1 -5.37608e-08 1.18958e-08 5.40864e-10 3875.69 -11.391 174.239 3999.91 -7.65022 3980.33 +EDGE_SE3:QUAT 1519 1569 -3.0728 0.285988 -5.21423 0.0610749 0.0990242 -0.0292266 0.992779 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4153.7 21.0276 838.422 3959.15 1.98836 4165.21 +EDGE_SE3:QUAT 1518 1569 -4.22102 10.0566 -5.66785 0.0487667 0.0411088 0.0461411 0.996897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.99 8.8573 301.078 3994.88 8.56164 4013.99 +EDGE_SE3:QUAT 1519 1568 -4.24144 -10.5311 -5.43503 0.0471401 -0.149265 -0.0509808 0.986356 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4346.38 -64.6314 -1244.03 3921.93 65.3766 4344.88 +EDGE_SE3:QUAT 1520 1570 -3.3191 0.16257 -5.22522 0.0297792 0.0343079 -0.0461918 0.997899 1 1.20371e-20 1.20371e-20 -6.94258e-09 3.07362e-10 -2.56411e-10 1 1.20371e-20 -6.94258e-09 3.07362e-10 -2.56411e-10 1 -6.94258e-09 3.07362e-10 -2.56411e-10 4017.52 3.03609 291.085 3994.62 -6.00684 4012.53 +EDGE_SE3:QUAT 1519 1570 -4.13831 10.5532 -5.32403 0.32621 0.0627367 0.161264 0.929325 1 7.70372e-19 7.70372e-19 2.89516e-09 -1.82126e-08 -5.15549e-08 1 7.70372e-19 2.89516e-09 -1.82126e-08 -5.15549e-08 1 2.89516e-09 -1.82126e-08 -5.15549e-08 3569.93 -68.366 -170.987 3989.19 -34.2642 3891.56 +EDGE_SE3:QUAT 1520 1569 -3.93687 -10.4328 -5.42226 -0.0472297 0.0544556 -0.0255024 0.997072 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.37 -11.9018 423.271 3989.46 -8.70418 4041.69 +EDGE_SE3:QUAT 1521 1571 -3.22672 0.12144 -5.84326 0.0183406 0.0894519 0.0140935 0.995723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4128.42 10.058 732.041 3968.54 9.21645 4128.97 +EDGE_SE3:QUAT 1520 1571 -3.97567 10.2595 -5.27196 -0.152356 -0.0344677 -0.0192411 0.987537 1 8.1852e-19 8.1852e-19 -5.50894e-08 -1.32618e-08 5.13504e-11 1 8.1852e-19 -5.50894e-08 -1.32618e-08 5.13504e-11 1 -5.50894e-08 -1.32618e-08 5.13504e-11 3929.86 23.3569 -302.278 3994.53 -2.04345 4021.23 +EDGE_SE3:QUAT 1521 1570 -4.21972 -10.4142 -5.53818 -0.0207606 -0.0189103 -0.151112 0.988118 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.66 0.243081 -183.475 3997.82 14.4986 3917.04 +EDGE_SE3:QUAT 1522 1572 -3.3862 -0.0992174 -5.31083 0.0410543 -0.170915 -0.0544192 0.982925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4473.72 -81.1983 -1467.32 3896.61 83.5955 4468.62 +EDGE_SE3:QUAT 1521 1572 -3.49996 10.3788 -5.42356 -0.0438099 0.184652 -0.00452691 0.981817 1 9.62965e-19 9.62965e-19 2.80144e-08 -5.51403e-08 2.75463e-09 1 9.62965e-19 2.80144e-08 -5.51403e-08 2.75463e-09 1 2.80144e-08 -5.51403e-08 2.75463e-09 4592.72 -54.1442 1661.96 3867.17 -47.3822 4600.32 +EDGE_SE3:QUAT 1522 1571 -4.31461 -10.644 -5.37374 0.155129 0.0156773 0.0350075 0.987149 1 4.81482e-20 4.81482e-20 -5.76837e-11 -2.16348e-09 -1.37006e-08 1 4.81482e-20 -5.76837e-11 -2.16348e-09 -1.37006e-08 1 -5.76837e-11 -2.16348e-09 -1.37006e-08 3904.4 2.65273 56.6012 3999.97 0.882591 3995.76 +EDGE_SE3:QUAT 1523 1573 -3.80162 0.0337065 -5.18404 0.10962 -0.11663 0.0347173 0.986497 1 4.33334e-19 4.33334e-19 2.67186e-08 -2.56509e-08 1.35313e-08 1 4.33334e-19 2.67186e-08 -2.56509e-08 1.35313e-08 1 2.67186e-08 -2.56509e-08 1.35313e-08 4193.4 -51.5865 -1012.01 3943.71 20.0933 4236.64 +EDGE_SE3:QUAT 1522 1573 -4.00173 10.3355 -5.58859 0.0338331 -0.113616 0.111397 0.98668 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4224.15 19.7377 -983.492 3946.65 -51.3679 4179.09 +EDGE_SE3:QUAT 1523 1572 -3.85826 -10.2176 -5.07006 -0.0546319 -0.0820795 0.0535492 0.993685 1 1.92593e-19 1.92593e-19 -1.7465e-09 2.75651e-08 1.77214e-09 1 1.92593e-19 -1.7465e-09 2.75651e-08 1.77214e-09 1 -1.7465e-09 2.75651e-08 1.77214e-09 4084.32 26.0149 -628.154 3978.23 -25.8233 4084.79 +EDGE_SE3:QUAT 1524 1574 -3.58243 -0.360381 -5.07368 -0.0449643 0.139823 -0.110162 0.983001 1 9.62965e-19 9.62965e-19 2.12103e-08 -5.81017e-08 -6.67221e-10 1 9.62965e-19 2.12103e-08 -5.81017e-08 -6.67221e-10 1 2.12103e-08 -5.81017e-08 -6.67221e-10 4271.8 -78.9189 1095.17 3944 -90.9448 4231.34 +EDGE_SE3:QUAT 1523 1574 -3.94223 10.1288 -5.33535 0.0197734 -0.0383975 0.0989858 0.994151 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4025.12 0.535607 -327.821 3993.35 -16.0305 3987.49 +EDGE_SE3:QUAT 1524 1573 -3.64491 -10.2845 -5.09274 -0.0534322 0.0262313 -0.0179683 0.998065 1 6.01853e-20 6.01853e-20 -1.37243e-08 7.2126e-09 4.20552e-11 1 6.01853e-20 -1.37243e-08 7.2126e-09 4.20552e-11 1 -1.37243e-08 7.2126e-09 4.20552e-11 3998.33 -5.4783 197.752 3997.7 -2.55715 4008.46 +EDGE_SE3:QUAT 1525 1575 -3.33026 -0.230459 -5.00329 0.0122853 -0.0318991 0.0756241 0.99655 1 1.92593e-19 1.92593e-19 -9.28554e-10 2.0451e-10 2.77206e-08 1 1.92593e-19 -9.28554e-10 2.0451e-10 2.77206e-08 1 -9.28554e-10 2.0451e-10 2.77206e-08 4016.89 0.29937 -265.095 3995.64 -9.92936 3994.62 +EDGE_SE3:QUAT 1524 1575 -4.31795 10.3593 -5.42122 -0.0243344 -0.0636199 0.209653 0.975401 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4040.63 20.3561 -419.016 3993.39 -43.9017 3867.18 +EDGE_SE3:QUAT 1525 1574 -3.7546 -10.2186 -5.04891 -0.0382571 -0.038747 -0.151841 0.986904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.08 0.267638 -370.269 3991.35 28.3009 3941.71 +EDGE_SE3:QUAT 1526 1576 -3.10594 -0.16099 -5.24551 -0.122911 -0.016785 0.0783242 0.98918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3939.24 -1.41849 -16.0993 3999.98 0.859846 3975.13 +EDGE_SE3:QUAT 1525 1576 -4.31287 10.317 -5.50863 -0.0755669 0.0520444 -0.0124339 0.995704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.73 -16.307 404.929 3990.45 -7.26869 4039.95 +EDGE_SE3:QUAT 1526 1575 -3.80879 -10.3985 -5.15826 0.0658554 -0.0120348 -0.102858 0.992441 1 3.85186e-19 3.85186e-19 -2.75945e-08 1.01652e-09 -2.75945e-08 1 3.85186e-19 -2.75945e-08 1.01652e-09 -2.75945e-08 1 -2.75945e-08 1.01652e-09 -2.75945e-08 3982.51 0.43068 -13.6416 3999.99 -0.705956 3957.54 +EDGE_SE3:QUAT 1527 1577 -3.20989 0.145957 -5.21189 0.14395 -0.00707772 0.00439905 0.98955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3918.09 -4.62548 -62.3775 3999.76 0.0621462 4000.89 +EDGE_SE3:QUAT 1526 1577 -3.53876 10.103 -5.53307 0.0521246 0.0911745 2.30815e-05 0.99447 1 4.81482e-20 4.81482e-20 1.40331e-08 1.35967e-10 1.27943e-09 1 4.81482e-20 1.40331e-08 1.35967e-10 1.27943e-09 1 1.40331e-08 1.35967e-10 1.27943e-09 4124.37 21.1803 747.834 3967.51 10.7822 4135.24 +EDGE_SE3:QUAT 1527 1576 -4.23962 -10.1768 -5.37087 0.0855537 -0.0328489 0.00432117 0.995783 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.25 -11.3891 -265.341 3995.74 1.67494 4017.45 +EDGE_SE3:QUAT 1528 1578 -3.33948 -0.0649862 -5.2357 -0.142827 -0.0119186 -0.203606 0.968505 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.95 29.2072 -426.079 3983.46 48.6944 3876.73 +EDGE_SE3:QUAT 1527 1578 -3.96723 10.4741 -5.28482 0.270278 0.121596 -0.0126322 0.954989 1 1.92593e-19 1.92593e-19 1.48594e-09 -2.64669e-08 7.63943e-09 1 1.92593e-19 1.48594e-09 -2.64669e-08 7.63943e-09 1 1.48594e-09 -2.64669e-08 7.63943e-09 3920.39 140.714 948.18 3970.75 88.6051 4211.96 +EDGE_SE3:QUAT 1528 1577 -3.63567 -10.1924 -5.28792 -0.185253 0.0983131 -0.0318525 0.977242 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.99 -72.3144 690.65 3980.55 -47.2089 4111.21 +EDGE_SE3:QUAT 1529 1579 -3.74824 -0.224562 -5.56553 0.0775121 -0.0102145 0.0544391 0.995452 1 1.95602e-19 1.95602e-19 -2.78253e-08 2.0038e-09 2.48364e-10 1 1.95602e-19 -2.78253e-08 2.0038e-09 2.48364e-10 1 -2.78253e-08 2.0038e-09 2.48364e-10 3980.2 -5.43566 -131.097 3998.67 -3.60449 3992.37 +EDGE_SE3:QUAT 1528 1579 -4.35572 10.1209 -5.56054 -0.00909984 -0.0125414 0.132536 0.991057 1 3.00927e-21 3.00927e-21 3.43918e-09 4.60769e-10 -3.36852e-11 1 3.00927e-21 3.43918e-09 4.60769e-10 -3.36852e-11 1 3.43918e-09 4.60769e-10 -3.36852e-11 4001.4 0.734496 -83.4096 3999.66 -5.1819 3931.46 +EDGE_SE3:QUAT 1529 1578 -4.1189 -10.4275 -4.53677 0.0197599 -0.116538 0.0546463 0.991485 1 2.52778e-19 2.52778e-19 -6.82063e-09 2.70539e-08 -1.35107e-08 1 2.52778e-19 -6.82063e-09 2.70539e-08 -1.35107e-08 1 -6.82063e-09 2.70539e-08 -1.35107e-08 4229.31 8.14398 -988.338 3944.94 -24.0347 4218.93 +EDGE_SE3:QUAT 1530 1580 -3.43087 -0.0211212 -5.47167 0.225444 -0.0502477 0.00715752 0.972933 1 7.70372e-19 7.70372e-19 5.42807e-08 -8.75622e-10 -2.69318e-09 1 7.70372e-19 5.42807e-08 -8.75622e-10 -2.69318e-09 1 5.42807e-08 -8.75622e-10 -2.69318e-09 3835.03 -44.6891 -393.703 3992.79 12.1202 4038.13 +EDGE_SE3:QUAT 1529 1580 -3.88809 10.4937 -5.19462 0.108125 0.0720619 0.0831268 0.988031 1 2.40741e-19 2.40741e-19 2.6251e-08 1.64165e-08 -2.22769e-10 1 2.40741e-19 2.6251e-08 1.64165e-08 -2.22769e-10 1 2.6251e-08 1.64165e-08 -2.22769e-10 4004.38 30.9117 457.569 3990.98 27.6857 4023.51 +EDGE_SE3:QUAT 1530 1579 -3.83326 -10.0959 -4.79814 0.109446 -0.0307848 -0.131348 0.984795 1 7.70372e-19 7.70372e-19 -3.40508e-11 6.31437e-09 5.46682e-08 1 7.70372e-19 -3.40508e-11 6.31437e-09 5.46682e-08 1 -3.40508e-11 6.31437e-09 5.46682e-08 3952.24 -0.81956 -66.1834 4000.13 0.786649 3931.15 +EDGE_SE3:QUAT 1531 1581 -3.69194 0.0659816 -5.27378 -0.108141 0.0920993 0.186766 0.972081 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4176.82 -2.94601 972.88 3944.86 73.6654 4084.07 +EDGE_SE3:QUAT 1530 1581 -4.19555 10.2836 -5.3064 0.0242389 0.214999 -0.0916866 0.971999 1 7.52316e-22 7.52316e-22 1.86058e-09 -1.71974e-10 4.12949e-10 1 7.52316e-22 1.86058e-09 -1.71974e-10 4.12949e-10 1 1.86058e-09 -1.71974e-10 4.12949e-10 4860.43 -92.6796 2048.3 3821.01 -107.897 4829.16 +EDGE_SE3:QUAT 1531 1580 -3.9514 -10.2114 -5.1815 -0.0673843 0.0812077 -0.0594946 0.992635 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4071.11 -29.4768 604.605 3980.49 -28.1356 4075.12 +EDGE_SE3:QUAT 1532 1582 -3.23943 -0.0681138 -5.42063 -0.00586786 0.22033 -0.168576 0.96073 1 4.81482e-20 4.81482e-20 -1.46447e-08 2.88625e-09 -3.11322e-09 1 4.81482e-20 -1.46447e-08 2.88625e-09 -3.11322e-09 1 -1.46447e-08 2.88625e-09 -3.11322e-09 4797.87 -239.778 1957.8 3871.37 -256.702 4684.34 +EDGE_SE3:QUAT 1531 1582 -3.99538 10.3307 -5.53455 -0.0155074 0.0805224 0.00957144 0.996586 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4105.33 -3.93513 660.665 3973.93 0.881083 4105.93 +EDGE_SE3:QUAT 1532 1581 -3.86182 -10.4514 -4.98265 -0.150901 0.0211126 -0.136887 0.978798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3908.91 12.7339 -82.5609 3998.22 11.5513 3925.04 +EDGE_SE3:QUAT 1533 1583 -3.41337 0.0956716 -5.23319 -0.221742 0.0478674 0.0279563 0.973528 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3849.29 -48.9677 431.267 3989.98 -8.6453 4042.84 +EDGE_SE3:QUAT 1532 1583 -4.4772 10.4027 -5.3136 0.0400055 -0.00941069 0.0271492 0.998786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.53 -1.77487 -88.0757 3999.47 -1.14565 3998.99 +EDGE_SE3:QUAT 1533 1582 -3.93133 -10.2787 -5.04385 0.0883254 -0.0891508 0.0282297 0.991692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4107.1 -30.761 -756.564 3966.63 6.72977 4135.12 +EDGE_SE3:QUAT 1534 1584 -3.25602 -0.193063 -5.51965 0.0985907 0.0494194 0.0846323 0.99029 1 1.92593e-19 1.92593e-19 2.75564e-08 2.58825e-09 8.65671e-10 1 1.92593e-19 2.75564e-08 2.58825e-09 8.65671e-10 1 2.75564e-08 2.58825e-09 8.65671e-10 3981.23 15.6856 287.06 3996.66 14.4129 3991.46 +EDGE_SE3:QUAT 1533 1584 -4.52405 10.5564 -5.11436 0.00108313 -0.0642242 0.142349 0.98773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.21 13.6304 -506.921 3986.05 -37.1971 3982.17 +EDGE_SE3:QUAT 1534 1583 -3.93854 -10.3642 -5.12394 0.199802 0.0489386 -0.0304874 0.978138 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3889 45.1491 444.034 3988.87 7.04835 4044.97 +EDGE_SE3:QUAT 1535 1585 -3.75284 0.208201 -5.12629 -0.067156 0.0212565 0.0132658 0.997428 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.03 -6.01857 179.846 3997.95 0.423455 4007.36 +EDGE_SE3:QUAT 1534 1585 -4.34795 9.94754 -5.83757 0.0674215 0.189351 0.0195765 0.979396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4596.32 97.7775 1684 3869.65 90.0174 4612.97 +EDGE_SE3:QUAT 1535 1584 -4.0382 -10.2865 -4.84701 -0.0382972 0.0579325 -0.121092 0.990209 1 4.81482e-20 4.81482e-20 1.38107e-08 -1.75607e-09 6.52442e-10 1 4.81482e-20 1.38107e-08 -1.75607e-09 6.52442e-10 1 1.38107e-08 -1.75607e-09 6.52442e-10 4033.6 -15.313 400.137 3992.09 -26.082 3980.82 +EDGE_SE3:QUAT 1536 1586 -3.52809 0.161507 -5.46332 -0.0172324 0.106928 0.079906 0.990901 1 1.95602e-19 1.95602e-19 -6.59835e-09 -2.74853e-10 -2.85485e-08 1 1.95602e-19 -6.59835e-09 -2.74853e-10 -2.85485e-08 1 -6.59835e-09 -2.74853e-10 -2.85485e-08 4192.05 14.9046 900.159 3954.25 35.4203 4167.7 +EDGE_SE3:QUAT 1535 1586 -4.07335 10.4453 -5.11663 0.078897 -0.213463 0.122203 0.966062 1 4.81482e-20 4.81482e-20 1.49061e-08 1.50343e-09 -3.47286e-09 1 4.81482e-20 1.49061e-08 1.50343e-09 -3.47286e-09 1 1.49061e-08 1.50343e-09 -3.47286e-09 4903.43 54.5908 -2138.98 3805.71 -82.7133 4868.6 +EDGE_SE3:QUAT 1536 1585 -4.06471 -10.0669 -4.86698 0.0771653 0.129741 0.0387498 0.987781 1 1.92593e-19 1.92593e-19 2.82876e-08 1.71943e-09 3.48025e-09 1 1.92593e-19 2.82876e-08 1.71943e-09 3.48025e-09 1 2.82876e-08 1.71943e-09 3.48025e-09 4232.11 62.3068 1043.87 3944.17 54.746 4249.92 +EDGE_SE3:QUAT 1537 1587 -3.0205 -0.221466 -4.93176 0.034851 -0.00165831 -0.0800795 0.996178 1 2.40741e-19 2.40741e-19 1.37159e-08 -2.07248e-09 -2.75952e-08 1 2.40741e-19 1.37159e-08 -2.07248e-09 -2.75952e-08 1 1.37159e-08 -2.07248e-09 -2.75952e-08 3995.21 0.542976 20.2052 3999.94 -1.25605 3974.42 +EDGE_SE3:QUAT 1536 1587 -3.85843 10.0235 -5.23168 0.0240242 0.110934 -0.0978619 0.988706 1 3.88195e-19 3.88195e-19 2.92254e-09 2.70511e-08 -2.7822e-08 1 3.88195e-19 2.92254e-09 2.70511e-08 -2.7822e-08 1 2.92254e-09 2.70511e-08 -2.7822e-08 4209.51 -18.814 944.531 3950.39 -44.9019 4173.51 +EDGE_SE3:QUAT 1537 1586 -4.01613 -10.1942 -4.86114 -0.149103 -0.0721896 -0.0718072 0.983565 1 4.81482e-20 4.81482e-20 1.26252e-09 1.95868e-09 -1.3856e-08 1 4.81482e-20 1.26252e-09 1.95868e-09 -1.3856e-08 1 1.26252e-09 1.95868e-09 -1.3856e-08 4029.82 46.1607 -699.868 3970.16 2.68391 4098.12 +EDGE_SE3:QUAT 1538 1588 -3.65966 0.170104 -5.33579 -0.0974262 0.119881 0.21112 0.965176 1 1.92593e-19 1.92593e-19 2.7959e-08 5.53382e-09 4.29288e-09 1 1.92593e-19 2.7959e-08 5.53382e-09 4.29288e-09 1 2.7959e-08 5.53382e-09 4.29288e-09 4301.74 33.0203 1214.6 3923.78 110.452 4161.42 +EDGE_SE3:QUAT 1537 1588 -4.54902 9.96586 -5.35144 0.0905543 0.0135143 0.151884 0.984149 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.3 -5.21016 -58.5314 3999.17 -8.74798 3907.83 +EDGE_SE3:QUAT 1538 1587 -4.13414 -10.3173 -4.82356 -0.0683488 0.0308678 -0.170748 0.982457 1 9.62965e-19 9.62965e-19 2.75965e-08 -8.97025e-09 5.47102e-08 1 9.62965e-19 2.75965e-08 -8.97025e-09 5.47102e-08 1 2.75965e-08 -8.97025e-09 5.47102e-08 3983.01 -2.68478 97.4431 4000.06 -4.43378 3885.08 +EDGE_SE3:QUAT 1539 1589 -3.6905 0.275848 -5.01625 -0.105581 -0.076477 0.0450841 0.99044 1 4.81482e-20 4.81482e-20 -9.08395e-10 -1.58603e-09 1.38741e-08 1 4.81482e-20 -9.08395e-10 -1.58603e-09 1.38741e-08 1 -9.08395e-10 -1.58603e-09 1.38741e-08 4029.73 34.8647 -550.977 3984.56 -25.2641 4066.19 +EDGE_SE3:QUAT 1538 1589 -4.26952 9.85177 -5.32746 0.0021716 0.00161177 0.135222 0.990812 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000 0.0134441 9.06121 4000 0.525246 3926.88 +EDGE_SE3:QUAT 1539 1588 -4.48796 -10.1069 -5.16256 0.0771084 -0.0701044 -0.243643 0.96425 1 2.40741e-19 2.40741e-19 3.03315e-08 6.31199e-09 -2.08023e-09 1 2.40741e-19 3.03315e-08 6.31199e-09 -2.08023e-09 1 3.03315e-08 6.31199e-09 -2.08023e-09 3994.53 -19.2288 -289.936 4000.52 28.3608 3780.87 +EDGE_SE3:QUAT 1540 1590 -3.62276 0.205087 -5.09461 0.116438 -0.145511 0.0108796 0.982421 1 1.95602e-19 1.95602e-19 -2.79498e-08 2.58642e-10 6.14628e-10 1 1.95602e-19 -2.79498e-08 2.58642e-10 6.14628e-10 1 -2.79498e-08 2.58642e-10 6.14628e-10 4301.7 -82.7858 -1245.2 3922.37 57.0838 4355.45 +EDGE_SE3:QUAT 1539 1590 -3.98097 10.3409 -5.39776 0.0794385 -0.0871107 0.106981 0.987247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4131.79 -11.6228 -808.255 3960.79 -30.5214 4111.25 +EDGE_SE3:QUAT 1540 1589 -4.18996 -10.6442 -5.43679 0.144195 0.0972471 -0.253537 0.951562 1 1.92593e-19 1.92593e-19 -2.75509e-08 6.43255e-09 -4.41423e-09 1 1.92593e-19 -2.75509e-08 6.43255e-09 -4.41423e-09 1 -2.75509e-08 6.43255e-09 -4.41423e-09 4242.91 -7.67772 1189.94 3921.79 -125.106 4068.95 +EDGE_SE3:QUAT 1541 1591 -3.37027 0.322477 -4.95525 0.0742463 -0.0876176 -0.0381237 0.992652 1 3.85186e-19 3.85186e-19 -2.65082e-08 2.8981e-08 -2.27006e-12 1 3.85186e-19 -2.65082e-08 2.8981e-08 -2.27006e-12 1 -2.65082e-08 2.8981e-08 -2.27006e-12 4088.71 -33.0834 -674.977 3975.11 26.4981 4104.95 +EDGE_SE3:QUAT 1540 1591 -4.27305 10.3516 -5.00392 0.183154 -0.0619712 0.0715664 0.978515 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3964.25 -55.487 -635.941 3975.16 -0.122211 4077.95 +EDGE_SE3:QUAT 1541 1590 -3.64974 -10.6803 -5.19975 -0.134678 -0.0817191 -0.041889 0.986625 1 7.70372e-19 7.70372e-19 -5.56424e-08 1.06718e-09 5.06396e-09 1 7.70372e-19 -5.56424e-08 1.06718e-09 5.06396e-09 1 -5.56424e-08 1.06718e-09 5.06396e-09 4053.66 45.6385 -721.718 3969.8 -8.66356 4119.19 +EDGE_SE3:QUAT 1542 1592 -3.66377 -0.354748 -5.1183 -0.101076 0.0460551 0.0194974 0.993621 1 1.95602e-19 1.95602e-19 -2.78799e-08 7.15286e-11 -4.83055e-09 1 1.95602e-19 -2.78799e-08 7.15286e-11 -4.83055e-09 1 -2.78799e-08 7.15286e-11 -4.83055e-09 3996.68 -19.3629 389.385 3990.76 -1.68597 4036.03 +EDGE_SE3:QUAT 1541 1592 -4.25718 10.0125 -5.24656 -0.0987934 -0.0738933 0.110572 0.986181 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.19 30.0117 -445.44 3992.28 -31.4292 3999.33 +EDGE_SE3:QUAT 1542 1591 -4.15713 -10.4586 -5.25639 -0.0226676 0.0872912 -0.186434 0.978319 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4092.44 -36.3619 623.377 3983.31 -63.0593 3955.46 +EDGE_SE3:QUAT 1543 1593 -3.90301 0.370317 -5.21995 -0.100416 0.106005 -0.00133145 0.989281 1 1.92593e-19 1.92593e-19 -2.80736e-08 6.49256e-10 -2.93835e-09 1 1.92593e-19 -2.80736e-08 6.49256e-10 -2.93835e-09 1 -2.80736e-08 6.49256e-10 -2.93835e-09 4139.1 -48.7495 866.045 3959.18 -28.6013 4179.43 +EDGE_SE3:QUAT 1542 1593 -4.10935 10.3277 -5.19104 0.139584 -0.0635843 0.0673475 0.985869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4014.35 -38.5585 -615.049 3976.45 -4.47535 4074.14 +EDGE_SE3:QUAT 1543 1592 -3.97661 -9.99287 -5.29004 0.130224 -0.00461231 -0.00851794 0.991437 1 7.70372e-19 7.70372e-19 -5.50367e-08 5.22941e-10 1.25213e-10 1 7.70372e-19 -5.50367e-08 5.22941e-10 1.25213e-10 1 -5.50367e-08 5.22941e-10 1.25213e-10 3932.29 -1.17733 -22.8002 3999.98 0.109791 3999.83 +EDGE_SE3:QUAT 1544 1594 -3.1885 -0.257036 -5.06274 0.0736118 0.179084 0.123792 0.973235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4411.87 156.668 1388.5 3928.19 163.895 4372.24 +EDGE_SE3:QUAT 1543 1594 -4.21604 10.0407 -5.67987 0.0144413 -0.172202 0.0346032 0.984348 1 3.00927e-21 3.00927e-21 3.63188e-09 1.16485e-10 -6.37441e-10 1 3.00927e-21 3.63188e-09 1.16485e-10 -6.37441e-10 1 3.63188e-09 1.16485e-10 -6.37441e-10 4522.33 14.0294 -1538.29 3881.11 -23.2099 4518.37 +EDGE_SE3:QUAT 1544 1593 -4.14518 -10.5385 -5.07784 -0.0685492 0.12796 -0.0686892 0.98702 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4216.63 -64.9741 999.037 3950.5 -65.0007 4216.55 +EDGE_SE3:QUAT 1545 1595 -3.69369 -0.0475397 -5.55703 -0.149751 -0.0263523 0.00689433 0.988349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3919.47 14.0756 -191.902 3998.09 -2.82582 4008.98 +EDGE_SE3:QUAT 1544 1595 -4.26158 10.0848 -5.53332 0.0365595 -0.0586036 0.196021 0.978164 1 1.20371e-20 1.20371e-20 6.84886e-09 1.34991e-09 -4.76727e-10 1 1.20371e-20 6.84886e-09 1.34991e-09 -4.76727e-10 1 6.84886e-09 1.34991e-09 -4.76727e-10 4064.63 9.62624 -533.723 3983.96 -52.7098 3916.27 +EDGE_SE3:QUAT 1545 1594 -3.96421 -10.1245 -5.3637 -0.0589329 0.0655517 -0.071626 0.993529 1 2.40741e-19 2.40741e-19 -2.66645e-08 1.6e-08 -6.16883e-10 1 2.40741e-19 -2.66645e-08 1.6e-08 -6.16883e-10 1 -2.66645e-08 1.6e-08 -6.16883e-10 4041 -20.2179 472.289 3988.17 -22.0946 4034.37 +EDGE_SE3:QUAT 1546 1596 -3.38212 0.10674 -5.59776 -0.112821 0.000265201 -0.0358696 0.992968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3949.55 3.49454 -46.0367 3999.76 1.06408 3995.32 +EDGE_SE3:QUAT 1545 1596 -4.30755 10.2095 -5.60951 0.135526 0.0838378 -0.368703 0.915785 1 1.92593e-19 1.92593e-19 2.65333e-08 -9.9173e-09 4.39902e-09 1 1.92593e-19 2.65333e-08 -9.9173e-09 4.39902e-09 1 2.65333e-08 -9.9173e-09 4.39902e-09 4233.79 -59.2983 1151.97 3939.31 -215.476 3763.49 +EDGE_SE3:QUAT 1546 1595 -3.9008 -10.1963 -5.06638 -0.0912838 0.286281 0.0751748 0.95082 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5787.71 -51.3521 3255.83 3660.92 -52.6031 5798.44 +EDGE_SE3:QUAT 1547 1597 -3.55636 0.144508 -5.20844 0.149462 0.0303565 -0.0417207 0.98742 1 3.12964e-18 3.12964e-18 -1.09384e-07 5.49128e-09 9.15179e-09 1 3.12964e-18 -1.09384e-07 5.49128e-09 9.15179e-09 1 -1.09384e-07 5.49128e-09 9.15179e-09 3934.38 23.7155 309.595 3993.66 -2.08094 4016.78 +EDGE_SE3:QUAT 1546 1597 -4.26772 10.2479 -4.82405 0.0275443 -0.0186113 0.0709152 0.996928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.27 -1.73335 -171.247 3998.05 -6.07388 3987.19 +EDGE_SE3:QUAT 1547 1596 -4.2703 -10.1414 -5.327 0.0245918 -0.110674 -0.143149 0.983186 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4168.22 -50.7578 -844.294 3965.98 72.8126 4088.67 +EDGE_SE3:QUAT 1548 1598 -3.25344 0.124228 -5.20385 -0.0755311 0.0175517 0.0547346 0.995485 1 2.0463e-19 2.0463e-19 2.80184e-08 -5.47749e-09 1.99995e-10 1 2.0463e-19 2.80184e-08 -5.47749e-09 1.99995e-10 1 2.80184e-08 -5.47749e-09 1.99995e-10 3985.97 -7.09716 188.325 3997.46 4.71708 3996.81 +EDGE_SE3:QUAT 1547 1598 -3.69594 9.96841 -5.21802 0.00325812 0.111741 0.0109247 0.993672 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4207.17 5.19902 933.707 3950.19 6.81189 4206.74 +EDGE_SE3:QUAT 1548 1597 -4.23332 -9.6961 -5.06052 -0.184074 0.0655866 0.0345678 0.980112 1 9.75002e-19 9.75002e-19 5.47144e-08 -2.54659e-08 -7.76887e-09 1 9.75002e-19 5.47144e-08 -2.54659e-08 -7.76887e-09 1 5.47144e-08 -2.54659e-08 -7.76887e-09 3947.75 -53.7067 583.19 3980.99 -11.8646 4078.5 +EDGE_SE3:QUAT 1549 1599 -3.33409 -0.00981256 -5.3924 -0.0635402 -0.057338 0.054705 0.994828 1 1.92593e-19 1.92593e-19 2.77601e-08 1.72713e-09 -1.38252e-09 1 1.92593e-19 2.77601e-08 1.72713e-09 -1.38252e-09 1 2.77601e-08 1.72713e-09 -1.38252e-09 4026.55 16.8453 -415.824 3990.59 -15.6217 4030.73 +EDGE_SE3:QUAT 1548 1599 -4.56044 9.99835 -5.50563 0.00641987 -0.0962741 0.0462743 0.994258 1 7.52316e-22 7.52316e-22 1.7575e-09 8.11262e-11 -1.70496e-10 1 7.52316e-22 1.7575e-09 8.11262e-11 -1.70496e-10 1 1.7575e-09 8.11262e-11 -1.70496e-10 4152.81 7.99596 -797.062 3963.11 -18.7682 4144.41 +EDGE_SE3:QUAT 1549 1598 -4.23302 -10.2577 -5.23697 -0.0178315 0.182701 -0.0676485 0.980676 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4567.4 -81.5812 1611.92 3878.06 -90.0541 4550.37 +EDGE_SE3:QUAT 1550 1600 -3.88121 -0.0914594 -5.23381 -0.0428702 0.0690679 -0.0424458 0.995786 1 3.85186e-19 3.85186e-19 2.65323e-08 -2.89926e-08 4.56871e-10 1 3.85186e-19 2.65323e-08 -2.89926e-08 4.56871e-10 1 2.65323e-08 -2.89926e-08 4.56871e-10 4063.09 -16.4805 535.562 3983.52 -16.4095 4063.24 +EDGE_SE3:QUAT 1549 1600 -4.1347 10.2698 -5.34395 0.101068 0.0287203 0.0984905 0.989576 1 1.92593e-19 1.92593e-19 2.74743e-08 2.84114e-09 2.17566e-10 1 1.92593e-19 2.74743e-08 2.84114e-09 2.17566e-10 1 2.74743e-08 2.84114e-09 2.17566e-10 3961.43 3.84034 104.945 3999.87 3.77582 3963.49 +EDGE_SE3:QUAT 1550 1599 -4.31269 -10.3846 -4.98421 0.0700706 -0.188034 -0.191461 0.960768 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4386.48 -200.152 -1343.97 3956.35 213.62 4259.49 +EDGE_SE3:QUAT 1551 1601 -3.602 0.130354 -5.09385 0.0182065 0.131048 -0.0416489 0.990333 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4291.92 -6.76946 1122.03 3930.66 -19.4699 4286.3 +EDGE_SE3:QUAT 1550 1601 -4.39821 9.82214 -5.12679 -0.0943397 -0.0159426 -0.0408887 0.994572 1 1.92593e-19 1.92593e-19 -2.76304e-08 1.03326e-09 6.46889e-10 1 1.92593e-19 -2.76304e-08 1.03326e-09 6.46889e-10 1 -2.76304e-08 1.03326e-09 6.46889e-10 3971.72 8.4277 -171.804 3997.89 2.89568 4000.63 +EDGE_SE3:QUAT 1551 1600 -3.75938 -10.3593 -5.12815 0.162017 0.207623 -0.0899107 0.960499 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4805 130.988 2113.82 3814.53 93.1521 4877.66 +EDGE_SE3:QUAT 1552 1602 -3.50099 -0.000448317 -4.99029 -0.00333929 -0.0329704 0.131695 0.990736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.83 3.65814 -252.558 3996.46 -16.6273 3946.5 +EDGE_SE3:QUAT 1551 1602 -4.13309 10.05 -5.15891 -0.0179014 -0.0422071 0.132818 0.99008 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.29 7.45017 -301.738 3995.31 -20.1847 3952.01 +EDGE_SE3:QUAT 1552 1601 -4.57931 -9.95637 -5.16706 -0.00111197 -0.0378777 -0.204172 0.978201 1 7.52316e-22 7.52316e-22 1.70147e-09 -3.56018e-10 -6.11508e-11 1 7.52316e-22 1.70147e-09 -3.56018e-10 -6.11508e-11 1 1.70147e-09 -3.56018e-10 -6.11508e-11 4020.62 -6.47674 -288.186 3996 29.2478 3853.88 +EDGE_SE3:QUAT 1553 1603 -3.7061 -0.319181 -5.32474 0.00595054 0.0374779 -0.109849 0.993224 1 4.23178e-22 4.23178e-22 1.29597e-09 -1.43153e-10 4.94161e-11 1 4.23178e-22 1.29597e-09 -1.43153e-10 4.94161e-11 1 1.29597e-09 -1.43153e-10 4.94161e-11 4022.79 -2.87824 303.714 3994.54 -16.7711 3974.66 +EDGE_SE3:QUAT 1552 1603 -4.24161 10.2326 -5.30246 0.189915 0.0384284 0.0143389 0.980943 1 8.30557e-19 8.30557e-19 -5.39763e-08 -1.3819e-08 7.7936e-09 1 8.30557e-19 -5.39763e-08 -1.3819e-08 7.7936e-09 1 -5.39763e-08 -1.3819e-08 7.7936e-09 3872.41 23.8123 259.752 3997.07 7.05898 4015.86 +EDGE_SE3:QUAT 1553 1602 -4.06766 -10.247 -5.26674 0.0906554 -0.123921 0.072797 0.985457 1 9.62965e-19 9.62965e-19 3.11863e-08 -5.33091e-08 2.73781e-10 1 9.62965e-19 3.11863e-08 -5.33091e-08 2.73781e-10 1 3.11863e-08 -5.33091e-08 2.73781e-10 4259.44 -28.4771 -1120.23 3930.17 -8.59647 4271.11 +EDGE_SE3:QUAT 1554 1604 -3.51334 -0.455482 -5.18459 -0.0457902 -0.0719568 0.0959157 0.991729 1 4.33334e-19 4.33334e-19 1.27405e-08 3.06057e-08 -2.69744e-08 1 4.33334e-19 1.27405e-08 3.06057e-08 -2.69744e-08 1 1.27405e-08 3.06057e-08 -2.69744e-08 4058.03 22.2614 -520.281 3985.94 -30.0496 4029.62 +EDGE_SE3:QUAT 1553 1604 -4.2621 9.98585 -5.28397 0.0698283 0.0307236 -0.025504 0.99676 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.12 8.96263 266.127 3995.48 -1.71764 4015.02 +EDGE_SE3:QUAT 1554 1603 -3.99873 -9.99894 -5.13867 -0.0118705 -0.0682576 0.148794 0.986438 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4064.3 18.4052 -513.827 3986.49 -40.2242 3976.3 +EDGE_SE3:QUAT 1555 1605 -3.62192 0.158784 -5.09439 -0.0813242 -0.0369222 -0.117609 0.989036 1 3.85186e-19 3.85186e-19 2.91093e-08 -1.10934e-09 -2.91093e-08 1 3.85186e-19 2.91093e-08 -1.10934e-09 -2.91093e-08 1 2.91093e-08 -1.10934e-09 -2.91093e-08 4013.63 11.802 -403.66 3988.73 21.8962 3984.76 +EDGE_SE3:QUAT 1554 1605 -4.35202 9.88766 -5.10818 0.0367965 0.296739 -0.0405779 0.953386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5910.35 -14.1576 3366.49 3645.1 -11.7377 5909.18 +EDGE_SE3:QUAT 1555 1604 -3.94311 -10.1379 -4.87172 -0.0701566 -0.143661 0.0281655 0.986735 1 1.92593e-19 1.92593e-19 2.85001e-08 1.43854e-09 -3.98005e-09 1 1.92593e-19 2.85001e-08 1.43854e-09 -3.98005e-09 1 2.85001e-08 1.43854e-09 -3.98005e-09 4309.62 65.1887 -1194.12 3927.26 -56.8996 4326.13 +EDGE_SE3:QUAT 1556 1606 -3.68228 -0.0895068 -5.2587 0.174708 0.0513591 -0.149501 0.971848 1 9.62965e-19 9.62965e-19 -5.13294e-08 3.4058e-08 -9.74712e-09 1 9.62965e-19 -5.13294e-08 3.4058e-08 -9.74712e-09 1 -5.13294e-08 3.4058e-08 -9.74712e-09 3996.41 49.9372 702.779 3965.63 -35.4865 4029.1 +EDGE_SE3:QUAT 1555 1606 -4.37984 9.78836 -5.08516 0.267915 -0.105055 0.326385 0.900365 1 1.54074e-18 1.54074e-18 6.88091e-08 -3.67388e-08 -5.36746e-09 1 1.54074e-18 6.88091e-08 -3.67388e-08 -5.36746e-09 1 6.88091e-08 -3.67388e-08 -5.36746e-09 4456.12 -37.5178 -1884.17 3823.8 -180.395 4317.12 +EDGE_SE3:QUAT 1556 1605 -4.05892 -9.99595 -5.54889 0.130604 -0.0294227 -0.191934 0.972234 1 1.54074e-18 1.54074e-18 -5.27095e-08 1.8032e-08 5.27095e-08 1 1.54074e-18 -5.27095e-08 1.8032e-08 5.27095e-08 1 -5.27095e-08 1.8032e-08 5.27095e-08 3930.53 11.8625 73.5061 3997.98 -17.3659 3851.4 +EDGE_SE3:QUAT 1557 1607 -3.72256 0.0349189 -5.09513 0.169172 -0.0541546 -0.0512602 0.982762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3909.19 -25.6832 -312.035 3996.62 14.4886 4013.15 +EDGE_SE3:QUAT 1556 1607 -4.20322 9.70801 -5.66886 -0.0658789 0.0463535 0.146643 0.985904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.57 -5.91387 477.092 3985.12 33.4358 3969.91 +EDGE_SE3:QUAT 1557 1606 -3.73846 -10.1785 -5.25265 0.0229846 -0.103501 -0.0528775 0.992957 1 6.01853e-20 6.01853e-20 -5.61317e-09 -7.16765e-11 -1.33581e-08 1 6.01853e-20 -5.61317e-09 -7.16765e-11 -1.33581e-08 1 -5.61317e-09 -7.16765e-11 -1.33581e-08 4166.58 -24.4502 -838.622 3960.58 30.4714 4157.51 +EDGE_SE3:QUAT 1558 1608 -3.54512 -0.210701 -4.96619 -0.177089 0.0423151 0.170341 0.968418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.52 -49.0299 675.234 3966.53 45.3369 3992.9 +EDGE_SE3:QUAT 1557 1608 -4.25185 9.89751 -5.19162 0.0533952 0.0594319 0.0575998 0.995138 1 1.44445e-19 1.44445e-19 -1.37375e-08 -1.55398e-08 -1.37896e-08 1 1.44445e-19 -1.37375e-08 -1.55398e-08 -1.37896e-08 1 -1.37375e-08 -1.55398e-08 -1.37896e-08 4036.03 16.0498 438.44 3989.37 16.6583 4034.16 +EDGE_SE3:QUAT 1558 1607 -4.15732 -10.3032 -5.42091 0.171157 0.0286987 -0.189087 0.966503 1 1.58889e-18 1.58889e-18 5.16725e-08 -4.38905e-09 -5.13917e-08 1 1.58889e-18 5.16725e-08 -4.38905e-09 -5.13917e-08 1 5.16725e-08 -4.38905e-09 -5.13917e-08 3966.22 43.8137 592.347 3971.94 -52.2 3940.39 +EDGE_SE3:QUAT 1559 1609 -3.63024 -0.0907207 -5.10694 -0.109939 -0.0224505 0.0709219 0.991151 1 3.88195e-19 3.88195e-19 2.74301e-08 8.60728e-09 -2.72985e-08 1 3.88195e-19 2.74301e-08 8.60728e-09 -2.72985e-08 1 2.74301e-08 8.60728e-09 -2.72985e-08 3953.08 3.02917 -82.4574 3999.91 -2.21313 3981.3 +EDGE_SE3:QUAT 1558 1609 -4.00242 9.88654 -4.86121 -0.0891239 -0.00140915 -0.131555 0.987293 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3973.31 8.05228 -149.373 3997.67 12.4421 3935.85 +EDGE_SE3:QUAT 1559 1608 -4.01302 -9.85265 -5.51226 -0.11666 0.0273882 -0.106427 0.987073 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3945.9 -1.0768 64.2902 4000.08 -1.05182 3955.03 +EDGE_SE3:QUAT 1560 1610 -3.71899 0.0218459 -5.19297 0.0412739 -0.0955236 -0.0744104 0.991784 1 4.81482e-20 4.81482e-20 1.3991e-08 -1.17723e-09 -1.23938e-09 1 4.81482e-20 1.3991e-08 -1.17723e-09 -1.23938e-09 1 1.3991e-08 -1.17723e-09 -1.23938e-09 4125.24 -31.7978 -738.917 3970.57 38.0055 4109.91 +EDGE_SE3:QUAT 1559 1610 -4.12605 9.5362 -5.31307 0.207277 0.0104001 0.0690068 0.97579 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3829.35 -15.2878 -88.8873 3998.64 -4.92651 3982.15 +EDGE_SE3:QUAT 1560 1609 -4.20117 -9.92913 -5.07979 -0.209982 -0.0491747 -0.0977461 0.971563 1 1.92593e-19 1.92593e-19 -2.36288e-09 -5.56135e-09 2.72891e-08 1 1.92593e-19 -2.36288e-09 -5.56135e-09 2.72891e-08 1 -2.36288e-09 -5.56135e-09 2.72891e-08 3915.1 63.0664 -614.257 3974.92 9.26034 4053.25 +EDGE_SE3:QUAT 1561 1611 -3.59459 0.142625 -4.97352 -0.0993629 0.158925 -0.0622463 0.980304 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4322.51 -113.584 1257.52 3930.31 -107.196 4346.51 +EDGE_SE3:QUAT 1560 1611 -4.21029 9.54574 -5.13616 0.0538899 0.0356349 0.0454367 0.996876 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.48 7.81893 254.464 3996.41 6.99211 4007.83 +EDGE_SE3:QUAT 1561 1610 -4.23272 -10.0761 -4.94081 0.0195894 -0.000867304 -0.0654043 0.997666 1 1.20371e-20 1.20371e-20 -6.92271e-09 4.53721e-10 -1.17771e-11 1 1.20371e-20 -6.92271e-09 4.53721e-10 -1.17771e-11 1 -6.92271e-09 4.53721e-10 -1.17771e-11 3998.48 0.132443 8.43701 3999.99 -0.443869 3982.9 +EDGE_SE3:QUAT 1562 1612 -3.76738 -0.235642 -5.28564 -0.0556096 0.100468 0.0253261 0.993062 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4159.67 -19.6241 847.208 3958.37 -2.59524 4169.47 +EDGE_SE3:QUAT 1561 1612 -4.35731 10.3249 -5.56911 0.20339 0.0172419 0.285443 0.936407 1 7.70372e-19 7.70372e-19 -5.24296e-08 -1.50043e-08 5.35185e-09 1 7.70372e-19 -5.24296e-08 -1.50043e-08 5.35185e-09 1 -5.24296e-08 -1.50043e-08 5.35185e-09 3895.59 -62.5234 -534.436 3966.05 -99.4391 3735.15 +EDGE_SE3:QUAT 1562 1611 -3.93884 -10.025 -4.87224 0.0385205 -0.00524727 -0.161167 0.986161 1 8.18567e-19 8.18567e-19 -1.33514e-08 3.92769e-09 5.46592e-08 1 8.18567e-19 -1.33514e-08 3.92769e-09 5.46592e-08 1 -1.33514e-08 3.92769e-09 5.46592e-08 3994.18 1.11019 32.8748 3999.79 -4.69398 3896.22 +EDGE_SE3:QUAT 1563 1613 -3.58274 -0.375069 -5.37668 -0.0540891 -0.0241858 0.11937 0.99108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.23 3.05082 -111.911 3999.65 -5.40345 3945.93 +EDGE_SE3:QUAT 1562 1613 -4.40197 10.1856 -5.46968 -0.00124245 0.261753 -0.057711 0.963407 1 1.20371e-20 1.20371e-20 7.73584e-09 -5.42787e-10 2.08418e-09 1 1.20371e-20 7.73584e-09 -5.42787e-10 2.08418e-09 1 7.73584e-09 -5.42787e-10 2.08418e-09 5350.7 -137.561 2688.37 3738.78 -140.104 5337.38 +EDGE_SE3:QUAT 1563 1612 -4.26197 -10.1547 -5.24109 -0.0154183 -0.0272205 0.139242 0.989764 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.66 3.32972 -186.255 3998.28 -12.5218 3931.06 +EDGE_SE3:QUAT 1564 1614 -3.16154 0.00695333 -5.74807 0.0581907 0.0890974 -0.126455 0.986248 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4143.47 -2.96655 808.083 3961.79 -43.8996 4093.06 +EDGE_SE3:QUAT 1563 1614 -4.10589 10.3774 -5.19955 -0.0748308 0.0265853 0.217363 0.972855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4014.36 -6.79947 388.184 3989.02 45.8494 3847.77 +EDGE_SE3:QUAT 1564 1613 -4.40352 -10.1955 -4.82686 -0.133047 -0.0353672 -0.0319434 0.989963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3955.8 21.8687 -327.48 3993.21 0.470454 4022.52 +EDGE_SE3:QUAT 1565 1615 -3.8309 -0.161853 -5.02041 0.148346 0.0170925 0.0872633 0.98493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3911.4 -5.60101 -21.5955 3999.65 -3.30008 3968.96 +EDGE_SE3:QUAT 1564 1615 -4.43715 9.74624 -5.37607 0.134822 -0.0277489 0.105986 0.984794 1 8.1852e-19 8.1852e-19 -5.6239e-08 8.38499e-09 1.276e-09 1 8.1852e-19 -5.6239e-08 8.38499e-09 1.276e-09 1 -5.6239e-08 8.38499e-09 1.276e-09 3963.26 -25.0924 -384.018 3988.86 -17.3612 3991.03 +EDGE_SE3:QUAT 1565 1614 -4.09543 -9.98387 -4.80209 -0.0266031 0.00360125 0.201369 0.979148 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.09 -1.02282 89.6083 3999.29 11.0637 3839.72 +EDGE_SE3:QUAT 1566 1616 -3.64962 -0.231972 -4.95936 0.00752569 -0.0928431 -0.0393959 0.994873 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4139.21 -11.518 -759.746 3966.47 17.892 4133.23 +EDGE_SE3:QUAT 1565 1616 -4.49274 9.96829 -5.45071 -0.0535484 0.0575348 -0.0518797 0.995556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4033.58 -15.1448 427.086 3989.81 -14.9058 4034.28 +EDGE_SE3:QUAT 1566 1615 -4.34437 -10.094 -5.13911 0.0155573 -0.113034 0.101599 0.988261 1 1.93345e-19 1.93345e-19 -1.48382e-09 -3.89948e-11 2.7962e-08 1 1.93345e-19 -1.48382e-09 -3.89948e-11 2.7962e-08 1 -1.48382e-09 -3.89948e-11 2.7962e-08 4214.02 25.2194 -951.925 3950.37 -49.9724 4173.69 +EDGE_SE3:QUAT 1567 1617 -3.72558 0.166659 -5.17056 -0.106828 0.225256 -0.201374 0.947257 1 7.70372e-19 7.70372e-19 -5.60362e-08 1.57772e-08 -8.99831e-09 1 7.70372e-19 -5.60362e-08 1.57772e-08 -8.99831e-09 1 -5.60362e-08 1.57772e-08 -8.99831e-09 4456.67 -308.963 1518.36 3985.4 -312.642 4340.11 +EDGE_SE3:QUAT 1566 1617 -4.15631 9.83544 -4.86308 0.00258971 -0.144106 0.1838 0.97234 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4319.56 93.5552 -1175.59 3940.77 -128.707 4184.46 +EDGE_SE3:QUAT 1567 1616 -4.38245 -10.0451 -5.02436 -0.046349 -0.0766519 -0.132161 0.987173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4105.65 -4.86214 -685.705 3972.24 41.9093 4044.38 +EDGE_SE3:QUAT 1568 1618 -3.46611 -0.446657 -4.93029 0.116364 -0.0646769 0.0932978 0.986697 1 1.92593e-19 1.92593e-19 2.77369e-08 2.15525e-09 -2.34726e-09 1 1.92593e-19 2.77369e-08 2.15525e-09 -2.34726e-09 1 2.77369e-08 2.15525e-09 -2.34726e-09 4046.81 -28.517 -644.28 3973.55 -16.9267 4066.15 +EDGE_SE3:QUAT 1567 1618 -4.51367 10.5986 -5.47853 0.0742137 0.0935821 0.0241375 0.992548 1 4.81482e-20 4.81482e-20 1.25237e-09 1.1284e-09 1.40025e-08 1 4.81482e-20 1.25237e-09 1.1284e-09 1.40025e-08 1 1.25237e-09 1.1284e-09 1.40025e-08 4110.68 34.5685 740.677 3969.59 24.9526 4130.38 +EDGE_SE3:QUAT 1568 1617 -4.563 -10.0383 -4.98707 0.0430319 0.0146786 -0.0702224 0.996495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.37 2.99107 152.554 3998.35 -5.44473 3986.05 +EDGE_SE3:QUAT 1569 1619 -3.6928 -0.0651808 -5.738 0.195967 0.0110666 0.0774183 0.977487 1 7.71124e-19 7.71124e-19 -5.44022e-08 -2.50727e-09 7.48115e-10 1 7.71124e-19 -5.44022e-08 -2.50727e-09 7.48115e-10 1 -5.44022e-08 -2.50727e-09 7.48115e-10 3847.72 -15.274 -93.9917 3998.48 -5.87228 3977.36 +EDGE_SE3:QUAT 1568 1619 -4.06941 10.1449 -5.41858 0.1944 -0.0937162 0.0926732 0.972027 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.69 -80.9041 -956.966 3948.02 8.5686 4182.5 +EDGE_SE3:QUAT 1569 1618 -4.13448 -10.1222 -4.89196 0.0234141 0.0678387 0.0887382 0.993466 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.78 15.3634 518.083 3985.07 25.9767 4034.47 +EDGE_SE3:QUAT 1570 1620 -3.74726 0.072812 -4.5467 0.0025216 0.10052 -0.0499456 0.993677 1 1.88079e-22 1.88079e-22 8.79631e-10 -4.46707e-11 8.87572e-11 1 1.88079e-22 8.79631e-10 -4.46707e-11 8.87572e-11 1 8.79631e-10 -4.46707e-11 8.87572e-11 4166.04 -11.543 831.76 3960.22 -22.3434 4156.08 +EDGE_SE3:QUAT 1569 1620 -4.21969 9.97615 -5.45328 -0.0944408 -0.0978192 0.108678 0.984734 1 1.92593e-19 1.92593e-19 -2.76848e-08 -3.57347e-09 2.0502e-09 1 1.92593e-19 -2.76848e-08 -3.57347e-09 2.0502e-09 1 -2.76848e-08 -3.57347e-09 2.0502e-09 4065.78 49.6702 -647.691 3982.4 -51.8233 4054.21 +EDGE_SE3:QUAT 1570 1619 -4.28872 -10.081 -4.74168 -0.146541 -0.0383496 -0.0656309 0.98628 1 7.70372e-19 7.70372e-19 5.50431e-08 -2.8975e-09 -3.09377e-09 1 7.70372e-19 5.50431e-08 -2.8975e-09 -3.09377e-09 1 5.50431e-08 -2.8975e-09 -3.09377e-09 3956.05 29.7005 -412.804 3988.51 6.58053 4024.72 +EDGE_SE3:QUAT 1571 1621 -3.50449 -0.0409508 -4.98513 -0.0790983 0.112745 0.115905 0.983666 1 1.92593e-19 1.92593e-19 -2.77088e-09 2.73511e-08 1.46577e-09 1 1.92593e-19 -2.77088e-09 2.73511e-08 1.46577e-09 1 -2.77088e-09 2.73511e-08 1.46577e-09 4230.51 -4.4319 1043.02 3938.41 41.1623 4201.8 +EDGE_SE3:QUAT 1570 1621 -4.58192 9.71791 -5.19063 -0.128284 -0.0150262 0.00478213 0.991612 1 7.71124e-19 7.71124e-19 -5.50898e-08 -6.92276e-10 2.46015e-09 1 7.71124e-19 -5.50898e-08 -6.92276e-10 2.46015e-09 1 -5.50898e-08 -6.92276e-10 2.46015e-09 3937.19 6.87436 -110.037 3999.35 -0.866769 4002.93 +EDGE_SE3:QUAT 1571 1620 -4.05138 -9.90707 -4.97216 -0.0534877 -0.0560889 -0.0928773 0.992656 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.93 6.02568 -507.653 3983.77 20.3684 4028.86 +EDGE_SE3:QUAT 1572 1622 -3.73956 -0.00546095 -4.97513 0.0363062 0.178143 -0.00911498 0.983292 1 1.88079e-22 1.88079e-22 1.6519e-10 3.27504e-11 9.10851e-10 1 1.88079e-22 1.6519e-10 3.27504e-11 9.10851e-10 1 1.6519e-10 3.27504e-11 9.10851e-10 4556.32 30.9062 1600.55 3873.5 22.6925 4561.26 +EDGE_SE3:QUAT 1571 1622 -4.16207 9.73163 -5.10438 0.110397 0.0222911 -0.12537 0.985697 1 1.01111e-18 1.01111e-18 5.51968e-08 4.30879e-09 -2.61706e-08 1 1.01111e-18 5.51968e-08 4.30879e-09 -2.61706e-08 1 5.51968e-08 4.30879e-09 -2.61706e-08 3978.77 17.4038 336.369 3991.12 -20.8638 3964.65 +EDGE_SE3:QUAT 1572 1621 -4.44414 -9.73539 -4.91829 -0.0528313 0.0765934 -0.0522643 0.994289 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.47 -22.8447 584.59 3980.99 -22.7473 4072.71 +EDGE_SE3:QUAT 1573 1623 -3.82062 -0.0501405 -4.8889 0.00378538 -0.202779 0.0323219 0.978684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4747.79 34.1059 -1884.31 3836.77 -39.5361 4743.66 +EDGE_SE3:QUAT 1572 1623 -4.35748 9.63513 -4.91847 0.0882674 -0.0321925 0.0635027 0.993549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.46 -13.0678 -321.747 3992.97 -7.88594 4009.49 +EDGE_SE3:QUAT 1573 1622 -4.42728 -10.27 -5.16684 0.114079 -0.0691389 -0.0569401 0.989426 1 2.40741e-19 2.40741e-19 -2.66545e-08 1.5721e-08 -1.89488e-10 1 2.40741e-19 -2.66545e-08 1.5721e-08 -1.89488e-10 1 -2.66545e-08 1.5721e-08 -1.89488e-10 4001.43 -31.0825 -466.952 3989.67 23.1644 4040.52 +EDGE_SE3:QUAT 1574 1624 -3.60164 0.555518 -5.13654 0.0809347 -0.057663 -0.0778182 0.992002 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.33 -19.3175 -379.939 3993.06 18.939 4011.31 +EDGE_SE3:QUAT 1573 1624 -4.37557 9.92815 -5.57467 -0.0936201 -0.031973 0.0626976 0.993117 1 2.0463e-19 2.0463e-19 -2.71232e-08 -8.76865e-09 -1.32107e-10 1 2.0463e-19 -2.71232e-08 -8.76865e-09 -1.32107e-10 1 -2.71232e-08 -8.76865e-09 -1.32107e-10 3972.96 8.29336 -181.24 3998.64 -6.31467 3992.3 +EDGE_SE3:QUAT 1574 1623 -4.13733 -10.0199 -4.75115 -0.0566897 -0.0108659 0.042736 0.997418 1 4.81482e-20 4.81482e-20 -8.21928e-11 -7.96935e-10 1.38433e-08 1 4.81482e-20 -8.21928e-11 -7.96935e-10 1.38433e-08 1 -8.21928e-11 -7.96935e-10 1.38433e-08 3987.94 1.40982 -57.299 3999.87 -1.10024 3993.49 +EDGE_SE3:QUAT 1575 1625 -3.66056 -0.310355 -5.2233 0.0293556 -0.215275 -0.200741 0.955248 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4650.85 -270.142 -1748.59 3919.95 286.237 4493.11 +EDGE_SE3:QUAT 1574 1625 -4.43009 9.89026 -5.00303 0.0572082 0.0275238 0.148503 0.986872 1 6.01853e-20 6.01853e-20 1.26544e-08 8.9389e-09 -3.06216e-10 1 6.01853e-20 1.26544e-08 8.9389e-09 -3.06216e-10 1 1.26544e-08 8.9389e-09 -3.06216e-10 3989.66 3.17617 111.573 3999.8 5.97727 3914.54 +EDGE_SE3:QUAT 1575 1624 -4.1433 -9.93904 -5.0767 0.0249998 0.0854148 -0.179518 0.979721 1 7.70372e-19 7.70372e-19 5.00453e-09 -3.81382e-10 5.52679e-08 1 7.70372e-19 5.00453e-09 -3.81382e-10 5.52679e-08 1 5.00453e-09 -3.81382e-10 5.52679e-08 4124.13 -24.8591 722.881 3972.57 -66.0247 3997.72 +EDGE_SE3:QUAT 1576 1626 -3.66321 0.416612 -4.81579 -0.0642386 0.123585 -0.0558236 0.988678 1 5.77779e-19 5.77779e-19 2.94474e-08 -3.17786e-08 2.9264e-08 1 5.77779e-19 2.94474e-08 -3.17786e-08 2.9264e-08 1 2.94474e-08 -3.17786e-08 2.9264e-08 4210.24 -55.8274 979.249 3950.64 -54.1856 4214.28 +EDGE_SE3:QUAT 1575 1626 -4.42908 9.56044 -5.33376 -0.17917 -0.0684506 0.00498731 0.981421 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3937.47 47.9879 -517.973 3986.94 -20.0802 4065.78 +EDGE_SE3:QUAT 1576 1625 -3.84858 -9.80574 -5.15185 0.125702 -0.150092 0.027354 0.980267 1 3.00927e-21 3.00927e-21 5.53632e-10 -4.4818e-10 -3.5677e-09 1 3.00927e-21 5.53632e-10 -4.4818e-10 -3.5677e-09 1 5.53632e-10 -4.4818e-10 -3.5677e-09 4332.11 -86.7612 -1318.17 3913.48 55.5549 4392.32 +EDGE_SE3:QUAT 1577 1627 -3.13928 -0.147184 -5.11563 -0.0664346 0.00814738 0.0903675 0.993657 1 1.92593e-19 1.92593e-19 2.75951e-08 2.45816e-09 5.52004e-10 1 1.92593e-19 2.75951e-08 2.45816e-09 5.52004e-10 1 2.75951e-08 2.45816e-09 5.52004e-10 3986.81 -4.80628 135.552 3998.46 6.84331 3971.8 +EDGE_SE3:QUAT 1576 1627 -4.43187 9.94654 -5.25727 0.000175106 0.0752798 0.0287118 0.996749 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4091.99 4.0642 613.516 3977.49 9.3546 4088.69 +EDGE_SE3:QUAT 1577 1626 -4.07099 -9.65594 -4.96478 -0.209278 -0.110146 -0.090025 0.967453 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4109.32 102.567 -1104.48 3935.46 -27.6201 4252.09 +EDGE_SE3:QUAT 1578 1628 -3.59134 -0.227787 -5.18199 -0.105126 0.0611054 -0.144901 0.981946 1 2.40741e-19 2.40741e-19 -2.51715e-08 1.79237e-08 8.95257e-10 1 2.40741e-19 -2.51715e-08 1.79237e-08 8.95257e-10 1 -2.51715e-08 1.79237e-08 8.95257e-10 3974.86 -17.7845 286.373 3998.33 -20.5796 3935.08 +EDGE_SE3:QUAT 1577 1628 -4.36906 9.49165 -5.231 0.16656 -0.065073 0.0537092 0.982415 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.53 -49.2322 -615.572 3977.38 4.09832 4080.96 +EDGE_SE3:QUAT 1578 1627 -4.24772 -9.75051 -5.00384 0.107683 0.0809619 -0.030137 0.990425 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4069.95 35.227 692.006 3972.02 7.47613 4112.7 +EDGE_SE3:QUAT 1579 1629 -3.67211 -0.0900619 -5.14889 -0.0614463 -0.0783176 0.029359 0.9946 1 4.81482e-20 4.81482e-20 1.03769e-09 9.3643e-10 -1.39608e-08 1 4.81482e-20 1.03769e-09 9.3643e-10 -1.39608e-08 1 1.03769e-09 9.3643e-10 -1.39608e-08 4076.47 23.8749 -612.214 3978.72 -18.1406 4088.13 +EDGE_SE3:QUAT 1578 1629 -4.41771 9.9459 -5.19638 -0.210107 0.0855235 0.103756 0.968388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.19 -85.6268 926.715 3950.12 -3.66607 4160.7 +EDGE_SE3:QUAT 1579 1628 -4.49981 -9.77739 -5.15455 -0.162592 0.00711798 0.0555501 0.985103 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3900.46 -15.582 160.96 3997.72 4.28753 3993.86 +EDGE_SE3:QUAT 1580 1630 -4.32383 -0.0639992 -4.76159 -0.0352038 0.0393035 -0.05126 0.99729 1 4.81482e-20 4.81482e-20 -1.3877e-08 7.52118e-10 -4.92346e-10 1 4.81482e-20 -1.3877e-08 7.52118e-10 -4.92346e-10 1 -1.3877e-08 7.52118e-10 -4.92346e-10 4016.27 -6.78326 292.265 3995.09 -8.56905 4010.71 +EDGE_SE3:QUAT 1579 1630 -4.57368 9.77477 -5.22624 0.021619 0.0345836 -0.0425459 0.998262 1 1.20371e-20 1.20371e-20 -6.94472e-09 2.86025e-10 -2.52315e-10 1 1.20371e-20 -6.94472e-09 2.86025e-10 -2.52315e-10 1 -6.94472e-09 2.86025e-10 -2.52315e-10 4018.77 1.89027 288.077 3994.78 -5.6194 4013.4 +EDGE_SE3:QUAT 1580 1629 -4.13466 -9.5413 -5.12088 -0.0578266 0.046611 -0.106549 0.99153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.67 -11.6807 292.421 3996.1 -16.4897 3975.64 +EDGE_SE3:QUAT 1581 1631 -3.53931 -0.0139432 -5.2806 -0.0375602 -0.0194163 0.0163289 0.998972 1 4.81482e-20 4.81482e-20 1.3873e-08 2.46538e-10 -2.51698e-10 1 4.81482e-20 1.3873e-08 2.46538e-10 -2.51698e-10 1 1.3873e-08 2.46538e-10 -2.51698e-10 3999.81 2.87354 -147.756 3998.7 -1.50451 4004.38 +EDGE_SE3:QUAT 1580 1631 -4.60974 9.85432 -5.03264 -0.0887165 -0.0623058 -0.0701075 0.991631 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4049.1 19.4744 -573.722 3979.28 11.5085 4060.92 +EDGE_SE3:QUAT 1581 1630 -4.66006 -9.62019 -4.921 0.000969204 -0.00272416 0.00204187 0.999994 1 1.17549e-23 1.17549e-23 -2.16842e-10 -4.41628e-13 5.91569e-13 1 1.17549e-23 -2.16842e-10 -4.41628e-13 5.91569e-13 1 -2.16842e-10 -4.41628e-13 5.91569e-13 4000.12 -0.0102131 -21.8174 3999.97 -0.022111 4000.1 +EDGE_SE3:QUAT 1582 1632 -3.48505 -0.112074 -4.92064 0.0280823 -0.0294068 0.0610649 0.997305 1 7.22224e-20 7.22224e-20 -6.89375e-09 6.16925e-09 -1.38109e-08 1 7.22224e-20 -6.89375e-09 6.16925e-09 -1.38109e-08 1 -6.89375e-09 6.16925e-09 -1.38109e-08 4013.04 -2.26583 -255.131 3995.82 -7.39842 4001.28 +EDGE_SE3:QUAT 1581 1632 -4.05469 9.84322 -5.31809 0.141756 0.0799188 0.133267 0.977629 1 7.70372e-19 7.70372e-19 -5.45088e-08 -8.44872e-09 -2.02177e-09 1 7.70372e-19 -5.45088e-08 -8.44872e-09 -2.02177e-09 1 -5.45088e-08 -8.44872e-09 -2.02177e-09 3953.52 31.6701 382.02 3997.5 30.9829 3962.86 +EDGE_SE3:QUAT 1582 1631 -4.30823 -9.88771 -5.16026 0.178321 -0.151005 -0.0391646 0.971527 1 1.92593e-19 1.92593e-19 -3.62729e-09 5.69811e-09 2.79789e-08 1 1.92593e-19 -3.62729e-09 5.69811e-09 2.79789e-08 1 -3.62729e-09 5.69811e-09 2.79789e-08 4167.31 -137.713 -1126.99 3953.09 115.103 4288.37 +EDGE_SE3:QUAT 1583 1633 -3.50864 -0.324023 -5.05605 -0.133483 -0.0813883 0.0175533 0.987548 1 8.1852e-19 8.1852e-19 5.65003e-08 4.12165e-09 -1.80046e-08 1 8.1852e-19 5.65003e-08 4.12165e-09 -1.80046e-08 1 5.65003e-08 4.12165e-09 -1.80046e-08 4021.73 45.464 -617.329 3980.36 -25.3232 4091.76 +EDGE_SE3:QUAT 1582 1633 -4.51637 9.9338 -4.98154 -0.0104743 0.00377658 0.152278 0.988275 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.13 -0.170864 48.0129 3999.83 4.10735 3907.81 +EDGE_SE3:QUAT 1583 1632 -4.24317 -9.92184 -4.69307 0.162914 -0.0575513 -0.00379346 0.984953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3941.46 -36.5594 -439.281 3990.07 13.0324 4047.56 +EDGE_SE3:QUAT 1584 1634 -3.83863 -0.0672612 -5.41925 0.0526496 0.0910768 -0.116926 0.987553 1 4.33334e-19 4.33334e-19 1.41539e-08 2.5027e-08 -2.73878e-08 1 4.33334e-19 1.41539e-08 2.5027e-08 -2.73878e-08 1 1.41539e-08 2.5027e-08 -2.73878e-08 4147.68 -3.65712 812.697 3961.48 -40.8143 4104.09 +EDGE_SE3:QUAT 1583 1634 -4.65939 10.1212 -5.15191 0.153416 0.101418 0.112501 0.976484 1 7.70372e-19 7.70372e-19 5.47494e-08 7.84777e-09 3.32431e-09 1 7.70372e-19 5.47494e-08 7.84777e-09 3.32431e-09 1 5.47494e-08 7.84777e-09 3.32431e-09 3983.13 57.2063 569.67 3991.51 52.4936 4026.65 +EDGE_SE3:QUAT 1584 1633 -4.37829 -9.58279 -5.11526 0.152557 0.11744 -0.0229071 0.981025 1 7.71124e-19 7.71124e-19 -5.58582e-08 -5.12648e-10 -5.04041e-09 1 7.71124e-19 -5.58582e-08 -5.12648e-10 -5.04041e-09 1 -5.58582e-08 -5.12648e-10 -5.04041e-09 4141.66 79.5225 997.084 3949.01 42.4097 4232.65 +EDGE_SE3:QUAT 1585 1635 -3.57855 0.224586 -5.17838 0.0640016 -0.0602221 0.0520869 0.994768 1 4.81482e-20 4.81482e-20 1.39222e-08 6.20436e-10 -9.25149e-10 1 4.81482e-20 1.39222e-08 6.20436e-10 -9.25149e-10 1 1.39222e-08 6.20436e-10 -9.25149e-10 4051.29 -12.6886 -524.751 3982.85 -8.17584 4056.82 +EDGE_SE3:QUAT 1584 1635 -4.52587 9.9215 -5.10799 -0.0394605 -0.0819803 0.198078 0.975955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4062.23 33.8224 -530.769 3989.83 -55.8113 3911.52 +EDGE_SE3:QUAT 1585 1634 -4.15765 -10.0236 -4.97526 -0.147178 0.0137651 0.103011 0.983635 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3932.75 -23.053 284.329 3993.07 14.4151 3976.95 +EDGE_SE3:QUAT 1586 1636 -3.73364 -0.113771 -5.05684 -0.0157727 0.0870936 0.191223 0.977548 1 2.30397e-21 2.30397e-21 3.0147e-09 5.9042e-10 2.67122e-10 1 2.30397e-21 3.0147e-09 5.9042e-10 2.67122e-10 1 3.0147e-09 5.9042e-10 2.67122e-10 4122.25 30.5321 713.006 3974.74 70.7397 3976.98 +EDGE_SE3:QUAT 1585 1636 -4.84567 9.79645 -4.82566 3.08459e-05 0.0544698 0.0615069 0.996619 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4047.34 4.41846 437.74 3988.5 13.8581 4032.21 +EDGE_SE3:QUAT 1586 1635 -4.20956 -9.99146 -4.92285 0.154951 0.0185996 0.110715 0.981522 1 1.92593e-19 1.92593e-19 -4.56286e-10 4.30755e-09 2.72417e-08 1 1.92593e-19 -4.56286e-10 4.30755e-09 2.72417e-08 1 -4.56286e-10 4.30755e-09 2.72417e-08 3903.68 -10.2032 -60.1388 3998.92 -7.29989 3950.68 +EDGE_SE3:QUAT 1587 1637 -4.04318 0.516821 -5.14133 0.16875 0.0317031 -0.0323394 0.984618 1 4.81482e-20 4.81482e-20 -2.77782e-10 -1.36689e-08 2.31519e-09 1 4.81482e-20 -2.77782e-10 -1.36689e-08 2.31519e-09 1 -2.77782e-10 -1.36689e-08 2.31519e-09 3909.7 26.8286 308.47 3994.01 0.284778 4019.42 +EDGE_SE3:QUAT 1586 1637 -4.4248 9.69691 -5.24718 0.120043 0.133047 0.0385341 0.983058 1 1.54074e-18 1.54074e-18 -5.23429e-08 -5.855e-08 6.25755e-10 1 1.54074e-18 -5.23429e-08 -5.855e-08 6.25755e-10 1 -5.23429e-08 -5.855e-08 6.25755e-10 4193.8 87.0779 1034.63 3949.76 71.9089 4245.5 +EDGE_SE3:QUAT 1587 1636 -4.27546 -9.43249 -5.06391 -0.197609 0.0477676 -0.0979994 0.9742 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3846 -5.4765 128.949 4000.52 -4.60447 3963.78 +EDGE_SE3:QUAT 1588 1638 -3.6151 -0.70835 -4.73321 -0.0169624 0.0618988 -0.0846019 0.994346 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4055.19 -11.5318 478.142 3987 -22.1635 4027.71 +EDGE_SE3:QUAT 1587 1638 -4.38266 9.87082 -5.45835 0.125717 0.12751 -0.00767032 0.983808 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4203.02 75.1857 1065.83 3941.85 47.7093 4266 +EDGE_SE3:QUAT 1588 1637 -4.18889 -9.70581 -5.07096 -0.179363 -0.0232978 -0.167734 0.969098 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3936.93 45.5705 -525.564 3977.09 40.8654 3953.07 +EDGE_SE3:QUAT 1589 1639 -3.89088 -0.10904 -4.98414 0.0875984 0.157093 -0.158449 0.970846 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4482.64 -37.2561 1522.25 3886.11 -90.6207 4412.91 +EDGE_SE3:QUAT 1588 1639 -4.38704 9.79075 -4.99109 0.0393328 0.128416 -0.0114042 0.990874 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4273.02 20.391 1093.06 3933.92 9.64242 4278.68 +EDGE_SE3:QUAT 1589 1638 -4.46367 -9.80958 -5.08967 0.0988065 0.0544291 0.00560305 0.993601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.91 21.8842 426.523 3989.56 8.04644 4044.84 +EDGE_SE3:QUAT 1590 1640 -3.53362 0.256834 -5.33935 0.110543 -0.0319558 -0.0588216 0.991614 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3958.34 -8.86103 -172.538 3998.88 5.80408 3993.37 +EDGE_SE3:QUAT 1589 1640 -4.49998 10.0221 -5.04747 -0.0316014 -0.0204778 0.0197616 0.999095 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.09 2.62178 -156.193 3998.54 -1.81949 4004.53 +EDGE_SE3:QUAT 1590 1639 -4.2197 -10.2952 -5.07776 -0.00575676 0.0450745 -0.135859 0.989686 1 3.00927e-21 3.00927e-21 3.44643e-09 -4.7677e-10 1.45713e-10 1 3.00927e-21 3.44643e-09 -4.7677e-10 1.45713e-10 1 3.44643e-09 -4.7677e-10 1.45713e-10 4029.12 -7.18609 343.474 3993.59 -23.6294 3955.43 +EDGE_SE3:QUAT 1591 1641 -3.51398 -0.102767 -5.16479 0.0814145 -0.14435 -0.0296369 0.985726 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4300.73 -73.7567 -1190.16 3929.04 63.674 4323.73 +EDGE_SE3:QUAT 1590 1641 -4.42883 9.79379 -5.06848 -0.0204448 -0.242711 0.0520254 0.968487 1 4.81482e-20 4.81482e-20 1.51913e-08 1.0945e-09 -3.74121e-09 1 4.81482e-20 1.51913e-08 1.0945e-09 -3.74121e-09 1 1.51913e-08 1.0945e-09 -3.74121e-09 5103.17 137.481 -2374.92 3781.3 -140.048 5094.02 +EDGE_SE3:QUAT 1591 1640 -4.19803 -9.62869 -4.73362 0.145837 0.123135 -0.0197308 0.981417 1 4.23178e-22 4.23178e-22 -1.65914e-10 -1.95349e-10 -1.31792e-09 1 4.23178e-22 -1.65914e-10 -1.95349e-10 -1.31792e-09 1 -1.65914e-10 -1.95349e-10 -1.31792e-09 4170.65 80.9124 1043.25 3944.53 46.1392 4254.16 +EDGE_SE3:QUAT 1592 1642 -3.98551 -0.168986 -5.12174 0.00380658 0.0261011 -0.00901989 0.999611 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.9 0.253816 209.693 3997.26 -0.890438 4010.64 +EDGE_SE3:QUAT 1591 1642 -4.19907 9.83443 -4.93827 0.0977731 -0.00920213 0.109927 0.989076 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3971.23 -10.6051 -198.857 3996.51 -12.2085 3961.13 +EDGE_SE3:QUAT 1592 1641 -4.31784 -10.0383 -5.19625 -0.078387 -0.0379127 0.0542173 0.994725 1 1.92593e-19 1.92593e-19 -2.76627e-08 -1.65787e-09 7.99051e-10 1 1.92593e-19 -2.76627e-08 -1.65787e-09 7.99051e-10 1 -2.76627e-08 -1.65787e-09 7.99051e-10 3990.78 10.5536 -249.135 3996.89 -8.34942 4003.6 +EDGE_SE3:QUAT 1593 1643 -3.60919 -0.0975852 -4.77129 -0.0431948 0.0435183 -0.100906 0.993005 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.49 -9.47568 291.056 3995.77 -15.439 3980.23 +EDGE_SE3:QUAT 1592 1643 -4.31238 9.70466 -4.91867 0.094703 -0.0945055 0.138942 0.981221 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4166.36 -9.95512 -922.442 3949.86 -46.717 4125.02 +EDGE_SE3:QUAT 1593 1642 -4.00401 -9.95744 -4.75407 -0.0280033 0.104703 0.0390121 0.993343 1 1.20371e-20 1.20371e-20 -7.05155e-09 -2.40482e-10 -7.55693e-10 1 1.20371e-20 -7.05155e-09 -2.40482e-10 -7.55693e-10 1 -7.05155e-09 -2.40482e-10 -7.55693e-10 4182.97 -2.80108 882.655 3954.94 11.3765 4180.02 +EDGE_SE3:QUAT 1594 1644 -3.52193 0.146641 -4.73201 0.00452224 0.112178 -0.0159223 0.99355 1 1.88079e-22 1.88079e-22 -8.84049e-10 1.36128e-11 -9.98911e-11 1 1.88079e-22 -8.84049e-10 1.36128e-11 -9.98911e-11 1 -8.84049e-10 1.36128e-11 -9.98911e-11 4209.38 -2.71288 938.997 3949.64 -7.0227 4208.45 +EDGE_SE3:QUAT 1593 1644 -4.53161 9.53981 -5.13053 0.16869 -0.173317 0.0881521 0.966299 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4513.9 -113.099 -1704.48 3865.73 61.8922 4596.65 +EDGE_SE3:QUAT 1594 1643 -4.20131 -9.67166 -5.04953 0.0901132 -0.0357745 -0.307669 0.946541 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3965.27 8.89888 66.9121 3997.73 -29.7914 3619.11 +EDGE_SE3:QUAT 1595 1645 -3.57751 0.117736 -4.8945 0.222555 0.0974476 0.110312 0.963745 1 7.70372e-19 7.70372e-19 -5.37832e-08 -7.99123e-09 -2.05182e-09 1 7.70372e-19 -5.37832e-08 -7.99123e-09 -2.05182e-09 1 -5.37832e-08 -7.99123e-09 -2.05182e-09 3841.62 46.5945 423.46 4000.76 39.373 3991.07 +EDGE_SE3:QUAT 1594 1645 -4.67104 9.78119 -5.07825 0.0318751 -0.0126763 0.141926 0.989283 1 1.20371e-20 1.20371e-20 -6.86953e-09 -9.78401e-10 1.46488e-10 1 1.20371e-20 -6.86953e-09 -9.78401e-10 1.46488e-10 1 -6.86953e-09 -9.78401e-10 1.46488e-10 4001.64 -1.63495 -151.955 3998.32 -11.7821 3925.13 +EDGE_SE3:QUAT 1595 1644 -4.76046 -9.40335 -5.21623 -0.0329706 0.0122661 -0.170868 0.984666 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.69 -0.171921 27.4525 4000.02 -0.314366 3883.26 +EDGE_SE3:QUAT 1596 1646 -3.9798 -0.241555 -5.07195 0.0353075 0.116267 0.11233 0.986214 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4187.02 52.1869 897.684 3960.09 66.7749 4141.54 +EDGE_SE3:QUAT 1595 1646 -4.48534 9.85934 -5.29987 0.0961468 0.104277 0.0178942 0.989728 1 2.0463e-19 2.0463e-19 -3.61222e-10 2.81766e-08 4.18124e-09 1 2.0463e-19 -3.61222e-10 2.81766e-08 4.18124e-09 1 -3.61222e-10 2.81766e-08 4.18124e-09 4128.3 48.4377 829.858 3963.1 33.0487 4164 +EDGE_SE3:QUAT 1596 1645 -4.42822 -9.54724 -4.921 -0.0354382 -0.0914158 -0.0850841 0.991538 1 1.92593e-19 1.92593e-19 2.21655e-09 2.75328e-08 5.51006e-10 1 1.92593e-19 2.21655e-09 2.75328e-08 5.51006e-10 1 2.21655e-09 2.75328e-08 5.51006e-10 4142.89 -3.62088 -783.308 3964.11 28.9213 4118.96 +EDGE_SE3:QUAT 1597 1647 -3.9757 0.205019 -4.81994 0.178911 -0.125711 0.277984 0.935367 1 1.54074e-18 1.54074e-18 6.86899e-08 -3.89874e-08 -6.64911e-09 1 1.54074e-18 6.86899e-08 -3.89874e-08 -6.64911e-09 1 6.86899e-08 -3.89874e-08 -6.64911e-09 4439.99 29.0774 -1613.03 3873.19 -163.643 4258.92 +EDGE_SE3:QUAT 1596 1647 -4.38827 9.92279 -5.03346 -0.0108399 -0.150674 0.0573752 0.986858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4379.26 42.9981 -1289.63 3913.99 -52.2766 4366.56 +EDGE_SE3:QUAT 1597 1646 -4.29821 -9.92816 -4.83278 0.149063 0.0418622 -0.00844697 0.987905 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3939.95 25.6141 340.832 3993.43 5.03676 4028.55 +EDGE_SE3:QUAT 1598 1648 -3.71622 -0.163087 -5.11294 -0.136094 0.0475763 0.0796334 0.986343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.72 -31.1699 502.133 3983.25 10.6045 4036.44 +EDGE_SE3:QUAT 1597 1648 -4.33708 9.64876 -5.13463 -0.0450089 -0.14041 0.0615474 0.987153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4299.11 60.8726 -1150.48 3932.68 -64.1151 4292.06 +EDGE_SE3:QUAT 1598 1647 -4.46456 -9.73112 -4.50922 -0.016837 -0.0919335 0.126127 0.987601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4121.09 30.7267 -710.131 3973.85 -50.9154 4058.6 +EDGE_SE3:QUAT 1599 1649 -3.89109 0.0589832 -5.03378 -0.00763994 0.0537127 0.0842343 0.994968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4047.02 4.27851 437.302 3988.57 18.4859 4018.87 +EDGE_SE3:QUAT 1598 1649 -4.62295 9.70303 -5.0006 -0.0703467 0.00251075 0.108689 0.99158 1 1.92593e-19 1.92593e-19 4.8841e-10 -1.89214e-09 2.75318e-08 1 1.92593e-19 4.8841e-10 -1.89214e-09 2.75318e-08 1 4.8841e-10 -1.89214e-09 2.75318e-08 3983.04 -4.62345 110.39 3998.79 7.4419 3955.58 +EDGE_SE3:QUAT 1599 1648 -4.18094 -9.72623 -5.41539 0.201625 -0.0892195 -0.106923 0.969513 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3875.19 -41.6366 -407.72 3999 34.631 3992.07 +EDGE_SE3:QUAT 1600 1650 -3.76512 0.106495 -5.02802 -0.034077 -0.00549436 -0.0443804 0.998418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.3 1.10085 -61.8739 3999.71 1.46353 3993.07 +EDGE_SE3:QUAT 1599 1650 -5.01722 9.72022 -4.88133 -0.0283472 -0.00109077 0.118043 0.992603 1 2.0463e-19 2.0463e-19 -6.73275e-09 -1.59019e-09 2.75122e-08 1 2.0463e-19 -6.73275e-09 -1.59019e-09 2.75122e-08 1 -6.73275e-09 -1.59019e-09 2.75122e-08 3996.99 -0.611686 31.2272 3999.88 2.6317 3944.46 +EDGE_SE3:QUAT 1600 1649 -4.36388 -9.48815 -4.96459 0.130548 -0.0206552 -0.113659 0.984689 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3930.98 5.12433 16.6868 3999.63 -4.46001 3947.47 +EDGE_SE3:QUAT 1601 1651 -3.75034 0.227528 -4.77812 -0.110519 0.104391 -0.1009 0.983213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.22 -58.4445 688.116 3980.89 -56.9896 4073.35 +EDGE_SE3:QUAT 1600 1651 -4.68638 9.65425 -5.09386 -0.10232 -0.0263035 0.133081 0.985458 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3957.72 -0.544374 -41.1141 4000.05 0.86273 3928.76 +EDGE_SE3:QUAT 1601 1650 -4.61684 -9.92875 -4.91413 0.181607 0.101507 -0.0843158 0.974477 1 1.15556e-18 1.15556e-18 6.04828e-08 2.93666e-08 3.03228e-08 1 1.15556e-18 6.04828e-08 2.93666e-08 3.03228e-08 1 6.04828e-08 2.93666e-08 3.03228e-08 4102.49 78.0855 996.725 3944.64 12.7943 4205.98 +EDGE_SE3:QUAT 1602 1652 -3.70175 0.151761 -5.12457 0.00611137 0.0251818 -0.0639011 0.99762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.37 -0.368406 205.363 3997.39 -6.54693 3994.18 +EDGE_SE3:QUAT 1601 1652 -4.47566 10.0591 -4.98555 -0.180271 -0.0375932 0.0514161 0.981553 1 7.82409e-19 7.82409e-19 -5.49649e-08 3.38927e-09 2.19958e-09 1 7.82409e-19 -5.49649e-08 3.38927e-09 2.19958e-09 1 -5.49649e-08 3.38927e-09 2.19958e-09 3877.26 13.0083 -176.354 3999.35 -6.31698 3996.68 +EDGE_SE3:QUAT 1602 1651 -4.4134 -9.88004 -4.69783 -0.178365 0.0209623 -0.184766 0.966234 1 7.70372e-19 7.70372e-19 -5.3701e-08 1.00115e-08 2.52779e-09 1 7.70372e-19 -5.3701e-08 1.00115e-08 2.52779e-09 1 -5.3701e-08 1.00115e-08 2.52779e-09 3881.7 31.2037 -227.125 3991.87 32.4164 3872.4 +EDGE_SE3:QUAT 1603 1653 -3.89707 0.322458 -4.8369 0.0501856 -0.010469 -0.0014054 0.998684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.63 -2.06944 -82.6212 3999.58 0.187255 4001.7 +EDGE_SE3:QUAT 1602 1653 -4.609 9.51158 -5.33007 -0.0492342 -0.0896223 0.0411605 0.993906 1 4.81482e-20 4.81482e-20 -1.19382e-09 -8.07177e-10 1.40011e-08 1 4.81482e-20 -1.19382e-09 -8.07177e-10 1.40011e-08 1 -1.19382e-09 -8.07177e-10 1.40011e-08 4111.18 26.287 -705.871 3972.03 -24.7619 4114.1 +EDGE_SE3:QUAT 1603 1652 -4.29623 -9.6889 -5.26032 -0.00308375 0.253751 -0.152643 0.955145 1 4.81482e-20 4.81482e-20 1.50816e-08 -2.7927e-09 3.77492e-09 1 4.81482e-20 1.50816e-08 -2.7927e-09 3.77492e-09 1 1.50816e-08 -2.7927e-09 3.77492e-09 5144.07 -314.031 2426.78 3820.67 -321.147 5050.91 +EDGE_SE3:QUAT 1604 1654 -3.92896 0.0874452 -4.85403 0.0357464 0.0105981 0.0681381 0.996979 1 1.92593e-19 1.92593e-19 1.5585e-10 1.02318e-09 2.76743e-08 1 1.92593e-19 1.5585e-10 1.02318e-09 2.76743e-08 1 1.5585e-10 1.02318e-09 2.76743e-08 3995.62 0.90047 54.9223 3999.88 1.58275 3982.16 +EDGE_SE3:QUAT 1603 1654 -4.52299 9.35306 -5.14566 -0.0296769 -0.140077 0.0978846 0.984843 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4296.31 66.9422 -1135.74 3936.45 -80.1129 4261.51 +EDGE_SE3:QUAT 1604 1653 -4.65599 -9.08179 -4.70719 0.0199279 0.0796658 -0.13257 0.987766 1 3.00927e-21 3.00927e-21 -3.47396e-09 4.60893e-10 -2.88699e-10 1 3.00927e-21 -3.47396e-09 4.60893e-10 -2.88699e-10 1 -3.47396e-09 4.60893e-10 -2.88699e-10 4106.84 -14.6382 667.431 3974.9 -44.3948 4038.13 +EDGE_SE3:QUAT 1605 1655 -4.00062 -0.0503674 -4.66527 -0.119537 -0.14727 -0.0339081 0.981261 1 1.20371e-20 1.20371e-20 -1.09816e-09 -8.33093e-10 7.13516e-09 1 1.20371e-20 -1.09816e-09 -8.33093e-10 7.13516e-09 1 -1.09816e-09 -8.33093e-10 7.13516e-09 4329.68 76.6455 -1302.68 3913.75 -44.7152 4382.23 +EDGE_SE3:QUAT 1604 1655 -4.66915 9.4856 -5.47497 0.0714358 -0.180702 0.0217264 0.9807 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4564.93 -59.2402 -1638.29 3870.3 42.6137 4583.46 +EDGE_SE3:QUAT 1605 1654 -4.11287 -9.51868 -4.7359 0.102777 0.0226237 -0.0357048 0.993806 1 2.40741e-19 2.40741e-19 2.80349e-08 5.60139e-10 1.46303e-08 1 2.40741e-19 2.80349e-08 5.60139e-10 1.46303e-08 1 2.80349e-08 5.60139e-10 1.46303e-08 3970.01 11.5841 222.142 3996.66 -2.47902 4007.16 +EDGE_SE3:QUAT 1606 1656 -3.62153 0.203344 -4.83339 0.243354 -0.0465785 -0.048655 0.967596 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3772.28 -18.7535 -202.213 3999.9 8.87634 3999.7 +EDGE_SE3:QUAT 1605 1656 -4.87542 9.42135 -5.18397 -0.24576 0.066596 0.110349 0.960724 1 7.70372e-19 7.70372e-19 5.44654e-08 3.76495e-09 6.22675e-09 1 7.70372e-19 5.44654e-08 3.76495e-09 6.22675e-09 1 5.44654e-08 3.76495e-09 6.22675e-09 3918.83 -95.888 819.245 3959.19 0.0222748 4111.71 +EDGE_SE3:QUAT 1606 1655 -4.57287 -9.4757 -5.11193 -0.0848409 0.102554 -0.0999196 0.986053 1 3.85186e-19 3.85186e-19 -9.62389e-10 -3.02847e-08 2.48761e-08 1 3.85186e-19 -9.62389e-10 -3.02847e-08 2.48761e-08 1 -9.62389e-10 -3.02847e-08 2.48761e-08 4094.42 -52.0049 714.491 3976.93 -54.4791 4083.28 +EDGE_SE3:QUAT 1607 1657 -3.89184 0.0490667 -5.10775 0.103722 -0.0477604 -0.125542 0.985495 1 1.92593e-19 1.92593e-19 2.73897e-08 -3.69766e-09 -5.3941e-10 1 1.92593e-19 2.73897e-08 -3.69766e-09 -5.3941e-10 1 2.73897e-08 -3.69766e-09 -5.3941e-10 3967.41 -11.2065 -213.253 3999.06 12.4206 3947.4 +EDGE_SE3:QUAT 1606 1657 -4.38024 9.37224 -5.15494 -0.220614 0.262543 0.17928 0.922095 1 3.08149e-18 3.08149e-18 1.25901e-07 8.94596e-09 4.177e-08 1 3.08149e-18 1.25901e-07 8.94596e-09 4.177e-08 1 1.25901e-07 8.94596e-09 4.177e-08 5727.93 -147.73 3374.67 3660.66 -130.929 5794.05 +EDGE_SE3:QUAT 1607 1656 -4.57805 -9.57676 -5.27058 -0.117541 0.057352 -0.131626 0.982634 1 2.40741e-19 2.40741e-19 -2.53595e-08 1.75638e-08 1.14396e-09 1 2.40741e-19 -2.53595e-08 1.75638e-08 1.14396e-09 1 -2.53595e-08 1.75638e-08 1.14396e-09 3959.65 -15.7058 255.322 3998.86 -16.5688 3945.61 +EDGE_SE3:QUAT 1608 1658 -3.8958 -0.000219481 -5.06568 -0.0434695 -0.0331622 0.126877 0.990411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.56 5.7897 -192.992 3998.47 -11.5066 3944.73 +EDGE_SE3:QUAT 1607 1658 -4.63459 9.68598 -4.99913 -0.0261409 0.147097 0.240247 0.959146 1 3.00927e-21 3.00927e-21 3.47955e-09 8.83548e-10 5.15203e-10 1 3.00927e-21 3.47955e-09 8.83548e-10 5.15203e-10 1 3.47955e-09 8.83548e-10 5.15203e-10 4348.43 117.805 1236.94 3942.82 168.316 4120.28 +EDGE_SE3:QUAT 1608 1657 -4.42547 -9.46861 -4.86494 -0.0695401 0.0846268 -0.0667959 0.991736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4075.5 -32.5525 623.711 3979.68 -32.0857 4076.99 +EDGE_SE3:QUAT 1609 1659 -3.77215 -0.180398 -4.70078 0.0837389 0.144605 -0.0361423 0.985277 1 8.1852e-19 8.1852e-19 5.50473e-08 -1.82421e-09 -5.6816e-09 1 8.1852e-19 5.50473e-08 -1.82421e-09 -5.6816e-09 1 5.50473e-08 -1.82421e-09 -5.6816e-09 4344.42 45.1919 1276.18 3913.96 19.9342 4367.25 +EDGE_SE3:QUAT 1608 1659 -4.64885 9.72317 -4.87924 -0.19568 0.0656854 0.0502674 0.977173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3941.43 -60.2751 622.58 3977.78 -9.65567 4084.49 +EDGE_SE3:QUAT 1609 1658 -4.40447 -9.36721 -4.4618 0.0917078 0.0684454 0.0409981 0.992585 1 1.92593e-19 1.92593e-19 -2.77633e-08 -1.48918e-09 -1.66385e-09 1 1.92593e-19 -2.77633e-08 -1.48918e-09 -1.66385e-09 1 -2.77633e-08 -1.48918e-09 -1.66385e-09 4027.93 27.1783 500.516 3986.69 19.3646 4054.85 +EDGE_SE3:QUAT 1610 1660 -3.86186 0.219968 -5.20295 -0.141043 -0.0942876 -0.128595 0.977077 1 1.92593e-19 1.92593e-19 2.77421e-09 2.72122e-08 3.20656e-09 1 1.92593e-19 2.77421e-09 2.72122e-08 3.20656e-09 1 2.77421e-09 2.72122e-08 3.20656e-09 4146.31 40.3122 -978.112 3943.03 29.0525 4159.74 +EDGE_SE3:QUAT 1609 1660 -4.79258 9.38821 -5.01115 0.0474546 0.118032 0.159499 0.978967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4160.25 66.8802 842.063 3970.7 85.7921 4067.5 +EDGE_SE3:QUAT 1610 1659 -4.24095 -9.42375 -5.19577 -0.102485 0.0718129 -0.0916183 0.9879 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.5 -29.7462 450.369 3991.41 -28.3721 4015.94 +EDGE_SE3:QUAT 1611 1661 -4.1025 -0.122761 -5.02437 -0.118385 0.0880468 -0.0455463 0.988007 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.14 -45.9814 635.279 3980.24 -33.8193 4089.9 +EDGE_SE3:QUAT 1610 1661 -4.81156 9.52398 -4.64249 -0.00838769 0.0301582 -0.0331291 0.998961 1 1.20371e-20 1.20371e-20 2.33771e-10 6.93155e-09 7.20532e-11 1 1.20371e-20 2.33771e-10 6.93155e-09 7.20532e-11 1 2.33771e-10 6.93155e-09 7.20532e-11 4013.86 -1.71243 238.237 3996.53 -4.14214 4009.75 +EDGE_SE3:QUAT 1611 1660 -4.25229 -9.31871 -4.99016 -0.00123717 -0.0352437 0.0363861 0.998715 1 1.88079e-22 1.88079e-22 8.68391e-10 3.17925e-11 -3.04848e-11 1 1.88079e-22 8.68391e-10 3.17925e-11 -3.04848e-11 1 8.68391e-10 3.17925e-11 -3.04848e-11 4019.79 1.26182 -282.062 3995.11 -5.22858 4014.5 +EDGE_SE3:QUAT 1612 1662 -3.75561 -0.248945 -5.15002 -0.0366234 0.18192 -0.227435 0.955948 1 1.92593e-19 1.92593e-19 -2.79229e-08 7.46818e-09 -4.19748e-09 1 1.92593e-19 -2.79229e-08 7.46818e-09 -4.19748e-09 1 -2.79229e-08 7.46818e-09 -4.19748e-09 4397.69 -194.794 1337.61 3957.24 -218.248 4196.15 +EDGE_SE3:QUAT 1611 1662 -4.80787 9.43142 -4.77386 0.00749384 -0.248112 0.064344 0.966563 1 1.20371e-20 1.20371e-20 -7.64534e-09 -5.48076e-10 1.95269e-09 1 1.20371e-20 -7.64534e-09 -5.48076e-10 1.95269e-09 1 -7.64534e-09 -5.48076e-10 1.95269e-09 5191.9 114.699 -2487.91 3763.01 -119.924 5175.56 +EDGE_SE3:QUAT 1612 1661 -4.29569 -9.49686 -4.91749 0.0540405 0.0921638 -0.0139414 0.994179 1 3.00927e-21 3.00927e-21 -3.28753e-10 -1.84865e-10 -3.50999e-09 1 3.00927e-21 -3.28753e-10 -1.84865e-10 -3.50999e-09 1 -3.28753e-10 -1.84865e-10 -3.50999e-09 4130.01 19.63 766.069 3965.7 5.80798 4140.92 +EDGE_SE3:QUAT 1613 1663 -3.84656 -0.264386 -5.0532 0.0854681 -0.0020949 0.0457677 0.995287 1 1.92593e-19 1.92593e-19 2.7628e-08 1.24204e-09 -2.73209e-10 1 1.92593e-19 2.7628e-08 1.24204e-09 -2.73209e-10 1 2.7628e-08 1.24204e-09 -2.73209e-10 3971.72 -3.31843 -63.1851 3999.62 -1.71329 3992.56 +EDGE_SE3:QUAT 1612 1663 -4.39346 9.05182 -4.79778 0.122395 0.0346192 0.0365833 0.991203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3951.74 12.9338 217.445 3997.83 6.1048 4006.31 +EDGE_SE3:QUAT 1613 1662 -4.26355 -9.30672 -4.64883 0.136236 0.0401543 0.0822683 0.986438 1 9.75002e-19 9.75002e-19 5.49919e-08 -5.7511e-09 -2.55406e-08 1 9.75002e-19 5.49919e-08 -5.7511e-09 -2.55406e-08 1 5.49919e-08 -5.7511e-09 -2.55406e-08 3932.91 10.1587 176.726 3999.35 7.55541 3980.08 +EDGE_SE3:QUAT 1614 1664 -4.02772 0.11242 -4.72832 0.165591 -0.107067 -0.124252 0.97246 1 9.62965e-19 9.62965e-19 -5.02344e-08 3.55479e-08 -2.08141e-09 1 9.62965e-19 -5.02344e-08 3.55479e-08 -2.08141e-09 1 -5.02344e-08 3.55479e-08 -2.08141e-09 3965.15 -60.8532 -564.351 3994.19 56.6602 4013.08 +EDGE_SE3:QUAT 1613 1664 -4.47015 9.61739 -5.62306 -0.0312846 0.0281287 0.136193 0.989789 1 7.70372e-19 7.70372e-19 1.97435e-09 -1.25642e-09 5.50711e-08 1 7.70372e-19 1.97435e-09 -1.25642e-09 5.50711e-08 1 1.97435e-09 -1.25642e-09 5.50711e-08 4014.21 -1.01595 270.129 3995.27 18.7987 3943.93 +EDGE_SE3:QUAT 1614 1663 -4.82301 -9.45048 -5.25157 -0.0990408 0.198647 0.0441173 0.974055 1 1.92593e-19 1.92593e-19 2.94683e-08 1.62057e-10 6.14778e-09 1 1.92593e-19 2.94683e-08 1.62057e-10 6.14778e-09 1 2.94683e-08 1.62057e-10 6.14778e-09 4705.25 -81.8189 1879.42 3840.37 -59.157 4736.7 +EDGE_SE3:QUAT 1615 1665 -3.9269 0.297715 -4.78537 -0.128866 -0.180861 -0.121051 0.967486 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4638.32 33.6972 -1821.11 3844.32 14.8779 4646.13 +EDGE_SE3:QUAT 1614 1665 -4.51061 9.4604 -4.98039 0.0986784 0.0552391 0.0604465 0.991745 1 1.92593e-19 1.92593e-19 -2.76402e-08 -1.96386e-09 -1.16551e-09 1 1.92593e-19 -2.76402e-08 -1.96386e-09 -1.16551e-09 1 -2.76402e-08 -1.96386e-09 -1.16551e-09 3993.71 20.4219 364.137 3993.63 15.8941 4018.05 +EDGE_SE3:QUAT 1615 1664 -4.65249 -9.78499 -5.02313 -0.103059 -0.0763732 0.131899 0.982929 1 2.40741e-19 2.40741e-19 -2.54142e-08 -1.76881e-08 -4.14431e-10 1 2.40741e-19 -2.54142e-08 -1.76881e-08 -4.14431e-10 1 -2.54142e-08 -1.76881e-08 -4.14431e-10 4001.43 30.652 -427.173 3994.15 -33.7564 3974.32 +EDGE_SE3:QUAT 1616 1666 -3.71827 -0.310767 -4.55952 0.0332806 -0.0511881 0.00904745 0.998093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.43 -6.55284 -416.274 3989.37 0.204723 4042.53 +EDGE_SE3:QUAT 1615 1666 -4.483 9.35478 -4.7202 -0.0264465 0.107355 -0.111208 0.987628 1 1.92593e-19 1.92593e-19 3.30906e-09 2.73862e-08 1.4005e-09 1 1.92593e-19 3.30906e-09 2.73862e-08 1.4005e-09 1 3.30906e-09 2.73862e-08 1.4005e-09 4164.41 -41.6268 835.098 3964.26 -57.8394 4117.74 +EDGE_SE3:QUAT 1616 1665 -4.43481 -9.25319 -4.92695 -0.104769 -0.124814 -0.150098 0.975149 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4302.85 2.21768 -1228.15 3917.86 60.1883 4256.63 +EDGE_SE3:QUAT 1617 1667 -4.42156 -0.395272 -5.02546 -0.0794035 0.0593976 -0.00731338 0.995044 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.06 -19.7577 469.128 3987.17 -8.36423 4054.06 +EDGE_SE3:QUAT 1616 1667 -4.73539 9.59875 -5.01015 -0.160692 0.0769602 0.135546 0.974619 1 7.70372e-19 7.70372e-19 -5.53493e-08 -6.02328e-09 -6.44215e-09 1 7.70372e-19 -5.53493e-08 -6.02328e-09 -6.44215e-09 1 -5.53493e-08 -6.02328e-09 -6.44215e-09 4075.91 -48.628 867.349 3952.84 29.4926 4105.7 +EDGE_SE3:QUAT 1617 1666 -4.80716 -9.3451 -4.57284 0.0406131 -0.0485485 -0.0626877 0.996024 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.97 -10.302 -356.95 3992.87 13.1067 4015.85 +EDGE_SE3:QUAT 1618 1668 -4.18255 0.155394 -4.8509 0.0127409 0.020089 -0.0545065 0.99823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.44 0.525217 168.544 3998.2 -4.54979 3995.2 +EDGE_SE3:QUAT 1617 1668 -4.49611 9.37182 -5.08439 0.0242962 0.110852 0.0197581 0.993343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4198.28 18.6755 918.047 3952.24 17.7314 4199.07 +EDGE_SE3:QUAT 1618 1667 -4.74118 -9.76795 -4.63255 -0.0367675 -0.0307069 -0.128252 0.990584 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.42 1.88395 -296.621 3994.25 19.2003 3956.03 +EDGE_SE3:QUAT 1619 1669 -4.21204 -0.234162 -5.02292 0.0930355 -0.164602 -0.00450152 0.981952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4418.98 -88.1503 -1421.41 3902.1 71.5816 4453.53 +EDGE_SE3:QUAT 1618 1669 -4.98986 9.31726 -5.01174 0.0593168 -0.0253061 0.117247 0.991007 1 1.92593e-19 1.92593e-19 1.06419e-09 -1.44381e-09 -2.75741e-08 1 1.92593e-19 1.06419e-09 -1.44381e-09 -2.75741e-08 1 1.06419e-09 -1.44381e-09 -2.75741e-08 4005.45 -6.11989 -281.122 3994.4 -16.6221 3964.54 +EDGE_SE3:QUAT 1619 1668 -4.59009 -9.59773 -4.78178 -0.163892 -0.0271486 -0.217427 0.961836 1 7.70372e-19 7.70372e-19 -5.16539e-09 -7.72511e-09 5.40305e-08 1 7.70372e-19 -5.16539e-09 -7.72511e-09 5.40305e-08 1 -5.16539e-09 -7.72511e-09 5.40305e-08 3982.04 39.9078 -614.791 3969.52 66.2679 3900.38 +EDGE_SE3:QUAT 1620 1670 -4.28055 0.0159497 -5.06886 -0.024184 -0.00475706 -0.0203657 0.999489 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.14 0.540844 -43.9108 3999.87 0.450662 3998.82 +EDGE_SE3:QUAT 1619 1670 -4.58828 9.14257 -5.18038 0.0163219 -0.0113541 0.248497 0.968429 1 3.00927e-21 3.00927e-21 3.36177e-09 8.61223e-10 -6.18075e-11 1 3.00927e-21 3.36177e-09 8.61223e-10 -6.18075e-11 1 3.36177e-09 8.61223e-10 -6.18075e-11 4003.09 0.241265 -129.316 3998.96 -17.6576 3757.15 +EDGE_SE3:QUAT 1620 1669 -4.42503 -9.31189 -4.89913 -0.0937216 -0.0431768 -0.149369 0.983382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4026.41 14.299 -501.833 3982.66 34.7182 3972.3 +EDGE_SE3:QUAT 1621 1671 -3.88146 -0.236595 -5.2124 0.245099 0.0921205 0.0278965 0.964708 1 4.81482e-20 4.81482e-20 -9.43457e-10 -3.5608e-09 -1.35428e-08 1 4.81482e-20 -9.43457e-10 -3.5608e-09 -1.35428e-08 1 -9.43457e-10 -3.5608e-09 -1.35428e-08 3846.78 77.1273 600.64 3989.63 45.9921 4083.96 +EDGE_SE3:QUAT 1620 1671 -4.68501 9.7017 -4.91558 -0.0346283 -0.140536 0.0852134 0.985794 1 8.1852e-19 8.1852e-19 -8.73965e-09 -5.60721e-08 -1.43056e-09 1 8.1852e-19 -8.73965e-09 -5.60721e-08 -1.43056e-09 1 -8.73965e-09 -5.60721e-08 -1.43056e-09 4298.9 64.8389 -1143.49 3934.8 -74.6491 4274.65 +EDGE_SE3:QUAT 1621 1670 -4.91838 -9.53671 -4.76477 0.00197384 0.118755 -0.0304663 0.992454 1 1.20841e-20 1.20841e-20 1.2901e-09 -5.20673e-11 7.13929e-09 1 1.20841e-20 1.2901e-09 -5.20673e-11 7.13929e-09 1 1.2901e-09 -5.20673e-11 7.13929e-09 4235.24 -9.91279 998.172 3943.92 -16.7684 4231.54 +EDGE_SE3:QUAT 1622 1672 -3.96906 -0.354271 -4.52097 0.166138 0.0300186 -0.0503513 0.984359 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3916.49 28.4469 330.008 3992.63 -3.10799 4016.75 +EDGE_SE3:QUAT 1621 1672 -4.90618 9.13176 -4.82884 0.177772 -0.0267686 0.0105367 0.983651 1 7.82409e-19 7.82409e-19 -5.46903e-08 -6.85418e-09 2.8306e-09 1 7.82409e-19 -5.46903e-08 -6.85418e-09 2.8306e-09 1 -5.46903e-08 -6.85418e-09 2.8306e-09 3886.4 -20.4761 -226.717 3997.09 2.17011 4012.37 +EDGE_SE3:QUAT 1622 1671 -4.4855 -9.5777 -4.3549 0.0682813 -0.00582886 -0.0198121 0.997452 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.57 -0.847516 -30.0992 3999.96 0.272629 3998.65 +EDGE_SE3:QUAT 1623 1673 -4.08063 0.12567 -4.47497 -0.0821333 -0.10313 -0.00634826 0.991251 1 1.92593e-19 1.92593e-19 2.81116e-08 3.0515e-10 -2.91445e-09 1 1.92593e-19 2.81116e-08 3.0515e-10 -2.91445e-09 1 2.81116e-08 3.0515e-10 -2.91445e-09 4147.86 37.3272 -854.364 3958.98 -19.056 4174.68 +EDGE_SE3:QUAT 1622 1673 -4.54596 9.65143 -4.82146 0.0351129 -0.0479994 -0.161834 0.985024 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.55 -11.2267 -302.419 3996.19 24.0252 3917.72 +EDGE_SE3:QUAT 1623 1672 -4.57138 -9.81711 -4.49386 -0.0626776 -0.0306842 -0.0992389 0.992614 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.04 7.39744 -316.321 3993.12 14.9279 3985.36 +EDGE_SE3:QUAT 1624 1674 -4.01563 -0.155877 -4.86659 0.0176366 -0.0657994 -0.00713384 0.997651 1 2.0463e-19 2.0463e-19 6.71824e-09 -2.77565e-08 6.15232e-11 1 2.0463e-19 6.71824e-09 -2.77565e-08 6.15232e-11 1 6.71824e-09 -2.77565e-08 6.15232e-11 4068.45 -5.65766 -532.571 3982.87 3.84556 4069.49 +EDGE_SE3:QUAT 1623 1674 -4.81789 9.4187 -4.95086 -0.00478551 0.154632 0.102139 0.982667 1 3.00927e-21 3.00927e-21 -3.57836e-09 -3.85101e-10 -5.54488e-10 1 3.00927e-21 -3.57836e-09 -3.85101e-10 -5.54488e-10 1 -3.57836e-09 -3.85101e-10 -5.54488e-10 4401.96 61.1406 1330.4 3912.22 82.1013 4360.32 +EDGE_SE3:QUAT 1624 1673 -4.69963 -9.21097 -4.56161 -0.074379 0.0343692 -0.246042 0.96579 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.58 0.982669 37.8961 4000.12 5.29262 3756.56 +EDGE_SE3:QUAT 1625 1675 -3.9832 -0.0028077 -5.06447 -0.1739 0.13966 0.00217088 0.974807 1 7.70372e-19 7.70372e-19 -5.61844e-08 2.71785e-09 -7.58781e-09 1 7.70372e-19 -5.61844e-08 2.71785e-09 -7.58781e-09 1 -5.61844e-08 2.71785e-09 -7.58781e-09 4181.23 -117.168 1140.72 3942.01 -83.2902 4302.18 +EDGE_SE3:QUAT 1624 1675 -5.00097 9.36112 -5.03167 -0.00248007 -0.209622 0.078599 0.974615 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4786.86 105.402 -1940.85 3837.17 -115.801 4762.18 +EDGE_SE3:QUAT 1625 1674 -4.27456 -9.3403 -4.63188 0.0492122 0.0663461 0.0553253 0.995045 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.84 17.8665 500.079 3986.01 18.8327 4049.28 +EDGE_SE3:QUAT 1626 1676 -4.25835 0.249901 -4.7494 -0.0567126 -0.0566305 -0.0240705 0.996492 1 6.01853e-20 6.01853e-20 1.43362e-08 1.32924e-10 -7.78582e-09 1 6.01853e-20 1.43362e-08 1.32924e-10 -7.78582e-09 1 1.43362e-08 1.32924e-10 -7.78582e-09 4042.2 12.0247 -472.571 3986.27 1.28314 4052.75 +EDGE_SE3:QUAT 1625 1676 -4.7037 9.38787 -4.91277 -0.127918 0.0870365 0.122353 0.980353 1 9.62965e-19 9.62965e-19 5.84526e-08 -2.16989e-08 3.49602e-09 1 9.62965e-19 5.84526e-08 -2.16989e-08 3.49602e-09 1 5.84526e-08 -2.16989e-08 3.49602e-09 4122.12 -33.3053 887.244 3952.21 28.937 4127.69 +EDGE_SE3:QUAT 1626 1675 -4.47341 -9.44411 -5.0379 -0.0554694 -0.107991 -0.0211805 0.992377 1 5.11575e-20 5.11575e-20 -1.44994e-08 -5.18211e-11 5.08613e-09 1 5.11575e-20 -1.44994e-08 -5.18211e-11 5.08613e-09 1 -1.44994e-08 -5.18211e-11 5.08613e-09 4185.64 22.1491 -911.587 3952.46 -5.87549 4196.16 +EDGE_SE3:QUAT 1627 1677 -3.63827 -0.0491408 -4.93784 0.00100127 0.0515231 -0.0572214 0.997031 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4042.53 -3.46692 414.666 3989.62 -12.1182 4029.44 +EDGE_SE3:QUAT 1626 1677 -4.70716 9.40962 -4.91393 -0.0829883 0.054643 -0.13516 0.985829 1 1.92593e-19 1.92593e-19 -2.74325e-08 3.97687e-09 -8.23451e-10 1 1.92593e-19 -2.74325e-08 3.97687e-09 -8.23451e-10 1 -2.74325e-08 3.97687e-09 -8.23451e-10 3992.46 -15.4208 288.752 3997.37 -19.7426 3946.94 +EDGE_SE3:QUAT 1627 1676 -4.53456 -9.33958 -4.95276 -0.108324 -0.0612067 -0.168149 0.977878 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4069.3 16.5459 -693.575 3968.73 49.9952 4003.14 +EDGE_SE3:QUAT 1628 1678 -4.2671 -0.366214 -4.75524 -0.162405 0.00282677 0.149738 0.975292 1 7.70372e-19 7.70372e-19 5.42903e-08 7.84696e-09 2.78291e-09 1 7.70372e-19 5.42903e-08 7.84696e-09 2.78291e-09 1 5.42903e-08 7.84696e-09 2.78291e-09 3915.74 -29.4105 304.995 3990.49 26.5715 3931.55 +EDGE_SE3:QUAT 1627 1678 -4.8225 8.90701 -5.18546 -0.0424606 -0.119073 0.00403048 0.991969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4227.19 25.7562 -996.278 3944.58 -17.6839 4234.34 +EDGE_SE3:QUAT 1628 1677 -4.33476 -9.28183 -4.99016 0.049516 -0.0496832 -0.0735063 0.994825 1 2.88889e-19 2.88889e-19 -1.39307e-08 1.64674e-08 2.75138e-08 1 2.88889e-19 -1.39307e-08 1.64674e-08 2.75138e-08 1 -1.39307e-08 1.64674e-08 2.75138e-08 4020.75 -12.1125 -351.382 3993.4 15.048 4008.94 +EDGE_SE3:QUAT 1629 1679 -3.88015 0.125026 -4.72771 0.0135453 -0.0463249 0.0348421 0.998227 1 5.11575e-20 5.11575e-20 3.94666e-09 -1.37362e-08 -2.08561e-11 1 5.11575e-20 3.94666e-09 -1.37362e-08 -2.08561e-11 1 3.94666e-09 -1.37362e-08 -2.08561e-11 4034.75 -0.780351 -378.427 3991.15 -6.05229 4030.63 +EDGE_SE3:QUAT 1628 1679 -4.58137 9.24173 -4.77813 0.255375 0.0400304 0.178111 0.949451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3745.3 -54.6953 -236.139 3988.32 -37.6099 3879.27 +EDGE_SE3:QUAT 1629 1678 -4.39474 -9.63533 -4.91972 -0.0559531 0.00183401 0.00918642 0.998389 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.58 -0.636296 20.7568 3999.97 0.0967749 3999.77 +EDGE_SE3:QUAT 1630 1680 -4.1335 -0.0279733 -4.76904 -0.0113242 0.040569 -0.00635878 0.999092 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4025.8 -2.12485 325.464 3993.47 -1.50048 4026.15 +EDGE_SE3:QUAT 1629 1680 -4.85525 9.62714 -4.84162 -0.0888154 -0.180405 -0.0572261 0.977901 1 4.81482e-20 4.81482e-20 2.79041e-09 1.08759e-09 -1.4584e-08 1 4.81482e-20 2.79041e-09 1.08759e-09 -1.4584e-08 1 2.79041e-09 1.08759e-09 -1.4584e-08 4582.07 47.0903 -1682.59 3863.27 -20.2634 4600.53 +EDGE_SE3:QUAT 1630 1679 -4.6846 -9.37235 -4.72385 0.0636099 -0.00759593 -0.106163 0.992283 1 1.92593e-19 1.92593e-19 -2.75411e-08 2.9494e-09 -1.67631e-10 1 1.92593e-19 -2.75411e-08 2.9494e-09 -1.67631e-10 1 -2.75411e-08 2.9494e-09 -1.67631e-10 3983.74 1.53969 20.8345 3999.85 -2.56651 3954.84 +EDGE_SE3:QUAT 1631 1681 -3.9903 0.0631469 -4.6641 0.268861 -0.0590723 0.109543 0.955104 1 1.92593e-19 1.92593e-19 -3.00181e-09 7.15115e-09 2.7025e-08 1 1.92593e-19 -3.00181e-09 7.15115e-09 2.7025e-08 1 -3.00181e-09 7.15115e-09 2.7025e-08 3855.54 -103.959 -777.132 3962.93 1.3518 4096.69 +EDGE_SE3:QUAT 1630 1681 -4.85734 9.65389 -4.77491 -0.0280454 -0.0857704 0.122712 0.988331 1 1.92593e-19 1.92593e-19 3.58024e-09 -2.74095e-08 -1.3504e-09 1 1.92593e-19 3.58024e-09 -2.74095e-08 -1.3504e-09 1 3.58024e-09 -2.74095e-08 -1.3504e-09 4097.17 29.0396 -641.838 3978.96 -45.5019 4040.08 +EDGE_SE3:QUAT 1631 1680 -4.59902 -9.30508 -4.74534 -0.20819 -0.0360092 0.0544185 0.975909 1 7.82409e-19 7.82409e-19 -5.37547e-08 -1.03469e-08 -8.81837e-10 1 7.82409e-19 -5.37547e-08 -1.03469e-08 -8.81837e-10 1 -5.37547e-08 -1.03469e-08 -8.81837e-10 3830.53 9.43734 -136.32 4000 -4.5775 3992.06 +EDGE_SE3:QUAT 1632 1682 -4.16747 -0.291438 -4.80577 -0.238259 0.0442037 -0.0894554 0.966062 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3771.98 2.08892 74.4083 4000.47 -0.56455 3967.04 +EDGE_SE3:QUAT 1631 1682 -4.98397 8.99058 -4.62848 0.134498 -0.0217574 0.110508 0.984492 1 2.40741e-19 2.40741e-19 1.55593e-11 -1.01476e-08 2.91856e-08 1 2.40741e-19 1.55593e-11 -1.01476e-08 2.91856e-08 1 1.55593e-11 -1.01476e-08 2.91856e-08 3956.29 -23.2945 -343.584 3990.63 -17.5882 3979.8 +EDGE_SE3:QUAT 1632 1681 -4.4535 -9.31059 -4.67784 -0.0234972 -0.0283807 -0.261329 0.964546 1 3.00927e-21 3.00927e-21 -3.35492e-09 9.05269e-10 1.26415e-10 1 3.00927e-21 -3.35492e-09 9.05269e-10 1.26415e-10 1 -3.35492e-09 9.05269e-10 1.26415e-10 4016.69 -3.65902 -275.628 3995.94 37.9245 3745.72 +EDGE_SE3:QUAT 1633 1683 -3.85666 0.0670277 -4.69368 -0.128126 0.0969258 0.00419057 0.987001 1 7.70372e-19 7.70372e-19 5.58208e-08 -1.17951e-09 5.35978e-09 1 7.70372e-19 5.58208e-08 -1.17951e-09 5.35978e-09 1 5.58208e-08 -1.17951e-09 5.35978e-09 4083.78 -54.2267 787.556 3966.75 -27.8938 4149.38 +EDGE_SE3:QUAT 1632 1683 -4.8159 9.5562 -4.71909 0.0272203 -0.0734401 0.162716 0.983559 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4093.8 14.4642 -629.606 3977.96 -51.2339 3990.85 +EDGE_SE3:QUAT 1633 1682 -5.09796 -9.20517 -4.72855 -0.119067 -0.0119603 -0.000115479 0.992814 1 1.88079e-22 1.88079e-22 1.01062e-11 1.0333e-10 -8.61369e-10 1 1.88079e-22 1.01062e-11 1.0333e-10 -8.61369e-10 1 1.01062e-11 1.0333e-10 -8.61369e-10 3945.49 5.55844 -93.8634 3999.49 -0.394156 4002.2 +EDGE_SE3:QUAT 1634 1684 -4.35865 0.223966 -5.16527 -0.0880847 -0.0347901 -0.0448383 0.994495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.89 13.4396 -323.34 3993.15 4.43088 4017.89 +EDGE_SE3:QUAT 1633 1684 -4.68317 9.09863 -5.11167 -0.142099 -0.0212281 0.185603 0.972064 1 7.71124e-19 7.71124e-19 5.43002e-08 8.52704e-09 1.55515e-09 1 7.71124e-19 5.43002e-08 8.52704e-09 1.55515e-09 1 5.43002e-08 8.52704e-09 1.55515e-09 3922.12 -18.0421 148.959 3995.83 23.7664 3865.1 +EDGE_SE3:QUAT 1634 1683 -4.74164 -9.15252 -5.01017 0.0822451 -0.0541344 -0.20498 0.973801 1 2.40741e-19 2.40741e-19 2.41257e-08 -1.93784e-08 9.10796e-10 1 2.40741e-19 2.41257e-08 -1.93784e-08 9.10796e-10 1 2.41257e-08 -1.93784e-08 9.10796e-10 3981.77 -10.4033 -205.296 4000.13 15.3364 3840.76 +EDGE_SE3:QUAT 1635 1685 -3.91512 0.0207412 -5.36601 0.00597456 -0.19574 -0.121213 0.973117 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4646.31 -136.519 -1733.38 3873.34 153.738 4587.68 +EDGE_SE3:QUAT 1634 1685 -4.60015 9.08076 -4.69974 0.0177575 0.0362899 -0.022883 0.998921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.56 1.93479 296.252 3994.53 -2.87568 4019.73 +EDGE_SE3:QUAT 1635 1684 -4.52107 -9.06685 -4.27945 -0.0402247 0.0624278 -0.21017 0.97484 1 8.66668e-19 8.66668e-19 -1.2826e-08 2.00145e-08 -5.40372e-08 1 8.66668e-19 -1.2826e-08 2.00145e-08 -5.40372e-08 1 -1.2826e-08 2.00145e-08 -5.40372e-08 4026.51 -19.4416 368.705 3995.85 -37.5489 3856.3 +EDGE_SE3:QUAT 1636 1686 -4.16349 -0.324159 -4.70218 -0.0357047 0.13015 -0.178859 0.974575 1 4.81482e-20 4.81482e-20 -1.38963e-08 2.76183e-09 -1.54156e-09 1 4.81482e-20 -1.38963e-08 2.76183e-09 -1.54156e-09 1 -1.38963e-08 2.76183e-09 -1.54156e-09 4209.27 -83.429 952.56 3964.33 -107.87 4086.41 +EDGE_SE3:QUAT 1635 1686 -4.69212 9.13557 -5.09174 -0.0683175 0.0242022 -0.119476 0.990188 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3983.11 -2.5312 91.3639 3999.88 -3.74328 3944.68 +EDGE_SE3:QUAT 1636 1685 -4.30242 -9.35154 -4.61963 -0.0708448 -0.114774 0.0625219 0.988888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4167.1 53.3749 -885.714 3959.98 -51.7945 4171.54 +EDGE_SE3:QUAT 1637 1687 -4.12301 -0.0700542 -4.49499 0.0558135 -0.0853914 -0.147017 0.983859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4066.22 -35.4144 -568.673 3986.26 48.8567 3992.23 +EDGE_SE3:QUAT 1636 1687 -4.44789 9.39926 -4.84327 0.0561342 0.289619 -0.0534017 0.954001 1 3.27408e-18 3.27408e-18 3.4912e-08 1.05151e-07 6.2937e-09 1 3.27408e-18 3.4912e-08 1.05151e-07 6.2937e-09 1 3.4912e-08 1.05151e-07 6.2937e-09 5807 8.02642 3254.14 3659.01 9.62616 5808.2 +EDGE_SE3:QUAT 1637 1686 -4.4021 -9.25782 -4.62581 0.0395903 0.0769666 -0.0835195 0.99274 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4100.78 0.893548 663.107 3973.58 -23.6786 4079.14 +EDGE_SE3:QUAT 1638 1688 -4.30524 -0.122147 -4.89123 -0.137 0.163378 -0.0298413 0.976549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4320.68 -132.341 1319.8 3925.53 -113.969 4392.2 +EDGE_SE3:QUAT 1637 1688 -4.70365 9.39095 -4.86745 0.0348727 -0.00333109 0.00133962 0.999385 1 4.70198e-23 4.70198e-23 1.48164e-12 -1.51204e-11 -4.33424e-10 1 4.70198e-23 1.48164e-12 -1.51204e-11 -4.33424e-10 1 1.48164e-12 -1.51204e-11 -4.33424e-10 3995.32 -0.476257 -27.1613 3999.95 -0.00873676 4000.18 +EDGE_SE3:QUAT 1638 1687 -4.74251 -9.08502 -4.77707 -0.282452 0.00671133 -0.112281 0.952664 1 3.09352e-18 3.09352e-18 -1.05396e-07 1.75269e-08 8.03978e-09 1 3.09352e-18 -1.05396e-07 1.75269e-08 8.03978e-09 1 -1.05396e-07 1.75269e-08 8.03978e-09 3702.21 60.1887 -312.387 3988.78 18.9285 3970.9 +EDGE_SE3:QUAT 1639 1689 -4.0599 0.0543054 -4.388 0.131247 0.200573 -0.106837 0.964951 1 1.92593e-19 1.92593e-19 -2.95671e-08 1.75563e-09 -6.70719e-09 1 1.92593e-19 -2.95671e-08 1.75563e-09 -6.70719e-09 1 -2.95671e-08 1.75563e-09 -6.70719e-09 4786.01 55.0342 2037.41 3817.03 15.9542 4809.26 +EDGE_SE3:QUAT 1638 1689 -4.9113 8.98676 -4.92635 0.069957 0.0265315 0.0667372 0.994961 1 2.0463e-19 2.0463e-19 -2.71513e-08 -8.84283e-09 4.14171e-11 1 2.0463e-19 -2.71513e-08 -8.84283e-09 4.14171e-11 1 -2.71513e-08 -8.84283e-09 4.14171e-11 3986.22 5.41341 153.711 3998.96 5.23001 3987.98 +EDGE_SE3:QUAT 1639 1688 -4.52372 -9.36561 -4.4097 0.03872 -0.202423 -0.0229265 0.978264 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4722.19 -79.0023 -1855.55 3844.17 76.6625 4726.08 +EDGE_SE3:QUAT 1640 1690 -4.04577 0.275392 -4.58881 -0.0806226 -0.0256002 0.115026 0.989754 1 1.92593e-19 1.92593e-19 2.74767e-08 3.26788e-09 -1.72235e-10 1 1.92593e-19 2.74767e-08 3.26788e-09 -1.72235e-10 1 2.74767e-08 3.26788e-09 -1.72235e-10 3975.58 2.57633 -88.8545 3999.93 -3.26746 3948.66 +EDGE_SE3:QUAT 1639 1690 -4.80317 9.3643 -4.67348 -0.0368578 -0.120217 -0.0243421 0.991765 1 4.81482e-20 4.81482e-20 -1.41812e-08 2.28092e-10 1.73866e-09 1 4.81482e-20 -1.41812e-08 2.28092e-10 1.73866e-09 1 -1.41812e-08 2.28092e-10 1.73866e-09 4240.62 12.6143 -1022.14 3941.15 0.472474 4243.69 +EDGE_SE3:QUAT 1640 1689 -4.95432 -9.4148 -4.97452 -0.103558 0.0801315 0.125919 0.983361 1 3.85186e-19 3.85186e-19 3.08423e-08 -2.42799e-08 6.15503e-10 1 3.85186e-19 3.08423e-08 -2.42799e-08 6.15503e-10 1 3.08423e-08 -2.42799e-08 6.15503e-10 4110.29 -19.6597 798.434 3960.78 34.7607 4089.77 +EDGE_SE3:QUAT 1641 1691 -4.17131 -0.0296324 -4.94636 0.133038 0.052875 -0.0542564 0.988211 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.37 31.4904 502.892 3984.05 -2.99118 4050.39 +EDGE_SE3:QUAT 1640 1691 -5.22339 9.41545 -4.95402 0.160337 -0.000126469 0.0764072 0.984101 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3901.9 -15.2009 -145.058 3997.72 -6.64702 3981.38 +EDGE_SE3:QUAT 1641 1690 -4.57434 -9.21139 -4.68042 0.0662717 -0.057538 0.0130728 0.996055 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.66 -15.2374 -473.253 3986.43 2.27888 4054.55 +EDGE_SE3:QUAT 1642 1692 -4.10205 0.135027 -4.53598 0.0183576 -0.14694 0.033749 0.988399 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4371.36 5.16567 -1276.61 3912.96 -15.9108 4368.15 +EDGE_SE3:QUAT 1641 1692 -5.10473 9.25248 -5.01159 -0.0492465 -0.0365754 0.132769 0.989247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.71 6.97548 -206.656 3998.35 -12.864 3939.9 +EDGE_SE3:QUAT 1642 1691 -4.42566 -9.2387 -4.59897 0.0175184 -0.0862732 -0.151754 0.98449 1 7.70372e-19 7.70372e-19 4.32073e-09 -2.42432e-09 -5.53612e-08 1 7.70372e-19 4.32073e-09 -2.42432e-09 -5.53612e-08 1 4.32073e-09 -2.42432e-09 -5.53612e-08 4100.96 -30.7657 -648.014 3979.37 54.2024 4010.07 +EDGE_SE3:QUAT 1643 1693 -4.03064 0.239377 -4.5118 -0.0454508 -0.000389187 -0.0311039 0.998482 1 4.81953e-20 4.81953e-20 -1.38703e-08 -3.63984e-12 2.48846e-11 1 4.81953e-20 -1.38703e-08 -3.63984e-12 2.48846e-11 1 -1.38703e-08 -3.63984e-12 2.48846e-11 3991.83 0.580544 -20.0299 3999.96 0.394918 3996.22 +EDGE_SE3:QUAT 1642 1693 -4.57819 9.17348 -5.22596 -0.0481393 0.189173 0.188407 0.962496 1 7.70372e-19 7.70372e-19 1.02129e-08 -5.34768e-08 1.43506e-09 1 7.70372e-19 1.02129e-08 -5.34768e-08 1.43506e-09 1 1.02129e-08 -5.34768e-08 1.43506e-09 4658.36 144.78 1765.39 3873.89 183.81 4525.64 +EDGE_SE3:QUAT 1643 1692 -4.65919 -8.98143 -4.94476 -0.0900111 0.21198 0.0708424 0.970538 1 9.62965e-19 9.62965e-19 3.18078e-08 -5.28765e-08 3.08523e-09 1 9.62965e-19 3.18078e-08 -5.28765e-08 3.08523e-09 1 3.18078e-08 -5.28765e-08 3.08523e-09 4855.31 -40.4529 2083.03 3810.38 -17.7196 4867.65 +EDGE_SE3:QUAT 1644 1694 -4.37864 -0.265503 -4.53053 -0.121214 0.121712 0.12054 0.977734 1 9.62965e-19 9.62965e-19 -3.33302e-08 5.1815e-08 9.55523e-10 1 9.62965e-19 -3.33302e-08 5.1815e-08 9.55523e-10 1 -3.33302e-08 5.1815e-08 9.55523e-10 4268.28 -30.0218 1190.1 3921.29 29.2012 4268.94 +EDGE_SE3:QUAT 1643 1694 -4.47466 8.88008 -4.69514 0.0264949 0.00128892 -0.0125555 0.999569 1 3.00927e-21 3.00927e-21 6.77149e-12 9.17825e-11 3.46797e-09 1 3.00927e-21 6.77149e-12 9.17825e-11 3.46797e-09 1 6.77149e-12 9.17825e-11 3.46797e-09 3997.24 0.206006 14.2878 3999.98 -0.0962392 3999.42 +EDGE_SE3:QUAT 1644 1693 -4.44771 -9.54638 -4.68418 -0.0678911 0.139213 -0.0901608 0.98381 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4251.78 -82.1316 1075.02 3946.3 -86.1756 4237.7 +EDGE_SE3:QUAT 1645 1695 -4.25221 0.0285592 -4.73075 -0.0283872 0.00585442 0.051593 0.998247 1 1.27894e-20 1.27894e-20 -7.01641e-09 1.37653e-09 -1.27003e-11 1 1.27894e-20 -7.01641e-09 1.37653e-09 -1.27003e-11 1 -7.01641e-09 1.37653e-09 -1.27003e-11 3997.8 -0.922503 64.1429 3999.7 1.76584 3990.37 +EDGE_SE3:QUAT 1644 1695 -4.75475 9.28093 -4.79441 0.139486 -0.17019 0.0894392 0.97138 1 7.70372e-19 7.70372e-19 5.78818e-08 2.53166e-09 -1.11347e-08 1 7.70372e-19 5.78818e-08 2.53166e-09 -1.11347e-08 1 5.78818e-08 2.53166e-09 -1.11347e-08 4517.15 -74.8517 -1653.57 3868.15 28.4168 4562.98 +EDGE_SE3:QUAT 1645 1694 -4.58811 -9.05092 -4.81835 -0.129396 0.0910022 0.196416 0.967676 1 1.92593e-19 1.92593e-19 -2.77126e-08 -4.88834e-09 -3.7636e-09 1 1.92593e-19 -2.77126e-08 -4.88834e-09 -3.7636e-09 1 -2.77126e-08 -4.88834e-09 -3.7636e-09 4178.84 -12.2735 1023.35 3938.28 77.1311 4091.5 +EDGE_SE3:QUAT 1646 1696 -4.1962 0.398593 -4.57568 0.0970091 0.0654024 0.0357126 0.99249 1 4.81482e-20 4.81482e-20 -7.9708e-10 -1.42876e-09 -1.38715e-08 1 4.81482e-20 -7.9708e-10 -1.42876e-09 -1.38715e-08 1 -7.9708e-10 -1.42876e-09 -1.38715e-08 4018.8 26.5731 478.894 3987.79 17.3282 4051.34 +EDGE_SE3:QUAT 1645 1696 -4.9049 9.03123 -4.7574 0.117935 -0.00185894 0.015202 0.992903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3944.68 -2.5265 -35.8714 3999.89 -0.283157 3999.39 +EDGE_SE3:QUAT 1646 1695 -4.47586 -9.37754 -4.99773 0.102136 -0.0991785 0.0300152 0.989359 1 1.20371e-20 1.20371e-20 7.31087e-10 -6.95024e-10 -7.01301e-09 1 1.20371e-20 7.31087e-10 -6.95024e-10 -7.01301e-09 1 7.31087e-10 -6.95024e-10 -7.01301e-09 4130.68 -40.5997 -848.145 3959.07 12.478 4168.8 +EDGE_SE3:QUAT 1647 1697 -4.2617 -0.521562 -4.93285 -0.1162 -0.145765 0.126357 0.974312 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4169.51 112.84 -976.651 3968.92 -114.28 4159.66 +EDGE_SE3:QUAT 1646 1697 -4.69278 8.84117 -4.77515 -0.0772055 -0.0231834 0.203229 0.975807 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.11 -2.93824 9.96461 3999.66 7.83262 3833.75 +EDGE_SE3:QUAT 1647 1696 -4.63555 -9.2471 -4.80948 -0.17588 0.137908 0.181905 0.957579 1 1.54074e-18 1.54074e-18 4.94558e-08 6.13386e-08 1.7794e-08 1 1.54074e-18 4.94558e-08 6.13386e-08 1.7794e-08 1 4.94558e-08 6.13386e-08 1.7794e-08 4406.39 -41.6167 1551.03 3876.36 52.6502 4397.76 +EDGE_SE3:QUAT 1648 1698 -3.90491 -0.38037 -4.82064 -0.111923 -0.028826 0.0352475 0.992673 1 1.92593e-19 1.92593e-19 -2.75799e-08 -1.13435e-09 5.60697e-10 1 1.92593e-19 -2.75799e-08 -1.13435e-09 5.60697e-10 1 -2.75799e-08 -1.13435e-09 5.60697e-10 3957.82 9.60233 -179.168 3998.51 -4.40491 4002.95 +EDGE_SE3:QUAT 1647 1698 -4.85704 9.42935 -5.12892 0.0247679 0.117279 -0.0172783 0.99264 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4229.1 7.92982 989.867 3944.48 -1.00741 4230.36 +EDGE_SE3:QUAT 1648 1697 -4.79013 -9.34322 -4.64516 -0.0197121 0.122863 -0.0162689 0.992095 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4248.68 -18.0707 1031.29 3940.71 -17.3469 4249.17 +EDGE_SE3:QUAT 1649 1699 -3.92635 0.159322 -4.43213 -0.0230762 0.00921391 0.0675151 0.997409 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.97 -0.934918 91.8291 3999.41 3.24075 3983.87 +EDGE_SE3:QUAT 1648 1699 -5.02095 9.09169 -4.69849 -0.0840641 0.188649 0.149085 0.967015 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4702 60.7078 1858.65 3844.56 102.305 4641.36 +EDGE_SE3:QUAT 1649 1698 -4.65925 -8.98235 -4.60588 0.0542907 -0.0261632 -0.0839683 0.994644 1 1.92593e-19 1.92593e-19 -4.59803e-10 1.60989e-09 2.76267e-08 1 1.92593e-19 -4.59803e-10 1.60989e-09 2.76267e-08 1 -4.59803e-10 1.60989e-09 2.76267e-08 3993.87 -4.47786 -151.936 3998.98 6.1547 3977.46 +EDGE_SE3:QUAT 1650 1700 -4.49057 -0.165011 -4.70984 0.0974697 0.079927 -0.0190044 0.991842 1 3.85186e-19 3.85186e-19 2.79935e-08 2.74431e-08 -3.45824e-10 1 3.85186e-19 2.79935e-08 2.74431e-08 -3.45824e-10 1 2.79935e-08 2.74431e-08 -3.45824e-10 4070.56 31.9119 667.87 3974.03 9.17261 4107.12 +EDGE_SE3:QUAT 1649 1700 -4.71574 9.21083 -4.91658 0.165107 0.0876364 0.166009 0.968246 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3912.31 27.4679 323.908 4001.44 27.5038 3911.11 +EDGE_SE3:QUAT 1650 1699 -4.71875 -9.56658 -4.24401 0.110507 -0.0692492 -0.059535 0.989671 1 1.92593e-19 1.92593e-19 -2.76553e-08 2.06417e-09 1.50471e-09 1 1.92593e-19 -2.76553e-08 2.06417e-09 1.50471e-09 1 -2.76553e-08 2.06417e-09 1.50471e-09 4004.7 -30.5128 -467.206 3989.64 23.4533 4039.37 +EDGE_SE3:QUAT 1651 1701 -3.91902 -0.110364 -4.64078 -0.0201128 0.0111714 0.012395 0.999658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.51 -0.900494 92.3311 3999.46 0.515634 4001.52 +EDGE_SE3:QUAT 1650 1701 -4.8677 9.37426 -5.12144 -0.156492 0.0786679 0.264851 0.948249 1 3.08149e-18 3.08149e-18 1.65933e-08 -1.11503e-08 1.09128e-07 1 3.08149e-18 1.65933e-08 -1.11503e-08 1.09128e-07 1 1.65933e-08 -1.11503e-08 1.09128e-07 4174.81 -8.88847 1083.46 3930.2 123.132 3992.18 +EDGE_SE3:QUAT 1651 1700 -4.48285 -9.06652 -4.39616 0.0731556 -0.0272504 -0.104989 0.991405 1 1.92593e-19 1.92593e-19 2.75289e-08 -2.99704e-09 -3.08226e-10 1 1.92593e-19 2.75289e-08 -2.99704e-09 -3.08226e-10 1 2.75289e-08 -2.99704e-09 -3.08226e-10 3982 -4.0757 -121.465 3999.61 5.25527 3959.32 +EDGE_SE3:QUAT 1652 1702 -4.03484 0.0439801 -4.61325 0.0280994 0.0943457 -0.00628546 0.995123 1 1.88079e-22 1.88079e-22 8.34993e-11 2.42033e-11 8.7884e-10 1 1.88079e-22 8.34993e-11 2.42033e-11 8.7884e-10 1 8.34993e-11 2.42033e-11 8.7884e-10 4143.64 10.5967 780.225 3964.35 3.60361 4146.64 +EDGE_SE3:QUAT 1651 1702 -4.47275 9.27631 -4.77013 0.0587616 0.0785458 0.222256 0.970041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.19 30.2796 429.558 3996.12 47.1729 3846.41 +EDGE_SE3:QUAT 1652 1701 -4.41016 -8.87516 -4.7968 -0.0250765 -0.0333785 0.0960225 0.994503 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.21 4.9591 -235.002 3997.04 -11.4247 3976.84 +EDGE_SE3:QUAT 1653 1703 -4.32871 -0.262726 -4.85218 -0.11272 0.126146 -0.0677043 0.983259 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4153.26 -80.7561 927.684 3961.48 -72.8706 4185.75 +EDGE_SE3:QUAT 1652 1703 -4.97601 8.86358 -4.6 -0.0806415 0.0914539 -0.000173177 0.992539 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4108.41 -32.6457 745.519 3968.4 -16.7147 4134.43 +EDGE_SE3:QUAT 1653 1702 -4.95313 -9.4138 -4.60702 0.107469 -0.107928 -0.0678522 0.986001 1 1.92593e-19 1.92593e-19 2.78685e-08 -2.57587e-09 -2.52932e-09 1 1.92593e-19 2.78685e-08 -2.57587e-09 -2.52932e-09 1 2.78685e-08 -2.57587e-09 -2.52932e-09 4098.92 -60.53 -776.88 3971.93 53.6973 4126.7 +EDGE_SE3:QUAT 1654 1704 -4.30571 0.265952 -4.77415 0.0226454 -0.0568892 -0.0611829 0.996247 1 6.01853e-20 6.01853e-20 -6.06495e-09 1.42706e-08 -3.64249e-11 1 6.01853e-20 -6.06495e-09 1.42706e-08 -3.64249e-11 1 -6.06495e-09 1.42706e-08 -3.64249e-11 4045.77 -9.58436 -440.024 3988.75 15.3697 4032.85 +EDGE_SE3:QUAT 1653 1704 -4.98492 9.12248 -5.07078 -0.0979681 -0.129021 0.0638959 0.98472 1 3.85186e-19 3.85186e-19 -2.48977e-08 7.61685e-10 -2.48977e-08 1 3.85186e-19 -2.48977e-08 7.61685e-10 -2.48977e-08 1 -2.48977e-08 7.61685e-10 -2.48977e-08 4187.88 77.6773 -978.797 3955.06 -71.4735 4209.94 +EDGE_SE3:QUAT 1654 1703 -4.81702 -8.86312 -4.44397 -0.0961214 0.109373 -0.0242658 0.989045 1 3.85186e-19 3.85186e-19 -2.67996e-08 2.87269e-08 -2.9902e-11 1 3.85186e-19 -2.67996e-08 2.87269e-08 -2.9902e-11 1 -2.67996e-08 2.87269e-08 -2.9902e-11 4142.31 -52.8546 865.767 3960.54 -38.7713 4176.91 +EDGE_SE3:QUAT 1655 1705 -4.1026 -0.00363607 -5.05531 -0.102754 -0.029164 -0.0438358 0.993312 1 2.40741e-19 2.40741e-19 -2.81537e-08 -1.27584e-08 -3.47469e-10 1 2.40741e-19 -2.81537e-08 -1.27584e-08 -3.47469e-10 1 -2.81537e-08 -1.27584e-08 -3.47469e-10 3977.77 14.3787 -283.948 3994.6 3.77887 4012.32 +EDGE_SE3:QUAT 1654 1705 -5.02226 9.19104 -4.85777 0.125032 -0.0151695 0.0255485 0.991708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.56 -10.3433 -156.559 3998.32 -1.11166 4003.48 +EDGE_SE3:QUAT 1655 1704 -4.69316 -9.1168 -4.43136 -0.0218832 -0.0926475 -0.172828 0.980341 1 3.00927e-21 3.00927e-21 3.46446e-09 -6.06983e-10 -3.34096e-10 1 3.00927e-21 3.46446e-09 -6.06983e-10 -3.34096e-10 1 3.46446e-09 -6.06983e-10 -3.34096e-10 4143.64 -29.3408 -776.836 3968.64 68.9933 4026.08 +EDGE_SE3:QUAT 1656 1706 -4.11631 -0.101909 -4.7638 0.0406052 -0.0354551 -0.136189 0.989215 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.21 -6.42984 -209.915 3998.18 13.5111 3936.61 +EDGE_SE3:QUAT 1655 1706 -5.03837 9.19055 -4.6262 0.273178 -0.0325377 -0.0540878 0.959891 1 3.14167e-18 3.14167e-18 1.07017e-07 3.46591e-09 1.15167e-08 1 3.14167e-18 1.07017e-07 3.46591e-09 1.15167e-08 1 1.07017e-07 3.46591e-09 1.15167e-08 3701.26 0.777538 -62.1971 4000.34 0.906271 3988.06 +EDGE_SE3:QUAT 1656 1705 -5.02121 -9.35911 -4.44134 -0.0616258 0.132992 0.0492973 0.98797 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4300.44 -19.348 1167.13 3925.3 4.70068 4305.91 +EDGE_SE3:QUAT 1657 1707 -4.44008 0.217748 -5.00081 -0.12453 0.147079 0.0528924 0.979828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4342.5 -71.5811 1334.85 3908.61 -33.6382 4393.34 +EDGE_SE3:QUAT 1656 1707 -4.48063 9.1754 -4.90994 -0.0442015 0.0561155 0.13151 0.988738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4056.8 0.135088 512.671 3983.83 32.1336 3995.43 +EDGE_SE3:QUAT 1657 1706 -4.80738 -9.13506 -4.77763 0.112444 -0.00503085 -0.0370932 0.992953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3949.38 1.52677 10.1805 3999.95 -0.504812 3994.45 +EDGE_SE3:QUAT 1658 1708 -4.26717 0.262128 -4.31431 -0.0440991 0.222963 0.168056 0.959218 1 1.20371e-20 1.20371e-20 -7.42561e-09 -1.28175e-09 -1.73918e-09 1 1.20371e-20 -7.42561e-09 -1.28175e-09 -1.73918e-09 1 -7.42561e-09 -1.28175e-09 -1.73918e-09 4941.87 192.616 2168.16 3825.77 216.76 4836.68 +EDGE_SE3:QUAT 1657 1708 -4.77093 8.8823 -4.60646 -0.0882039 0.0434757 -0.00220788 0.995151 1 4.89006e-20 4.89006e-20 -6.27559e-11 -1.39643e-08 5.0138e-10 1 4.89006e-20 -6.27559e-11 -1.39643e-08 5.0138e-10 1 -6.27559e-11 -1.39643e-08 5.0138e-10 3998.18 -15.4545 343.591 3993.05 -4.32199 4029.28 +EDGE_SE3:QUAT 1658 1707 -4.58323 -8.99273 -4.52856 0.110084 0.0632075 -0.0263483 0.99156 1 1.92593e-19 1.92593e-19 -2.77689e-08 3.3638e-10 -1.8875e-09 1 1.92593e-19 -2.77689e-08 3.3638e-10 -1.8875e-09 1 -2.77689e-08 3.3638e-10 -1.8875e-09 4022.91 28.6782 539.127 3982.64 4.17133 4068.61 +EDGE_SE3:QUAT 1659 1709 -4.16087 0.127559 -4.90054 0.0876754 -0.215862 -0.0738568 0.969671 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4697.38 -210.723 -1856.47 3873.47 209.201 4706.31 +EDGE_SE3:QUAT 1658 1709 -4.64393 8.80705 -4.70593 0.0175216 0.0843919 0.0413168 0.995421 1 4.81482e-20 4.81482e-20 -1.16201e-09 -3.4833e-10 -1.40078e-08 1 4.81482e-20 -1.16201e-09 -3.4833e-10 -1.40078e-08 1 -1.16201e-09 -3.4833e-10 -1.40078e-08 4111.39 13.5029 680.569 3973.03 18.0498 4105.79 +EDGE_SE3:QUAT 1659 1708 -4.63099 -8.9792 -4.79859 -0.00288711 0.0856868 -0.128617 0.987981 1 7.73381e-19 7.73381e-19 -8.09625e-09 1.86472e-09 -5.59115e-08 1 7.73381e-19 -8.09625e-09 1.86472e-09 -5.59115e-08 1 -8.09625e-09 1.86472e-09 -5.59115e-08 4112.42 -23.5519 680.184 3975.16 -47.1147 4046.29 +EDGE_SE3:QUAT 1660 1710 -4.46288 0.243012 -5.19301 -0.0725828 0.0711204 -0.0204807 0.994613 1 1.92593e-19 1.92593e-19 -2.78672e-08 8.6405e-10 -1.88566e-09 1 1.92593e-19 -2.78672e-08 8.6405e-10 -1.88566e-09 1 -2.78672e-08 8.6405e-10 -1.88566e-09 4054.51 -23.2945 555.082 3982.42 -14.3837 4073.9 +EDGE_SE3:QUAT 1659 1710 -5.09415 8.58136 -4.90714 -0.0207107 0.169516 0.0276065 0.984923 1 1.20371e-20 1.20371e-20 -7.25462e-09 -1.61543e-10 -1.25451e-09 1 1.20371e-20 -7.25462e-09 -1.61543e-10 -1.25451e-09 1 -7.25462e-09 -1.61543e-10 -1.25451e-09 4504.96 1.59423 1511.09 3884.25 10.7747 4503.62 +EDGE_SE3:QUAT 1660 1709 -4.80692 -9.14537 -4.62397 -0.177627 0.00745752 -0.0917611 0.979782 1 7.73381e-19 7.73381e-19 -5.47212e-08 1.5177e-09 7.8197e-10 1 7.73381e-19 -5.47212e-08 1.5177e-09 7.8197e-10 1 -5.47212e-08 1.5177e-09 7.8197e-10 3877.33 17.5523 -134.366 3997.53 8.6671 3969.86 +EDGE_SE3:QUAT 1661 1711 -4.15453 0.0218539 -4.65517 -0.0481308 -0.0829624 0.0471888 0.994271 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4092.27 23.8113 -645.459 3976.6 -23.6403 4092.63 +EDGE_SE3:QUAT 1660 1711 -4.83713 9.39793 -4.79075 0.0472754 -0.10283 0.145272 0.982897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4190.67 18.953 -915.626 3953.62 -61.8633 4115.2 +EDGE_SE3:QUAT 1661 1710 -4.68735 -9.02343 -5.21996 -0.066721 -0.00392547 0.134434 0.988666 1 1.92593e-19 1.92593e-19 2.74449e-08 3.71282e-09 3.88264e-10 1 1.92593e-19 2.74449e-08 3.71282e-09 3.88264e-10 1 2.74449e-08 3.71282e-09 3.88264e-10 3983.32 -3.60238 75.6885 3999.23 7.45821 3928.84 +EDGE_SE3:QUAT 1662 1712 -4.51682 0.087246 -5.09997 -0.159178 -0.00125997 -0.059488 0.985455 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3902 12.4476 -121.195 3998.47 4.17084 3989.2 +EDGE_SE3:QUAT 1661 1712 -5.0967 8.94857 -5.12101 -0.0643505 -0.0953272 -0.0809702 0.990058 1 2.40741e-19 2.40741e-19 -1.59633e-08 -2.65188e-08 1.06351e-10 1 2.40741e-19 -1.59633e-08 -2.65188e-08 1.06351e-10 1 -1.59633e-08 -2.65188e-08 1.06351e-10 4154.36 9.91943 -844.454 3957.97 22.0558 4144.7 +EDGE_SE3:QUAT 1662 1711 -4.22006 -9.19045 -4.85542 0.147985 0.0807579 -0.0824366 0.982234 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4062.6 48.6761 790.116 3962.38 -5.02574 4123.02 +EDGE_SE3:QUAT 1663 1713 -4.24957 -0.0558624 -4.47656 -0.277352 0.139905 -0.0239529 0.950226 1 1.92593e-19 1.92593e-19 2.96823e-09 -8.40208e-09 2.71238e-08 1 1.92593e-19 2.96823e-09 -8.40208e-09 2.71238e-08 1 2.96823e-09 -8.40208e-09 2.71238e-08 3903.49 -154.538 949.897 3983.13 -118.457 4208.89 +EDGE_SE3:QUAT 1662 1713 -4.78322 9.04487 -4.69144 -0.0950894 0.0444158 0.0313873 0.993982 1 2.40741e-19 2.40741e-19 2.80312e-08 -1.31696e-08 9.58568e-11 1 2.40741e-19 2.80312e-08 -1.31696e-08 9.58568e-11 1 2.80312e-08 -1.31696e-08 9.58568e-11 4001.28 -17.686 388.933 3990.52 1.20033 4033.51 +EDGE_SE3:QUAT 1663 1712 -4.94014 -8.89378 -4.38906 0.063074 0.197548 0.0391383 0.977479 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4643.84 120.18 1753.52 3864.48 116.613 4653.63 +EDGE_SE3:QUAT 1664 1714 -4.29388 0.259775 -4.52932 0.224506 -0.118165 -0.0502514 0.965976 1 9.62965e-19 9.62965e-19 5.73183e-08 2.11178e-08 -1.13304e-08 1 9.62965e-19 5.73183e-08 2.11178e-08 -1.13304e-08 1 5.73183e-08 2.11178e-08 -1.13304e-08 3934.52 -99.2769 -756.317 3984.79 74.7048 4126.03 +EDGE_SE3:QUAT 1663 1714 -4.93256 9.08369 -4.6144 -0.00511219 0.179217 0.0103461 0.983742 1 1.88079e-22 1.88079e-22 -9.11875e-10 -8.46264e-12 -1.66184e-10 1 1.88079e-22 -9.11875e-10 -8.46264e-12 -1.66184e-10 1 -9.11875e-10 -8.46264e-12 -1.66184e-10 4568.27 3.82386 1611.38 3871.48 6.60333 4567.95 +EDGE_SE3:QUAT 1664 1713 -4.48003 -8.76063 -4.37588 -0.0704506 0.101169 -0.200695 0.971866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4065.23 -51.9615 596.581 3990.67 -68.2043 3923.97 +EDGE_SE3:QUAT 1665 1715 -3.95156 0.284561 -4.56409 0.0921478 0.104015 -0.0128457 0.990214 1 1.88079e-22 1.88079e-22 -9.27654e-11 -8.1126e-11 -8.78203e-10 1 1.88079e-22 -9.27654e-11 -8.1126e-11 -8.78203e-10 1 -9.27654e-11 -8.1126e-11 -8.78203e-10 4146.54 41.1814 868.681 3957.76 19.2875 4179.84 +EDGE_SE3:QUAT 1664 1715 -4.82327 8.83689 -4.94775 -0.0793153 -0.0110181 -0.0804831 0.993534 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.3 6.81386 -162.69 3997.86 6.93309 3980.55 +EDGE_SE3:QUAT 1665 1714 -4.62279 -8.85347 -4.43387 0.0974414 0.105902 -0.0909779 0.9854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4188.86 24.9357 979.456 3944.48 -19.069 4193.74 +EDGE_SE3:QUAT 1666 1716 -4.31349 0.607254 -4.14069 -0.0479313 0.0235586 -0.0381748 0.997843 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.65 -4.22575 165.721 3998.47 -3.55757 4001.01 +EDGE_SE3:QUAT 1665 1716 -5.13296 9.04221 -4.42983 -0.0490039 -0.0726322 0.0430712 0.995223 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4067.56 19.3966 -561.007 3982.11 -18.3852 4069.74 +EDGE_SE3:QUAT 1666 1715 -4.91963 -9.43265 -4.49081 0.0122168 0.0840993 -0.0532097 0.994961 1 4.89006e-20 4.89006e-20 2.94679e-09 -4.5005e-11 1.41589e-08 1 4.89006e-20 2.94679e-09 -4.5005e-11 1.41589e-08 1 2.94679e-09 -4.5005e-11 1.41589e-08 4116.74 -4.89635 695.077 3971.47 -17.7592 4106.02 +EDGE_SE3:QUAT 1667 1717 -4.04832 0.107134 -4.72565 -0.0794713 0.0837477 0.218543 0.968974 1 1.92593e-19 1.92593e-19 5.74376e-09 -2.6965e-08 -1.03081e-09 1 1.92593e-19 5.74376e-09 -2.6965e-08 -1.03081e-09 1 5.74376e-09 -2.6965e-08 -1.03081e-09 4148.9 15.5861 853.196 3959.34 88.3136 3983.12 +EDGE_SE3:QUAT 1666 1717 -4.506 8.90581 -4.85721 -0.046472 0.00873121 0.0143841 0.998778 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.87 -1.83474 77.6381 3999.6 0.477006 4000.68 +EDGE_SE3:QUAT 1667 1716 -5.10109 -8.97109 -4.58542 0.106518 0.110053 0.153787 0.976162 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4055.49 62.4665 650.371 3987.86 68.4219 4006.28 +EDGE_SE3:QUAT 1668 1718 -4.16672 -0.2234 -4.76708 0.0551457 -0.0300593 0.112077 0.991713 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.63 -5.62314 -310.102 3993.42 -17.0814 3973.55 +EDGE_SE3:QUAT 1667 1718 -4.74315 8.87419 -4.6091 0.121302 0.0831269 -0.0512036 0.987803 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4075.01 39.8583 744.042 3967.33 2.93325 4123.38 +EDGE_SE3:QUAT 1668 1717 -4.92946 -9.10377 -4.22018 0.0838788 0.0702098 -0.26941 0.956793 1 1.92593e-19 1.92593e-19 -2.70794e-08 7.29478e-09 -2.91335e-09 1 1.92593e-19 -2.70794e-08 7.29478e-09 -2.91335e-09 1 -2.70794e-08 7.29478e-09 -2.91335e-09 4118.95 -17.6609 781.931 3966.43 -105.732 3856.77 +EDGE_SE3:QUAT 1669 1719 -4.31968 -0.263486 -4.41025 -0.198779 0.141952 0.101157 0.964419 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4299.53 -114.992 1428.47 3899.4 -43.8955 4416.65 +EDGE_SE3:QUAT 1668 1719 -5.0532 9.13922 -5.02759 0.0543553 0.0793948 -0.193783 0.976314 1 1.01111e-18 1.01111e-18 1.36757e-08 2.33369e-08 -5.4375e-08 1 1.01111e-18 1.36757e-08 2.33369e-08 -5.4375e-08 1 1.36757e-08 2.33369e-08 -5.4375e-08 4121.78 -15.4437 743.29 3969.19 -70.0415 3983.39 +EDGE_SE3:QUAT 1669 1718 -4.66291 -8.65821 -4.35348 -0.0100495 0.0454372 0.0237822 0.998634 1 3.00927e-21 3.00927e-21 -3.47928e-09 -7.9996e-11 -1.59767e-10 1 3.00927e-21 -3.47928e-09 -7.9996e-11 -1.59767e-10 1 -3.47928e-09 -7.9996e-11 -1.59767e-10 4033.3 -0.693893 368.714 3991.61 3.98184 4031.44 +EDGE_SE3:QUAT 1670 1720 -3.9556 -0.0928387 -5.06675 -0.00870463 0.0886779 0.0321189 0.995504 1 5.11575e-20 5.11575e-20 -2.25376e-09 -1.5273e-10 1.37239e-08 1 5.11575e-20 -2.25376e-09 -1.5273e-10 1.37239e-08 1 -2.25376e-09 -1.5273e-10 1.37239e-08 4129.38 2.87998 731.821 3968.41 11.0299 4125.56 +EDGE_SE3:QUAT 1669 1720 -5.10374 9.10473 -4.87528 0.0558615 0.0608073 0.0978148 0.991773 1 9.62965e-20 9.62965e-20 -1.23863e-08 -1.52141e-08 2.55824e-10 1 9.62965e-20 -1.23863e-08 -1.52141e-08 2.55824e-10 1 -1.23863e-08 -1.52141e-08 2.55824e-10 4030.01 18.1405 415.38 3991.43 23.67 4004.22 +EDGE_SE3:QUAT 1670 1719 -4.59905 -8.91856 -4.54121 0.235885 0.00375125 -0.125461 0.963641 1 1.92593e-19 1.92593e-19 -1.67974e-09 -6.34382e-09 -2.6858e-08 1 1.92593e-19 -1.67974e-09 -6.34382e-09 -2.6858e-08 1 -1.67974e-09 -6.34382e-09 -2.6858e-08 3808.55 53.4459 368.117 3986.55 -22.7935 3968.16 +EDGE_SE3:QUAT 1671 1721 -4.46529 0.0299518 -4.67517 0.0494277 -0.0638705 -0.243759 0.966467 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.26 -19.2807 -325.943 3998.53 35.4766 3787.36 +EDGE_SE3:QUAT 1670 1721 -5.04865 8.9981 -4.39813 -0.0567569 0.00714356 0.143331 0.98802 1 5.11575e-20 5.11575e-20 -1.42127e-08 1.46171e-09 -1.35907e-10 1 5.11575e-20 -1.42127e-08 1.46171e-09 -1.35907e-10 1 -1.42127e-08 1.46171e-09 -1.35907e-10 3992.62 -4.28678 151.42 3997.99 12.7914 3923.33 +EDGE_SE3:QUAT 1671 1720 -4.71027 -8.995 -4.41354 0.0938781 0.00657516 -0.0463549 0.994482 1 4.81482e-20 4.81482e-20 2.09457e-10 1.28942e-09 1.38058e-08 1 4.81482e-20 2.09457e-10 1.28942e-09 1.38058e-08 1 2.09457e-10 1.28942e-09 1.38058e-08 3967.36 5.52562 103.65 3999.11 -2.50096 3994.02 +EDGE_SE3:QUAT 1672 1722 -4.43607 0.6859 -4.52403 -0.070207 -0.0372895 -0.19713 0.977149 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029 4.90301 -445.816 3986.58 45.28 3893.28 +EDGE_SE3:QUAT 1671 1722 -5.07214 8.67871 -5.03386 -0.0564738 -0.0989564 0.0813023 0.990156 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4121.28 39.8324 -744.882 3971.39 -44.3488 4107.59 +EDGE_SE3:QUAT 1672 1721 -5.22109 -8.94637 -4.49472 -0.00976529 -0.0784839 0.147799 0.98585 1 2.0463e-19 2.0463e-19 -2.72551e-09 -2.84095e-08 -3.98593e-10 1 2.0463e-19 -2.72551e-09 -2.84095e-08 -3.98593e-10 1 -2.72551e-09 -2.84095e-08 -3.98593e-10 4087.92 23.6677 -601.163 3981.48 -47.5956 4000.92 +EDGE_SE3:QUAT 1673 1723 -4.15919 0.0716561 -4.87705 0.193357 0.0181098 -0.0773899 0.977904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3874.04 33.6984 311.911 3992.26 -8.79479 3999.63 +EDGE_SE3:QUAT 1672 1723 -4.74656 9.01856 -4.67911 0.0321727 -0.161465 0.150272 0.97484 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4459.03 80.6907 -1437.81 3903.24 -116.241 4372.84 +EDGE_SE3:QUAT 1673 1722 -4.91829 -9.04213 -4.49032 0.138327 -0.0170302 -0.0607912 0.988372 1 9.65974e-19 9.65974e-19 -5.46358e-08 1.08024e-08 2.6928e-08 1 9.65974e-19 -5.46358e-08 1.08024e-08 2.6928e-08 1 -5.46358e-08 1.08024e-08 2.6928e-08 3923.41 0.140982 -32.1902 4000.03 0.0604444 3985.17 +EDGE_SE3:QUAT 1674 1724 -4.41175 0.126777 -4.59007 -0.0530305 -0.104256 -0.0305792 0.992665 1 1.20371e-20 1.20371e-20 7.58118e-10 3.38318e-10 -7.04737e-09 1 1.20371e-20 7.58118e-10 3.38318e-10 -7.04737e-09 1 7.58118e-10 3.38318e-10 -7.04737e-09 4175.37 17.6579 -883.926 3954.86 0.130486 4182.88 +EDGE_SE3:QUAT 1673 1724 -5.11116 8.61476 -4.63191 -0.00329953 -0.0526728 0.143815 0.988196 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4040.77 9.81092 -406.254 3991.11 -29.7952 3958.09 +EDGE_SE3:QUAT 1674 1723 -4.7374 -8.55338 -4.41387 -0.105207 -0.269831 -0.110122 0.950787 1 3.46667e-18 3.46667e-18 2.91164e-08 1.02139e-07 2.81233e-08 1 3.46667e-18 2.91164e-08 1.02139e-07 2.81233e-08 1 2.91164e-08 1.02139e-07 2.81233e-08 5591.43 -10.802 -3036.21 3687.81 17.2788 5587.2 +EDGE_SE3:QUAT 1675 1725 -4.52482 -0.163655 -4.6801 -0.174196 0.193815 -0.0743887 0.962579 1 7.70372e-19 7.70372e-19 -5.65109e-08 8.51314e-09 -8.86215e-09 1 7.70372e-19 -5.65109e-08 8.51314e-09 -8.86215e-09 1 -5.65109e-08 8.51314e-09 -8.86215e-09 4330.05 -220.526 1422.87 3946.63 -209.585 4429.3 +EDGE_SE3:QUAT 1674 1725 -4.83733 8.87856 -4.83295 -0.0974584 0.0568945 0.204714 0.972295 1 1.92593e-19 1.92593e-19 2.73691e-08 5.39705e-09 2.54097e-09 1 1.92593e-19 2.73691e-08 5.39705e-09 2.54097e-09 1 2.73691e-08 5.39705e-09 2.54097e-09 4070.72 -7.5884 670.353 3971.08 65.1109 3941.09 +EDGE_SE3:QUAT 1675 1724 -4.76246 -8.86021 -4.53994 -0.0332314 0.0080609 -0.042859 0.998496 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.13 -0.729333 47.1483 3999.9 -0.919131 3993.2 +EDGE_SE3:QUAT 1676 1726 -4.41533 0.114384 -4.82579 -0.0944381 -0.0363306 -0.0299479 0.994417 1 1.92593e-19 1.92593e-19 2.76901e-08 -6.30828e-10 -1.14902e-09 1 1.92593e-19 2.76901e-08 -6.30828e-10 -1.14902e-09 1 2.76901e-08 -6.30828e-10 -1.14902e-09 3990.07 14.7943 -322.027 3993.41 1.51878 4022.15 +EDGE_SE3:QUAT 1675 1726 -4.82123 8.71361 -4.35458 -0.00362655 0.00156533 0.147648 0.989032 1 1.88079e-22 1.88079e-22 8.57858e-10 1.28053e-10 2.21719e-12 1 1.88079e-22 8.57858e-10 1.28053e-10 2.21719e-12 1 8.57858e-10 1.28053e-10 2.21719e-12 4000.03 -0.0206478 18.4476 3999.98 1.50936 3912.88 +EDGE_SE3:QUAT 1676 1725 -4.86611 -9.14201 -4.69259 0.00497363 0.0658875 -0.131168 0.989156 1 1.92781e-19 1.92781e-19 -2.78885e-09 -2.7568e-08 -2.87458e-10 1 1.92781e-19 -2.78885e-09 -2.7568e-08 -2.87458e-10 1 -2.78885e-09 -2.7568e-08 -2.87458e-10 4068.7 -12.4639 529.129 3984.39 -35.6474 3999.98 +EDGE_SE3:QUAT 1677 1727 -4.35406 -0.393403 -4.33857 0.106489 -0.124436 -0.11037 0.980303 1 1.92593e-19 1.92593e-19 -2.77986e-08 3.90478e-09 2.67477e-09 1 1.92593e-19 -2.77986e-08 3.90478e-09 2.67477e-09 1 -2.77986e-08 3.90478e-09 2.67477e-09 4124.87 -80.3983 -845.762 3972.18 81.0048 4121.5 +EDGE_SE3:QUAT 1676 1727 -5.06603 9.15406 -4.58576 -0.0132023 -0.0528042 0.0980156 0.993695 1 1.92593e-19 1.92593e-19 1.37176e-09 6.51717e-10 -2.7721e-08 1 1.92593e-19 1.37176e-09 6.51717e-10 -2.7721e-08 1 1.37176e-09 6.51717e-10 -2.7721e-08 4039.72 8.84479 -404.222 3990.78 -20.8347 4001.99 +EDGE_SE3:QUAT 1677 1726 -4.82982 -8.59508 -4.42183 -0.0222772 0.0215713 0.0214564 0.999289 1 1.20371e-20 1.20371e-20 -6.94084e-09 -1.42348e-10 -1.56187e-10 1 1.20371e-20 -6.94084e-09 -1.42348e-10 -1.56187e-10 1 -6.94084e-09 -1.42348e-10 -1.56187e-10 4005.95 -1.76495 178.372 3997.98 1.68097 4006.1 +EDGE_SE3:QUAT 1678 1728 -4.72317 -0.328703 -4.48953 0.0857081 0.00482366 0.0173369 0.996158 1 2.0463e-19 2.0463e-19 2.76368e-08 -9.85357e-11 -6.86265e-09 1 2.0463e-19 2.76368e-08 -9.85357e-11 -6.86265e-09 1 2.76368e-08 -9.85357e-11 -6.86265e-09 3970.71 0.617441 20.4071 3999.99 0.143236 3998.89 +EDGE_SE3:QUAT 1677 1728 -4.95816 8.82423 -4.7267 -0.0687902 0.155058 0.0495745 0.98426 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4417.2 -27.2367 1390.96 3899.24 -2.86931 4426.3 +EDGE_SE3:QUAT 1678 1727 -4.64772 -8.78175 -4.70032 0.0564677 0.120255 0.10399 0.985665 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4182.52 61.3341 905.974 3960.81 70.0235 4152.02 +EDGE_SE3:QUAT 1679 1729 -4.16056 0.0538794 -4.56007 0.170144 -0.0645756 -0.0661937 0.981071 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3915.44 -30.8671 -359.9 3995.98 20.5659 4013.71 +EDGE_SE3:QUAT 1678 1729 -5.19733 9.06645 -4.54206 -0.0540228 -0.0619843 0.00812052 0.996581 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4048.61 14.5758 -494.769 3985.45 -7.04023 4060.02 +EDGE_SE3:QUAT 1679 1728 -4.71726 -8.97123 -4.41648 -0.114663 0.101233 0.0689072 0.985828 1 3.85186e-19 3.85186e-19 2.93154e-08 -2.61134e-08 3.9687e-10 1 3.85186e-19 2.93154e-08 -2.61134e-08 3.9687e-10 1 2.93154e-08 -2.61134e-08 3.9687e-10 4150.39 -40.09 923.826 3950.65 1.96826 4183.99 +EDGE_SE3:QUAT 1680 1730 -4.09896 0.0659033 -4.41795 0.0438287 0.00548701 0.0566019 0.997419 1 4.83363e-20 4.83363e-20 1.37927e-08 1.65429e-09 -3.1625e-11 1 4.83363e-20 1.37927e-08 1.65429e-09 -3.1625e-11 1 1.37927e-08 1.65429e-09 -3.1625e-11 3992.34 0.0932274 13.8901 4000 0.115878 3987.21 +EDGE_SE3:QUAT 1679 1730 -5.32805 9.06476 -4.69368 0.0518172 -0.178212 -0.0632636 0.980588 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4501.43 -104.722 -1520.44 3893.95 106.651 4496.16 +EDGE_SE3:QUAT 1680 1729 -4.59591 -8.77483 -4.53531 -0.0760391 -0.0287665 -0.110674 0.990526 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.05 9.88485 -325.887 3992.43 17.3658 3977.18 +EDGE_SE3:QUAT 1681 1731 -3.78164 0.221873 -4.32042 0.130424 0.219141 -0.0728777 0.964186 1 2.40741e-19 2.40741e-19 -3.34702e-08 -1.1667e-09 -2.20787e-08 1 2.40741e-19 -3.34702e-08 -1.1667e-09 -2.20787e-08 1 -3.34702e-08 -1.1667e-09 -2.20787e-08 4909.13 109.352 2205.36 3799.72 83.0824 4955.93 +EDGE_SE3:QUAT 1680 1731 -5.09237 8.53746 -4.49912 -0.00430479 0.0197678 0.191958 0.981195 1 2.38038e-22 2.38038e-22 -9.58219e-10 -1.87446e-10 -1.94659e-11 1 2.38038e-22 -9.58219e-10 -1.87446e-10 -1.94659e-11 1 -9.58219e-10 -1.87446e-10 -1.94659e-11 4006.26 1.51076 159.378 3998.65 15.3509 3858.95 +EDGE_SE3:QUAT 1681 1730 -4.76764 -8.61537 -4.34309 -0.0942531 -0.0215254 -0.140577 0.985338 1 2.40741e-19 2.40741e-19 2.9303e-08 9.947e-09 -1.17174e-10 1 2.40741e-19 2.9303e-08 9.947e-09 -1.17174e-10 1 2.9303e-08 9.947e-09 -1.17174e-10 3989.87 13.3094 -322.998 3991.84 23.5187 3946.35 +EDGE_SE3:QUAT 1682 1732 -4.41172 0.0565161 -4.5549 0.0537406 -0.0243389 0.0662468 0.996058 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.27 -5.47222 -235.899 3996.21 -7.28537 3996.27 +EDGE_SE3:QUAT 1681 1732 -4.70988 8.82917 -4.82344 -0.00336012 0.00593242 -0.0235767 0.999699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.49 -0.0968334 46.4741 3999.87 -0.546904 3998.32 +EDGE_SE3:QUAT 1682 1731 -5.09756 -8.90312 -4.43845 -0.173216 -0.107321 -0.184327 0.96151 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4237.81 44.0192 -1250.87 3911.23 58.513 4221.92 +EDGE_SE3:QUAT 1683 1733 -4.65513 -0.316024 -4.80661 0.0739677 -0.0683432 -0.0442564 0.993931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.55 -23.5095 -507.994 3985.91 18.8313 4055.6 +EDGE_SE3:QUAT 1682 1733 -5.22422 8.75045 -4.51335 0.00318122 -0.0631893 -0.0999017 0.992984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.68 -10.2859 -500.752 3985.65 26.1599 4021.8 +EDGE_SE3:QUAT 1683 1732 -4.73887 -9.01904 -4.4653 0.00533982 -0.01838 -0.0720713 0.997216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.88 -0.925306 -141.437 3998.81 5.0856 3984.22 +EDGE_SE3:QUAT 1684 1734 -4.13291 0.0668963 -4.31378 0.0093154 0.0859871 0.0376538 0.995541 1 1.95602e-19 1.95602e-19 -2.39963e-09 -2.77697e-08 1.43944e-10 1 1.95602e-19 -2.39963e-09 -2.77697e-08 1.43944e-10 1 -2.39963e-09 -2.77697e-08 1.43944e-10 4118.53 10.3406 699.749 3971.32 15.8505 4113.21 +EDGE_SE3:QUAT 1683 1734 -4.44208 9.148 -5.06194 -0.083701 0.0888768 0.12073 0.985149 1 1.92593e-19 1.92593e-19 -2.7927e-08 -3.01206e-09 -2.988e-09 1 1.92593e-19 -2.7927e-08 -3.01206e-09 -2.988e-09 1 -2.7927e-08 -3.01206e-09 -2.988e-09 4141.23 -10.252 840.454 3957.8 37.1334 4110.96 +EDGE_SE3:QUAT 1684 1733 -5.11458 -8.63866 -4.66738 0.0565366 0.0238037 -0.071245 0.995571 1 6.01853e-20 6.01853e-20 -1.43139e-08 -5.9615e-09 -7.16997e-11 1 6.01853e-20 -1.43139e-08 -5.9615e-09 -7.16997e-11 1 -1.43139e-08 -5.9615e-09 -7.16997e-11 4001.15 5.80819 236.953 3996.13 -7.96125 3993.63 +EDGE_SE3:QUAT 1685 1735 -4.63955 -0.0821563 -4.66718 0.0984336 -0.0884621 0.166527 0.977115 1 7.70372e-19 7.70372e-19 -6.52025e-09 3.72039e-09 5.55817e-08 1 7.70372e-19 -6.52025e-09 3.72039e-09 5.55817e-08 1 -6.52025e-09 3.72039e-09 5.55817e-08 4154.74 -5.61408 -901.646 3951.86 -60.411 4082.57 +EDGE_SE3:QUAT 1684 1735 -4.85268 8.62201 -4.71577 0.00648433 0.0318681 -0.0650082 0.997355 1 7.52316e-22 7.52316e-22 -1.73377e-09 1.12513e-10 -5.63907e-11 1 7.52316e-22 -1.73377e-09 1.12513e-10 -5.63907e-11 1 -1.73377e-09 1.12513e-10 -5.63907e-11 4016.57 -0.775814 259.317 3995.86 -8.39532 3999.84 +EDGE_SE3:QUAT 1685 1734 -4.78359 -8.93608 -4.47138 -0.260666 -0.131768 -0.0522237 0.954968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4052.36 162.633 -1184.12 3943.77 -95.6248 4313.24 +EDGE_SE3:QUAT 1686 1736 -4.48525 -0.0805834 -4.5749 -0.160682 -0.00873825 -0.203782 0.965701 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3942.36 36.2537 -443.648 3981.38 50.8848 3879.53 +EDGE_SE3:QUAT 1685 1736 -5.22201 8.64365 -4.44775 -0.00703619 0.0138772 0.0977148 0.995093 1 3.00927e-21 3.00927e-21 3.45393e-09 3.38593e-10 5.19946e-11 1 3.00927e-21 3.45393e-09 3.38593e-10 5.19946e-11 1 3.45393e-09 3.38593e-10 5.19946e-11 4003.26 0.0745131 117.714 3999.13 5.83619 3965.27 +EDGE_SE3:QUAT 1686 1735 -4.40502 -8.49492 -4.18033 0.0761414 -0.0211743 0.00175283 0.996871 1 2.93874e-24 2.93874e-24 -2.30003e-12 8.2621e-12 1.08179e-10 1 2.93874e-24 -2.30003e-12 8.2621e-12 1.08179e-10 1 -2.30003e-12 8.2621e-12 1.08179e-10 3984 -6.47711 -169.786 3998.25 0.674886 4007.18 +EDGE_SE3:QUAT 1687 1737 -4.2253 -0.0949269 -4.7177 0.01769 -0.0312332 -0.015184 0.99924 1 2.40741e-20 2.40741e-20 6.83364e-09 -7.04689e-09 -8.36396e-11 1 2.40741e-20 6.83364e-09 -7.04689e-09 -8.36396e-11 1 6.83364e-09 -7.04689e-09 -8.36396e-11 4013.97 -2.54853 -247.251 3996.25 2.29473 4014.3 +EDGE_SE3:QUAT 1686 1737 -5.33825 8.83895 -4.18578 -0.0559492 -0.030143 0.23312 0.970369 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.81 1.29271 -69.9249 4000.24 -1.4933 3782.95 +EDGE_SE3:QUAT 1687 1736 -4.50571 -8.97957 -4.62596 -0.0388754 -0.101058 -0.084239 0.990545 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4175.53 -4.07017 -871.394 3956.2 30.6256 4153.19 +EDGE_SE3:QUAT 1688 1738 -4.52623 -0.108127 -4.57558 0.0414098 -0.208312 0.0658092 0.974967 1 6.01853e-20 6.01853e-20 -1.06544e-08 -1.68123e-10 1.64708e-08 1 6.01853e-20 -1.06544e-08 -1.68123e-10 1.64708e-08 1 -1.06544e-08 -1.68123e-10 1.64708e-08 4812.57 26.5781 -1987.26 3823.09 -42.0693 4802.11 +EDGE_SE3:QUAT 1687 1738 -4.8333 9.06351 -4.34178 0.0664466 -0.0677948 0.102294 0.990214 1 4.81482e-20 4.81482e-20 -1.39069e-08 -1.31196e-09 1.11539e-09 1 4.81482e-20 -1.39069e-08 -1.31196e-09 1.11539e-09 1 -1.39069e-08 -1.31196e-09 1.11539e-09 4077.61 -8.58393 -624.921 3975.75 -25.7946 4053.41 +EDGE_SE3:QUAT 1688 1737 -4.85328 -8.89355 -3.90728 0.0241114 0.123722 -0.015081 0.991909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4256.13 8.72239 1049.09 3938.36 0.393827 4257.54 +EDGE_SE3:QUAT 1689 1739 -4.5815 -0.211707 -4.38312 -0.0255812 0.00698439 -0.166442 0.985695 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.31 0.173016 3.38522 3999.99 1.20063 3889.11 +EDGE_SE3:QUAT 1688 1739 -5.11929 8.49946 -4.81424 0.230234 0.0665022 0.0959836 0.966104 1 3.32223e-18 3.32223e-18 1.0621e-07 3.29422e-08 2.52012e-08 1 3.32223e-18 1.0621e-07 3.29422e-08 2.52012e-08 1 1.0621e-07 3.29422e-08 2.52012e-08 3797.79 17.6418 227.232 4001.12 13.5948 3972.96 +EDGE_SE3:QUAT 1689 1738 -5.17649 -8.477 -4.21827 0.0744739 -0.111194 0.106568 0.985258 1 1.92593e-19 1.92593e-19 2.8177e-08 2.61662e-09 -3.53485e-09 1 1.92593e-19 2.8177e-08 2.61662e-09 -3.53485e-09 1 2.8177e-08 2.61662e-09 -3.53485e-09 4220.86 -5.51578 -1015.68 3941.27 -36.2939 4197.62 +EDGE_SE3:QUAT 1690 1740 -4.04692 -0.208025 -4.29302 0.100223 -0.077599 0.136322 0.982522 1 7.70372e-19 7.70372e-19 -5.68318e-09 4.34321e-09 5.55628e-08 1 7.70372e-19 -5.68318e-09 4.34321e-09 5.55628e-08 1 -5.68318e-09 4.34321e-09 5.55628e-08 4107.23 -16.2152 -782.772 3962.15 -39.9369 4073.07 +EDGE_SE3:QUAT 1689 1740 -4.81257 8.72279 -4.43169 -0.116103 0.184348 0.307324 0.92633 1 4.81482e-20 4.81482e-20 -1.42241e-08 -4.33951e-09 -3.31472e-09 1 4.81482e-20 -1.42241e-08 -4.33951e-09 -3.31472e-09 1 -1.42241e-08 -4.33951e-09 -3.31472e-09 4754.73 230.985 1971.98 3877.5 307.841 4430.86 +EDGE_SE3:QUAT 1690 1739 -4.92853 -9.00312 -4.31837 0.0378776 0.111834 -0.240065 0.963549 1 3.00927e-21 3.00927e-21 -3.4402e-09 8.48525e-10 -4.15977e-10 1 3.00927e-21 -3.4402e-09 8.48525e-10 -4.15977e-10 1 -3.4402e-09 8.48525e-10 -4.15977e-10 4216.53 -62.2259 968.922 3958.79 -121.47 3991.75 +EDGE_SE3:QUAT 1691 1741 -4.41978 0.138427 -4.93791 -0.0412354 0.0960647 -0.0233468 0.994247 1 4.81482e-20 4.81482e-20 -1.40482e-08 4.48243e-10 -1.32332e-09 1 4.81482e-20 -1.40482e-08 4.48243e-10 -1.32332e-09 1 -1.40482e-08 4.48243e-10 -1.32332e-09 4139.22 -22.7343 778.109 3965.4 -19.1745 4143.84 +EDGE_SE3:QUAT 1690 1741 -4.90755 8.75453 -4.14747 0.00896918 0.0527409 0.151917 0.986944 1 7.70372e-19 7.70372e-19 -2.65379e-09 -1.36688e-09 -5.50555e-08 1 7.70372e-19 -2.65379e-09 -1.36688e-09 -5.50555e-08 1 -2.65379e-09 -1.36688e-09 -5.50555e-08 4038.13 11.0047 394.364 3991.96 30.5317 3946.14 +EDGE_SE3:QUAT 1691 1740 -4.7244 -8.94375 -4.5883 0.0852911 -0.135303 -0.191891 0.968296 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4137.01 -96.3963 -839.837 3982.64 110.105 4018.82 +EDGE_SE3:QUAT 1692 1742 -4.23127 -0.0899321 -4.56199 0.0359007 -0.035388 -0.0849698 0.995108 1 4.33334e-19 4.33334e-19 2.72552e-08 -1.73924e-08 -2.78937e-08 1 4.33334e-19 2.72552e-08 -1.73924e-08 -2.78937e-08 1 2.72552e-08 -1.73924e-08 -2.78937e-08 4009.59 -6.22242 -243.762 3996.86 10.7626 3985.87 +EDGE_SE3:QUAT 1691 1742 -5.22579 8.84177 -4.70668 0.0251822 -0.0941493 0.185673 0.977767 1 7.71124e-19 7.71124e-19 7.20863e-09 9.45129e-10 -5.55082e-08 1 7.71124e-19 7.20863e-09 9.45129e-10 -5.55082e-08 1 7.20863e-09 9.45129e-10 -5.55082e-08 4149.75 32.4372 -795.248 3967.79 -75.826 4014.39 +EDGE_SE3:QUAT 1692 1741 -4.77326 -8.94287 -4.44223 0.042907 0.0657246 0.136339 0.987548 1 9.62965e-20 9.62965e-20 -1.18134e-08 -1.56833e-08 1.08091e-10 1 9.62965e-20 -1.18134e-08 -1.56833e-08 1.08091e-10 1 -1.18134e-08 -1.56833e-08 1.08091e-10 4041.12 20.3127 444.327 3990.83 32.9392 3974.13 +EDGE_SE3:QUAT 1693 1743 -4.48635 -0.113844 -4.33979 -0.102771 0.169022 0.0441138 0.979247 1 9.62965e-19 9.62965e-19 2.83895e-08 5.46991e-08 1.03287e-08 1 9.62965e-19 2.83895e-08 5.46991e-08 1.03287e-08 1 2.83895e-08 5.46991e-08 1.03287e-08 4483.72 -68.6327 1542.9 3882.93 -40.1753 4518.18 +EDGE_SE3:QUAT 1692 1743 -5.24505 8.62301 -4.4855 -0.0549067 0.210638 0.00316189 0.976016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4798.47 -76.3271 1974.61 3827.5 -68.3229 4810.49 +EDGE_SE3:QUAT 1693 1742 -4.5146 -8.56404 -4.20712 -0.00181564 -0.137398 -0.203282 0.96943 1 1.20371e-20 1.20371e-20 6.96943e-09 -1.51532e-09 -9.08378e-10 1 1.20371e-20 6.96943e-09 -1.51532e-09 -9.08378e-10 1 6.96943e-09 -1.51532e-09 -9.08378e-10 4280.98 -92.2062 -1097.75 3950.87 130.559 4115.7 +EDGE_SE3:QUAT 1694 1744 -4.25185 0.198867 -4.6542 0.000529202 -0.0667134 -0.0139195 0.997675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.1 -1.66845 -541.869 3982.23 4.00532 4071.33 +EDGE_SE3:QUAT 1693 1744 -5.23215 8.72677 -4.51996 -0.0579658 -0.177598 0.126298 0.974242 1 1.54074e-18 1.54074e-18 -4.9798e-10 -6.00826e-08 5.12104e-08 1 1.54074e-18 -4.9798e-10 -6.00826e-08 5.12104e-08 1 -4.9798e-10 -6.00826e-08 5.12104e-08 4431.48 147.047 -1407.81 3922.43 -157.364 4381.12 +EDGE_SE3:QUAT 1694 1743 -4.92538 -8.67068 -4.28528 0.0141877 0.0608822 0.0478162 0.996898 1 4.81482e-20 4.81482e-20 6.92221e-10 -1.38333e-08 2.78557e-10 1 4.81482e-20 6.92221e-10 -1.38333e-08 2.78557e-10 1 6.92221e-10 -1.38333e-08 2.78557e-10 4056.69 7.73003 483.016 3986.15 13.1548 4048.35 +EDGE_SE3:QUAT 1695 1745 -4.40338 0.2588 -4.52547 -0.0761002 -0.00877696 0.0512337 0.995744 1 1.92593e-19 1.92593e-19 2.76377e-08 1.4426e-09 -2.39628e-11 1 1.92593e-19 2.76377e-08 1.4426e-09 -2.39628e-11 1 2.76377e-08 1.4426e-09 -2.39628e-11 3976.9 0.283946 -22.8019 4000 -0.20809 3989.57 +EDGE_SE3:QUAT 1694 1745 -5.13041 8.74073 -4.54946 -0.109062 -0.0165896 0.0792227 0.990734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3952.28 -0.4264 -26.6523 4000.01 0.263773 3974.75 +EDGE_SE3:QUAT 1695 1744 -4.87998 -8.29486 -4.39051 0.171435 0.0448654 0.00578992 0.984156 1 8.1852e-19 8.1852e-19 5.45384e-08 1.48066e-08 -1.5282e-10 1 8.1852e-19 5.45384e-08 1.48066e-08 -1.5282e-10 1 5.45384e-08 1.48066e-08 -1.5282e-10 3909.99 28.5984 333.408 3994.43 8.45108 4027.42 +EDGE_SE3:QUAT 1696 1746 -4.28659 0.0429938 -4.24725 0.0290391 0.0636154 0.0431161 0.99662 1 4.81482e-20 4.81482e-20 1.39365e-08 6.58623e-10 8.49414e-10 1 4.81482e-20 1.39365e-08 6.58623e-10 8.49414e-10 1 1.39365e-08 6.58623e-10 8.49414e-10 4057.75 11.4991 498.254 3985.46 13.7874 4053.68 +EDGE_SE3:QUAT 1695 1746 -5.03826 8.57481 -4.43079 -0.109162 0.0590572 -0.0509363 0.99096 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.52 -24.3432 398.89 3992.25 -16.918 4028.81 +EDGE_SE3:QUAT 1696 1745 -5.02266 -8.60242 -4.62567 -0.192086 0.018038 0.0439703 0.980227 1 4.81482e-20 4.81482e-20 -4.61775e-10 2.64106e-09 -1.36275e-08 1 4.81482e-20 -4.61775e-10 2.64106e-09 -1.36275e-08 1 -4.61775e-10 2.64106e-09 -1.36275e-08 3866.07 -24.9646 235.564 3995.99 2.48764 4005.93 +EDGE_SE3:QUAT 1697 1747 -4.21851 0.0420991 -4.39612 0.109806 -0.0109974 0.135159 0.984659 1 2.0463e-19 2.0463e-19 2.82862e-08 -3.23309e-09 -3.8605e-10 1 2.0463e-19 2.82862e-08 -3.23309e-09 -3.8605e-10 1 2.82862e-08 -3.23309e-09 -3.8605e-10 3967.84 -15.0109 -259.621 3994.01 -19.5286 3943 +EDGE_SE3:QUAT 1696 1747 -4.81426 8.77607 -4.74238 -0.110159 0.0088658 0.0642932 0.991793 1 7.82409e-19 7.82409e-19 5.55175e-08 -3.50523e-09 5.06591e-10 1 7.82409e-19 5.55175e-08 -3.50523e-09 5.06591e-10 1 5.55175e-08 -3.50523e-09 5.06591e-10 3957.17 -9.56072 153.504 3998.01 5.07986 3989.18 +EDGE_SE3:QUAT 1697 1746 -4.62874 -8.59854 -4.62743 -0.0685576 -0.101062 -0.11117 0.986269 1 2.40741e-19 2.40741e-19 1.67736e-08 2.60079e-08 -3.3843e-10 1 2.40741e-19 1.67736e-08 2.60079e-08 -3.3843e-10 1 1.67736e-08 2.60079e-08 -3.3843e-10 4182.42 2.8952 -919.629 3951.01 38.1579 4151.79 +EDGE_SE3:QUAT 1698 1748 -4.30444 -0.0929501 -4.58431 -0.0610779 -0.0406327 -0.134528 0.988191 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.74 5.93884 -416.044 3988.52 27.0099 3970.27 +EDGE_SE3:QUAT 1697 1748 -5.21742 8.56297 -4.23853 0.0666546 0.0234955 0.0114336 0.997434 1 3.00927e-21 3.00927e-21 7.55614e-11 2.33534e-10 3.46397e-09 1 3.00927e-21 7.55614e-11 2.33534e-10 3.46397e-09 1 7.55614e-11 2.33534e-10 3.46397e-09 3990.12 5.9829 177.85 3998.15 1.81473 4007.37 +EDGE_SE3:QUAT 1698 1747 -4.73864 -8.35799 -4.76844 -0.126025 -0.041299 -0.216225 0.967295 1 1.92593e-19 1.92593e-19 2.71848e-08 -5.6331e-09 -2.50725e-09 1 1.92593e-19 2.71848e-08 -5.6331e-09 -2.50725e-09 1 2.71848e-08 -5.6331e-09 -2.50725e-09 4031.6 21.3195 -629.087 3971.63 66.3461 3908.11 +EDGE_SE3:QUAT 1699 1749 -4.57949 -0.226324 -4.1813 0.176915 0.0634806 -0.21546 0.958253 1 7.70372e-19 7.70372e-19 5.46361e-08 -1.04252e-08 7.28843e-09 1 7.70372e-19 5.46361e-08 -1.04252e-08 7.28843e-09 1 5.46361e-08 -1.04252e-08 7.28843e-09 4079.39 44.4381 932.946 3942.33 -77.0853 4018.9 +EDGE_SE3:QUAT 1698 1749 -5.33783 8.63878 -4.23028 0.00123266 0.0700685 -0.0417632 0.996667 1 4.70198e-23 4.70198e-23 4.36516e-10 -1.83966e-11 3.06257e-11 1 4.70198e-23 4.36516e-10 -1.83966e-11 3.06257e-11 1 4.36516e-10 -1.83966e-11 3.06257e-11 4079.47 -4.6632 569.419 3980.58 -12.3518 4072.5 +EDGE_SE3:QUAT 1699 1748 -5.08973 -8.7983 -4.65592 0.236778 -0.138849 -0.11685 0.954465 1 1.92593e-19 1.92593e-19 -4.72661e-09 -2.62676e-08 7.41703e-09 1 1.92593e-19 -4.72661e-09 -2.62676e-08 7.41703e-09 1 -4.72661e-09 -2.62676e-08 7.41703e-09 3879.9 -99.7772 -678.689 4002.75 91.2238 4049.54 +EDGE_SE3:QUAT 1700 1750 -4.64633 -0.141011 -4.74982 -0.0722874 -0.0558278 0.0556068 0.994266 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.83 17.5423 -396.007 3991.67 -15.3366 4026.36 +EDGE_SE3:QUAT 1699 1750 -4.56398 8.25598 -4.57722 0.0685232 0.01368 0.0748814 0.994741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.65 0.976597 46.5877 3999.97 1.04911 3978 +EDGE_SE3:QUAT 1700 1749 -4.58447 -8.66969 -4.63767 0.182218 -0.0493216 -0.0803364 0.978729 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3875.93 -14.1569 -199.852 3999.7 9.51508 3982.93 +EDGE_SE3:QUAT 1701 1751 -4.703 0.15973 -4.75972 0.00849049 0.0532804 -0.020841 0.998326 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.92 0.44364 432.382 3988.54 -4.05674 4044.47 +EDGE_SE3:QUAT 1700 1751 -4.99672 8.27517 -4.7277 0.0243805 0.203349 0.00813275 0.978769 1 5.11575e-20 5.11575e-20 -1.55677e-08 -4.07694e-10 -6.7645e-09 1 5.11575e-20 -1.55677e-08 -4.07694e-10 -6.7645e-09 1 -1.55677e-08 -4.07694e-10 -6.7645e-09 4746.79 43.2568 1886.25 3836.81 40.8331 4748.91 +EDGE_SE3:QUAT 1701 1750 -4.96279 -8.47634 -4.10554 0.11023 0.0173836 -0.0675553 0.991455 1 1.20371e-20 1.20371e-20 4.31528e-10 6.88204e-09 -7.42643e-10 1 1.20371e-20 4.31528e-10 6.88204e-09 -7.42643e-10 1 4.31528e-10 6.88204e-09 -7.42643e-10 3963.8 12.957 224.689 3996.16 -6.84196 3994.15 +EDGE_SE3:QUAT 1702 1752 -4.29082 0.0646563 -4.4879 0.0166082 0.0460441 -0.00302045 0.998797 1 1.88079e-22 1.88079e-22 -4.01723e-11 -1.42852e-11 -8.70017e-10 1 1.88079e-22 -4.01723e-11 -1.42852e-11 -8.70017e-10 1 -4.01723e-11 -1.42852e-11 -8.70017e-10 4033.12 3.00005 371.56 3991.5 0.281625 4034.19 +EDGE_SE3:QUAT 1701 1752 -5.04636 8.71761 -4.68579 0.0615407 0.121089 0.101584 0.985511 1 1.92593e-19 1.92593e-19 -3.29111e-09 2.73007e-08 -2.40817e-09 1 1.92593e-19 -3.29111e-09 2.73007e-08 -2.40817e-09 1 -3.29111e-09 2.73007e-08 -2.40817e-09 4180.87 63.3744 907.84 3960.97 70.6422 4154.74 +EDGE_SE3:QUAT 1702 1751 -4.8216 -8.90633 -4.27358 -0.0495479 -0.0319121 -0.169645 0.983741 1 7.70372e-19 7.70372e-19 -2.59166e-09 -2.01363e-09 5.48149e-08 1 7.70372e-19 -2.59166e-09 -2.01363e-09 5.48149e-08 1 -2.59166e-09 -2.01363e-09 5.48149e-08 4019.54 2.60105 -344.77 3992.07 30.2339 3914.24 +EDGE_SE3:QUAT 1703 1753 -4.58347 0.187907 -4.45911 0.0694817 -0.0656662 -0.00268707 0.995416 1 7.52316e-22 7.52316e-22 1.13106e-10 -1.23233e-10 -1.74152e-09 1 7.52316e-22 1.13106e-10 -1.23233e-10 -1.74152e-09 1 1.13106e-10 -1.23233e-10 -1.74152e-09 4048.95 -19.3426 -526.989 3983.64 7.96353 4068.23 +EDGE_SE3:QUAT 1702 1753 -5.29392 8.90071 -4.606 0.00865706 -0.171728 0.126817 0.976909 1 3.00927e-21 3.00927e-21 -3.59856e-09 -4.85178e-10 6.19508e-10 1 3.00927e-21 -3.59856e-09 -4.85178e-10 6.19508e-10 1 -3.59856e-09 -4.85178e-10 6.19508e-10 4500.08 93.7229 -1500.76 3896.61 -118.134 4436.05 +EDGE_SE3:QUAT 1703 1752 -4.77866 -8.53673 -4.63582 0.0002043 -0.118133 -0.0550985 0.991468 1 7.52316e-22 7.52316e-22 -1.76897e-09 1.01217e-10 2.09415e-10 1 7.52316e-22 -1.76897e-09 1.01217e-10 2.09415e-10 1 -1.76897e-09 1.01217e-10 2.09415e-10 4230.67 -19.7553 -987.885 3945.69 31.2789 4218.53 +EDGE_SE3:QUAT 1704 1754 -4.16984 0.190407 -4.16911 -0.0146564 0.0990652 -0.123287 0.987305 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4144.24 -34.3664 775.792 3968.75 -55.1086 4084.3 +EDGE_SE3:QUAT 1703 1754 -5.09318 8.68762 -4.71438 0.104399 -0.0731117 -0.0586693 0.990108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.98 -32.1858 -505.286 3987.55 25.4643 4048.81 +EDGE_SE3:QUAT 1704 1753 -5.13584 -8.56323 -4.57817 -0.056754 0.122155 -0.0212677 0.990659 1 1.20371e-20 1.20371e-20 -8.48202e-10 4.55312e-10 -7.07732e-09 1 1.20371e-20 -8.48202e-10 4.55312e-10 -7.07732e-09 1 -8.48202e-10 4.55312e-10 -7.07732e-09 4226.11 -40.7486 1006.57 3944.97 -33.4569 4237.19 +EDGE_SE3:QUAT 1705 1755 -4.25973 0.31462 -4.19494 0.00308079 -0.118322 -0.0209326 0.99275 1 1.93345e-19 1.93345e-19 1.15326e-09 -2.75933e-08 1.75891e-11 1 1.93345e-19 1.15326e-09 -2.75933e-08 1.75891e-11 1 1.15326e-09 -2.75933e-08 1.75891e-11 4232.99 -9.27349 -993.178 3944.36 13.0421 4231.27 +EDGE_SE3:QUAT 1704 1755 -4.83425 8.81144 -4.66941 0.0125075 -0.0308663 0.0898458 0.995399 1 3.00927e-21 3.00927e-21 -3.4607e-09 -3.1021e-10 1.13344e-10 1 3.00927e-21 -3.4607e-09 -3.1021e-10 1.13344e-10 1 -3.4607e-09 -3.1021e-10 1.13344e-10 4015.98 0.557178 -258.268 3995.88 -11.5738 3984.32 +EDGE_SE3:QUAT 1705 1754 -4.63687 -8.63437 -4.09665 0.180513 -0.0883151 0.0728111 0.97689 1 8.1852e-19 8.1852e-19 -5.69761e-08 2.65298e-10 1.99834e-08 1 8.1852e-19 -5.69761e-08 2.65298e-10 1.99834e-08 1 -5.69761e-08 2.65298e-10 1.99834e-08 4044.88 -70.1885 -855.709 3958.23 10.3489 4154.01 +EDGE_SE3:QUAT 1706 1756 -4.21653 0.018538 -4.28961 0.103768 -0.0978942 -0.0999209 0.984716 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4058.13 -51.0901 -646.924 3982.49 50.5099 4061.27 +EDGE_SE3:QUAT 1705 1756 -4.99409 8.74238 -4.45117 0.08148 -0.0266001 0.0119517 0.996248 1 2.07639e-19 2.07639e-19 2.76485e-08 -6.42382e-09 3.24002e-09 1 2.07639e-19 2.76485e-08 -6.42382e-09 3.24002e-09 1 2.76485e-08 -6.42382e-09 3.24002e-09 3985.83 -9.06295 -222.897 3996.9 0.130432 4011.81 +EDGE_SE3:QUAT 1706 1755 -4.53086 -8.56636 -4.3899 0.12843 -0.13097 0.0378755 0.982302 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4242.2 -70.9472 -1152.25 3930.34 34.8864 4302.44 +EDGE_SE3:QUAT 1707 1757 -4.22952 0.104389 -4.27253 0.143669 -0.0276603 -0.0674906 0.986934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3919.41 -4.50461 -98.4559 3999.93 2.77673 3983.75 +EDGE_SE3:QUAT 1706 1757 -4.96759 8.79818 -4.38411 0.213218 0.147305 0.160866 0.952345 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3911.59 96.5771 654.251 4007.95 94.1932 3989.93 +EDGE_SE3:QUAT 1707 1756 -4.78641 -8.42877 -4.51591 -0.00117863 -0.155747 -0.0815331 0.984426 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4409.93 -51.8939 -1344.58 3908.76 68.1391 4383.35 +EDGE_SE3:QUAT 1708 1758 -4.43491 0.179846 -4.55026 0.0190604 -0.252151 0.0177647 0.967337 1 3.00927e-21 3.00927e-21 -1.00434e-09 4.7311e-11 3.84675e-09 1 3.00927e-21 -1.00434e-09 4.7311e-11 3.84675e-09 1 -1.00434e-09 4.7311e-11 3.84675e-09 5252.9 -4.03884 -2567.25 3745.09 1.57576 5253.09 +EDGE_SE3:QUAT 1707 1758 -4.90857 8.39549 -4.26046 0.0902447 -0.0624706 0.0875847 0.990092 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.62 -18.6003 -593.941 3977.6 -17.4054 4055.51 +EDGE_SE3:QUAT 1708 1757 -4.86164 -8.70902 -4.48308 -0.0072165 -0.0217235 -0.193967 0.980741 1 1.88079e-22 1.88079e-22 8.51558e-10 -1.68302e-10 -1.98269e-11 1 1.88079e-22 8.51558e-10 -1.68302e-10 -1.98269e-11 1 8.51558e-10 -1.68302e-10 -1.98269e-11 4007.94 -1.71713 -180.774 3998.22 17.755 3857.66 +EDGE_SE3:QUAT 1709 1759 -4.44366 0.231692 -4.42749 -0.0327224 -0.0338607 0.00322635 0.998886 1 4.81482e-20 4.81482e-20 -7.55697e-11 1.38622e-08 4.58177e-10 1 4.81482e-20 -7.55697e-11 1.38622e-08 4.58177e-10 1 -7.55697e-11 1.38622e-08 4.58177e-10 4013.89 4.55361 -270.245 3995.51 -1.33726 4018.13 +EDGE_SE3:QUAT 1708 1759 -5.02673 8.24322 -4.35341 -0.0443668 -0.144904 -0.0478163 0.987293 1 8.66668e-19 8.66668e-19 -1.42032e-08 -5.38412e-08 -1.3945e-08 1 8.66668e-19 -1.42032e-08 -5.38412e-08 -1.3945e-08 1 -1.42032e-08 -5.38412e-08 -1.3945e-08 4363.38 7.33527 -1273.92 3913.06 12.038 4362.11 +EDGE_SE3:QUAT 1709 1758 -4.7253 -8.76592 -4.04734 0.0236845 -0.056388 0.0147309 0.998019 1 1.20371e-20 1.20371e-20 -6.97024e-09 -8.46905e-11 3.98112e-10 1 1.20371e-20 -6.97024e-09 -8.46905e-11 3.98112e-10 1 -6.97024e-09 -8.46905e-11 3.98112e-10 4049.97 -4.48928 -459.99 3987.03 -1.65171 4051.35 +EDGE_SE3:QUAT 1710 1760 -4.40174 0.250223 -4.42931 0.145524 0.0645116 -0.0854509 0.983544 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.29 41.13 657.405 3972.67 -10.0484 4075.79 +EDGE_SE3:QUAT 1709 1760 -5.34883 8.43209 -4.44459 -0.0270666 0.00585717 -0.283773 0.958491 1 1.20371e-20 1.20371e-20 -6.65115e-09 1.96833e-09 6.81347e-11 1 1.20371e-20 -6.65115e-09 1.96833e-09 6.81347e-11 1 -6.65115e-09 1.96833e-09 6.81347e-11 3997.38 0.998458 -45.9158 3999.62 11.1399 3678.2 +EDGE_SE3:QUAT 1710 1759 -4.87512 -8.447 -4.58511 0.0915688 -0.0914497 0.0516557 0.990244 1 3.85186e-19 3.85186e-19 -2.89858e-08 2.652e-08 4.90768e-10 1 3.85186e-19 -2.89858e-08 2.652e-08 4.90768e-10 1 -2.89858e-08 2.652e-08 4.90768e-10 4121.8 -29.0326 -803.507 3961.96 -1.89316 4144.67 +EDGE_SE3:QUAT 1711 1761 -4.39889 0.0622928 -4.26981 0.0328392 0.144166 0.237318 0.960114 1 1.92593e-19 1.92593e-19 -2.74785e-08 -7.32492e-09 -3.17721e-09 1 1.92593e-19 -2.74785e-08 -7.32492e-09 -3.17721e-09 1 -2.74785e-08 -7.32492e-09 -3.17721e-09 4232.54 117.931 1006.74 3973 148.348 4011.57 +EDGE_SE3:QUAT 1710 1761 -5.14736 8.7293 -4.66556 -0.0420532 0.172648 0.104165 0.978557 1 9.75002e-19 9.75002e-19 7.29257e-09 -5.34758e-08 -2.80201e-08 1 9.75002e-19 7.29257e-09 -5.34758e-08 -2.80201e-08 1 7.29257e-09 -5.34758e-08 -2.80201e-08 4541.16 45.9902 1579.08 3878.86 73.7186 4504.83 +EDGE_SE3:QUAT 1711 1760 -5.02728 -8.5036 -4.26535 -0.0572164 -0.101792 -0.0380727 0.992429 1 4.81482e-20 4.81482e-20 1.4081e-08 -3.80694e-10 -1.49366e-09 1 4.81482e-20 1.4081e-08 -3.80694e-10 -1.49366e-09 1 1.4081e-08 -3.80694e-10 -1.49366e-09 4167.22 17.4523 -868.229 3956.22 2.89629 4174.52 +EDGE_SE3:QUAT 1712 1762 -4.38333 -0.321327 -4.20003 -0.0871925 0.0759448 0.0317247 0.992786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4071.75 -25.5685 647.375 3974.97 -2.25786 4098.13 +EDGE_SE3:QUAT 1711 1762 -5.52868 8.33052 -4.6602 0.0250632 0.0282632 0.0777781 0.996255 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.54 3.6772 200.946 3997.78 7.94118 3985.85 +EDGE_SE3:QUAT 1712 1761 -4.90719 -8.61674 -4.63197 0.0197341 0.104403 -0.139923 0.984445 1 1.93345e-19 1.93345e-19 5.60224e-09 2.70814e-08 4.66026e-10 1 1.93345e-19 5.60224e-09 2.70814e-08 4.66026e-10 1 5.60224e-09 2.70814e-08 4.66026e-10 4182.51 -29.9479 877.609 3958.86 -63.3463 4105.76 +EDGE_SE3:QUAT 1713 1763 -4.49235 0.139547 -4.3772 -0.0860482 -0.0597879 0.0839242 0.990948 1 2.40741e-19 2.40741e-19 2.63348e-08 1.63465e-08 1.06976e-10 1 2.40741e-19 2.63348e-08 1.63465e-08 1.06976e-10 1 2.63348e-08 1.63465e-08 1.06976e-10 4006.67 20.8332 -384.38 3993.19 -20.5791 4008.12 +EDGE_SE3:QUAT 1712 1763 -5.15747 8.48012 -4.6048 -0.147018 0.134165 0.027739 0.9796 1 7.70372e-19 7.70372e-19 -5.65109e-08 7.2522e-10 -7.86751e-09 1 7.70372e-19 -5.65109e-08 7.2522e-10 -7.86751e-09 1 -5.65109e-08 7.2522e-10 -7.86751e-09 4226.36 -89.2613 1161.54 3932.26 -52.436 4309.74 +EDGE_SE3:QUAT 1713 1762 -5.21369 -8.58233 -4.14636 -0.0462101 -0.163399 0.175477 0.969728 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4334.57 137.545 -1223.5 3947.7 -157.191 4219.94 +EDGE_SE3:QUAT 1714 1764 -4.38256 0.0616021 -4.29546 0.0793933 -0.136231 -0.0108436 0.987431 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4276.07 -58.873 -1138.44 3932.31 44.9464 4300.81 +EDGE_SE3:QUAT 1713 1764 -5.00508 8.41907 -4.55575 -0.111977 -0.0320025 0.12638 0.985122 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3950.46 1.6611 -78.3072 4000.13 -1.71916 3936.72 +EDGE_SE3:QUAT 1714 1763 -5.28581 -8.36621 -4.14837 -0.0653179 0.0743939 -0.0614548 0.993188 1 1.92593e-19 1.92593e-19 -2.78213e-08 1.99808e-09 -1.82307e-09 1 1.92593e-19 -2.78213e-08 1.99808e-09 -1.82307e-09 1 -2.78213e-08 1.99808e-09 -1.82307e-09 4056.54 -25.441 547.989 3983.93 -24.8158 4058.5 +EDGE_SE3:QUAT 1715 1765 -4.65853 0.0826969 -4.16882 0.0150999 0.0377534 0.0324048 0.998647 1 4.81482e-20 4.81482e-20 -4.66597e-10 1.38585e-08 -2.43699e-10 1 4.81482e-20 -4.66597e-10 1.38585e-08 -2.43699e-10 1 -4.66597e-10 1.38585e-08 -2.43699e-10 4021.01 3.33842 296.974 3994.65 5.35032 4017.73 +EDGE_SE3:QUAT 1714 1765 -5.09359 8.23089 -4.40451 -0.0519656 0.0372246 -0.1037 0.992552 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.01 -7.69919 228.139 3997.64 -11.8966 3969.8 +EDGE_SE3:QUAT 1715 1764 -4.92475 -8.70451 -4.19395 -0.0414622 0.242454 0.0558079 0.967669 1 1.20371e-20 1.20371e-20 -7.63077e-09 -3.2357e-10 -1.93354e-09 1 1.20371e-20 -7.63077e-09 -3.2357e-10 -1.93354e-09 1 -7.63077e-09 -3.2357e-10 -1.93354e-09 5154.78 24.4736 2448.69 3761.44 32.8479 5149.2 +EDGE_SE3:QUAT 1716 1766 -4.36953 0.298844 -3.96716 0.0120934 0.0647824 0.10141 0.99266 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4061.44 12.8765 502.056 3985.88 27.3133 4020.89 +EDGE_SE3:QUAT 1715 1766 -5.13329 8.1517 -4.35472 0.0841808 0.0090219 0.0656518 0.994244 1 1.92593e-19 1.92593e-19 2.75954e-08 1.83838e-09 -6.03665e-11 1 1.92593e-19 2.75954e-08 1.83838e-09 -6.03665e-11 1 2.75954e-08 1.83838e-09 -6.03665e-11 3971.54 -0.723826 5.12347 3999.98 -0.560261 3982.64 +EDGE_SE3:QUAT 1716 1765 -4.63403 -8.3894 -3.83197 -0.11206 0.0206288 -0.0704263 0.990988 1 3.85186e-19 3.85186e-19 2.73905e-08 1.12727e-09 -2.73905e-08 1 3.85186e-19 2.73905e-08 1.12727e-09 -2.73905e-08 1 2.73905e-08 1.12727e-09 -2.73905e-08 3950.62 -2.11913 67.061 3999.97 -1.53022 3981.01 +EDGE_SE3:QUAT 1717 1767 -4.65579 0.0436923 -4.59038 0.00723433 0.153364 -0.121612 0.980631 1 3.00927e-21 3.00927e-21 -3.56785e-09 4.5608e-10 -5.47351e-10 1 3.00927e-21 -3.56785e-09 4.5608e-10 -5.47351e-10 1 -3.56785e-09 4.5608e-10 -5.47351e-10 4392.47 -70.0287 1313.44 3916.27 -95.2067 4333.52 +EDGE_SE3:QUAT 1716 1767 -5.42045 8.44163 -4.29952 0.0639478 0.0609859 0.0252838 0.995767 1 1.20371e-20 1.20371e-20 3.99262e-10 4.71051e-10 6.95672e-09 1 1.20371e-20 3.99262e-10 4.71051e-10 6.95672e-09 1 3.99262e-10 4.71051e-10 6.95672e-09 4038.2 17.4915 470.419 3987.26 11.4714 4052 +EDGE_SE3:QUAT 1717 1766 -4.92886 -8.26358 -4.1619 -0.00297279 0.00316951 -0.272846 0.962048 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000 -0.0401116 13.3273 4000 -1.24114 3702.26 +EDGE_SE3:QUAT 1718 1768 -4.53894 0.215394 -4.31493 0.0829643 -0.0532479 -0.103878 0.989692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.46 -16.1863 -313.469 3996 18.2278 3980.83 +EDGE_SE3:QUAT 1717 1768 -5.3564 8.38667 -4.49183 -0.223932 0.148763 0.0303475 0.962706 1 1.20371e-20 1.20371e-20 1.06807e-09 -1.63811e-09 7.00056e-09 1 1.20371e-20 1.06807e-09 -1.63811e-09 7.00056e-09 1 1.06807e-09 -1.63811e-09 7.00056e-09 4172.15 -160.057 1277.13 3934.42 -110.679 4369.05 +EDGE_SE3:QUAT 1718 1767 -4.78209 -8.25649 -3.80583 0.0604319 -0.063337 -0.0157203 0.996037 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4046.65 -17.0227 -498.812 3985.44 9.72257 4060.27 +EDGE_SE3:QUAT 1719 1769 -4.29489 -0.195052 -4.16639 -0.139474 0.0496277 -0.0324052 0.98845 1 7.70372e-19 7.70372e-19 -5.50615e-08 2.50836e-09 -2.14942e-09 1 7.70372e-19 -5.50615e-08 2.50836e-09 -2.14942e-09 1 -5.50615e-08 2.50836e-09 -2.14942e-09 3949.56 -23.6476 332.985 3994.77 -11.5154 4023.17 +EDGE_SE3:QUAT 1718 1769 -4.83553 8.64267 -4.17484 0.162608 -0.0844442 -0.00435747 0.983061 1 1.20371e-20 1.20371e-20 5.51871e-10 -1.16486e-09 -6.9122e-09 1 1.20371e-20 5.51871e-10 -1.16486e-09 -6.9122e-09 1 5.51871e-10 -1.16486e-09 -6.9122e-09 3998.57 -56.8601 -654.716 3978.55 28.3027 4104.26 +EDGE_SE3:QUAT 1719 1768 -5.20703 -8.22638 -4.43823 0.186664 -0.110207 0.147998 0.964939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4205.84 -70.694 -1226.33 3915.58 -21.6457 4257.6 +EDGE_SE3:QUAT 1720 1770 -4.64044 0.0342845 -4.09263 0.0277659 -0.00135378 -0.139001 0.989902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.17 0.672635 35.1901 3999.84 -3.51991 3922.97 +EDGE_SE3:QUAT 1719 1770 -5.227 8.83932 -4.65407 0.0565487 0.0974976 0.116683 0.986753 1 1.92593e-19 1.92593e-19 -3.57782e-09 2.73457e-08 -2.18533e-09 1 1.92593e-19 -3.57782e-09 2.73457e-08 -2.18533e-09 1 -3.57782e-09 2.73457e-08 -2.18533e-09 4104.91 43.1002 697.359 3977.01 53.261 4063.24 +EDGE_SE3:QUAT 1720 1769 -4.92022 -8.49899 -4.2827 0.148107 -0.0900794 0.00509808 0.984847 1 7.70372e-19 7.70372e-19 -5.5554e-08 1.22747e-09 4.94037e-09 1 7.70372e-19 -5.5554e-08 1.22747e-09 4.94037e-09 1 -5.5554e-08 1.22747e-09 4.94037e-09 4039.76 -56.9678 -725.552 3972.36 27.3627 4127.4 +EDGE_SE3:QUAT 1721 1771 -4.8342 0.226628 -4.3267 -0.0812907 0.00731239 0.0945334 0.99217 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3978.87 -6.69531 148.611 3998.06 7.96425 3969.56 +EDGE_SE3:QUAT 1720 1771 -5.12875 8.12358 -4.336 0.0378666 0.0450858 -0.0487899 0.997072 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.77 4.93769 383.907 3990.72 -7.70684 4026.98 +EDGE_SE3:QUAT 1721 1770 -5.32437 -8.08276 -3.92627 0.172119 -0.189403 -0.0127755 0.966612 1 1.58889e-18 1.58889e-18 5.92701e-08 5.15053e-08 -6.42054e-09 1 1.58889e-18 5.92701e-08 5.15053e-08 -6.42054e-09 1 5.92701e-08 5.15053e-08 -6.42054e-09 4432.99 -196.708 -1585.51 3907.32 173.688 4550.84 +EDGE_SE3:QUAT 1722 1772 -4.65355 0.20872 -4.08572 -0.0355308 -0.0833834 0.282711 0.954913 1 2.40741e-19 2.40741e-19 5.28708e-09 3.05102e-08 1.39802e-09 1 2.40741e-19 5.28708e-09 3.05102e-08 1.39802e-09 1 5.28708e-09 3.05102e-08 1.39802e-09 4049.01 37.273 -476.303 3997.12 -64.9169 3734.35 +EDGE_SE3:QUAT 1721 1772 -4.90708 8.08191 -4.40112 0.0101662 -0.0361505 -0.0897232 0.995259 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.52 -4.02126 -275.88 3995.62 12.6183 3986.73 +EDGE_SE3:QUAT 1722 1771 -5.30444 -8.16413 -4.15795 -0.0188611 -0.0334555 0.0359535 0.998615 1 1.20371e-20 1.20371e-20 -6.94384e-09 -2.59155e-10 2.22414e-10 1 1.20371e-20 -6.94384e-09 -2.59155e-10 2.22414e-10 1 -6.94384e-09 -2.59155e-10 2.22414e-10 4015.38 3.37235 -259.779 3995.94 -5.154 4011.63 +EDGE_SE3:QUAT 1723 1773 -4.14505 -0.11511 -4.07558 -0.0655062 -0.0848236 -0.130521 0.985636 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4131.25 0.475703 -784.925 3963.46 43.3107 4080.27 +EDGE_SE3:QUAT 1722 1773 -5.40158 8.17786 -4.1782 -0.0312238 0.0470649 0.0149996 0.998291 1 1.20371e-20 1.20371e-20 -6.95872e-09 -8.42778e-11 -3.33843e-10 1 1.20371e-20 -6.95872e-09 -8.42778e-11 -3.33843e-10 1 -6.95872e-09 -8.42778e-11 -3.33843e-10 4032.73 -5.34827 384.547 3990.86 1.2509 4035.73 +EDGE_SE3:QUAT 1723 1772 -5.00967 -8.52232 -4.57682 0.033853 0.10042 -0.229073 0.967623 1 1.95602e-19 1.95602e-19 9.73647e-09 2.60648e-08 7.76076e-10 1 1.95602e-19 9.73647e-09 2.60648e-08 7.76076e-10 1 9.73647e-09 2.60648e-08 7.76076e-10 4173.87 -46.8832 863.63 3965.46 -102.308 3968.56 +EDGE_SE3:QUAT 1724 1774 -4.14303 0.229145 -4.18262 0.00969605 0.169395 0.0284985 0.985088 1 5.11575e-20 5.11575e-20 6.10358e-09 4.23422e-10 1.51168e-08 1 5.11575e-20 6.10358e-09 4.23422e-10 1.51168e-08 1 6.10358e-09 4.23422e-10 1.51168e-08 4497.07 31.9831 1495.75 3887.27 35.5197 4494.2 +EDGE_SE3:QUAT 1723 1774 -5.30531 8.35007 -4.2833 -0.095201 0.0458497 0.164518 0.980698 1 7.70372e-19 7.70372e-19 -4.11638e-09 4.23969e-09 -5.49388e-08 1 7.70372e-19 -4.11638e-09 4.23969e-09 -5.49388e-08 1 -4.11638e-09 4.23969e-09 -5.49388e-08 4034.94 -13.6176 540.382 3980.09 41.6065 3962.93 +EDGE_SE3:QUAT 1724 1773 -5.09334 -8.17907 -4.23729 -0.149345 0.0116312 0.0532532 0.987282 1 4.81482e-20 4.81482e-20 3.71753e-10 -2.04694e-09 1.37157e-08 1 4.81482e-20 3.71753e-10 -2.04694e-09 1.37157e-08 1 3.71753e-10 -2.04694e-09 1.37157e-08 3919.02 -15.5206 183.805 3997.28 4.21062 3996.89 +EDGE_SE3:QUAT 1725 1775 -4.8012 0.394828 -4.09823 -0.10559 0.119766 -0.0980069 0.982294 1 3.85186e-19 3.85186e-19 2.44035e-08 -3.06949e-08 -9.49774e-10 1 3.85186e-19 2.44035e-08 -3.06949e-08 -9.49774e-10 1 2.44035e-08 -3.06949e-08 -9.49774e-10 4119.67 -74.0277 829.561 3971.45 -72.7979 4125.85 +EDGE_SE3:QUAT 1724 1775 -5.34209 8.18595 -4.25293 -0.206853 0.0349467 0.00328518 0.977742 1 8.19273e-19 8.19273e-19 5.43077e-08 -1.45492e-08 6.77565e-10 1 8.19273e-19 5.43077e-08 -1.45492e-08 6.77565e-10 1 5.43077e-08 -1.45492e-08 6.77565e-10 3847.08 -27.9203 270.812 3996.41 -5.44672 4018.19 +EDGE_SE3:QUAT 1725 1774 -4.74544 -8.52992 -4.49518 -0.203318 0.0525021 -0.0405506 0.976863 1 8.1852e-19 8.1852e-19 5.39372e-08 -3.55191e-10 -1.18279e-08 1 8.1852e-19 5.39372e-08 -3.55191e-10 -1.18279e-08 1 5.39372e-08 -3.55191e-10 -1.18279e-08 3856.12 -28.2236 297.807 3997.37 -13.4961 4014.89 +EDGE_SE3:QUAT 1726 1776 -4.78602 0.041504 -3.75285 0.0506872 -0.00325334 0.144434 0.98821 1 5.11575e-20 5.11575e-20 1.42168e-08 -1.43858e-09 -7.8608e-11 1 5.11575e-20 1.42168e-08 -1.43858e-09 -7.8608e-11 1 1.42168e-08 -1.43858e-09 -7.8608e-11 3992.65 -3.09955 -111.683 3998.81 -10.001 3919.49 +EDGE_SE3:QUAT 1725 1776 -5.3505 8.45505 -4.09379 0.102419 0.0684595 0.0214595 0.992151 1 1.92593e-19 1.92593e-19 -2.77677e-08 -9.86332e-10 -1.7499e-09 1 1.92593e-19 -2.77677e-08 -9.86332e-10 -1.7499e-09 1 -2.77677e-08 -9.86332e-10 -1.7499e-09 4024.37 29.4638 519.553 3985.26 16.3665 4064.49 +EDGE_SE3:QUAT 1726 1775 -4.81281 -8.18725 -4.0253 -0.112401 0.150754 -0.0328721 0.98161 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4290.95 -101.16 1218.1 3930.96 -86.5124 4337.17 +EDGE_SE3:QUAT 1727 1777 -4.54195 -0.410422 -4.44834 -0.0200217 -0.0285971 0.0087001 0.999353 1 2.40741e-20 2.40741e-20 6.87717e-09 7.00281e-09 -5.35477e-11 1 2.40741e-20 6.87717e-09 7.00281e-09 -5.35477e-11 1 6.87717e-09 7.00281e-09 -5.35477e-11 4011.25 2.45466 -227.156 3996.82 -1.38183 4012.56 +EDGE_SE3:QUAT 1726 1777 -5.10003 8.44769 -4.24359 -0.0869648 -0.0632959 0.0452672 0.993167 1 2.40741e-19 2.40741e-19 -2.85007e-08 -2.86155e-09 1.53851e-08 1 2.40741e-19 -2.85007e-08 -2.86155e-09 1.53851e-08 1 -2.85007e-08 -2.86155e-09 1.53851e-08 4021.12 23.5348 -456.683 3988.94 -17.4732 4043.18 +EDGE_SE3:QUAT 1727 1776 -5.22618 -8.4507 -4.25517 -0.0623136 0.187599 0.0441572 0.979272 1 9.62965e-20 9.62965e-20 -1.75205e-08 4.01819e-10 -1.75205e-08 1 9.62965e-20 -1.75205e-08 4.01819e-10 -1.75205e-08 1 -1.75205e-08 4.01819e-10 -1.75205e-08 4634.48 -29.6638 1738.55 3855.37 -11.2393 4642.21 +EDGE_SE3:QUAT 1728 1778 -4.85428 -0.142399 -4.50535 0.0655611 -0.0606373 -0.00505828 0.995992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4040.53 -16.8381 -483.961 3986.14 7.03029 4057.62 +EDGE_SE3:QUAT 1727 1778 -5.19618 8.17177 -4.14907 0.0708565 0.175984 0.0376849 0.981116 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4484.72 101.063 1508.17 3894.09 95.3434 4499.12 +EDGE_SE3:QUAT 1728 1777 -5.05323 -7.9272 -3.76831 0.0804382 -0.0459373 0.0158744 0.995574 1 7.70372e-19 7.70372e-19 -5.55165e-08 -4.65496e-10 2.66973e-09 1 7.70372e-19 -5.55165e-08 -4.65496e-10 2.66973e-09 1 -5.55165e-08 -4.65496e-10 2.66973e-09 4010.3 -15.026 -382.137 3991.06 1.20354 4035.17 +EDGE_SE3:QUAT 1729 1779 -5.18175 0.16256 -4.28855 0.0605254 0.196281 -0.148026 0.967419 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4737.76 -96.6466 1890.97 3844.97 -130.531 4664.76 +EDGE_SE3:QUAT 1728 1779 -5.1381 8.76077 -4.01168 -0.0549187 0.147936 -0.0160184 0.987341 1 6.01853e-20 6.01853e-20 1.53642e-08 -9.35856e-10 9.25928e-09 1 6.01853e-20 1.53642e-08 -9.35856e-10 9.25928e-09 1 1.53642e-08 -9.35856e-10 9.25928e-09 4350.96 -51.5731 1258.56 3917.74 -43.7861 4362 +EDGE_SE3:QUAT 1729 1778 -5.08151 -8.16883 -4.22917 -0.0588158 -0.120255 -0.188374 0.972931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4271.36 -42.8446 -1105.53 3937.86 99.4119 4143.26 +EDGE_SE3:QUAT 1730 1780 -4.51539 0.00685926 -3.86698 -0.00228704 -0.0858067 0.0610397 0.994438 1 4.81482e-20 4.81482e-20 1.19523e-09 1.81331e-10 -1.40042e-08 1 4.81482e-20 1.19523e-09 1.81331e-10 -1.40042e-08 1 1.19523e-09 1.81331e-10 -1.40042e-08 4118.44 11.9145 -698.492 3971.68 -23.3263 4103.56 +EDGE_SE3:QUAT 1729 1780 -4.98296 8.28231 -4.52417 -0.138444 -0.20049 0.0840071 0.966219 1 1.92593e-19 1.92593e-19 4.84414e-09 5.40909e-09 -2.85821e-08 1 1.92593e-19 4.84414e-09 5.40909e-09 -2.85821e-08 1 4.84414e-09 5.40909e-09 -2.85821e-08 4446.95 220.714 -1542.59 3927.21 -214.655 4495.38 +EDGE_SE3:QUAT 1730 1779 -5.27222 -8.4259 -4.1269 0.0769535 -0.00330626 -0.327283 0.941782 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3991.3 8.87767 258.374 3992.78 -57.9106 3586.53 +EDGE_SE3:QUAT 1731 1781 -4.54301 0.0382577 -4.21844 -0.0694959 0.163972 0.0263708 0.983661 1 1.95602e-19 1.95602e-19 2.95019e-08 -1.21571e-10 8.48665e-09 1 1.95602e-19 2.95019e-08 -1.21571e-10 8.48665e-09 1 2.95019e-08 -1.21571e-10 8.48665e-09 4457.89 -46.0434 1461.7 3891.72 -27.2947 4474.43 +EDGE_SE3:QUAT 1730 1781 -5.16727 8.36781 -4.69754 0.0589276 -0.0353368 0.143965 0.987195 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.97 -5.30915 -375.956 3990.46 -26.9595 3951.96 +EDGE_SE3:QUAT 1731 1780 -5.02042 -8.39508 -4.40938 -0.0855832 -0.0195249 -0.163521 0.982627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.71 11.0243 -314.429 3992.16 27.7952 3917.05 +EDGE_SE3:QUAT 1732 1782 -4.88178 0.169793 -4.54039 -0.0705735 0.199502 0.0992741 0.972298 1 4.81482e-20 4.81482e-20 -1.47663e-08 -1.17365e-09 -3.16685e-09 1 4.81482e-20 -1.47663e-08 -1.17365e-09 -3.16685e-09 1 -1.47663e-08 -1.17365e-09 -3.16685e-09 4760.87 24.7679 1932.07 3830.85 52.04 4741.37 +EDGE_SE3:QUAT 1731 1782 -5.32272 8.30958 -4.58161 0.0148783 -0.166681 0.0237477 0.985613 1 3.00927e-21 3.00927e-21 -3.62179e-09 -7.33467e-11 6.14263e-10 1 3.00927e-21 -3.62179e-09 -7.33467e-11 6.14263e-10 1 -3.62179e-09 -7.33467e-11 6.14263e-10 4485.97 3.96391 -1477.99 3888.43 -11.3875 4484.6 +EDGE_SE3:QUAT 1732 1781 -5.03354 -8.46902 -3.99821 0.0204876 0.043777 -0.162732 0.985486 1 3.00927e-21 3.00927e-21 3.43465e-09 -5.62847e-10 1.67373e-10 1 3.00927e-21 3.43465e-09 -5.62847e-10 1.67373e-10 1 3.43465e-09 -5.62847e-10 1.67373e-10 4033.83 -4.50678 378.585 3991.68 -31.12 3929.59 +EDGE_SE3:QUAT 1733 1783 -4.1758 -0.172033 -4.20729 0.0974077 0.0132413 -0.107625 0.98932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.57 11.4881 227.395 3995.69 -13.0194 3966.19 +EDGE_SE3:QUAT 1732 1783 -5.45912 8.09757 -4.28959 0.0755321 -0.00485382 0.104265 0.991665 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.27 -5.66776 -131.472 3998.39 -8.13998 3960.61 +EDGE_SE3:QUAT 1733 1782 -5.06116 -8.09046 -3.84986 0.0825578 -0.0724085 -0.0126312 0.993872 1 9.75002e-19 9.75002e-19 -5.5525e-08 2.95556e-08 8.48451e-09 1 9.75002e-19 -5.5525e-08 2.95556e-08 8.48451e-09 1 -5.5525e-08 2.95556e-08 8.48451e-09 4052.44 -26.1007 -570.3 3981.45 13.907 4079.07 +EDGE_SE3:QUAT 1734 1784 -4.55595 0.135459 -4.18665 0.0414195 -0.0102131 0.110811 0.992926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.6 -2.53254 -134.717 3998.6 -8.22906 3955.35 +EDGE_SE3:QUAT 1733 1784 -5.17556 7.98168 -4.40446 -0.069357 0.0840656 0.124172 0.986258 1 4.81482e-20 4.81482e-20 -1.39406e-08 -1.60068e-09 -1.38512e-09 1 4.81482e-20 -1.39406e-08 -1.60068e-09 -1.38512e-09 1 -1.39406e-08 -1.60068e-09 -1.38512e-09 4127.58 -3.7325 780.567 3963.58 39.5528 4085.14 +EDGE_SE3:QUAT 1734 1783 -5.11153 -8.44259 -3.90235 -0.0144307 -0.0315943 -0.186763 0.981791 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.62 -3.08373 -272.329 3995.82 25.9204 3878.93 +EDGE_SE3:QUAT 1735 1785 -4.81885 0.43198 -4.04267 0.240785 0.133581 0.0435008 0.960357 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3950.04 127.528 878.796 3981.8 99.7153 4174.39 +EDGE_SE3:QUAT 1734 1785 -5.19311 8.10475 -4.51647 -0.0564216 -0.0346273 -0.0967837 0.993101 1 1.92593e-19 1.92593e-19 -1.24361e-09 -1.36056e-09 2.76632e-08 1 1.92593e-19 -1.24361e-09 -1.36056e-09 2.76632e-08 1 -1.24361e-09 -1.36056e-09 2.76632e-08 4015.74 6.43351 -339.157 3992.3 15.4044 3991 +EDGE_SE3:QUAT 1735 1784 -5.25696 -8.48301 -4.32893 0.15259 -0.0547841 -0.0504565 0.985479 1 7.70372e-19 7.70372e-19 -5.4894e-08 3.61607e-09 2.04089e-09 1 7.70372e-19 -5.4894e-08 3.61607e-09 2.04089e-09 1 -5.4894e-08 3.61607e-09 2.04089e-09 3933.79 -25.5355 -331.831 3995.65 14.9574 4016.74 +EDGE_SE3:QUAT 1736 1786 -4.38318 -0.29632 -4.25443 0.0690271 0.0393849 0.117009 0.989946 1 1.92593e-19 1.92593e-19 -2.75141e-08 -3.379e-09 -6.07891e-10 1 1.92593e-19 -2.75141e-08 -3.379e-09 -6.07891e-10 1 -2.75141e-08 -3.379e-09 -6.07891e-10 3991.68 8.55169 210.825 3998.4 11.8256 3955.97 +EDGE_SE3:QUAT 1735 1786 -5.26701 8.19929 -4.39209 -0.0467486 0.0448275 0.0198313 0.997703 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4025.4 -7.93248 371.152 3991.44 1.41475 4032.57 +EDGE_SE3:QUAT 1736 1785 -5.12956 -8.10531 -4.06867 0.0392729 0.0585849 0.0407895 0.996675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4044.25 12.2161 451.981 3988.12 12.447 4043.76 +EDGE_SE3:QUAT 1737 1787 -4.34381 0.292628 -3.90337 -0.0597257 0.0583946 -0.0739443 0.993758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.49 -17.0734 411.39 3991.13 -18.9862 4019.88 +EDGE_SE3:QUAT 1736 1787 -5.0805 8.02167 -4.31343 -0.091793 0.07827 0.135334 0.983429 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4110.65 -12.4184 774.193 3963.23 40.5817 4071.1 +EDGE_SE3:QUAT 1737 1786 -5.18897 -7.88215 -4.16376 0.145407 -0.059272 0.0248251 0.987283 1 1.20371e-20 1.20371e-20 -4.46851e-10 1.00305e-09 6.90617e-09 1 1.20371e-20 -4.46851e-10 1.00305e-09 6.90617e-09 1 -4.46851e-10 1.00305e-09 6.90617e-09 3979.14 -36.8141 -508.848 3984.96 7.11736 4061.25 +EDGE_SE3:QUAT 1738 1788 -4.80508 -0.0693331 -4.3321 0.114966 -0.0295504 -0.0573021 0.991275 1 2.0463e-19 2.0463e-19 -2.70986e-08 8.61507e-09 -3.86569e-10 1 2.0463e-19 -2.70986e-08 8.61507e-09 -3.86569e-10 1 -2.70986e-08 8.61507e-09 -3.86569e-10 3952.71 -7.81452 -152.428 3999.19 4.84706 3992.45 +EDGE_SE3:QUAT 1737 1788 -4.91388 7.91137 -4.11819 -0.16869 -0.0662461 0.202605 0.962344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3881.92 -3.9154 -82.1692 4000.75 5.54493 3831.55 +EDGE_SE3:QUAT 1738 1787 -5.01639 -8.20189 -4.0797 0.116195 -0.102565 -0.00746516 0.987888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4107.92 -54.2572 -821.058 3964.25 32.7956 4161.7 +EDGE_SE3:QUAT 1739 1789 -4.52712 0.283264 -4.30905 -0.088137 0.0407299 -0.100166 0.990222 1 1.92593e-19 1.92593e-19 2.75222e-08 -2.946e-09 6.036e-10 1 1.92593e-19 2.75222e-08 -2.946e-09 6.036e-10 1 2.75222e-08 -2.946e-09 6.036e-10 3979.8 -9.91986 212.612 3998.44 -10.7261 3970.74 +EDGE_SE3:QUAT 1738 1789 -5.27504 8.46807 -4.38925 0.117649 -0.129796 0.221848 0.959216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4371.36 36.1556 -1375.03 3905 -122.981 4229.85 +EDGE_SE3:QUAT 1739 1788 -4.69099 -8.23258 -4.3474 0.117381 -0.00353635 -0.0920139 0.988809 1 1.93345e-19 1.93345e-19 -2.76089e-08 7.91259e-10 -2.97859e-10 1 1.93345e-19 -2.76089e-08 7.91259e-10 -2.97859e-10 1 -2.76089e-08 7.91259e-10 -2.97859e-10 3946.97 8.27305 100.383 3998.72 -6.39938 3968.21 +EDGE_SE3:QUAT 1740 1790 -4.64448 -0.502054 -3.89322 0.0847754 -0.0734571 -0.180869 0.977089 1 2.40741e-19 2.40741e-19 2.45767e-08 -1.88852e-08 4.33553e-10 1 2.40741e-19 2.45767e-08 -1.88852e-08 4.33553e-10 1 2.45767e-08 -1.88852e-08 4.33553e-10 4004.32 -25.5512 -374.095 3996.98 34.1202 3902.21 +EDGE_SE3:QUAT 1739 1790 -5.42577 8.15238 -4.42992 0.0840418 -0.183922 0.135788 0.969882 1 8.1852e-19 8.1852e-19 -2.64495e-09 -3.79212e-09 -5.53877e-08 1 8.1852e-19 -2.64495e-09 -3.79212e-09 -5.53877e-08 1 -2.64495e-09 -3.79212e-09 -5.53877e-08 4659.12 40.8734 -1795.06 3850.7 -81.4924 4613.62 +EDGE_SE3:QUAT 1740 1789 -5.18568 -8.05712 -4.28225 -0.127679 -0.0326968 -0.107388 0.985443 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.26 24.4919 -416.82 3987.3 18.532 3996.34 +EDGE_SE3:QUAT 1741 1791 -5.10142 -0.261807 -4.28472 0.0983372 0.0435918 -0.0193946 0.994009 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.08 17.854 369.046 3991.65 1.20477 4032.25 +EDGE_SE3:QUAT 1740 1791 -5.42049 8.1531 -4.10688 -0.0646423 0.140026 0.0631415 0.986016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4340.65 -14.8054 1247.89 3915.94 12.8273 4341.41 +EDGE_SE3:QUAT 1741 1790 -4.9375 -8.14873 -4.30712 0.114798 0.162455 0.0062531 0.979995 1 1.92593e-19 1.92593e-19 2.86496e-08 1.31573e-09 4.57216e-09 1 1.92593e-19 2.86496e-08 1.31573e-09 4.57216e-09 1 2.86496e-08 1.31573e-09 4.57216e-09 4378.46 105.208 1382.43 3910.04 85.0912 4431.02 +EDGE_SE3:QUAT 1742 1792 -4.82448 0.18089 -4.17357 -0.066039 0.123904 0.010089 0.990043 1 7.70372e-19 7.70372e-19 -5.67126e-08 3.66527e-10 -7.1114e-09 1 7.70372e-19 -5.67126e-08 3.66527e-10 -7.1114e-09 1 -5.67126e-08 3.66527e-10 -7.1114e-09 4240.83 -36.3168 1048.72 3939.47 -20.2095 4257.87 +EDGE_SE3:QUAT 1741 1792 -5.20981 8.06705 -3.94347 -0.0193963 0.0398635 0.118554 0.991958 1 5.11575e-20 5.11575e-20 -5.08261e-09 1.33596e-08 -1.8799e-11 1 5.11575e-20 -5.08261e-09 1.33596e-08 -1.8799e-11 1 -5.08261e-09 1.33596e-08 -1.8799e-11 4027.46 1.62559 341.626 3992.89 20.2009 3972.74 +EDGE_SE3:QUAT 1742 1791 -5.27062 -8.12438 -4.39412 0.0104177 0.0274209 -0.00683851 0.999546 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.71 1.03584 220.758 3996.96 -0.571957 4011.96 +EDGE_SE3:QUAT 1743 1793 -4.53809 -0.0832353 -4.17932 -0.0164727 -0.0841408 0.0929869 0.991969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4105.09 21.1178 -660.393 3975.88 -35.2081 4071.59 +EDGE_SE3:QUAT 1742 1793 -4.84203 7.78997 -4.33077 -0.0273571 0.0552752 0.131284 0.989424 1 7.82409e-19 7.82409e-19 -1.02945e-08 -2.22726e-10 -5.57405e-08 1 7.82409e-19 -1.02945e-08 -2.22726e-10 -5.57405e-08 1 -1.02945e-08 -2.22726e-10 -5.57405e-08 4053.58 4.05715 479.114 3986.3 30.9634 3987.64 +EDGE_SE3:QUAT 1743 1792 -5.0693 -8.40278 -4.17915 -0.040897 0.230151 -0.103264 0.966796 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4879.69 -222.854 2081.79 3843.64 -228.606 4843.73 +EDGE_SE3:QUAT 1744 1794 -4.58525 -0.329912 -4.54741 -0.0212002 -0.0479089 -0.0161001 0.998497 1 1.20371e-20 1.20371e-20 -6.96106e-09 9.84562e-11 3.38308e-10 1 1.20371e-20 -6.96106e-09 9.84562e-11 3.38308e-10 1 -6.96106e-09 9.84562e-11 3.38308e-10 4035.91 3.33922 -390.174 3990.6 2.02825 4036.67 +EDGE_SE3:QUAT 1743 1794 -5.13693 8.02607 -4.37689 0.00885782 0.0672949 -0.0236527 0.997413 1 7.52316e-22 7.52316e-22 -1.74618e-09 3.96812e-11 -1.18404e-10 1 7.52316e-22 -1.74618e-09 3.96812e-11 -1.18404e-10 1 -1.74618e-09 3.96812e-11 -1.18404e-10 4073.7 -0.0927684 549.129 3981.74 -5.82342 4071.78 +EDGE_SE3:QUAT 1744 1793 -4.78082 -8.18272 -4.2731 -0.0501901 0.0919543 0.119721 0.987265 1 4.81482e-20 4.81482e-20 -1.39778e-08 -1.58606e-09 -1.42976e-09 1 4.81482e-20 -1.39778e-08 -1.58606e-09 -1.42976e-09 1 -1.39778e-08 -1.58606e-09 -1.42976e-09 4150.63 5.68912 817.795 3961.21 42.8607 4103.37 +EDGE_SE3:QUAT 1745 1795 -4.76651 0.137866 -4.092 0.0140359 0.102508 0.114351 0.988038 1 1.20371e-20 1.20371e-20 -6.99197e-09 -8.46525e-10 -6.82584e-10 1 1.20371e-20 -6.99197e-09 -8.46525e-10 -6.82584e-10 1 -6.99197e-09 -8.46525e-10 -6.82584e-10 4157.3 34.6347 810.959 3965.43 54.1479 4105.78 +EDGE_SE3:QUAT 1744 1795 -5.33449 8.04619 -4.32886 -0.147687 0.0435887 0.0219275 0.98783 1 3.00927e-21 3.00927e-21 1.67545e-10 -5.09719e-10 3.44274e-09 1 3.00927e-21 1.67545e-10 -5.09719e-10 3.44274e-09 1 1.67545e-10 -5.09719e-10 3.44274e-09 3948.25 -28.0961 378.509 3991.49 -3.39163 4033.57 +EDGE_SE3:QUAT 1745 1794 -5.19228 -7.73921 -3.98744 0.00676906 0.0930226 -0.18964 0.977414 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4132.23 -36.916 740.06 3973.79 -74.3853 3988.56 +EDGE_SE3:QUAT 1746 1796 -4.31977 -0.21562 -4.19804 -0.0805687 0.00709842 0.0246735 0.996418 1 1.92593e-19 1.92593e-19 2.76617e-08 6.44514e-10 3.04259e-10 1 1.92593e-19 2.76617e-08 6.44514e-10 3.04259e-10 1 2.76617e-08 6.44514e-10 3.04259e-10 3975.62 -3.48395 79.958 3999.53 0.913279 3999.15 +EDGE_SE3:QUAT 1745 1796 -5.43188 8.21321 -4.06685 0.0284397 -0.0114983 -0.0368549 0.99885 1 4.81482e-20 4.81482e-20 1.29835e-10 -4.05533e-10 -1.38645e-08 1 4.81482e-20 1.29835e-10 -4.05533e-10 -1.38645e-08 1 1.29835e-10 -4.05533e-10 -1.38645e-08 3998.33 -1.15878 -79.1505 3999.65 1.45291 3996.13 +EDGE_SE3:QUAT 1746 1795 -5.12263 -8.13034 -3.997 0.21237 0.0186035 -0.0300856 0.976549 1 7.70372e-19 7.70372e-19 -5.42896e-08 1.09373e-09 -1.63362e-09 1 7.70372e-19 -5.42896e-08 1.09373e-09 -1.63362e-09 1 -5.42896e-08 1.09373e-09 -1.63362e-09 3830.9 24.6993 213.628 3996.98 -0.324537 4007.69 +EDGE_SE3:QUAT 1747 1797 -4.27831 -0.104127 -4.24937 0.0126451 -0.0482757 0.0835936 0.99525 1 3.00927e-21 3.00927e-21 -3.46998e-09 -2.88497e-10 1.73286e-10 1 3.00927e-21 -3.46998e-09 -2.88497e-10 1.73286e-10 1 -3.46998e-09 -2.88497e-10 1.73286e-10 4038.61 2.31362 -398.157 3990.39 -16.4401 4011.3 +EDGE_SE3:QUAT 1746 1797 -5.12139 8.07413 -4.33213 0.0890559 0.156632 0.000341096 0.983634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4380.28 75.7796 1348.29 3909.32 58.5078 4412.01 +EDGE_SE3:QUAT 1747 1796 -4.87071 -8.28379 -4.34323 -0.0156475 0.0897894 -0.242127 0.965954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4093.04 -43.7208 622.967 3986.92 -79.0996 3859.52 +EDGE_SE3:QUAT 1748 1798 -4.86828 -0.139644 -4.33467 -0.0568435 -0.0488422 -0.103748 0.991776 1 9.62965e-20 9.62965e-20 1.52157e-08 1.24013e-08 -1.91574e-10 1 9.62965e-20 1.52157e-08 1.24013e-08 -1.91574e-10 1 1.52157e-08 1.24013e-08 -1.91574e-10 4038.84 6.34517 -458.327 3986.5 21.3817 4008.71 +EDGE_SE3:QUAT 1747 1798 -5.18215 7.99737 -4.21053 0.0399152 0.00575043 0.0742825 0.996422 1 4.81482e-20 4.81482e-20 -1.38281e-08 -1.03397e-09 3.33786e-12 1 4.81482e-20 -1.38281e-08 -1.03397e-09 3.33786e-12 1 -1.38281e-08 -1.03397e-09 3.33786e-12 3993.62 -0.0297175 10.1008 4000 -0.066765 3977.92 +EDGE_SE3:QUAT 1748 1797 -5.30943 -7.81253 -3.97141 -0.0162007 -0.151033 -0.166932 0.974197 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4377.76 -88.3 -1288.15 3924.62 123.899 4267.35 +EDGE_SE3:QUAT 1749 1799 -4.32172 -0.223981 -4.31644 -0.0378868 0.116997 -0.0554896 0.990857 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4206.33 -38.6581 945.215 3951.81 -42.2029 4199.75 +EDGE_SE3:QUAT 1748 1799 -5.151 7.85965 -4.68615 0.234774 -0.057507 0.0118416 0.970275 1 7.70372e-19 7.70372e-19 5.42314e-08 -8.81597e-10 -3.16123e-09 1 7.70372e-19 5.42314e-08 -8.81597e-10 -3.16123e-09 1 5.42314e-08 -8.81597e-10 -3.16123e-09 3831.67 -54.7549 -459.904 3990.29 16.3097 4051.58 +EDGE_SE3:QUAT 1749 1798 -4.98341 -7.94162 -4.24724 -0.0664053 -0.102614 -0.0432413 0.99156 1 1.92593e-19 1.92593e-19 2.81582e-08 -8.51829e-10 -3.04368e-09 1 1.92593e-19 2.81582e-08 -8.51829e-10 -3.04368e-09 1 2.81582e-08 -8.51829e-10 -3.04368e-09 4168.59 20.8587 -882.964 3954.8 2.80505 4178.74 +EDGE_SE3:QUAT 1750 1800 -4.9902 0.107448 -4.31826 -0.0675657 -0.151685 -0.0396462 0.98532 1 2.40741e-19 2.40741e-19 -2.64613e-08 1.43268e-09 -9.83267e-09 1 2.40741e-19 -2.64613e-08 1.43268e-09 -9.83267e-09 1 -2.64613e-08 1.43268e-09 -9.83267e-09 4392.99 31.8746 -1346.9 3904.83 -9.70913 4404.96 +EDGE_SE3:QUAT 1749 1800 -5.37282 7.90815 -4.28402 -0.0755029 0.0225043 -0.173225 0.981726 1 7.73381e-19 7.73381e-19 8.72662e-10 7.77122e-09 -5.42191e-08 1 7.73381e-19 8.72662e-10 7.77122e-09 -5.42191e-08 1 8.72662e-10 7.77122e-09 -5.42191e-08 3976.52 1.28946 17.175 3999.96 3.25772 3879.29 +EDGE_SE3:QUAT 1750 1799 -5.46917 -7.73884 -4.23642 0.185588 -0.0745174 0.0231117 0.979525 1 7.70372e-19 7.70372e-19 -5.50504e-08 3.16944e-10 4.37214e-09 1 7.70372e-19 -5.50504e-08 3.16944e-10 4.37214e-09 1 -5.50504e-08 3.16944e-10 4.37214e-09 3958.81 -59.2878 -629.018 3979.11 19.4695 4094.44 +EDGE_SE3:QUAT 1751 1801 -4.43177 0.276902 -4.308 0.0301351 -0.0548487 -0.056179 0.996457 1 1.44445e-19 1.44445e-19 -1.3787e-08 1.51655e-08 1.41119e-08 1 1.44445e-19 -1.3787e-08 1.51655e-08 1.41119e-08 1 -1.3787e-08 1.51655e-08 1.41119e-08 4039.9 -10.1849 -419.636 3989.82 13.9559 4030.91 +EDGE_SE3:QUAT 1750 1801 -5.50373 8.12253 -4.15063 -0.11331 0.202412 -0.0717033 0.970077 1 7.70372e-19 7.70372e-19 6.85238e-09 5.35604e-08 8.40689e-09 1 7.70372e-19 6.85238e-09 5.35604e-08 8.40689e-09 1 6.85238e-09 5.35604e-08 8.40689e-09 4543.55 -202.687 1655.03 3901.72 -197.601 4574.34 +EDGE_SE3:QUAT 1751 1800 -5.28555 -7.81115 -4.07942 0.00808775 -0.169599 -0.145029 0.97475 1 8.1852e-19 8.1852e-19 5.61619e-09 -5.63094e-08 9.34011e-10 1 8.1852e-19 5.61619e-09 -5.63094e-08 9.34011e-10 1 5.61619e-09 -5.63094e-08 9.34011e-10 4455.76 -115.594 -1425.97 3912.08 139.327 4371.89 +EDGE_SE3:QUAT 1752 1802 -4.69108 0.278986 -3.92797 -0.0182803 -0.29501 0.0235315 0.95503 1 1.20371e-20 1.20371e-20 8.01099e-09 3.43329e-10 -2.46015e-09 1 1.20371e-20 8.01099e-09 3.43329e-10 -2.46015e-09 1 8.01099e-09 3.43329e-10 -2.46015e-09 5841.03 137.733 -3280.82 3662.15 -137.587 5840.15 +EDGE_SE3:QUAT 1751 1802 -5.11313 7.83365 -4.42917 0.12117 0.0583375 0.00326946 0.990911 1 1.95602e-19 1.95602e-19 2.78773e-08 9.10612e-10 5.01965e-09 1 1.95602e-19 2.78773e-08 9.10612e-10 5.01965e-09 1 2.78773e-08 9.10612e-10 5.01965e-09 3992.74 28.5953 456.733 3988.36 10.3914 4051.43 +EDGE_SE3:QUAT 1752 1801 -4.91374 -7.90155 -3.94568 -0.0649896 -0.0863765 0.0612155 0.992254 1 1.92593e-19 1.92593e-19 2.7894e-08 2.04866e-09 -2.16207e-09 1 1.92593e-19 2.7894e-08 2.04866e-09 -2.16207e-09 1 2.7894e-08 2.04866e-09 -2.16207e-09 4085.48 31.937 -648.424 3977.59 -31.2747 4087.38 +EDGE_SE3:QUAT 1753 1803 -4.71568 -0.0731883 -4.01269 -0.0308652 -0.0788278 -0.0916394 0.992187 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4106 -3.86569 -671.821 3973.25 28.2279 4076.22 +EDGE_SE3:QUAT 1752 1803 -5.23395 8.30314 -4.05513 -0.214211 0.0120692 0.0342071 0.976114 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3824 -21.4046 175.348 3997.72 1.41711 4002.87 +EDGE_SE3:QUAT 1753 1802 -5.23811 -7.74798 -3.79084 -0.1122 0.132758 -0.0919585 0.980475 1 9.62965e-19 9.62965e-19 -5.8882e-08 1.09529e-08 -3.39579e-08 1 9.62965e-19 -5.8882e-08 1.09529e-08 -3.39579e-08 1 -5.8882e-08 1.09529e-08 -3.39579e-08 4159.03 -90.9739 941.26 3963.94 -87.6649 4175.56 +EDGE_SE3:QUAT 1754 1804 -4.731 0.16497 -4.32733 0.049374 0.119955 0.114184 0.984954 1 1.92593e-19 1.92593e-19 -2.97285e-09 -2.19469e-09 -2.80069e-08 1 1.92593e-19 -2.97285e-09 -2.19469e-09 -2.80069e-08 1 -2.97285e-09 -2.19469e-09 -2.80069e-08 4184.81 60.8505 904.254 3961.23 72.7039 4142.41 +EDGE_SE3:QUAT 1753 1804 -5.98523 7.6999 -4.01548 -0.0183815 -0.0861948 -0.0972908 0.991346 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4124.43 -11.3787 -720.39 3970.09 34.5593 4087.92 +EDGE_SE3:QUAT 1754 1803 -4.84249 -8.26682 -4.20897 -0.0249306 -0.192341 -0.107571 0.975096 1 2.0463e-19 2.0463e-19 -1.51978e-09 2.76663e-10 -2.78208e-08 1 2.0463e-19 -1.51978e-09 2.76663e-10 -2.78208e-08 1 -1.51978e-09 2.76663e-10 -2.78208e-08 4668 -85.6577 -1769.62 3858.55 107.247 4624.2 +EDGE_SE3:QUAT 1755 1805 -4.73438 -0.023025 -3.87105 0.111519 0.026487 -0.0688015 0.991024 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3972.33 16.4516 299.167 3993.61 -8.1093 4003.15 +EDGE_SE3:QUAT 1754 1805 -5.26361 8.34344 -4.03427 0.0465841 -0.0963765 0.0389132 0.993492 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4151.6 -11.6461 -816.607 3960.88 -6.31222 4154.23 +EDGE_SE3:QUAT 1755 1804 -5.17757 -8.15252 -3.93359 -0.0546317 -0.194079 -0.258901 0.944626 1 3.0907e-18 3.0907e-18 -1.73025e-08 4.55706e-09 1.12887e-07 1 3.0907e-18 -1.73025e-08 4.55706e-09 1.12887e-07 1 -1.73025e-08 4.55706e-09 1.12887e-07 4677.2 -228.295 -1798.43 3899.46 274.749 4421.02 +EDGE_SE3:QUAT 1756 1806 -4.57167 0.110955 -4.27339 -0.0731689 -0.151636 0.00687704 0.985701 1 2.40741e-19 2.40741e-19 3.08107e-08 2.01899e-09 -1.865e-08 1 2.40741e-19 3.08107e-08 2.01899e-09 -1.865e-08 1 3.08107e-08 2.01899e-09 -1.865e-08 4362.02 62.9963 -1296.48 3914.22 -49.8692 4383.25 +EDGE_SE3:QUAT 1755 1806 -5.63296 7.93122 -4.16263 -0.00505713 0.210266 0.105169 0.971958 1 1.20371e-20 1.20371e-20 7.38696e-09 8.59768e-10 1.56819e-09 1 1.20371e-20 7.38696e-09 8.59768e-10 1.56819e-09 1 7.38696e-09 8.59768e-10 1.56819e-09 4788.67 129.94 1943.6 3841.72 144.706 4744.53 +EDGE_SE3:QUAT 1756 1805 -5.02835 -7.79693 -3.85989 0.00285941 0.0171094 -0.03707 0.999162 1 4.81482e-20 4.81482e-20 -2.39869e-10 -2.20101e-11 -1.38744e-08 1 4.81482e-20 -2.39869e-10 -2.20101e-11 -1.38744e-08 1 -2.39869e-10 -2.20101e-11 -1.38744e-08 4004.72 -0.0655374 138.007 3998.81 -2.55164 3999.26 +EDGE_SE3:QUAT 1757 1807 -4.4959 0.275539 -3.94383 0.0191797 0.0126008 0.0969279 0.995027 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000 0.912857 77.1867 3999.72 3.41001 3963.89 +EDGE_SE3:QUAT 1756 1807 -5.43951 7.53258 -4.04208 0.0340879 0.0168466 0.0884774 0.995352 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.66 1.81022 97.0095 3999.58 3.88202 3971 +EDGE_SE3:QUAT 1757 1806 -5.34999 -8.18664 -4.11975 0.0366839 0.0669403 -0.181307 0.98046 1 7.70372e-19 7.70372e-19 4.24095e-09 5.93779e-10 5.50395e-08 1 7.70372e-19 4.24095e-09 5.93779e-10 5.50395e-08 1 4.24095e-09 5.93779e-10 5.50395e-08 4082.22 -11.6312 598.462 3979.85 -54.0468 3956.12 +EDGE_SE3:QUAT 1758 1808 -4.66013 0.383671 -4.21065 0.0445219 -0.0431944 0.0181716 0.997909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.6 -7.30676 -356.542 3992.1 -1.23796 4030.21 +EDGE_SE3:QUAT 1757 1808 -5.49348 7.85765 -4.33875 -0.170906 -0.0318558 0.0766412 0.981785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3884.26 3.10306 -87.8163 4000.14 -2.17761 3977.6 +EDGE_SE3:QUAT 1758 1807 -5.19872 -7.93921 -3.90697 0.111657 -0.122062 0.161133 0.97297 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4296.12 -2.6018 -1226.82 3917.84 -65.7121 4242.13 +EDGE_SE3:QUAT 1759 1809 -4.53584 0.149353 -4.06838 -0.108813 0.219954 0.131089 0.960518 1 1.92593e-19 1.92593e-19 -7.43267e-09 1.73123e-09 -3.00124e-08 1 1.92593e-19 -7.43267e-09 1.73123e-09 -3.00124e-08 1 -7.43267e-09 1.73123e-09 -3.00124e-08 4997.54 23.7894 2296.05 3783.31 55.3902 4976.17 +EDGE_SE3:QUAT 1758 1809 -5.24623 8.22363 -4.27477 -0.0236501 -0.0503753 0.169404 0.983974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4026.28 11.9203 -340.044 3994.82 -28.7067 3913.73 +EDGE_SE3:QUAT 1759 1808 -5.30655 -8.11404 -3.81522 0.0419131 0.0982586 -0.210608 0.971716 1 1.20371e-20 1.20371e-20 -6.90072e-09 1.46445e-09 -7.57777e-10 1 1.20371e-20 -6.90072e-09 1.46445e-09 -7.57777e-10 1 -6.90072e-09 1.46445e-09 -7.57777e-10 4174.23 -37.4608 870.558 3962.13 -92.5586 4003.83 +EDGE_SE3:QUAT 1760 1810 -4.55733 0.0271492 -3.83105 -0.13918 0.0928196 0.00152083 0.985906 1 3.08149e-18 3.08149e-18 1.11313e-07 -2.75862e-09 1.01149e-08 1 3.08149e-18 1.11313e-07 -2.75862e-09 1.01149e-08 1 1.11313e-07 -2.75862e-09 1.01149e-08 4056.57 -55.7359 744.572 3970.78 -28.4545 4134.05 +EDGE_SE3:QUAT 1759 1810 -5.25553 7.60969 -4.44886 -0.0692314 -0.0381437 0.119001 0.989743 1 2.0463e-19 2.0463e-19 -2.90779e-10 8.98799e-09 -2.69742e-08 1 2.0463e-19 -2.90779e-10 8.98799e-09 -2.69742e-08 1 -2.90779e-10 8.98799e-09 -2.69742e-08 3990.35 7.93461 -198.996 3998.64 -11.1109 3952.88 +EDGE_SE3:QUAT 1760 1809 -4.75612 -7.81463 -4.14137 0.115351 -0.0530986 -0.21254 0.968866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3946.39 -1.99789 -104.138 4000.74 0.621684 3818.92 +EDGE_SE3:QUAT 1761 1811 -4.83451 -0.0220158 -3.93234 -0.0525837 -0.00222926 -0.0207886 0.998398 1 4.81482e-20 4.81482e-20 -1.3856e-08 2.83669e-10 6.10339e-11 1 4.81482e-20 -1.3856e-08 2.83669e-10 6.10339e-11 1 -1.3856e-08 2.83669e-10 6.10339e-11 3989.17 0.919061 -30.8403 3999.92 0.350357 3998.5 +EDGE_SE3:QUAT 1760 1811 -5.08895 7.8334 -4.26636 -0.0606106 -0.24101 0.177906 0.95215 1 7.70372e-19 7.70372e-19 -1.20435e-08 -9.50193e-09 5.81227e-08 1 7.70372e-19 -1.20435e-08 -9.50193e-09 5.81227e-08 1 -1.20435e-08 -9.50193e-09 5.81227e-08 4780.18 351.08 -1957.27 3919.06 -356.514 4668.27 +EDGE_SE3:QUAT 1761 1810 -5.25511 -7.97068 -3.95992 0.16723 -0.0576542 -0.0228927 0.983964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3927.46 -34.058 -399.517 3992.66 15.3104 4037.23 +EDGE_SE3:QUAT 1762 1812 -4.82441 -0.113839 -4.33441 0.0787551 -0.0840096 0.0802773 0.990099 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4114.11 -16.7963 -758.475 3965.26 -17.7499 4113.14 +EDGE_SE3:QUAT 1761 1812 -5.09651 7.77831 -4.20838 0.110421 -0.0366661 -0.0357301 0.992565 1 4.81482e-20 4.81482e-20 3.86706e-10 -1.57119e-09 -1.37997e-08 1 4.81482e-20 3.86706e-10 -1.57119e-09 -1.37997e-08 1 3.86706e-10 -1.57119e-09 -1.37997e-08 3965.61 -13.3408 -241.093 3997.15 6.69796 4009.28 +EDGE_SE3:QUAT 1762 1811 -5.21417 -7.7938 -4.13712 -0.131388 0.0496148 0.0155479 0.989967 1 7.70372e-19 7.70372e-19 -5.52508e-08 -1.18047e-10 -2.89907e-09 1 7.70372e-19 -5.52508e-08 -1.18047e-10 -2.89907e-09 1 -5.52508e-08 -1.18047e-10 -2.89907e-09 3973.5 -27.3129 414.736 3989.93 -5.02306 4041.58 +EDGE_SE3:QUAT 1763 1813 -5.19123 0.16933 -4.38846 -0.0164063 -0.0877917 0.0221929 0.995756 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4123.22 10.5468 -715.987 3969.92 -11.6823 4122.33 +EDGE_SE3:QUAT 1762 1813 -5.29247 7.79668 -4.3387 0.085079 -0.176983 -0.00927285 0.980486 1 1.92593e-19 1.92593e-19 2.89753e-08 -1.21865e-09 -5.09814e-09 1 1.92593e-19 2.89753e-08 -1.21865e-09 -5.09814e-09 1 2.89753e-08 -1.21865e-09 -5.09814e-09 4501.02 -95.5377 -1549.52 3886.87 82.2237 4529.63 +EDGE_SE3:QUAT 1763 1812 -5.19275 -7.99016 -3.90391 -0.0859957 -0.0672827 0.125261 0.986097 1 9.62965e-19 9.62965e-19 2.98807e-08 9.40476e-09 -5.61932e-08 1 9.62965e-19 2.98807e-08 9.40476e-09 -5.61932e-08 1 2.98807e-08 9.40476e-09 -5.61932e-08 4008.18 24.0253 -394.242 3994.17 -28.3521 3975 +EDGE_SE3:QUAT 1764 1814 -5.02121 -0.171391 -4.47035 -0.0665332 -0.157569 0.0638045 0.983196 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4360.86 92.0483 -1287.85 3921.66 -91.5525 4362.28 +EDGE_SE3:QUAT 1763 1814 -5.74848 8.14568 -4.03361 -0.0211842 0.0680356 0.173083 0.982326 1 3.00927e-21 3.00927e-21 3.4433e-09 6.0211e-10 2.49458e-10 1 3.00927e-21 3.4433e-09 6.0211e-10 2.49458e-10 1 3.4433e-09 6.0211e-10 2.49458e-10 4078.7 14.642 573.112 3982.13 50.1723 3960.66 +EDGE_SE3:QUAT 1764 1813 -5.42521 -7.91424 -3.99392 0.0603709 0.125172 0.0681779 0.987947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4214.32 58.6681 984.234 3950.96 60.1724 4210.31 +EDGE_SE3:QUAT 1765 1815 -4.83547 0.111717 -3.67943 0.17763 -0.0735782 0.0756185 0.978425 1 8.1852e-19 8.1852e-19 -5.65655e-08 -2.34063e-10 1.91579e-08 1 8.1852e-19 -5.65655e-08 -2.34063e-10 1.91579e-08 1 -5.65655e-08 -2.34063e-10 1.91579e-08 4004.87 -60.0022 -736.5 3967.53 1.72704 4108.2 +EDGE_SE3:QUAT 1764 1815 -5.23861 7.93388 -4.28356 0.214164 -0.0693827 -0.128717 0.965791 1 7.70372e-19 7.70372e-19 -5.36421e-08 8.13368e-09 3.80052e-10 1 7.70372e-19 -5.36421e-08 8.13368e-09 3.80052e-10 1 -5.36421e-08 8.13368e-09 3.80052e-10 3820.71 -9.70595 -184.399 4001.62 9.44204 3937.9 +EDGE_SE3:QUAT 1765 1814 -5.32302 -7.90299 -4.08445 0.0900296 -0.103141 -0.110983 0.984347 1 3.85186e-19 3.85186e-19 2.99394e-08 -6.82949e-09 -2.99394e-08 1 3.85186e-19 2.99394e-08 -6.82949e-09 -2.99394e-08 1 2.99394e-08 -6.82949e-09 -2.99394e-08 4084.23 -54.0758 -695.418 3979.5 57.3528 4067.38 +EDGE_SE3:QUAT 1766 1816 -4.46628 -0.0882511 -3.7652 -0.140336 0.00344221 -0.0370356 0.989405 1 3.08153e-18 3.08153e-18 1.09865e-07 -3.6269e-09 -7.14989e-10 1 3.08153e-18 1.09865e-07 -3.6269e-09 -7.14989e-10 1 1.09865e-07 -3.6269e-09 -7.14989e-10 3921.42 3.917 -34.8226 3999.81 1.01401 3994.71 +EDGE_SE3:QUAT 1765 1816 -5.27773 7.87619 -3.98369 -0.109033 -0.03588 0.0304146 0.992925 1 4.81482e-20 4.81482e-20 -5.20954e-10 1.37762e-08 1.54364e-09 1 4.81482e-20 -5.20954e-10 1.37762e-08 1.54364e-09 1 -5.20954e-10 1.37762e-08 1.54364e-09 3967.05 13.2879 -242.721 3997.02 -6.12553 4010.91 +EDGE_SE3:QUAT 1766 1815 -5.05972 -8.22026 -4.10657 0.129271 -0.164942 0.0533971 0.976336 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4445.6 -86.9547 -1520.66 3887.38 50.5217 4501.04 +EDGE_SE3:QUAT 1767 1817 -4.71952 -0.0192564 -4.15695 0.0796948 -0.0727897 -0.0324854 0.993627 1 2.40741e-19 2.40741e-19 -2.69072e-08 4.21166e-11 -1.20568e-08 1 2.40741e-19 -2.69072e-08 4.21166e-11 -1.20568e-08 1 -2.69072e-08 4.21166e-11 -1.20568e-08 4049.69 -26.5251 -553.388 3983.07 18.6384 4070.87 +EDGE_SE3:QUAT 1766 1817 -5.29869 7.70201 -4.05082 0.0707576 0.135401 0.0768529 0.985268 1 1.92593e-19 1.92593e-19 2.82343e-08 2.82049e-09 3.46807e-09 1 1.92593e-19 2.82343e-08 2.82049e-09 3.46807e-09 1 2.82343e-08 2.82049e-09 3.46807e-09 4240.22 75.4485 1053.6 3946.8 76.5806 4236.62 +EDGE_SE3:QUAT 1767 1816 -5.1386 -7.75537 -4.13875 0.146664 0.136028 -0.127576 0.971448 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4340.87 48.0892 1375.31 3899.65 -19.0081 4361.81 +EDGE_SE3:QUAT 1768 1818 -4.81251 0.419692 -3.87202 -0.102552 0.158322 0.109221 0.975955 1 1.92593e-19 1.92593e-19 5.14918e-09 -2.06893e-09 2.87948e-08 1 1.92593e-19 5.14918e-09 -2.06893e-09 2.87948e-08 1 5.14918e-09 -2.06893e-09 2.87948e-08 4468.24 -16.7896 1517.29 3883.03 28.7384 4462.59 +EDGE_SE3:QUAT 1767 1818 -5.90732 7.70776 -3.9861 -0.0342732 -0.0769926 0.00697914 0.996418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4090.57 12.3584 -624.624 3976.84 -7.27976 4095.07 +EDGE_SE3:QUAT 1768 1817 -5.20806 -7.92742 -4.01616 0.00225459 0.140472 -0.121169 0.98264 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4321.62 -60.0874 1179.1 3930.85 -84.8471 4262.91 +EDGE_SE3:QUAT 1769 1819 -4.8219 -0.111749 -3.98928 -0.0242392 0.0564826 -0.0971138 0.993374 1 6.01853e-20 6.01853e-20 -5.53893e-09 1.44815e-08 1.3088e-10 1 6.01853e-20 -5.53893e-09 1.44815e-08 1.3088e-10 1 -5.53893e-09 1.44815e-08 1.3088e-10 4041.38 -11.8025 420.742 3990.28 -22.1614 4006 +EDGE_SE3:QUAT 1768 1819 -5.47713 7.37757 -4.02417 0.11748 0.069173 0.283155 0.949335 1 7.70372e-19 7.70372e-19 5.2671e-08 1.6209e-08 -4.26425e-10 1 7.70372e-19 5.2671e-08 1.6209e-08 -4.26425e-10 1 5.2671e-08 1.6209e-08 -4.26425e-10 3941.02 0.463192 100.336 4001.51 -6.79789 3675.51 +EDGE_SE3:QUAT 1769 1818 -5.53301 -8.13611 -4.21784 0.015517 -0.100287 0.0551937 0.993305 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4167.75 6.97907 -838.636 3959.37 -21.7089 4156.53 +EDGE_SE3:QUAT 1770 1820 -4.46146 -0.21727 -4.32586 -0.0210311 0.227962 0.0135295 0.973349 1 8.21529e-19 8.21529e-19 -1.44546e-08 5.3899e-08 1.1637e-09 1 8.21529e-19 -1.44546e-08 5.3899e-08 1.1637e-09 1 -1.44546e-08 5.3899e-08 1.1637e-09 4982.62 -14.6036 2215.09 3791.79 -10.7444 4983.66 +EDGE_SE3:QUAT 1769 1820 -5.39029 7.81486 -4.37299 -0.0603642 -0.00756676 0.133469 0.989184 1 4.81482e-20 4.81482e-20 1.37278e-08 1.8513e-09 1.2071e-10 1 4.81482e-20 1.37278e-08 1.8513e-09 1.2071e-10 1 1.37278e-08 1.8513e-09 1.2071e-10 3985.5 -2.0942 36.7036 3999.7 4.64097 3928.82 +EDGE_SE3:QUAT 1770 1819 -5.4069 -7.85144 -4.06003 -0.0305645 -0.127309 -0.0397143 0.990596 1 4.81482e-20 4.81482e-20 -1.85425e-09 -3.03498e-10 1.42195e-08 1 4.81482e-20 -1.85425e-09 -3.03498e-10 1.42195e-08 1 -1.85425e-09 -3.03498e-10 1.42195e-08 4275.16 2.61302 -1092.42 3933.65 12.4366 4272.59 +EDGE_SE3:QUAT 1771 1821 -4.75399 0.0110636 -3.98792 -0.100827 -0.202242 0.0648677 0.971969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4580.9 187.542 -1695.96 3890.18 -182.928 4604.74 +EDGE_SE3:QUAT 1770 1821 -5.30241 8.09664 -4.17118 -0.0434786 -0.0274107 0.0969243 0.993964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.19 4.37555 -165.548 3998.75 -7.70714 3969.17 +EDGE_SE3:QUAT 1771 1820 -5.40467 -7.89271 -4.00072 -0.0601463 -0.0345733 -0.0649398 0.995475 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.23 7.89278 -321.944 3993.15 8.88618 4008.83 +EDGE_SE3:QUAT 1772 1822 -5.03363 0.186727 -3.93882 -0.0789465 -0.0564664 0.0612495 0.993392 1 1.92593e-19 1.92593e-19 2.77026e-08 1.94509e-09 -1.2727e-09 1 1.92593e-19 2.77026e-08 1.94509e-09 -1.2727e-09 1 2.77026e-08 1.94509e-09 -1.2727e-09 4012.6 18.738 -390.02 3992.2 -16.4674 4022.53 +EDGE_SE3:QUAT 1771 1822 -5.33163 7.28503 -3.8441 -0.00246466 0.243303 0.050535 0.96863 1 7.73381e-19 7.73381e-19 7.01769e-10 5.39734e-08 -3.92532e-10 1 7.73381e-19 7.01769e-10 5.39734e-08 -3.92532e-10 1 7.01769e-10 5.39734e-08 -3.92532e-10 5137.41 92.2014 2417.33 3769.8 96.5718 5127.22 +EDGE_SE3:QUAT 1772 1821 -5.30548 -7.75091 -3.91655 0.244083 0.0808777 0.096945 0.961501 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3781.25 29.7801 307.827 4001.67 23.329 3981.96 +EDGE_SE3:QUAT 1773 1823 -4.72381 -0.120241 -3.90909 -0.0390899 -0.0902477 0.0221768 0.994905 1 4.81482e-20 4.81482e-20 1.4028e-08 4.17444e-10 -1.24233e-09 1 4.81482e-20 1.4028e-08 4.17444e-10 -1.24233e-09 1 1.4028e-08 4.17444e-10 -1.24233e-09 4122.63 19.7594 -729.086 3969.32 -16.4539 4126.77 +EDGE_SE3:QUAT 1772 1823 -5.62965 7.72412 -4.24071 -0.185447 -0.00178613 0.0468749 0.981534 1 7.71124e-19 7.71124e-19 -5.45748e-08 -7.56779e-10 -5.34945e-10 1 7.71124e-19 -5.45748e-08 -7.56779e-10 -5.34945e-10 1 -5.45748e-08 -7.56779e-10 -5.34945e-10 3864.12 -11.3611 88.2938 3999.08 2.5918 3992.89 +EDGE_SE3:QUAT 1773 1822 -5.02503 -7.70186 -3.82609 0.126622 -0.13833 -0.131218 0.973454 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4118.19 -102.583 -879.823 3977.24 103.199 4113.45 +EDGE_SE3:QUAT 1774 1824 -4.72336 -0.067561 -3.87954 0.051726 -0.00273297 -0.129585 0.990214 1 7.70372e-19 7.70372e-19 -5.91127e-10 -2.81405e-09 -5.49727e-08 1 7.70372e-19 -5.91127e-10 -2.81405e-09 -5.49727e-08 1 -5.91127e-10 -2.81405e-09 -5.49727e-08 3989.97 2.1266 58.1714 3999.55 -5.48961 3933.51 +EDGE_SE3:QUAT 1773 1824 -5.26865 8.04011 -4.02316 -0.0533886 -0.154485 -0.0699662 0.984067 1 9.62965e-19 9.62965e-19 -3.18852e-08 -5.30365e-08 2.82881e-09 1 9.62965e-19 -3.18852e-08 -5.30365e-08 2.82881e-09 1 -3.18852e-08 -5.30365e-08 2.82881e-09 4423.64 -0.195808 -1389.06 3899.39 25.7128 4415.46 +EDGE_SE3:QUAT 1774 1823 -5.17903 -7.3073 -4.31984 0.0942442 -0.162384 -0.0825604 0.978741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4328 -122.808 -1260.83 3933.3 120.891 4336.27 +EDGE_SE3:QUAT 1775 1825 -4.68575 -0.0222514 -4.25256 0.0170487 -0.0446976 -0.0616937 0.996948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.36 -5.75825 -344.936 3993.01 11.4752 4014.29 +EDGE_SE3:QUAT 1774 1825 -5.39969 7.86951 -3.81725 -0.00433199 -0.0533935 0.043491 0.997617 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.17 3.93289 -427.835 3988.94 -9.85221 4037.68 +EDGE_SE3:QUAT 1775 1824 -5.25804 -7.74578 -3.89149 -0.0364803 -0.0326094 -0.0937618 0.994392 1 4.81482e-20 4.81482e-20 -1.38386e-08 1.27145e-09 5.396e-10 1 4.81482e-20 -1.38386e-08 1.27145e-09 5.396e-10 1 -1.38386e-08 1.27145e-09 5.396e-10 4016.91 2.77383 -299.276 3994.17 13.6359 3987.07 +EDGE_SE3:QUAT 1776 1826 -4.75543 -0.0322658 -4.30517 0.00346249 0.130807 -0.0986121 0.986485 1 7.73381e-19 7.73381e-19 -2.07329e-09 -5.511e-08 -8.04652e-10 1 7.73381e-19 -2.07329e-09 -5.511e-08 -8.04652e-10 1 -2.07329e-09 -5.511e-08 -8.04652e-10 4281.88 -41.25 1098.75 3936.68 -62.3418 4243.03 +EDGE_SE3:QUAT 1775 1826 -5.35137 7.77644 -4.23101 0.0463304 -0.0822046 -0.0207779 0.995321 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4096.91 -19.5673 -658.15 3974.89 14.7726 4103.77 +EDGE_SE3:QUAT 1776 1825 -5.0901 -7.73758 -3.93502 -0.0401016 -0.0309151 0.0134679 0.998626 1 4.81482e-20 4.81482e-20 -1.38838e-08 -2.21481e-10 4.13228e-10 1 4.81482e-20 -1.38838e-08 -2.21481e-10 4.13228e-10 1 -1.38838e-08 -2.21481e-10 4.13228e-10 4008.02 5.12665 -240.925 3996.5 -2.50569 4013.73 +EDGE_SE3:QUAT 1777 1827 -4.66065 0.283965 -4.04653 0.0658669 0.0151952 -0.190075 0.97944 1 7.70372e-19 7.70372e-19 -2.14266e-09 -3.08736e-09 -5.44873e-08 1 7.70372e-19 -2.14266e-09 -3.08736e-09 -5.44873e-08 1 -2.14266e-09 -3.08736e-09 -5.44873e-08 3999.26 6.38143 261.612 3994.52 -28.2201 3872.1 +EDGE_SE3:QUAT 1776 1827 -5.582 7.46453 -3.95481 -0.115458 -0.0991162 0.134268 0.979192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4027.04 51.6945 -579.103 3989.66 -54.0187 4008.25 +EDGE_SE3:QUAT 1777 1826 -5.15944 -7.66132 -4.07933 0.135059 0.235956 -0.0210574 0.962102 1 1.54375e-18 1.54375e-18 -6.17411e-08 5.10221e-08 -1.86052e-08 1 1.54375e-18 -6.17411e-08 5.10221e-08 -1.86052e-08 1 -6.17411e-08 5.10221e-08 -1.86052e-08 4968.5 213.975 2291.55 3807.72 199.908 5039.69 +EDGE_SE3:QUAT 1778 1828 -4.958 0.200443 -4.04992 0.00208317 -0.144485 0.0523546 0.988119 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4353.84 27.4008 -1241.23 3918.3 -38.5691 4342.89 +EDGE_SE3:QUAT 1777 1828 -5.57166 7.40426 -4.00491 0.0169269 0.132556 0.0823033 0.987608 1 1.20371e-20 1.20371e-20 7.09042e-09 6.44785e-10 9.16911e-10 1 1.20371e-20 7.09042e-09 6.44785e-10 9.16911e-10 1 7.09042e-09 6.44785e-10 9.16911e-10 4278.67 47.1558 1094.43 3937.61 60.3602 4252.72 +EDGE_SE3:QUAT 1778 1827 -5.41337 -8.01091 -3.94233 -0.16901 0.0217535 0.133689 0.976263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3930.04 -37.1676 429.908 3984.79 26.038 3972.8 +EDGE_SE3:QUAT 1779 1829 -4.77432 -0.158088 -3.85284 -0.133088 0.0521703 -0.122681 0.982097 1 8.1852e-19 8.1852e-19 -5.27453e-08 2.09739e-08 1.05592e-09 1 8.1852e-19 -5.27453e-08 2.09739e-08 1.05592e-09 1 -5.27453e-08 2.09739e-08 1.05592e-09 3938.2 -11.925 204.76 3999.66 -11.4703 3948.85 +EDGE_SE3:QUAT 1778 1829 -5.35208 7.46014 -3.9439 0.0202704 -0.00928861 -0.139266 0.990004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.69 -0.383475 -38.681 3999.97 1.873 3922.76 +EDGE_SE3:QUAT 1779 1828 -5.2892 -7.54753 -3.8862 -0.0149077 0.012247 -0.0238629 0.999529 1 1.20371e-20 1.20371e-20 -7.99311e-11 1.0744e-10 -6.93753e-09 1 1.20371e-20 -7.99311e-11 1.0744e-10 -6.93753e-09 1 -7.99311e-11 1.0744e-10 -6.93753e-09 4001.3 -0.768203 93.636 3999.47 -1.15149 3999.91 +EDGE_SE3:QUAT 1780 1830 -4.96593 0.103096 -4.16833 0.116584 -0.0469962 0.144022 0.981559 1 1.92593e-19 1.92593e-19 -3.61899e-09 2.72966e-08 -2.75472e-09 1 1.92593e-19 -3.61899e-09 2.72966e-08 -2.75472e-09 1 -3.61899e-09 2.72966e-08 -2.75472e-09 4023.23 -22.8625 -564.891 3977.93 -34.5958 3994.63 +EDGE_SE3:QUAT 1779 1830 -5.28168 7.6323 -3.90757 -0.0831737 0.091553 0.0621933 0.99037 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4130.36 -23.0641 810.73 3961.03 8.61731 4142.56 +EDGE_SE3:QUAT 1780 1829 -5.15409 -7.7748 -3.78639 -0.257561 0.108283 -0.0170535 0.960024 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3868.99 -104.833 748.963 3983.9 -66.6799 4133.18 +EDGE_SE3:QUAT 1781 1831 -5.03528 0.194178 -4.07603 -0.158891 -0.0299739 -0.0631273 0.98482 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3929.18 28.6152 -350.1 3991.42 5.98274 4014.23 +EDGE_SE3:QUAT 1780 1831 -5.59993 7.62438 -4.23156 -0.250829 -0.0252984 -0.00145505 0.9677 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3757.14 23.0769 -188.137 3998.54 -3.41411 4008.79 +EDGE_SE3:QUAT 1781 1830 -5.20412 -7.76461 -3.69034 -0.0763734 0.0624969 -0.152691 0.983334 1 1.92593e-19 1.92593e-19 2.73919e-08 -4.49371e-09 9.93258e-10 1 1.92593e-19 2.73919e-08 -4.49371e-09 9.93258e-10 1 2.73919e-08 -4.49371e-09 9.93258e-10 4004.81 -19.579 341.844 3996.31 -26.7967 3934.88 +EDGE_SE3:QUAT 1782 1832 -4.69129 0.236076 -3.96873 -0.0342859 0.144791 0.0181383 0.988702 1 5.11575e-20 5.11575e-20 1.48556e-08 1.53061e-11 5.69265e-09 1 5.11575e-20 1.48556e-08 1.53061e-11 5.69265e-09 1 1.48556e-08 1.53061e-11 5.69265e-09 4356.52 -16.1972 1255.14 3915.48 -5.33082 4359.91 +EDGE_SE3:QUAT 1781 1832 -5.13714 7.50445 -4.12408 0.122675 0.137858 -0.0975034 0.977977 1 9.62965e-19 9.62965e-19 -2.49043e-08 5.63085e-08 -9.99452e-09 1 9.62965e-19 -2.49043e-08 5.63085e-08 -9.99452e-09 1 -2.49043e-08 5.63085e-08 -9.99452e-09 4333.3 43.438 1315.1 3907.72 -7.55908 4355.47 +EDGE_SE3:QUAT 1782 1831 -5.11723 -7.79101 -4.09071 0.0307962 0.0765444 -0.159703 0.983711 1 1.92593e-19 1.92593e-19 4.35188e-09 2.73165e-08 -1.45515e-10 1 1.92593e-19 4.35188e-09 2.73165e-08 -1.45515e-10 1 4.35188e-09 2.73165e-08 -1.45515e-10 4102.96 -14.5343 662.142 3975.48 -52.4608 4004.74 +EDGE_SE3:QUAT 1783 1833 -5.06816 -0.0945828 -4.03728 0.0742902 -0.0396729 0.0146343 0.99634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.91 -11.9969 -329.642 3993.29 0.503424 4026.13 +EDGE_SE3:QUAT 1782 1833 -5.54412 7.39998 -4.17214 -0.017668 0.108461 -0.0196615 0.993749 1 1.92593e-19 1.92593e-19 6.66657e-10 2.75794e-08 6.22177e-10 1 1.92593e-19 6.66657e-10 2.75794e-08 6.22177e-10 1 6.66657e-10 2.75794e-08 6.22177e-10 4191.4 -14.7342 898.73 3953.91 -15.1488 4191.1 +EDGE_SE3:QUAT 1783 1832 -5.27237 -7.56501 -3.86902 -0.00614423 0.092037 -0.0175527 0.995582 1 3.00927e-21 3.00927e-21 -3.51339e-09 6.70465e-11 -3.23791e-10 1 3.00927e-21 -3.51339e-09 6.70465e-11 -3.23791e-10 1 -3.51339e-09 6.70465e-11 -3.23791e-10 4138.24 -6.23693 756.789 3966.39 -8.52804 4137.16 +EDGE_SE3:QUAT 1784 1834 -4.56076 0.250488 -3.92969 -0.117889 -0.00868903 0.100018 0.987939 1 1.92593e-19 1.92593e-19 -2.74235e-08 -2.75518e-09 -4.17049e-10 1 1.92593e-19 -2.74235e-08 -2.75518e-09 -4.17049e-10 1 -2.74235e-08 -2.75518e-09 -4.17049e-10 3945.17 -7.03109 72.2135 3999.1 5.94713 3960.75 +EDGE_SE3:QUAT 1783 1834 -5.65263 7.33833 -3.95668 0.0601139 0.160253 0.136719 0.975712 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4326.18 122.841 1217.88 3941.57 135.111 4265.87 +EDGE_SE3:QUAT 1784 1833 -5.13642 -7.55944 -3.78156 -9.72265e-05 0.0114435 0.112079 0.993633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.02 0.340797 89.9975 3999.53 5.01991 3951.78 +EDGE_SE3:QUAT 1785 1835 -4.71177 0.210395 -3.81445 0.0683508 0.00886623 0.206948 0.975921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.99 -5.08096 -98.4633 3998.49 -16.1273 3830.37 +EDGE_SE3:QUAT 1784 1835 -5.55377 7.33639 -3.9885 -0.0597236 -0.26667 -0.0227847 0.961666 1 6.77085e-21 6.77085e-21 -1.62462e-09 -3.40089e-10 5.84235e-09 1 6.77085e-21 -1.62462e-09 -3.40089e-10 5.84235e-09 1 -1.62462e-09 -3.40089e-10 5.84235e-09 5431.35 94.6273 -2805.75 3718.49 -91.6412 5443.54 +EDGE_SE3:QUAT 1785 1834 -5.38516 -7.34286 -3.94227 -0.00471435 -0.0803876 -0.0893541 0.992739 1 1.92593e-19 1.92593e-19 2.49136e-09 2.7553e-08 -2.70586e-10 1 1.92593e-19 2.49136e-09 2.7553e-08 -2.70586e-10 1 2.49136e-09 2.7553e-08 -2.70586e-10 4104.46 -12.6177 -655.076 3975.3 30.4808 4072.61 +EDGE_SE3:QUAT 1786 1836 -4.82474 -0.291395 -4.451 -0.0546642 -0.0887296 -0.141564 0.984428 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4144.1 -7.99898 -805.469 3962.55 51.441 4075.89 +EDGE_SE3:QUAT 1785 1836 -5.14421 7.7172 -4.27657 -0.0504852 -0.0840746 0.0342459 0.99459 1 2.40741e-19 2.40741e-19 1.27906e-08 2.82021e-08 4.5422e-10 1 2.40741e-19 1.27906e-08 2.82021e-08 4.5422e-10 1 1.27906e-08 2.82021e-08 4.5422e-10 4096.76 23.3983 -662.842 3975.03 -20.3865 4102.26 +EDGE_SE3:QUAT 1786 1835 -5.29927 -7.23502 -3.90594 0.0580178 -0.0361308 0.0569538 0.996035 1 4.81482e-20 4.81482e-20 -1.3869e-08 -7.31638e-10 5.88462e-10 1 4.81482e-20 -1.3869e-08 -7.31638e-10 5.88462e-10 1 -1.3869e-08 -7.31638e-10 5.88462e-10 4013.18 -7.83642 -327.72 3992.99 -7.61205 4013.67 +EDGE_SE3:QUAT 1787 1837 -4.66245 -0.0642586 -4.09324 0.119404 -0.0184101 -0.051777 0.991324 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3944.03 -2.79178 -70.1748 3999.92 1.48641 3990.33 +EDGE_SE3:QUAT 1786 1837 -5.6569 7.87402 -4.20413 -0.0537126 0.142184 0.17712 0.972382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4371.9 61.9722 1296.45 3918.51 111.898 4257.95 +EDGE_SE3:QUAT 1787 1836 -5.24542 -7.26569 -4.05448 -0.0347031 -0.100829 0.00394814 0.99429 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4161.58 16.9877 -832.64 3960.01 -10.6659 4166.34 +EDGE_SE3:QUAT 1788 1838 -4.96137 0.0944375 -4.0634 0.0896923 -0.00909006 0.10207 0.990684 1 1.92593e-19 1.92593e-19 -7.47394e-10 2.38972e-09 2.75241e-08 1 1.92593e-19 -7.47394e-10 2.38972e-09 2.75241e-08 1 -7.47394e-10 2.38972e-09 2.75241e-08 3975.58 -8.75601 -179.595 3997.19 -10.2067 3966.09 +EDGE_SE3:QUAT 1787 1838 -5.31079 7.48251 -3.898 -0.161785 -0.118132 0.152152 0.967843 1 7.70372e-19 7.70372e-19 -5.42976e-08 -1.03922e-08 3.18521e-09 1 7.70372e-19 -5.42976e-08 -1.03922e-08 3.18521e-09 1 -5.42976e-08 -1.03922e-08 3.18521e-09 3975.87 68.4255 -590.597 3996.68 -67.5798 3987.96 +EDGE_SE3:QUAT 1788 1837 -5.52724 -7.16257 -3.83795 0.0971096 0.157292 -0.0682303 0.980395 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4432.83 41.4142 1450.44 3892.14 6.88539 4451.93 +EDGE_SE3:QUAT 1789 1839 -4.66037 -0.25341 -3.6907 0.0464342 -0.126468 -0.000688077 0.990883 1 7.52316e-22 7.52316e-22 2.25468e-10 -8.62656e-11 -1.7754e-09 1 7.52316e-22 2.25468e-10 -8.62656e-11 -1.7754e-09 1 2.25468e-10 -8.62656e-11 -1.7754e-09 4258.02 -29.233 -1066.62 3937.33 19.6171 4266.64 +EDGE_SE3:QUAT 1788 1839 -5.59995 7.42803 -4.27964 -0.0263132 -0.0529396 0.0674329 0.995971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.27 9.52675 -402.29 3990.73 -15.2987 4021.85 +EDGE_SE3:QUAT 1789 1838 -5.12174 -7.02308 -3.99275 0.217753 -0.126058 -0.0572245 0.966136 1 9.62965e-19 9.62965e-19 -5.17353e-08 3.28085e-08 -1.58297e-09 1 9.62965e-19 -5.17353e-08 3.28085e-08 -1.58297e-09 1 -5.17353e-08 3.28085e-08 -1.58297e-09 3964.6 -107.301 -806.946 3983.01 84.9899 4141.17 +EDGE_SE3:QUAT 1790 1840 -4.59523 -0.122028 -3.8893 0.243015 0.169249 -0.128694 0.946434 1 7.70372e-19 7.70372e-19 5.73487e-08 -2.31836e-09 1.25645e-08 1 7.70372e-19 5.73487e-08 -2.31836e-09 1.25645e-08 1 5.73487e-08 -2.31836e-09 1.25645e-08 4480.08 180.234 1838.31 3856.38 99.7434 4650.06 +EDGE_SE3:QUAT 1789 1840 -5.41531 7.22354 -4.25426 0.0795931 -0.0421527 0.000956917 0.995935 1 1.92781e-19 1.92781e-19 2.77043e-08 -9.09405e-11 -2.96537e-10 1 1.92781e-19 2.77043e-08 -9.09405e-11 -2.96537e-10 1 2.77043e-08 -9.09405e-11 -2.96537e-10 4002.85 -13.5902 -336.994 3993.2 3.23408 4028.19 +EDGE_SE3:QUAT 1790 1839 -5.0179 -7.45223 -3.87573 0.0724934 -0.0128585 -0.0627844 0.995308 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.45 -1.1162 -47.1585 3999.96 0.99059 3984.7 +EDGE_SE3:QUAT 1791 1841 -4.93765 0.0858919 -4.06133 0.121695 0.246752 -0.022325 0.961148 1 3.0845e-18 3.0845e-18 -3.59676e-09 1.0714e-07 -1.02454e-08 1 3.0845e-18 -3.59676e-09 1.0714e-07 -1.02454e-08 1 -3.59676e-09 1.0714e-07 -1.02454e-08 5110.81 207.798 2459.61 3782.37 197.486 5168.06 +EDGE_SE3:QUAT 1790 1841 -5.59831 7.64651 -4.11251 -0.0252398 0.0014707 -0.0358581 0.999037 1 4.81482e-20 4.81482e-20 -4.76452e-12 -3.50834e-10 1.38644e-08 1 4.81482e-20 -4.76452e-12 -3.50834e-10 1.38644e-08 1 -4.76452e-12 -3.50834e-10 1.38644e-08 3997.45 0.0345343 0.884982 4000 0.0491537 3994.85 +EDGE_SE3:QUAT 1791 1840 -5.54971 -7.68101 -3.79282 0.00674998 0.156009 -0.165322 0.973799 1 1.54074e-18 1.54074e-18 -8.1914e-10 -5.66833e-08 5.41627e-08 1 1.54074e-18 -8.1914e-10 -5.66833e-08 5.41627e-08 1 -8.1914e-10 -5.66833e-08 5.41627e-08 4391.94 -99.3021 1312.73 3923.98 -131.452 4282.8 +EDGE_SE3:QUAT 1792 1842 -4.86433 -0.0840374 -4.13515 0.124857 0.107561 -0.145458 0.975543 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4218.51 23.6122 1097.38 3930.92 -45.7364 4196.23 +EDGE_SE3:QUAT 1791 1842 -5.50522 7.39239 -3.92703 0.123207 -0.0475967 0.143764 0.980758 1 9.62965e-19 9.62965e-19 -5.85949e-08 2.00591e-08 1.51292e-09 1 9.62965e-19 -5.85949e-08 2.00591e-08 1.51292e-09 1 -5.85949e-08 2.00591e-08 1.51292e-09 4021.01 -25.5323 -580.137 3976.67 -34.6383 3999.06 +EDGE_SE3:QUAT 1792 1841 -5.05933 -7.10831 -3.97761 -0.135856 0.0284249 -0.219357 0.965721 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3927.37 17.7601 -136.767 3995.66 28.8298 3808.73 +EDGE_SE3:QUAT 1793 1843 -4.86343 -0.165957 -3.60315 0.130816 -0.0936078 0.150364 0.975456 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4162.05 -27.7445 -988.746 3941.73 -45.7082 4140.07 +EDGE_SE3:QUAT 1792 1843 -5.47681 7.36616 -4.28274 -0.000117503 0.0467381 0.172933 0.983824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.1 8.64655 359.956 3993.31 31.3331 3912.48 +EDGE_SE3:QUAT 1793 1842 -5.46911 -7.8058 -3.94388 -0.0171652 0.0739612 0.0321188 0.996596 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4089.5 -1.15027 609.053 3977.66 8.03151 4086.55 +EDGE_SE3:QUAT 1794 1844 -4.52274 -0.144401 -3.7371 0.0121636 -0.0640046 0.113847 0.99136 1 1.92593e-19 1.92593e-19 1.8222e-09 7.33753e-11 -2.77521e-08 1 1.92593e-19 1.8222e-09 7.33753e-11 -2.77521e-08 1 1.8222e-09 7.33753e-11 -2.77521e-08 4067.51 8.37365 -526.334 3983.93 -30.1647 4016.25 +EDGE_SE3:QUAT 1793 1844 -5.29815 7.70004 -3.98749 -0.0156093 -0.00273571 -0.0195378 0.999684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.19 0.204219 -25.5243 3999.96 0.257643 3998.64 +EDGE_SE3:QUAT 1794 1843 -5.33559 -7.33217 -4.13449 0.0508829 -0.104941 0.193703 0.974103 1 2.0463e-19 2.0463e-19 -1.21368e-08 2.5741e-08 6.16066e-10 1 2.0463e-19 -1.21368e-08 2.5741e-08 6.16066e-10 1 -1.21368e-08 2.5741e-08 6.16066e-10 4203.97 34.859 -950.413 3953.24 -90.1013 4064.25 +EDGE_SE3:QUAT 1795 1845 -4.81348 0.301504 -4.1865 -0.094692 0.0819707 0.0429435 0.991196 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4087.47 -29.0783 713.211 3969.73 -0.640857 4115.96 +EDGE_SE3:QUAT 1794 1845 -5.41053 7.14845 -4.16151 -0.0438026 -0.0121651 -0.049483 0.99774 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.07 2.62405 -122.731 3998.94 3.02662 3993.95 +EDGE_SE3:QUAT 1795 1844 -5.18145 -7.65886 -3.69598 -0.135543 0.0348986 -0.0841229 0.986577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3930.35 -6.66063 133.899 3999.79 -4.99569 3975.53 +EDGE_SE3:QUAT 1796 1846 -5.00676 0.207872 -3.49605 -0.145943 -0.152443 0.0216733 0.977237 1 1.58889e-18 1.58889e-18 -5.48752e-08 -6.03392e-08 1.3353e-08 1 1.58889e-18 -5.48752e-08 -6.03392e-08 1.3353e-08 1 -5.48752e-08 -6.03392e-08 1.3353e-08 4259.33 120.772 -1224.19 3934.3 -98.3901 4342.65 +EDGE_SE3:QUAT 1795 1846 -5.60081 7.5657 -4.21496 -0.143282 -0.115947 -0.0231963 0.982593 1 7.52316e-22 7.52316e-22 -2.10139e-10 -2.53033e-10 1.75381e-09 1 7.52316e-22 -2.10139e-10 -2.53033e-10 1.75381e-09 1 -2.10139e-10 -2.53033e-10 1.75381e-09 4147.64 73.1259 -985.823 3949.24 -37.7727 4227.6 +EDGE_SE3:QUAT 1796 1845 -5.37 -7.45689 -3.29587 0.0663867 -0.0694876 -0.151351 0.983797 1 7.70372e-19 7.70372e-19 -2.54656e-09 4.7294e-09 5.49087e-08 1 7.70372e-19 -2.54656e-09 4.7294e-09 5.49087e-08 1 -2.54656e-09 4.7294e-09 5.49087e-08 4024.71 -24.3138 -417.232 3993.51 34.1812 3950.71 +EDGE_SE3:QUAT 1797 1847 -4.9622 0.0514188 -4.2261 0.0398085 0.0265672 -0.0575535 0.997195 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.9 3.79765 239.184 3996.24 -6.37737 4000.99 +EDGE_SE3:QUAT 1796 1847 -5.5531 7.23592 -3.90611 -0.289695 -0.0424661 0.31678 0.902177 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3774.55 -133.342 735.298 3928.79 151.662 3708.85 +EDGE_SE3:QUAT 1797 1846 -5.06683 -7.22357 -4.35947 0.0538963 -0.0104963 -0.00136293 0.99849 1 4.81953e-20 4.81953e-20 -1.38643e-08 5.78937e-11 5.75932e-10 1 4.81953e-20 -1.38643e-08 5.78937e-11 5.75932e-10 1 -1.38643e-08 5.78937e-11 5.75932e-10 3990.09 -2.22497 -82.7558 3999.58 0.195689 4001.7 +EDGE_SE3:QUAT 1798 1848 -5.11301 -0.00969529 -4.11277 0.123477 -0.0628142 0.108796 0.984363 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4043.93 -29.9398 -657.462 3972.04 -22.3394 4057.57 +EDGE_SE3:QUAT 1797 1848 -5.91734 7.47687 -3.76493 -0.0047788 0.0752442 -0.153226 0.985311 1 2.0463e-19 2.0463e-19 -2.59009e-09 2.84291e-08 2.73053e-10 1 2.0463e-19 -2.59009e-09 2.84291e-08 2.73053e-10 1 -2.59009e-09 2.84291e-08 2.73053e-10 4082.87 -21.4156 582.271 3982.5 -47.0348 3989.05 +EDGE_SE3:QUAT 1798 1847 -5.21494 -7.79146 -3.69484 0.0274482 -0.0819212 0.0848501 0.992641 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4113.67 4.58825 -693.076 3971.65 -27.0531 4087.88 +EDGE_SE3:QUAT 1799 1849 -4.95531 0.111933 -3.64088 0.102202 0.118634 0.0171143 0.987516 1 3.97223e-19 3.97223e-19 2.77886e-08 2.93599e-08 7.21324e-09 1 3.97223e-19 2.77886e-08 2.93599e-08 7.21324e-09 1 2.77886e-08 2.93599e-08 7.21324e-09 4174.4 61.0668 954.868 3952.61 44.0838 4215.01 +EDGE_SE3:QUAT 1798 1849 -5.89436 7.1418 -4.04571 0.018837 -0.0579742 -0.170192 0.983524 1 6.01853e-20 6.01853e-20 4.45676e-09 -1.48508e-08 1.8251e-10 1 6.01853e-20 4.45676e-09 -1.48508e-08 1.8251e-10 1 4.45676e-09 -1.48508e-08 1.8251e-10 4039.82 -15.2654 -409.048 3992.2 35.4821 3925.38 +EDGE_SE3:QUAT 1799 1848 -5.09159 -7.26903 -3.55639 0.0343221 0.00819144 -0.0810736 0.996083 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.66 1.6198 98.0501 3999.27 -4.31376 3976.08 +EDGE_SE3:QUAT 1800 1850 -4.96735 0.235861 -3.7193 0.0634967 0.0197824 -0.0631732 0.995784 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.27 6.12934 204.768 3997.05 -6.08893 3994.44 +EDGE_SE3:QUAT 1799 1850 -5.7466 7.20742 -3.75451 -0.140618 -0.0564665 -0.127687 0.980171 1 9.62965e-19 9.62965e-19 -5.81402e-08 -2.11958e-08 1.5283e-09 1 9.62965e-19 -5.81402e-08 -2.11958e-08 1.5283e-09 1 -5.81402e-08 -2.11958e-08 1.5283e-09 4024.75 35.0781 -654.993 3971.26 28.3814 4038.63 +EDGE_SE3:QUAT 1800 1849 -5.48539 -7.45344 -3.79227 -0.0335746 -0.0538435 -0.103202 0.992634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.02 0.0851802 -470.293 3986.38 22.986 4011.93 +EDGE_SE3:QUAT 1801 1851 -5.05598 0.198676 -3.99488 0.0486703 0.0363935 -0.00572646 0.998135 1 4.81482e-20 4.81482e-20 3.01036e-11 1.38521e-08 -6.7142e-10 1 4.81482e-20 3.01036e-11 1.38521e-08 -6.7142e-10 1 3.01036e-11 1.38521e-08 -6.7142e-10 4012.14 7.10896 294.837 3994.64 0.720021 4021.48 +EDGE_SE3:QUAT 1800 1851 -5.54771 7.57622 -3.88107 -0.113818 -0.107098 0.0207919 0.987493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4117.41 58.0544 -840.251 3963.57 -40.0732 4167.5 +EDGE_SE3:QUAT 1801 1850 -5.21485 -7.61087 -3.71378 -0.00573095 -0.104067 -0.033562 0.993987 1 4.81482e-20 4.81482e-20 1.47841e-09 -1.77688e-11 -1.41008e-08 1 4.81482e-20 1.47841e-09 -1.77688e-11 -1.41008e-08 1 1.47841e-09 -1.77688e-11 -1.41008e-08 4179.35 -6.45187 -866.105 3956.75 14.6382 4174.98 +EDGE_SE3:QUAT 1802 1852 -5.28745 0.224324 -3.77641 0.227934 -0.0120737 0.00167221 0.9736 1 7.73428e-19 7.73428e-19 5.40529e-08 -3.69114e-09 -2.7342e-10 1 7.73428e-19 5.40529e-08 -3.69114e-09 -2.7342e-10 1 5.40529e-08 -3.69114e-09 -2.7342e-10 3794.37 -10.5571 -93.6213 3999.59 0.702007 4002.18 +EDGE_SE3:QUAT 1801 1852 -5.6174 7.34281 -4.02264 0.0423398 0.119434 0.143855 0.981452 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4178.28 64.4681 882.312 3965.35 82.4768 4102.67 +EDGE_SE3:QUAT 1802 1851 -5.4268 -7.36697 -4.03033 0.0644519 -0.136906 -0.0432215 0.98754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4273.87 -62.3653 -1116.56 3936.24 58.1842 4283.01 +EDGE_SE3:QUAT 1803 1853 -5.12525 -0.220933 -4.00386 -0.0254746 0.144839 -0.0207124 0.98891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4349.76 -30.6861 1238.38 3918.46 -29.7145 4350.64 +EDGE_SE3:QUAT 1802 1853 -5.69063 6.83489 -4.0229 0.211013 -0.0972344 -0.00323591 0.97263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3953.46 -83.8754 -738.221 3976.82 46.3388 4131.52 +EDGE_SE3:QUAT 1803 1852 -5.14357 -7.35204 -3.46976 -0.0690592 -0.00372295 -0.0377546 0.996891 1 1.92593e-19 1.92593e-19 2.76724e-08 -1.02384e-09 -2.46373e-10 1 1.92593e-19 2.76724e-08 -1.02384e-09 -2.46373e-10 1 2.76724e-08 -1.02384e-09 -2.46373e-10 3981.82 2.41198 -60.6801 3999.69 1.26606 3995.19 +EDGE_SE3:QUAT 1804 1854 -5.08866 0.281801 -3.8266 -0.223303 -0.162542 0.0183455 0.960926 1 4.81482e-20 4.81482e-20 1.98441e-09 3.50028e-09 -1.39392e-08 1 4.81482e-20 1.98441e-09 3.50028e-09 -1.39392e-08 1 1.98441e-09 3.50028e-09 -1.39392e-08 4150.06 179.606 -1236.04 3952.67 -148.143 4348.17 +EDGE_SE3:QUAT 1803 1854 -5.77446 7.08124 -4.35126 -0.00112771 0.0443718 0.200195 0.97875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.4 8.76812 338.529 3994.45 33.8823 3868.09 +EDGE_SE3:QUAT 1804 1853 -5.18546 -7.13854 -3.94598 -0.0632694 -0.0350075 -0.0153027 0.997265 1 1.92593e-19 1.92593e-19 2.77528e-08 -3.00265e-10 -1.01989e-09 1 1.92593e-19 2.77528e-08 -3.00265e-10 -1.01989e-09 1 2.77528e-08 -3.00265e-10 -1.01989e-09 4005.08 8.9625 -291.243 3994.71 0.302973 4020.16 +EDGE_SE3:QUAT 1805 1855 -4.86462 -0.037062 -4.29722 -0.0678194 0.145782 -0.084422 0.983372 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4285.33 -87.7624 1144.04 3939.19 -90.7733 4275.22 +EDGE_SE3:QUAT 1804 1855 -5.45665 7.37544 -3.61535 -0.0671645 -0.0905129 -0.0069627 0.993603 1 1.92605e-19 1.92605e-19 -2.80205e-08 -1.33883e-10 2.3385e-09 1 1.92605e-19 -2.80205e-08 -1.33883e-10 2.3385e-09 1 -2.80205e-08 -1.33883e-10 2.3385e-09 4116.61 25.8202 -746.146 3967.76 -10.9746 4134.46 +EDGE_SE3:QUAT 1805 1854 -5.56144 -7.57158 -3.78886 -0.0488032 -0.0886612 -0.0552552 0.99333 1 4.81482e-20 4.81482e-20 -1.4024e-08 6.65813e-10 1.3154e-09 1 4.81482e-20 -1.4024e-08 6.65813e-10 1.3154e-09 1 -1.4024e-08 6.65813e-10 1.3154e-09 4129.58 8.81028 -758.824 3965.76 12.8491 4126.89 +EDGE_SE3:QUAT 1806 1856 -4.93654 0.228782 -3.89111 0.164575 -0.0381733 0.0337437 0.985048 1 1.20371e-20 1.20371e-20 -3.27513e-10 1.13018e-09 6.86341e-09 1 1.20371e-20 -3.27513e-10 1.13018e-09 6.86341e-09 1 -3.27513e-10 1.13018e-09 6.86341e-09 3923.9 -30.1705 -360.759 3991.96 1.08412 4027.68 +EDGE_SE3:QUAT 1805 1856 -5.7526 7.35176 -3.60855 0.0523494 0.0617976 0.0224437 0.996462 1 1.20371e-20 1.20371e-20 4.12523e-10 3.8772e-10 6.96418e-09 1 1.20371e-20 4.12523e-10 3.8772e-10 6.96418e-09 1 4.12523e-10 3.8772e-10 6.96418e-09 4046.7 14.9981 483.77 3986.3 10.2163 4055.65 +EDGE_SE3:QUAT 1806 1855 -5.19833 -7.42821 -3.79294 -0.0827305 -0.145309 -0.00866672 0.985883 1 7.7056e-19 7.7056e-19 7.4744e-10 -5.47985e-08 -3.75806e-09 1 7.7056e-19 7.4744e-10 -5.47985e-08 -3.75806e-09 1 7.4744e-10 -5.47985e-08 -3.75806e-09 4330.94 58.5216 -1249.67 3918.87 -39.8576 4358.01 +EDGE_SE3:QUAT 1807 1857 -5.12076 -0.148921 -3.49547 -0.0573657 -0.0180954 -0.0410597 0.997344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.21 4.79374 -172.163 3997.98 3.14125 4000.63 +EDGE_SE3:QUAT 1806 1857 -5.54962 7.02879 -3.58805 0.0427863 -0.106035 -0.135287 0.984187 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4137.38 -49.7597 -775.538 3972.07 66.0151 4071.49 +EDGE_SE3:QUAT 1807 1856 -5.23163 -7.26233 -4.11873 -0.0920897 0.158182 0.163299 0.969449 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4494.6 38.1801 1547.24 3883.09 93.6846 4421.86 +EDGE_SE3:QUAT 1808 1858 -5.07957 0.109353 -3.74684 -0.111644 0.0636157 0.182309 0.974809 1 3.85186e-19 3.85186e-19 -2.28995e-08 -3.18128e-08 -5.06304e-09 1 3.85186e-19 -2.28995e-08 -3.18128e-08 -5.06304e-09 1 -2.28995e-08 -3.18128e-08 -5.06304e-09 4080.35 -15.3167 735.387 3965.19 58.1495 3997.26 +EDGE_SE3:QUAT 1807 1858 -5.45409 7.63143 -3.99116 0.0566808 0.0789417 0.053986 0.993801 1 4.81482e-20 4.81482e-20 1.39436e-08 8.88004e-10 1.00695e-09 1 4.81482e-20 1.39436e-08 8.88004e-10 1.00695e-09 1 1.39436e-08 8.88004e-10 1.00695e-09 4075.09 25.0977 599.808 3980.19 24.6321 4076.28 +EDGE_SE3:QUAT 1808 1857 -5.19293 -7.04265 -3.73886 -0.211828 0.0105177 -0.0323236 0.976716 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3820.31 3.2391 -1.2447 3999.95 0.478015 3995.62 +EDGE_SE3:QUAT 1809 1859 -5.35198 0.116746 -3.69918 -0.00169136 -0.106111 -0.148638 0.983181 1 1.92593e-19 1.92593e-19 -4.20881e-09 -2.7276e-08 8.34393e-10 1 1.92593e-19 -4.20881e-09 -2.7276e-08 8.34393e-10 1 -4.20881e-09 -2.7276e-08 8.34393e-10 4175 -40.0675 -854.996 3962.94 69.9641 4086.64 +EDGE_SE3:QUAT 1808 1859 -5.94035 7.28771 -4.14903 0.0271416 -0.0451038 -0.0990174 0.993692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.2 -8.4506 -324.775 3994.32 16.8895 3986.93 +EDGE_SE3:QUAT 1809 1858 -5.49876 -6.81798 -3.97933 -0.0592925 0.035105 0.0141256 0.997523 1 5.11575e-20 5.11575e-20 -1.40069e-08 6.55093e-11 -3.97812e-09 1 5.11575e-20 -1.40069e-08 6.55093e-11 -3.97812e-09 1 -1.40069e-08 6.55093e-11 -3.97812e-09 4006.95 -8.37598 290.665 3994.74 0.24847 4020.21 +EDGE_SE3:QUAT 1810 1860 -4.77895 -0.294997 -3.59259 0.0652926 0.11159 0.106308 0.985892 1 1.92593e-19 1.92593e-19 2.79117e-08 3.47176e-09 2.65673e-09 1 1.92593e-19 2.79117e-08 3.47176e-09 2.65673e-09 1 2.79117e-08 3.47176e-09 2.65673e-09 4141.69 56.2541 813.689 3968.98 63.4608 4113.54 +EDGE_SE3:QUAT 1809 1860 -6.06849 7.28497 -3.89737 -0.0312598 0.19219 0.166781 0.966576 1 7.75074e-19 7.75074e-19 -1.60391e-08 -2.89484e-09 -5.89486e-08 1 7.75074e-19 -1.60391e-08 -2.89484e-09 -5.89486e-08 1 -1.60391e-08 -2.89484e-09 -5.89486e-08 4658.3 142.122 1757.25 3873.3 173.461 4550.95 +EDGE_SE3:QUAT 1810 1859 -5.12375 -7.054 -4.05358 -0.0120653 0.0185581 -0.0821862 0.996371 1 3.00927e-21 3.00927e-21 3.45884e-09 -2.86957e-10 5.66673e-11 1 3.00927e-21 3.45884e-09 -2.86957e-10 5.66673e-11 1 3.45884e-09 -2.86957e-10 5.66673e-11 4003.98 -1.38138 135.21 3998.97 -5.47674 3977.54 +EDGE_SE3:QUAT 1811 1861 -4.81557 -0.220366 -3.77725 0.0461263 -0.146394 0.137499 0.978537 1 1.20371e-20 1.20371e-20 -7.12372e-09 -9.4272e-10 1.11553e-09 1 1.20371e-20 -7.12372e-09 -9.4272e-10 1.11553e-09 1 -7.12372e-09 -9.4272e-10 1.11553e-09 4386.53 46.4186 -1317.66 3912.49 -85.3521 4319.42 +EDGE_SE3:QUAT 1810 1861 -5.2938 7.0308 -4.21341 -0.158402 0.014352 0.187812 0.969242 1 1.54074e-18 1.54074e-18 5.02155e-08 1.76753e-08 -5.02155e-08 1 1.54074e-18 5.02155e-08 1.76753e-08 -5.02155e-08 1 5.02155e-08 1.76753e-08 -5.02155e-08 3947.89 -35.3215 453.08 3981.65 45.409 3907.16 +EDGE_SE3:QUAT 1811 1860 -5.81219 -7.57113 -3.6422 -0.0907894 -0.133453 -0.134078 0.977738 1 1.92593e-19 1.92593e-19 2.8392e-08 -3.26853e-09 -4.39645e-09 1 1.92593e-19 2.8392e-08 -3.26853e-09 -4.39645e-09 1 2.8392e-08 -3.26853e-09 -4.39645e-09 4336.86 -2.98694 -1271.5 3913.39 55.5641 4297.92 +EDGE_SE3:QUAT 1812 1862 -4.83017 -0.252446 -3.83453 0.12997 -0.130023 -0.05568 0.981377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4151.44 -90.2265 -962.698 3959.43 77.2181 4206.6 +EDGE_SE3:QUAT 1811 1862 -5.81449 6.92433 -3.9445 -0.0470775 -0.108899 0.101284 0.987758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4154.16 47.6328 -824.431 3966.07 -57.6558 4122 +EDGE_SE3:QUAT 1812 1861 -5.28778 -7.53459 -3.55255 0.0246089 -0.218555 0.0238729 0.975222 1 7.70372e-19 7.70372e-19 8.19967e-10 -5.41457e-08 8.84482e-10 1 7.70372e-19 8.19967e-10 -5.41457e-08 8.84482e-10 1 8.19967e-10 -5.41457e-08 8.84482e-10 4892.82 -4.2216 -2093.43 3807.95 -1.96012 4892.97 +EDGE_SE3:QUAT 1813 1863 -5.48539 0.181432 -3.81498 0.30282 -0.0730821 0.306265 0.899534 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4215.54 -124.136 -1644.83 3843.06 -130.866 4207.14 +EDGE_SE3:QUAT 1812 1863 -5.82743 7.21146 -3.40929 0.072151 0.019631 0.128747 0.988854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.24 0.327717 42.0333 4000.04 0.324203 3933.76 +EDGE_SE3:QUAT 1813 1862 -5.14517 -7.06357 -3.55445 -0.0762898 0.162894 0.031194 0.983195 1 1.20371e-20 1.20371e-20 -1.21593e-09 5.13239e-10 -7.21755e-09 1 1.20371e-20 -1.21593e-09 5.13239e-10 -7.21755e-09 1 -1.21593e-09 5.13239e-10 -7.21755e-09 4450.73 -48.7014 1456.27 3892.49 -27.5085 4470.12 +EDGE_SE3:QUAT 1814 1864 -5.07866 0.189863 -3.4742 0.0346054 0.111924 -0.145901 0.982338 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4218.91 -30.5922 972.031 3949.6 -69.8912 4138.55 +EDGE_SE3:QUAT 1813 1864 -5.96259 7.35751 -3.85797 0.126765 -0.0471207 -0.192286 0.971975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3933.9 1.55186 -64.3545 4000.3 -3.37788 3850.28 +EDGE_SE3:QUAT 1814 1863 -5.43544 -7.00903 -3.72509 -0.0496023 0.0722775 -0.309178 0.946955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.27 -23.182 322.438 4001.64 -39.9916 3640.74 +EDGE_SE3:QUAT 1815 1865 -4.79755 0.0492446 -3.35399 0.183622 -0.172446 0.113155 0.961115 1 1.54074e-18 1.54074e-18 6.05007e-08 -5.07749e-08 -3.53903e-09 1 1.54074e-18 6.05007e-08 -5.07749e-08 -3.53903e-09 1 6.05007e-08 -5.07749e-08 -3.53903e-09 4537.17 -111.956 -1772.19 3855.62 50.3988 4620.82 +EDGE_SE3:QUAT 1814 1865 -5.56859 6.89966 -3.79619 0.0552704 -0.0794054 0.059066 0.993555 1 2.40741e-19 2.40741e-19 -1.53913e-08 2.68766e-08 -8.61354e-11 1 2.40741e-19 -1.53913e-08 2.68766e-08 -8.61354e-11 1 -1.53913e-08 2.68766e-08 -8.61354e-11 4101.94 -10.5519 -685.387 3971.62 -12.6119 4100.2 +EDGE_SE3:QUAT 1815 1864 -5.73685 -6.99501 -3.92891 0.127686 -0.0388253 -0.201542 0.970345 1 7.70372e-19 7.70372e-19 8.69444e-10 7.35934e-09 5.38442e-08 1 7.70372e-19 8.69444e-10 7.35934e-09 5.38442e-08 1 8.69444e-10 7.35934e-09 5.38442e-08 3931.88 7.85287 13.0438 3999.15 -12.5316 3834.62 +EDGE_SE3:QUAT 1816 1866 -5.0147 0.112085 -3.70503 -0.13379 0.0496475 -0.12866 0.981367 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3934.46 -9.12524 174.333 4000.03 -8.96416 3939.85 +EDGE_SE3:QUAT 1815 1866 -5.2624 6.96093 -4.11596 -0.0548964 0.00996523 0.165028 0.98471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.05 -4.39389 183.052 3997.2 17.5078 3899.17 +EDGE_SE3:QUAT 1816 1865 -5.17684 -7.28245 -3.87132 -0.0243729 -0.206057 0.0318823 0.977717 1 4.81482e-20 4.81482e-20 -3.08319e-09 -6.14894e-10 1.48061e-08 1 4.81482e-20 -3.08319e-09 -6.14894e-10 1.48061e-08 1 -3.08319e-09 -6.14894e-10 1.48061e-08 4758.72 73.5214 -1903.61 3837.23 -74.5993 4757.03 +EDGE_SE3:QUAT 1817 1867 -5.31405 0.516733 -4.09883 0.110983 0.230726 -0.117991 0.959441 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5100.85 -0.959674 2433.84 3764.44 -26.5352 5094.43 +EDGE_SE3:QUAT 1816 1867 -5.55705 6.77589 -3.96854 0.102057 0.0813807 0.184615 0.974104 1 9.62965e-19 9.62965e-19 2.51127e-08 -1.4588e-09 -5.32972e-08 1 9.62965e-19 2.51127e-08 -1.4588e-09 -5.32972e-08 1 2.51127e-08 -1.4588e-09 -5.32972e-08 3993.24 30.0538 388.242 3997.9 36.7114 3898.58 +EDGE_SE3:QUAT 1817 1866 -5.63675 -7.67818 -3.40282 0.0833441 -0.164041 0.00482176 0.982915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4433.21 -73.4332 -1434.07 3898.2 56.6082 4460.9 +EDGE_SE3:QUAT 1818 1868 -5.21897 0.144805 -3.6131 -0.0890648 0.150433 0.0284818 0.984188 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4367.7 -56.1626 1325.62 3909.09 -31.9925 4396.19 +EDGE_SE3:QUAT 1817 1868 -5.23366 7.29837 -3.59542 -0.191384 0.186072 -0.0310615 0.963216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4329 -208.621 1461.56 3932.01 -187.078 4471.65 +EDGE_SE3:QUAT 1818 1867 -5.52622 -7.29349 -3.74472 0.0474555 0.0744077 -0.215931 0.972412 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4106.65 -18.7566 690.006 3974.43 -74.5615 3929.15 +EDGE_SE3:QUAT 1819 1869 -4.70893 0.162966 -3.70591 -0.0899237 0.0902747 -0.0205796 0.991635 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4089.45 -37.934 708.678 3972.48 -24.8841 4120.1 +EDGE_SE3:QUAT 1818 1869 -5.37599 7.51661 -3.88259 -0.085418 -0.142709 0.141932 0.975804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4201.06 104.002 -990.564 3964.77 -112.609 4149.66 +EDGE_SE3:QUAT 1819 1868 -5.56848 -7.50575 -3.79332 -0.170026 -0.0309953 -0.0290511 0.984524 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3906.22 26.0051 -296.666 3994.52 -0.686742 4018.47 +EDGE_SE3:QUAT 1820 1870 -5.04027 0.43002 -3.5507 -0.0716345 0.175816 -0.0417625 0.980925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4479.03 -104.31 1499.48 3895.96 -99.1866 4492.58 +EDGE_SE3:QUAT 1819 1870 -5.89301 6.92203 -3.88346 0.113281 0.00720472 0.05287 0.992129 1 1.92593e-19 1.92593e-19 2.75368e-08 1.47473e-09 -1.3615e-10 1 1.92593e-19 2.75368e-08 1.47473e-09 -1.3615e-10 1 2.75368e-08 1.47473e-09 -1.3615e-10 3948.58 -2.22401 -14.8314 3999.9 -1.04012 3988.73 +EDGE_SE3:QUAT 1820 1869 -5.27695 -7.03677 -3.74801 -0.00641865 0.0317885 -0.0439521 0.998507 1 4.81482e-20 4.81482e-20 6.16785e-10 1.38568e-08 1.27707e-10 1 4.81482e-20 6.16785e-10 1.38568e-08 1.27707e-10 1 6.16785e-10 1.38568e-08 1.27707e-10 4015.53 -1.85468 251.023 3996.16 -5.69635 4007.96 +EDGE_SE3:QUAT 1821 1871 -5.26087 0.424342 -3.59907 -0.00516268 -0.091755 -0.0514767 0.994437 1 4.23178e-22 4.23178e-22 1.31604e-09 -6.80226e-11 -1.21485e-10 1 4.23178e-22 1.31604e-09 -6.80226e-11 -1.21485e-10 1 1.31604e-09 -6.80226e-11 -1.21485e-10 4138.19 -8.73168 -756.502 3966.66 20.125 4127.69 +EDGE_SE3:QUAT 1820 1871 -5.75143 6.9363 -3.5824 0.0802699 0.109655 -0.0207381 0.990506 1 1.92593e-19 1.92593e-19 -2.81922e-08 8.85194e-11 -3.17445e-09 1 1.92593e-19 -2.81922e-08 8.85194e-11 -3.17445e-09 1 -2.81922e-08 8.85194e-11 -3.17445e-09 4179.2 35.7702 928.401 3951.46 14.2666 4203.26 +EDGE_SE3:QUAT 1821 1870 -5.49657 -7.11729 -3.77039 -0.106612 0.124752 -0.157281 0.973824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4092.1 -81.0296 761.699 3983.69 -87.6253 4038.62 +EDGE_SE3:QUAT 1822 1872 -4.64835 0.174104 -3.63576 -0.00352335 -0.0177118 0.061362 0.997952 1 4.81482e-20 4.81482e-20 2.38091e-10 7.87279e-11 -1.38577e-08 1 4.81482e-20 2.38091e-10 7.87279e-11 -1.38577e-08 1 2.38091e-10 7.87279e-11 -1.38577e-08 4004.74 0.689116 -138.447 3998.84 -4.2522 3989.72 +EDGE_SE3:QUAT 1821 1872 -5.37971 7.14777 -3.58051 0.0660819 -0.131463 0.130266 0.980501 1 4.81482e-20 4.81482e-20 -1.41777e-08 -1.68287e-09 2.07468e-09 1 4.81482e-20 -1.41777e-08 -1.68287e-09 2.07468e-09 1 -1.41777e-08 -1.68287e-09 2.07468e-09 4318.55 17.9055 -1207.15 3922.14 -62.3972 4268.14 +EDGE_SE3:QUAT 1822 1871 -5.58225 -7.22891 -3.9023 0.034403 0.0410918 -0.0472115 0.997446 1 4.81482e-20 4.81482e-20 -6.16747e-10 -1.38441e-08 4.23141e-10 1 4.81482e-20 -6.16747e-10 -1.38441e-08 4.23141e-10 1 -6.16747e-10 -1.38441e-08 4.23141e-10 4025.46 4.1172 348.882 3992.32 -7.00186 4021.28 +EDGE_SE3:QUAT 1823 1873 -4.66505 0.104999 -3.92666 -0.101526 0.189432 -0.042466 0.975707 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4523 -150.132 1605.34 3891.77 -141.237 4557.02 +EDGE_SE3:QUAT 1822 1873 -5.59694 6.92872 -3.88157 0.0170835 0.0833214 0.0717285 0.993791 1 1.92593e-19 1.92593e-19 2.24761e-09 8.20839e-10 2.795e-08 1 1.92593e-19 2.24761e-09 8.20839e-10 2.795e-08 1 2.24761e-09 8.20839e-10 2.795e-08 4105.27 17.788 661.181 3975.19 27.9679 4085.86 +EDGE_SE3:QUAT 1823 1872 -5.12645 -7.33629 -3.94263 -0.0950352 0.118477 -0.127568 0.980132 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4112.19 -71.978 787.957 3976.41 -76.9381 4083.22 +EDGE_SE3:QUAT 1824 1874 -5.18387 -0.209899 -3.56483 0.076269 0.0106911 0.0200567 0.996828 1 3.00927e-21 3.00927e-21 -7.44285e-11 3.45834e-09 -2.65926e-10 1 3.00927e-21 -7.44285e-11 3.45834e-09 -2.65926e-10 1 -7.44285e-11 3.45834e-09 -2.65926e-10 3977.83 2.33092 66.4623 3999.78 0.746283 3999.48 +EDGE_SE3:QUAT 1823 1874 -5.53234 7.1635 -3.95432 -0.0696398 -0.0603026 0.0176862 0.995591 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4034.91 18.2071 -469.3 3987.25 -10.0774 4053.06 +EDGE_SE3:QUAT 1824 1873 -5.33843 -7.07651 -4.11437 0.201471 0.0479454 -0.236792 0.949232 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.85 59.1928 911.841 3940.63 -88.2864 3969.93 +EDGE_SE3:QUAT 1825 1875 -5.61052 0.254481 -3.71406 -0.202145 0.0419201 -0.103324 0.972987 1 1.92593e-19 1.92593e-19 -8.87571e-11 -5.73388e-09 2.70023e-08 1 1.92593e-19 -8.87571e-11 -5.73388e-09 2.70023e-08 1 -8.87571e-11 -5.73388e-09 2.70023e-08 3835.56 1.9548 67.1412 4000.31 0.153231 3956.31 +EDGE_SE3:QUAT 1824 1875 -5.71843 7.00528 -3.44372 0.137647 0.0983806 0.0689616 0.983168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.13 58.2196 658.748 3981.95 47.6653 4085.89 +EDGE_SE3:QUAT 1825 1874 -5.58285 -6.89122 -3.53905 0.058405 -0.0248742 0.0585828 0.996262 1 1.20371e-20 1.20371e-20 -3.84252e-10 6.91423e-09 -3.82947e-10 1 1.20371e-20 -3.84252e-10 6.91423e-09 -3.82947e-10 1 -3.84252e-10 6.91423e-09 -3.82947e-10 4000.51 -6.24277 -238.645 3996.14 -6.26884 4000.42 +EDGE_SE3:QUAT 1826 1876 -5.26076 -0.0495381 -3.53497 -0.0716275 -0.0798685 0.0952224 0.989658 1 1.92593e-19 1.92593e-19 2.77268e-08 2.99255e-09 -1.78817e-09 1 1.92593e-19 2.77268e-08 2.99255e-09 -1.78817e-09 1 2.77268e-08 2.99255e-09 -1.78817e-09 4053.85 31.4608 -551.695 3985.35 -35.055 4038.1 +EDGE_SE3:QUAT 1825 1876 -5.65967 6.93614 -3.77693 0.129191 0.0545799 0.00728594 0.99009 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.49 27.8428 418.33 3990.46 10.2489 4043.04 +EDGE_SE3:QUAT 1826 1875 -5.40514 -7.20742 -3.97672 -0.102088 -0.0626923 -0.0388914 0.992036 1 1.92593e-19 1.92593e-19 -2.77909e-08 7.17062e-10 1.93742e-09 1 1.92593e-19 -2.77909e-08 7.17062e-10 1.93742e-09 1 -2.77909e-08 7.17062e-10 1.93742e-09 4032.3 25.7377 -549.115 3981.58 0.29366 4067.94 +EDGE_SE3:QUAT 1827 1877 -4.87612 -0.142772 -3.62501 -0.0148164 -0.133098 0.0982462 0.98611 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4278.31 52.8916 -1093.16 3938.97 -69.5852 4240.58 +EDGE_SE3:QUAT 1826 1877 -5.34656 7.1531 -3.78102 0.148834 0.0643096 -0.00500471 0.986756 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.23 39.1773 513.446 3985.68 13.5264 4064.74 +EDGE_SE3:QUAT 1827 1876 -5.69173 -7.03984 -3.74332 0.0277588 -0.0348856 -0.0440213 0.998035 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4014.29 -4.82142 -264.265 3995.9 6.51614 4009.62 +EDGE_SE3:QUAT 1828 1878 -5.14898 0.0396058 -3.72405 -0.024416 -0.130188 -0.0272421 0.990814 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4286.85 3.92398 -1113.82 3931.34 7.05089 4286.27 +EDGE_SE3:QUAT 1827 1878 -5.23563 7.2498 -3.95963 -0.0665848 0.00790296 0.0423205 0.996852 1 4.81482e-20 4.81482e-20 -1.86348e-10 9.11903e-10 -1.38381e-08 1 4.81482e-20 -1.86348e-10 9.11903e-10 -1.38381e-08 1 -1.86348e-10 9.11903e-10 -1.38381e-08 3984.56 -3.45466 96.366 3999.29 2.07765 3995.13 +EDGE_SE3:QUAT 1828 1877 -5.62991 -6.96103 -3.56386 -0.0738158 0.0519348 0.0251464 0.995601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4025.72 -15.1287 438.551 3988.14 0.553615 4044.98 +EDGE_SE3:QUAT 1829 1879 -4.79492 0.193069 -3.75412 0.0123906 0.0125799 -0.00257993 0.999841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.94 0.617997 101.056 3999.36 -0.0833669 4002.52 +EDGE_SE3:QUAT 1828 1879 -5.61395 6.9765 -3.93747 -0.158177 0.013486 0.0120506 0.987245 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3903.91 -10.45 126.454 3998.99 -0.0979299 4003.41 +EDGE_SE3:QUAT 1829 1878 -5.55826 -6.84302 -3.78071 0.132503 0.055406 -0.0874424 0.985762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.43 32.6732 574.72 3978.45 -13.1622 4050.07 +EDGE_SE3:QUAT 1830 1880 -5.07781 -0.0225119 -3.69961 0.0210183 0.0278507 -0.0623151 0.997446 1 1.20371e-20 1.20371e-20 4.24632e-10 6.92166e-09 -1.20893e-10 1 1.20371e-20 4.24632e-10 6.92166e-09 -1.20893e-10 1 4.24632e-10 6.92166e-09 -1.20893e-10 4012.32 1.28464 237.799 3996.4 -7.18899 3998.55 +EDGE_SE3:QUAT 1829 1880 -5.74438 6.99486 -4.10889 -0.0494258 -0.0158809 -0.0398025 0.997858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.83 3.59394 -150.028 3998.47 2.75717 3999.27 +EDGE_SE3:QUAT 1830 1879 -5.48507 -6.98601 -3.21401 0.141045 -0.0623445 -0.107683 0.982153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3940.98 -21.3244 -296.752 3998.1 18.8818 3974.18 +EDGE_SE3:QUAT 1831 1881 -5.16927 -0.0709209 -3.54667 0.00448055 -0.0370122 -0.174487 0.983953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.64 -5.78513 -274.537 3996.22 23.7341 3896.94 +EDGE_SE3:QUAT 1830 1881 -5.39223 7.36262 -3.66794 0.0530607 -0.0823476 0.0256344 0.99486 1 1.20371e-20 1.20371e-20 -5.9497e-10 3.48216e-10 7.00233e-09 1 1.20371e-20 -5.9497e-10 3.48216e-10 7.00233e-09 1 -5.9497e-10 3.48216e-10 7.00233e-09 4104.04 -15.2769 -688.853 3971.72 -0.304785 4112.67 +EDGE_SE3:QUAT 1831 1880 -5.36439 -6.90635 -3.7001 0.148369 0.0729676 -0.323772 0.931576 1 1.92593e-19 1.92593e-19 2.6831e-08 -8.48794e-09 4.2002e-09 1 1.92593e-19 2.6831e-08 -8.48794e-09 4.2002e-09 1 2.6831e-08 -8.48794e-09 4.2002e-09 4183.49 -16.801 1080.7 3934.76 -168.996 3852.23 +EDGE_SE3:QUAT 1832 1882 -5.32255 -0.237042 -3.68959 -0.139475 0.0266817 -0.0459459 0.988799 1 4.81482e-20 4.81482e-20 -1.78196e-10 1.96421e-09 -1.37295e-08 1 4.81482e-20 -1.78196e-10 1.96421e-09 -1.37295e-08 1 -1.78196e-10 1.96421e-09 -1.37295e-08 3926.25 -7.59542 130.792 3999.49 -3.54414 3995.62 +EDGE_SE3:QUAT 1831 1882 -5.48449 6.88433 -3.7822 -0.0405924 0.0180936 0.060619 0.997171 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.89 -3.09007 173.333 3997.95 5.13771 3992.78 +EDGE_SE3:QUAT 1832 1881 -5.53113 -6.99988 -3.78428 0.061326 -0.00449311 -0.0665856 0.995884 1 2.93874e-24 2.93874e-24 7.22443e-12 1.07974e-10 -6.65463e-12 1 2.93874e-24 7.22443e-12 1.07974e-10 -6.65463e-12 1 7.22443e-12 1.07974e-10 -6.65463e-12 3984.93 0.911662 13.2299 3999.94 -0.989748 3982.24 +EDGE_SE3:QUAT 1833 1883 -4.88971 0.0374237 -3.663 -0.0659345 0.101627 -0.0660295 0.990437 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4126.42 -42.4769 772.387 3968.98 -42.4945 4126.37 +EDGE_SE3:QUAT 1832 1883 -5.44879 7.03649 -3.60433 -0.0847515 -0.077268 0.061999 0.991465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4046.17 31.221 -553.205 3984.37 -27.6231 4059.53 +EDGE_SE3:QUAT 1833 1882 -5.32695 -7.203 -3.29403 0.00890168 -0.0770439 -0.0370321 0.9963 1 3.00927e-21 3.00927e-21 3.49747e-09 -1.36389e-10 -2.67318e-10 1 3.00927e-21 3.49747e-09 -1.36389e-10 -2.67318e-10 1 3.49747e-09 -1.36389e-10 -2.67318e-10 4094.67 -8.29927 -623.662 3976.97 13.5205 4089.5 +EDGE_SE3:QUAT 1834 1884 -5.32196 -0.13468 -3.51756 -0.00204366 -0.079364 0.0721397 0.99423 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4100.47 11.7799 -641.912 3976.09 -24.9164 4079.67 +EDGE_SE3:QUAT 1833 1884 -5.46444 6.77363 -3.88085 -0.0146261 0.0575187 0.0755037 0.995378 1 2.43751e-19 2.43751e-19 2.85815e-09 -1.33917e-08 -2.76948e-08 1 2.43751e-19 2.85815e-09 -1.33917e-08 -2.76948e-08 1 2.85815e-09 -1.33917e-08 -2.76948e-08 4054.8 2.68412 475.093 3986.35 17.4742 4032.85 +EDGE_SE3:QUAT 1834 1883 -5.50766 -6.75495 -3.34894 0.051893 0.253039 -0.235244 0.936984 1 2.70834e-20 2.70834e-20 -1.12315e-08 2.9002e-09 -2.96631e-09 1 2.70834e-20 -1.12315e-08 2.9002e-09 -2.96631e-09 1 -1.12315e-08 2.9002e-09 -2.96631e-09 5215.91 -398.219 2533.14 3840.62 -411.041 5005.32 +EDGE_SE3:QUAT 1835 1885 -5.01689 0.0090591 -3.84536 -0.0520202 0.0642047 0.164323 0.982939 1 2.40741e-19 2.40741e-19 1.81961e-08 -2.50859e-08 2.87803e-10 1 2.40741e-19 1.81961e-08 -2.50859e-08 2.87803e-10 1 1.81961e-08 -2.50859e-08 2.87803e-10 4078.39 3.98041 604.284 3978.17 47.7697 3981.21 +EDGE_SE3:QUAT 1834 1885 -5.36835 6.54513 -3.67192 0.0568252 -0.0640183 0.0106643 0.996272 1 7.52316e-22 7.52316e-22 -1.13376e-10 9.78157e-11 1.74286e-09 1 7.52316e-22 -1.13376e-10 9.78157e-11 1.74286e-09 1 -1.13376e-10 9.78157e-11 1.74286e-09 4054.73 -14.5143 -524.551 3983.41 2.86789 4067.19 +EDGE_SE3:QUAT 1835 1884 -5.4901 -6.84321 -3.74712 -0.135944 -0.0802282 -0.10295 0.982081 1 9.62965e-19 9.62965e-19 -5.78002e-08 -2.28512e-08 2.56488e-09 1 9.62965e-19 -5.78002e-08 -2.28512e-08 2.56488e-09 1 -5.78002e-08 -2.28512e-08 2.56488e-09 4083.2 40.0344 -809.065 3959.79 17.3226 4114.73 +EDGE_SE3:QUAT 1836 1886 -4.82166 0.0876709 -4.08361 -0.0227602 0.0583959 0.0790576 0.994898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4057.17 1.12946 490.392 3985.36 18.3286 4034.24 +EDGE_SE3:QUAT 1835 1886 -5.36718 6.84658 -3.70021 0.0542453 0.000459608 0.072916 0.995862 1 4.81482e-20 4.81482e-20 -1.38211e-08 -1.0067e-09 1.03061e-10 1 4.81482e-20 -1.38211e-08 -1.0067e-09 1.03061e-10 1 -1.38211e-08 -1.0067e-09 1.03061e-10 3988.64 -1.58216 -43.5759 3999.78 -2.14435 3979.15 +EDGE_SE3:QUAT 1836 1885 -5.88123 -7.01455 -3.52586 -0.0671936 -0.0260749 -0.0943152 0.99293 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.49 7.85394 -281.172 3994.42 12.7497 3983.97 +EDGE_SE3:QUAT 1837 1887 -5.02124 0.0335696 -3.63332 0.0624381 -0.0978471 0.158594 0.980497 1 1.92593e-19 1.92593e-19 -4.12859e-09 2.72571e-08 -8.19782e-10 1 1.92593e-19 -4.12859e-09 2.72571e-08 -8.19782e-10 1 -4.12859e-09 2.72571e-08 -8.19782e-10 4179.84 13.5269 -905.673 3953.91 -64.4787 4094.83 +EDGE_SE3:QUAT 1836 1887 -5.71008 6.79446 -3.35344 -0.132524 0.0843358 0.115633 0.980792 1 7.70372e-19 7.70372e-19 -5.56672e-08 -5.17545e-09 -6.23367e-09 1 7.70372e-19 -5.56672e-08 -5.17545e-09 -6.23367e-09 1 -5.56672e-08 -5.17545e-09 -6.23367e-09 4106.4 -36.9375 859.925 3954.84 24.2597 4123.16 +EDGE_SE3:QUAT 1837 1886 -5.51285 -6.99483 -3.88119 -0.242626 -0.0383217 -0.0595025 0.967535 1 4.81482e-20 4.81482e-20 8.60709e-10 3.31725e-09 -1.35159e-08 1 4.81482e-20 8.60709e-10 3.31725e-09 -1.35159e-08 1 8.60709e-10 3.31725e-09 -1.35159e-08 3814.32 57.8577 -450.236 3987.25 -1.2327 4035.62 +EDGE_SE3:QUAT 1838 1888 -5.382 -0.107165 -3.63465 -0.0316287 -0.26237 -0.0979561 0.959461 1 7.52316e-22 7.52316e-22 1.93509e-09 -1.91779e-10 -5.31105e-10 1 7.52316e-22 1.93509e-09 -1.91779e-10 -5.31105e-10 1 1.93509e-09 -1.91779e-10 -5.31105e-10 5388.5 -158.404 -2740.27 3735.79 164.035 5354.12 +EDGE_SE3:QUAT 1837 1888 -5.56943 6.66606 -3.97949 0.075029 0.02366 0.0123675 0.996824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.28 6.65996 176.831 3998.19 1.98295 4007.18 +EDGE_SE3:QUAT 1838 1887 -5.62405 -6.80272 -3.48009 0.0361075 0.0620775 -0.183877 0.980322 1 1.20371e-20 1.20371e-20 6.86938e-09 -1.26514e-09 4.96553e-10 1 1.20371e-20 6.86938e-09 -1.26514e-09 4.96553e-10 1 6.86938e-09 -1.26514e-09 4.96553e-10 4071.29 -9.86608 558.521 3982.32 -51.3599 3941.26 +EDGE_SE3:QUAT 1839 1889 -5.37884 0.246959 -3.40863 -0.0344062 0.0300782 -0.0273683 0.99858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.36 -4.4624 229.269 3996.88 -3.80435 4010.1 +EDGE_SE3:QUAT 1838 1889 -5.53752 6.61875 -3.89277 -0.0836847 0.105929 0.137248 0.981294 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4209.82 -1.15074 1004.28 3942.48 51.6488 4162.49 +EDGE_SE3:QUAT 1839 1888 -5.25866 -6.52449 -3.60465 0.188228 0.050687 -0.0364585 0.980139 1 8.30557e-19 8.30557e-19 5.45802e-08 1.14627e-08 -6.03797e-09 1 8.30557e-19 5.45802e-08 1.14627e-08 -6.03797e-09 1 5.45802e-08 1.14627e-08 -6.03797e-09 3912.69 44.6767 469.813 3987.13 5.66998 4049.09 +EDGE_SE3:QUAT 1840 1890 -5.38072 -0.072163 -3.61384 -0.0250819 0.0125665 -0.0267737 0.999248 1 2.70834e-20 2.70834e-20 -6.9182e-09 3.83536e-09 -6.92393e-09 1 2.70834e-20 -6.9182e-09 3.83536e-09 -6.92393e-09 1 -6.9182e-09 3.83536e-09 -6.92393e-09 3999.61 -1.21397 92.3172 3999.5 -1.28423 3999.26 +EDGE_SE3:QUAT 1839 1890 -5.66782 6.63014 -3.58355 -0.115155 -0.0120634 -0.0113341 0.99321 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3949.99 6.56923 -110.177 3999.22 0.152362 4002.52 +EDGE_SE3:QUAT 1840 1889 -5.17983 -6.91916 -3.43109 -0.00795025 -0.0196065 -0.122593 0.992231 1 7.52316e-22 7.52316e-22 -1.72273e-09 2.12457e-10 3.63751e-11 1 7.52316e-22 -1.72273e-09 2.12457e-10 3.63751e-11 1 -1.72273e-09 2.12457e-10 3.63751e-11 4006.55 -0.565031 -165.15 3998.34 10.2529 3946.69 +EDGE_SE3:QUAT 1841 1891 -5.46004 -0.241271 -3.41877 -0.00431494 -0.189542 0.145598 0.971008 1 7.70372e-19 7.70372e-19 1.069e-08 3.70267e-09 -5.78233e-08 1 7.70372e-19 1.069e-08 3.70267e-09 -5.78233e-08 1 1.069e-08 3.70267e-09 -5.78233e-08 4588.61 146.735 -1644.03 3889.59 -168.4 4503.89 +EDGE_SE3:QUAT 1840 1891 -5.86464 6.84582 -3.77587 -0.0467606 0.365789 0.0963796 0.924512 1 1.20371e-20 1.20371e-20 8.81718e-09 8.41808e-10 3.50483e-09 1 1.20371e-20 8.81718e-09 8.41808e-10 3.50483e-09 1 8.81718e-09 8.41808e-10 3.50483e-09 7510.33 363.16 5143.95 3489 331.981 7481.92 +EDGE_SE3:QUAT 1841 1890 -5.75745 -6.67429 -3.43793 0.032604 0.0209214 -0.0410871 0.998404 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.1 2.58618 183.082 3997.81 -3.49117 4001.6 +EDGE_SE3:QUAT 1842 1892 -5.15293 0.0148811 -3.56251 -0.0790527 -0.0523988 0.045255 0.994463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.55 17.021 -373.768 3992.51 -12.6912 4026.36 +EDGE_SE3:QUAT 1841 1892 -5.83845 6.90193 -3.47035 -0.023575 -0.0815153 0.174206 0.981046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4080.72 30.7255 -583.093 3984.73 -54.841 3961.56 +EDGE_SE3:QUAT 1842 1891 -5.73758 -7.21314 -3.7083 -0.0606061 0.138675 -0.147623 0.977396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4222.36 -93.6336 1004.52 3960 -107.993 4149.88 +EDGE_SE3:QUAT 1843 1893 -4.98355 -0.00368666 -3.92339 -0.0585105 -0.21828 -0.141812 0.963753 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4930.08 -122.398 -2160.05 3811.6 147.993 4863.33 +EDGE_SE3:QUAT 1842 1893 -5.73377 6.95067 -3.76699 0.117246 0.0889917 0.119265 0.981891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4010.55 42.9509 521.612 3990.88 43.1975 4008.64 +EDGE_SE3:QUAT 1843 1892 -5.59136 -6.17807 -3.53815 0.0632972 0.111396 -0.136468 0.982324 1 7.70372e-19 7.70372e-19 7.08765e-09 1.82674e-09 5.62036e-08 1 7.70372e-19 7.08765e-09 1.82674e-09 5.62036e-08 1 7.08765e-09 1.82674e-09 5.62036e-08 4228.18 -12.2551 1018.18 3942.36 -58.2975 4169.71 +EDGE_SE3:QUAT 1844 1894 -5.59897 -0.17008 -3.31906 0.0750061 0.00348383 -0.0898068 0.993125 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3980.22 4.76609 107.472 3998.9 -5.80484 3970.46 +EDGE_SE3:QUAT 1843 1894 -5.59405 6.47141 -3.56252 -0.000572447 0.0509897 -0.166085 0.984792 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.26 -10.0296 393.228 3991.94 -33.0551 3927.92 +EDGE_SE3:QUAT 1844 1893 -5.3872 -6.87449 -3.37304 -0.0937437 0.00246428 -0.135272 0.986361 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.52 8.04032 -130.621 3997.98 11.9594 3930.48 +EDGE_SE3:QUAT 1845 1895 -5.58092 -0.106416 -3.59074 0.0520909 -0.121909 0.217934 0.966918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4273.42 61.1737 -1103.58 3942.61 -121.426 4094.29 +EDGE_SE3:QUAT 1844 1895 -5.97112 6.78185 -3.50129 -0.0576658 -0.0677772 0.0828445 0.992581 1 3.85186e-19 3.85186e-19 -2.61609e-08 -6.21203e-10 -2.61609e-08 1 3.85186e-19 -2.61609e-08 -6.21203e-10 -2.61609e-08 1 -2.61609e-08 -6.21203e-10 -2.61609e-08 4043.86 21.521 -482.232 3987.95 -25.242 4029.71 +EDGE_SE3:QUAT 1845 1894 -5.59745 -6.55127 -3.44695 -0.140126 -0.0341974 0.164159 0.975832 1 7.73381e-19 7.73381e-19 5.35737e-08 1.26618e-08 1.27348e-09 1 7.73381e-19 5.35737e-08 1.26618e-08 1.27348e-09 1 5.35737e-08 1.26618e-08 1.27348e-09 3919.2 -7.74254 13.0583 3999.3 9.09759 3889.95 +EDGE_SE3:QUAT 1846 1896 -5.33703 0.134051 -3.46946 0.0219024 0.157092 -0.0499766 0.986075 1 4.81482e-20 4.81482e-20 2.31479e-09 9.70099e-11 1.44068e-08 1 4.81482e-20 2.31479e-09 9.70099e-11 1.44068e-08 1 2.31479e-09 9.70099e-11 1.44068e-08 4430.28 -14.6557 1384.04 3900.45 -29.0633 4422.2 +EDGE_SE3:QUAT 1845 1896 -5.63956 6.86441 -3.62433 0.151662 -0.0953986 0.255385 0.950093 1 7.70372e-19 7.70372e-19 -5.50564e-08 -1.28593e-08 8.94956e-09 1 7.70372e-19 -5.50564e-08 -1.28593e-08 8.94956e-09 1 -5.50564e-08 -1.28593e-08 8.94956e-09 4238.97 2.37292 -1199.9 3919.61 -125.027 4070.09 +EDGE_SE3:QUAT 1846 1895 -5.4367 -7.03893 -3.81436 0.00512797 -0.0286899 -0.0469618 0.998471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.68 -1.4919 -226.49 3996.88 5.43406 4003.96 +EDGE_SE3:QUAT 1847 1897 -5.24882 -0.424472 -3.52289 -0.119549 0.0514396 0.0126147 0.991415 1 1.93345e-19 1.93345e-19 2.77649e-08 -2.05672e-10 3.20774e-09 1 1.93345e-19 2.77649e-08 -2.05672e-10 3.20774e-09 1 2.77649e-08 -2.05672e-10 3.20774e-09 3987.44 -25.4637 424.762 3989.41 -5.24419 4043.97 +EDGE_SE3:QUAT 1846 1897 -5.89401 6.95605 -3.43666 0.144499 -0.212945 0.206159 0.944073 1 7.70372e-19 7.70372e-19 1.57237e-08 -3.47972e-09 -5.96654e-08 1 7.70372e-19 1.57237e-08 -3.47972e-09 -5.96654e-08 1 1.57237e-08 -3.47972e-09 -5.96654e-08 5040.88 91.3602 -2400.64 3777.59 -143.356 4954.39 +EDGE_SE3:QUAT 1847 1896 -5.55132 -6.77515 -3.26709 -0.0110433 0.0740979 -0.108377 0.991283 1 1.20371e-20 1.20371e-20 -6.94923e-09 7.79365e-10 -4.90077e-10 1 1.20371e-20 -6.94923e-09 7.79365e-10 -4.90077e-10 1 -6.94923e-09 7.79365e-10 -4.90077e-10 4081.29 -17.1016 577.86 3981.58 -34.0128 4034.79 +EDGE_SE3:QUAT 1848 1898 -5.34904 0.304114 -3.27562 -0.315946 -0.2813 -0.211114 0.881181 1 3.85186e-18 3.85186e-18 1.04312e-07 -1.90922e-08 1.45176e-08 1 3.85186e-18 1.04312e-07 -1.90922e-08 1.45176e-08 1 1.04312e-07 -1.90922e-08 1.45176e-08 6252.55 510.355 -4199.98 3652.33 -522.453 6473.56 +EDGE_SE3:QUAT 1847 1898 -5.80132 6.68164 -3.23011 -0.0284596 0.0877408 0.104107 0.990279 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4131.72 9.54888 747.049 3967.72 36.835 4091.61 +EDGE_SE3:QUAT 1848 1897 -5.14669 -6.67633 -3.42727 0.324383 0.0497612 -0.0567704 0.942909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3653.52 95.4355 550.962 3985.16 16.6086 4061.53 +EDGE_SE3:QUAT 1849 1899 -5.10668 0.058858 -3.81185 0.142417 -0.023473 -0.0505473 0.988237 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3920.93 -4.9266 -96.271 3999.83 2.38301 3991.84 +EDGE_SE3:QUAT 1848 1899 -5.75751 6.83356 -3.45496 -0.160758 0.0487264 -0.0328933 0.985241 1 7.70372e-19 7.70372e-19 -5.48613e-08 2.60742e-09 -1.98242e-09 1 7.70372e-19 -5.48613e-08 2.60742e-09 -1.98242e-09 1 -5.48613e-08 2.60742e-09 -1.98242e-09 3920.75 -24.8928 313.084 3995.79 -11.4646 4019.8 +EDGE_SE3:QUAT 1849 1898 -5.45682 -6.64947 -3.62667 -0.0242173 -0.138848 -0.158147 0.977304 1 7.70795e-19 7.70795e-19 1.00757e-08 5.40421e-08 -1.34008e-09 1 7.70795e-19 1.00757e-08 5.40421e-08 -1.34008e-09 1 1.00757e-08 5.40421e-08 -1.34008e-09 4327.53 -64.5899 -1195.19 3930.8 102.184 4229.83 +EDGE_SE3:QUAT 1850 1900 -5.278 0.0438533 -3.70346 -0.127713 -0.0279982 0.0552579 0.989875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3938.99 7.14007 -133.905 3999.47 -4.0145 3992.02 +EDGE_SE3:QUAT 1849 1900 -5.70325 7.01207 -3.77314 -0.0326375 -0.0153001 0.0958456 0.994743 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.43 1.45072 -83.253 3999.72 -3.46981 3964.94 +EDGE_SE3:QUAT 1850 1899 -5.18316 -6.51383 -3.63027 0.0996146 0.117948 -0.153763 0.975972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4270.65 -0.404096 1157.04 3926.08 -62.7865 4215.77 +EDGE_SE3:QUAT 1851 1901 -5.4144 -0.00786121 -3.28363 0.0786985 -0.0335235 -0.245944 0.965502 1 1.92593e-19 1.92593e-19 2.6792e-08 -6.88783e-09 2.33253e-10 1 1.92593e-19 2.6792e-08 -6.88783e-09 2.33253e-10 1 2.6792e-08 -6.88783e-09 2.33253e-10 3973.54 2.21368 -19.5758 3999.9 -8.11932 3756.36 +EDGE_SE3:QUAT 1850 1901 -5.606 6.27271 -3.70803 -0.131832 0.0331792 0.117544 0.983719 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.81 -26.3328 440.655 3985.68 21.8254 3992.07 +EDGE_SE3:QUAT 1851 1900 -5.38446 -6.86872 -3.41575 0.0108514 0.0185878 -0.135873 0.990492 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.1 -0.396051 162.301 3998.38 -11.273 3932.73 +EDGE_SE3:QUAT 1852 1902 -5.02809 0.205435 -3.58909 -0.00306346 -0.00294318 -0.164663 0.986341 1 7.70372e-19 7.70372e-19 -2.09763e-10 -1.07769e-10 5.47543e-08 1 7.70372e-19 -2.09763e-10 -1.07769e-10 5.47543e-08 1 -2.09763e-10 -1.07769e-10 5.47543e-08 4000.17 -0.000825364 -28.5393 3999.95 2.48832 3891.75 +EDGE_SE3:QUAT 1851 1902 -5.73462 6.14789 -3.64063 -0.194472 -0.00319136 0.0116421 0.980834 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3848.7 -1.16082 2.39019 3999.99 0.0692147 3999.44 +EDGE_SE3:QUAT 1852 1901 -5.70061 -6.63721 -3.1817 -0.0673442 -0.0388714 -0.0709649 0.994443 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.08 9.82759 -366.418 3991.15 10.7064 4013.08 +EDGE_SE3:QUAT 1853 1903 -5.27186 0.084906 -3.85786 0.0122992 -0.00145698 0.0109906 0.999863 1 3.00927e-21 3.00927e-21 -3.46899e-09 -3.79958e-11 5.99005e-12 1 3.00927e-21 -3.46899e-09 -3.79958e-11 5.99005e-12 1 -3.46899e-09 -3.79958e-11 5.99005e-12 3999.44 -0.0842542 -13.273 3999.99 -0.0751347 3999.56 +EDGE_SE3:QUAT 1852 1903 -5.7567 6.74379 -3.41822 -0.19674 0.122269 0.0451529 0.971754 1 4.81482e-20 4.81482e-20 -1.86934e-09 2.74963e-09 -1.39632e-08 1 4.81482e-20 -1.86934e-09 2.74963e-09 -1.39632e-08 1 -1.86934e-09 2.74963e-09 -1.39632e-08 4122.08 -108.184 1088.27 3942.41 -54.9487 4268.75 +EDGE_SE3:QUAT 1853 1902 -5.1093 -6.74675 -3.61593 -0.116032 0.237537 0.0707077 0.961828 1 9.62965e-19 9.62965e-19 -3.13775e-08 5.29624e-08 -2.58572e-09 1 9.62965e-19 -3.13775e-08 5.29624e-08 -2.58572e-09 1 -3.13775e-08 5.29624e-08 -2.58572e-09 5109.37 -99.4774 2450.71 3766.11 -81.5555 5143.22 +EDGE_SE3:QUAT 1854 1904 -5.00704 -0.262261 -3.54938 -0.246901 -0.0353876 0.0630529 0.96634 1 3.09352e-18 3.09352e-18 -1.06786e-07 -1.47335e-08 -1.66228e-09 1 3.09352e-18 -1.06786e-07 -1.47335e-08 -1.66228e-09 1 -1.06786e-07 -1.47335e-08 -1.66228e-09 3756.34 1.00365 -76.9006 4000.37 -1.51765 3984.27 +EDGE_SE3:QUAT 1853 1904 -5.59874 6.46504 -3.65624 0.263161 0.0608467 0.134069 0.953451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3716.91 -17.7709 23.9777 3999.55 -8.13807 3922.03 +EDGE_SE3:QUAT 1854 1903 -5.36598 -7.3049 -3.52352 0.133235 0.151703 -0.188769 0.961041 1 9.62965e-19 9.62965e-19 -1.74573e-08 8.81944e-09 5.15907e-08 1 9.62965e-19 -1.74573e-08 8.81944e-09 5.15907e-08 1 -1.74573e-08 8.81944e-09 5.15907e-08 4492.93 -15.7444 1604.92 3873.44 -92.4729 4421.4 +EDGE_SE3:QUAT 1855 1905 -4.91011 0.0100778 -3.12068 0.0716869 -0.0621422 -0.10785 0.98963 1 1.92593e-19 1.92593e-19 2.76014e-08 -3.24492e-09 -1.24327e-09 1 1.92593e-19 2.76014e-08 -3.24492e-09 -1.24327e-09 1 2.76014e-08 -3.24492e-09 -1.24327e-09 4017.76 -20.4743 -395.304 3993.03 24.8228 3991.79 +EDGE_SE3:QUAT 1854 1905 -5.62997 6.66844 -3.55319 -0.155526 0.150342 0.0991446 0.971277 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4388.26 -77.0693 1475.13 3890.13 -19.4109 4445.69 +EDGE_SE3:QUAT 1855 1904 -5.77174 -6.42368 -3.55062 0.0928657 -0.0140503 -0.036055 0.994926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3966.71 -2.73124 -70.8216 3999.82 1.25006 3996 +EDGE_SE3:QUAT 1856 1906 -5.34141 0.235433 -3.58327 0.0614693 0.0314299 0.152747 0.985851 1 1.20371e-20 1.20371e-20 1.07933e-09 -6.83768e-09 4.72749e-10 1 1.20371e-20 1.07933e-09 -6.83768e-09 4.72749e-10 1 1.07933e-09 -6.83768e-09 4.72749e-10 3988.69 4.19331 130.542 3999.72 7.45934 3910.48 +EDGE_SE3:QUAT 1855 1906 -5.54788 6.77432 -3.45896 -0.0448305 -0.278969 0.15273 0.947016 1 3.27408e-18 3.27408e-18 7.57085e-09 1.10675e-07 8.1137e-09 1 3.27408e-18 7.57085e-09 1.10675e-07 8.1137e-09 1 7.57085e-09 1.10675e-07 8.1137e-09 5268.03 467.423 -2597.41 3854.06 -465.723 5182.76 +EDGE_SE3:QUAT 1856 1905 -5.5048 -6.29664 -3.47613 0.0125922 0.00762056 0.0682767 0.997558 1 3.00927e-21 3.00927e-21 3.46125e-09 2.37515e-10 2.02337e-11 1 3.00927e-21 3.46125e-09 2.37515e-10 2.02337e-11 1 3.46125e-09 2.37515e-10 2.02337e-11 3999.99 0.364957 50.2457 3999.87 1.60681 3981.98 +EDGE_SE3:QUAT 1857 1907 -5.33391 -0.190311 -3.37756 0.094135 -0.0466046 0.0127029 0.994387 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.31 -18.0093 -385.213 3991.04 2.65456 4036.11 +EDGE_SE3:QUAT 1856 1907 -5.74319 6.49781 -3.68802 -0.193379 0.120287 0.0380934 0.972977 1 3.00927e-21 3.00927e-21 4.50447e-10 -6.80139e-10 3.48777e-09 1 3.00927e-21 4.50447e-10 -6.80139e-10 3.48777e-09 1 4.50447e-10 -6.80139e-10 3.48777e-09 4110.21 -104.467 1052 3946.29 -54.3456 4253.98 +EDGE_SE3:QUAT 1857 1906 -5.42564 -6.94548 -3.37388 0.0112518 -0.0528429 -0.0387329 0.997788 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4043.2 -4.99378 -420.423 3989.35 9.08426 4037.71 +EDGE_SE3:QUAT 1858 1908 -5.51086 0.170319 -3.63145 -0.0928679 -0.101009 0.092345 0.986228 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4083.99 51.8756 -700.333 3977.86 -51.7905 4084.38 +EDGE_SE3:QUAT 1857 1908 -5.66353 6.96008 -3.35146 -0.0772631 0.060509 0.303466 0.947775 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4094.56 19.0288 699.238 3974.16 110.774 3750.08 +EDGE_SE3:QUAT 1858 1907 -5.4236 -6.68397 -3.2683 -0.23319 -0.194699 -0.136255 0.942947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4726.1 188.078 -2160.04 3815.91 -122.042 4869.35 +EDGE_SE3:QUAT 1859 1909 -5.2946 0.345559 -3.40095 0.0357533 -0.0947693 -0.0701942 0.992378 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4127.75 -28.8279 -741.186 3969.92 35.3618 4113.16 +EDGE_SE3:QUAT 1858 1909 -6.02203 6.64832 -3.30594 0.0460879 0.148368 0.088119 0.98392 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4322.68 80.3758 1198.07 3931.28 88.214 4300.12 +EDGE_SE3:QUAT 1859 1908 -5.76071 -6.66057 -3.43729 0.014282 -0.0799943 -0.11045 0.990554 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4093.45 -20.9199 -621.414 3979.03 38.0692 4045.47 +EDGE_SE3:QUAT 1860 1910 -5.06378 0.099877 -3.81576 0.0368639 0.00915227 0.0833575 0.995796 1 7.52316e-22 7.52316e-22 -1.45386e-10 1.72736e-09 -6.57005e-11 1 7.52316e-22 -1.45386e-10 1.72736e-09 -6.57005e-11 1 -1.45386e-10 1.72736e-09 -6.57005e-11 3994.84 0.484945 35.6339 3999.97 0.987294 3972.48 +EDGE_SE3:QUAT 1859 1910 -5.8593 6.38066 -3.9464 -0.155678 -0.074248 -0.0538844 0.983539 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.76 50.1612 -687.217 3972.19 -5.62424 4103.09 +EDGE_SE3:QUAT 1860 1909 -5.69535 -6.79537 -3.23753 0.01152 0.0859538 -0.0703811 0.993743 1 7.52316e-22 7.52316e-22 -1.75021e-09 1.22282e-10 -1.52723e-10 1 7.52316e-22 -1.75021e-09 1.22282e-10 -1.52723e-10 1 -1.75021e-09 1.22282e-10 -1.52723e-10 4122.01 -8.6846 710.774 3970.51 -24.9002 4102.73 +EDGE_SE3:QUAT 1861 1911 -5.60889 -0.016346 -3.3049 0.0870448 0.0201901 0.164734 0.982282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.88 -3.26262 -14.9603 3999.66 -6.1883 3890.64 +EDGE_SE3:QUAT 1860 1911 -5.89107 6.26627 -3.34045 -0.0730085 0.0394568 0.0633915 0.994532 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.45 -11.331 369.41 3991.03 8.9755 4017.7 +EDGE_SE3:QUAT 1861 1910 -5.44376 -6.29831 -3.23386 0.116841 -0.0159996 -0.162251 0.979677 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3946.55 10.3621 101.059 3997.99 -14.4715 3895.85 +EDGE_SE3:QUAT 1862 1912 -5.11341 -0.2873 -3.31707 0.007689 -0.0539605 -0.113696 0.992019 1 5.11575e-20 5.11575e-20 -1.86245e-09 1.41664e-08 -9.71889e-11 1 5.11575e-20 -1.86245e-09 1.41664e-08 -9.71889e-11 1 -1.86245e-09 1.41664e-08 -9.71889e-11 4042.68 -9.18553 -416.659 3990.29 24.5365 3991.21 +EDGE_SE3:QUAT 1861 1912 -5.97313 6.46858 -3.55349 0.203573 -0.0416958 0.112172 0.971719 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3916.62 -58.166 -583.747 3975.92 -16.9206 4032.06 +EDGE_SE3:QUAT 1862 1911 -5.70411 -6.62813 -3.30144 0.116766 0.256496 -0.0864217 0.955566 1 3.27408e-18 3.27408e-18 3.44146e-08 1.05459e-07 -7.02789e-10 1 3.27408e-18 3.44146e-08 1.05459e-07 -7.02789e-10 1 3.44146e-08 1.05459e-07 -7.02789e-10 5368.98 80.7228 2778.6 3722.29 68.7941 5393.64 +EDGE_SE3:QUAT 1863 1913 -5.52775 0.0739303 -3.33975 0.0877187 -0.0532962 0.0140066 0.99462 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.19 -19.0616 -440.675 3988.29 3.10376 4047.19 +EDGE_SE3:QUAT 1862 1913 -5.40573 6.55716 -3.37752 -0.016743 -0.138351 0.125445 0.982264 1 7.70372e-19 7.70372e-19 7.48529e-09 -5.44574e-08 -2.89854e-09 1 7.70372e-19 7.48529e-09 -5.44574e-08 -2.89854e-09 1 7.48529e-09 -5.44574e-08 -2.89854e-09 4291.16 69.8796 -1120.42 3939.67 -90.87 4229.33 +EDGE_SE3:QUAT 1863 1912 -5.66274 -6.39851 -3.89047 -0.0669841 0.192952 -0.1285 0.970449 1 1.92593e-19 1.92593e-19 -2.86834e-08 4.84995e-09 -4.89268e-09 1 1.92593e-19 -2.86834e-08 4.84995e-09 -4.89268e-09 1 -2.86834e-08 4.84995e-09 -4.89268e-09 4502.75 -183.458 1536.27 3915.71 -191.5 4454.65 +EDGE_SE3:QUAT 1864 1914 -5.35175 -0.0604196 -3.4929 -0.190822 0.166301 0.017296 0.967281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4309.91 -163.159 1425.2 3917.08 -126.003 4454.37 +EDGE_SE3:QUAT 1863 1914 -5.62742 6.70628 -3.58393 -0.0390509 -0.0466524 0.0858164 0.994452 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.87 10.0018 -329.972 3994.19 -15.4877 3997.51 +EDGE_SE3:QUAT 1864 1913 -5.73 -6.68286 -3.5821 0.0222868 -0.135357 0.128933 0.982119 1 7.52316e-22 7.52316e-22 -1.77055e-09 -2.3014e-10 2.46111e-10 1 7.52316e-22 -1.77055e-09 -2.3014e-10 2.46111e-10 1 -1.77055e-09 -2.3014e-10 2.46111e-10 4312.67 47.762 -1165.19 3930.68 -79.4288 4248.16 +EDGE_SE3:QUAT 1865 1915 -5.28255 -0.0728576 -3.60386 0.0745771 0.0171551 -0.202529 0.976282 1 4.81482e-20 4.81482e-20 -2.75031e-09 -1.3561e-08 8.57656e-10 1 4.81482e-20 -2.75031e-09 -1.3561e-08 8.57656e-10 1 -2.75031e-09 -1.3561e-08 8.57656e-10 4000.32 8.04528 305.246 3992.56 -34.9371 3858.49 +EDGE_SE3:QUAT 1864 1915 -5.77236 6.4942 -3.58454 -0.0294094 0.0477714 0.134544 0.989318 1 1.20371e-20 1.20371e-20 -6.90326e-09 -9.2236e-10 -3.75661e-10 1 1.20371e-20 -6.90326e-09 -9.2236e-10 -3.75661e-10 1 -6.90326e-09 -9.2236e-10 -3.75661e-10 4040.68 2.13057 422.574 3989.15 28.1262 3971.73 +EDGE_SE3:QUAT 1865 1914 -5.60029 -6.38481 -3.35647 0.168837 0.208137 -0.0974944 0.958472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4819.53 133.615 2146.15 3810.46 93.5491 4895.53 +EDGE_SE3:QUAT 1866 1916 -5.35439 0.102241 -3.34542 0.102717 -0.0847473 0.110076 0.984962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4118.98 -22.3416 -819.561 3959.17 -27.4946 4112.72 +EDGE_SE3:QUAT 1865 1916 -5.41591 6.48982 -3.626 -0.00900547 0.0126053 0.148017 0.988864 1 7.52316e-22 7.52316e-22 -1.71611e-09 -2.56533e-10 -2.54905e-11 1 7.52316e-22 -1.71611e-09 -2.56533e-10 -2.54905e-11 1 -1.71611e-09 -2.56533e-10 -2.54905e-11 4002.88 0.156171 113.382 3999.2 8.67719 3915.57 +EDGE_SE3:QUAT 1866 1915 -5.57697 -6.41572 -3.19624 0.0693339 0.14688 -0.208013 0.964546 1 4.81482e-20 4.81482e-20 1.41262e-08 -2.86566e-09 2.37168e-09 1 4.81482e-20 1.41262e-08 -2.86566e-09 2.37168e-09 1 1.41262e-08 -2.86566e-09 2.37168e-09 4415.23 -78.6135 1388.02 3911.19 -139.224 4261.38 +EDGE_SE3:QUAT 1867 1917 -5.27935 0.252694 -3.54629 0.150464 0.0180005 -0.0968797 0.983692 1 7.70372e-19 7.70372e-19 5.47697e-08 -4.85886e-09 2.53713e-09 1 7.70372e-19 5.47697e-08 -4.85886e-09 2.53713e-09 1 5.47697e-08 -4.85886e-09 2.53713e-09 3932.74 25.0343 310.265 3992.16 -13.6195 3985.75 +EDGE_SE3:QUAT 1866 1917 -5.81448 6.24158 -2.85689 0.0418903 0.097106 0.231688 0.967024 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4082.16 49.8035 609.087 3989.84 75.7365 3874.46 +EDGE_SE3:QUAT 1867 1916 -5.48019 -6.18608 -3.25238 -0.0502084 -0.0656833 -0.0211853 0.996351 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4062.72 12.0812 -544.542 3981.98 0.587154 4071.01 +EDGE_SE3:QUAT 1868 1918 -5.30724 -0.376528 -3.43939 0.127498 0.158351 -0.132623 0.970093 1 1.92593e-19 1.92593e-19 -2.87733e-08 2.79979e-09 -5.41796e-09 1 1.92593e-19 -2.87733e-08 2.79979e-09 -5.41796e-09 1 -2.87733e-08 2.79979e-09 -5.41796e-09 4487.09 24.0373 1585.69 3874.08 -33.8613 4481.76 +EDGE_SE3:QUAT 1867 1918 -5.51706 6.48002 -3.60202 -0.185412 -0.00167756 0.0688121 0.980247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3866.58 -17.1522 136.61 3997.87 5.72174 3985.15 +EDGE_SE3:QUAT 1868 1917 -5.66835 -6.4381 -3.38898 -0.153097 -0.0585963 -0.205404 0.964851 1 1.54074e-18 1.54074e-18 6.105e-08 -3.52371e-09 -6.105e-08 1 1.54074e-18 6.105e-08 -3.52371e-09 -6.105e-08 1 6.105e-08 -3.52371e-09 -6.105e-08 4065.35 32.9216 -818.02 3954.98 69.7994 3990.34 +EDGE_SE3:QUAT 1869 1919 -5.56073 -0.27351 -3.59046 0.0503685 0.0746173 -0.119164 0.988785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4099.04 -0.659648 669.984 3973.05 -35.6366 4052.39 +EDGE_SE3:QUAT 1868 1919 -5.87285 6.37286 -3.78759 -0.0750233 -0.217775 0.118285 0.965895 1 9.62965e-19 9.62965e-19 -2.009e-08 -5.81833e-08 -1.76082e-09 1 9.62965e-19 -2.009e-08 -5.81833e-08 -1.76082e-09 1 -2.009e-08 -5.81833e-08 -1.76082e-09 4669.13 240.627 -1803.48 3894.01 -244.876 4635.68 +EDGE_SE3:QUAT 1869 1918 -5.4565 -6.4477 -3.07646 -0.171979 -0.0737602 0.0319422 0.981816 1 8.1852e-19 8.1852e-19 5.57527e-08 5.5973e-09 -1.69935e-08 1 8.1852e-19 5.57527e-08 5.5973e-09 -1.69935e-08 1 5.57527e-08 5.5973e-09 -1.69935e-08 3943.91 46.1151 -504.276 3988.99 -25.8712 4058.14 +EDGE_SE3:QUAT 1870 1920 -5.36976 0.0656802 -3.03223 -0.0699247 0.031811 -0.0779825 0.993991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.88 -6.90747 185.543 3998.5 -7.44465 3984.12 +EDGE_SE3:QUAT 1869 1920 -6.05363 6.28156 -3.45146 0.15367 0.154315 0.0970286 0.971163 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4157.27 133.875 1040.1 3967.32 126.159 4214.07 +EDGE_SE3:QUAT 1870 1919 -5.89736 -6.65223 -3.53986 -0.0985497 -0.0331808 0.0183658 0.994409 1 2.0463e-19 2.0463e-19 2.78514e-08 1.37749e-09 -7.71626e-09 1 2.0463e-19 2.78514e-08 1.37749e-09 -7.71626e-09 1 2.78514e-08 1.37749e-09 -7.71626e-09 3975.54 11.9728 -240.567 3996.83 -4.40146 4013.04 +EDGE_SE3:QUAT 1871 1921 -4.77797 0.136149 -3.16159 -0.127224 -0.0171031 0.137409 0.982161 1 7.70384e-19 7.70384e-19 -5.4552e-08 -7.40511e-09 -9.96425e-10 1 7.70384e-19 -5.4552e-08 -7.40511e-09 -9.96425e-10 1 -5.4552e-08 -7.40511e-09 -9.96425e-10 3935.45 -9.37237 75.2057 3998.64 10.125 3924.67 +EDGE_SE3:QUAT 1870 1921 -5.60771 6.67688 -3.77521 -0.135328 0.0843345 0.15019 0.975714 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4125.51 -31.2629 915.104 3948.66 43.4658 4108.53 +EDGE_SE3:QUAT 1871 1920 -5.65213 -6.54464 -2.86317 -0.0576791 -0.0665897 -0.0829585 0.992651 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.79 8.02549 -593.307 3978.21 19.3159 4058.57 +EDGE_SE3:QUAT 1872 1922 -5.52416 0.0934003 -3.16022 0.104993 0.120932 -0.140549 0.977035 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4278.8 8.64101 1181.91 3922.74 -51.4883 4243.88 +EDGE_SE3:QUAT 1871 1922 -5.52867 6.48592 -3.25694 0.126864 -0.0160884 -0.0448893 0.990773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3936.31 -2.23414 -57.6912 3999.96 1.01363 3992.62 +EDGE_SE3:QUAT 1872 1921 -5.56111 -6.58483 -3.38237 -0.0367035 -0.0380523 -0.0236513 0.998321 1 4.81482e-20 4.81482e-20 1.38974e-08 -2.90397e-10 -5.51925e-10 1 4.81482e-20 1.38974e-08 -2.90397e-10 -5.51925e-10 1 1.38974e-08 -2.90397e-10 -5.51925e-10 4019.37 5.07396 -315.694 3993.75 2.48027 4022.52 +EDGE_SE3:QUAT 1873 1923 -5.55798 0.206248 -3.00071 0.0690515 -0.0581514 0.0328452 0.995375 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4041.25 -15.0679 -494.944 3984.89 -2.38939 4056.01 +EDGE_SE3:QUAT 1872 1923 -5.87158 6.42014 -3.59242 0.0549987 -0.0154419 0.125955 0.99039 1 8.30557e-19 8.30557e-19 -1.30307e-08 2.40906e-09 -5.49941e-08 1 8.30557e-19 -1.30307e-08 2.40906e-09 -5.49941e-08 1 -1.30307e-08 2.40906e-09 -5.49941e-08 3997.99 -4.69891 -202.67 3996.87 -13.7842 3946.64 +EDGE_SE3:QUAT 1873 1922 -5.39286 -6.37156 -3.18866 0.0494509 -0.115393 -0.0312834 0.991595 1 3.85186e-19 3.85186e-19 2.7029e-08 -2.87508e-08 -1.56196e-09 1 3.85186e-19 2.7029e-08 -2.87508e-08 -1.56196e-09 1 2.7029e-08 -2.87508e-08 -1.56196e-09 4200.21 -36.4984 -940.304 3951.55 32.7968 4206.08 +EDGE_SE3:QUAT 1874 1924 -4.97473 -0.158692 -3.04643 -0.0296896 -0.162886 -0.00619184 0.986179 1 4.70198e-23 4.70198e-23 -7.46408e-11 -1.33982e-11 4.51694e-10 1 4.70198e-23 -7.46408e-11 -1.33982e-11 4.51694e-10 1 -7.46408e-11 -1.33982e-11 4.51694e-10 4457.72 22.8826 -1434.48 3894.17 -15.893 4461.1 +EDGE_SE3:QUAT 1873 1924 -5.65401 6.45356 -3.69625 -0.0717052 0.0555346 -0.0200096 0.995678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4024.59 -16.945 427.452 3989.47 -9.34595 4043.55 +EDGE_SE3:QUAT 1874 1923 -5.32037 -6.31717 -3.44161 0.0747841 -0.0433999 -0.0883431 0.99233 1 1.92593e-19 1.92593e-19 -2.76016e-08 2.61729e-09 8.08141e-10 1 1.92593e-19 -2.76016e-08 2.61729e-09 8.08141e-10 1 -2.76016e-08 2.61729e-09 8.08141e-10 3994.52 -11.5052 -262.277 3996.96 12.7097 3985.67 +EDGE_SE3:QUAT 1875 1925 -5.59879 -0.191018 -3.42979 0.0186088 -0.0988726 0.0588263 0.993185 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4163.5 6.22255 -828.681 3960.24 -22.3557 4151.04 +EDGE_SE3:QUAT 1874 1925 -5.7203 6.79088 -3.29351 0.0524121 -0.0197081 0.272154 0.960623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.67 -1.52294 -304.145 3993.5 -47.196 3726.38 +EDGE_SE3:QUAT 1875 1924 -5.80964 -6.53927 -2.93949 0.154831 -0.209567 0.131283 0.95649 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4906.07 -61.7946 -2238.9 3791.11 18.0782 4933.02 +EDGE_SE3:QUAT 1876 1926 -4.9583 0.0769927 -3.23674 0.0685706 -0.0543388 -0.0305131 0.995698 1 2.88889e-19 2.88889e-19 -2.79454e-08 1.58775e-08 1.42705e-08 1 2.88889e-19 -2.79454e-08 1.58775e-08 1.42705e-08 1 -2.79454e-08 1.58775e-08 1.42705e-08 4022.65 -16.0902 -409.493 3990.49 10.72 4037.74 +EDGE_SE3:QUAT 1875 1926 -5.91121 6.30662 -3.5273 0.19003 0.165302 0.0672569 0.965422 1 7.70372e-19 7.70372e-19 7.17775e-09 1.27436e-08 5.56992e-08 1 7.70372e-19 7.17775e-09 1.27436e-08 5.56992e-08 1 7.17775e-09 1.27436e-08 5.56992e-08 4160.3 165.327 1150.92 3963.31 149.077 4286.65 +EDGE_SE3:QUAT 1876 1925 -5.95107 -6.57091 -3.23405 0.137697 -0.101548 -0.225108 0.959194 1 1.73334e-18 1.73334e-18 4.80846e-08 -4.97075e-08 -5.02073e-08 1 1.73334e-18 4.80846e-08 -4.97075e-08 -5.02073e-08 1 4.80846e-08 -4.97075e-08 -5.02073e-08 3951.07 -34.7857 -368.738 4003.66 37.6654 3824.22 +EDGE_SE3:QUAT 1877 1927 -5.4232 -0.140235 -3.24951 -0.12962 0.0247691 -0.0331486 0.9907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3937.73 -8.31136 141.989 3999.18 -3.216 4000.54 +EDGE_SE3:QUAT 1876 1927 -5.63081 6.45774 -3.21155 0.0608657 0.0453338 0.0416083 0.996247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.39 11.7256 331.223 3993.87 9.40947 4020.28 +EDGE_SE3:QUAT 1877 1926 -5.59552 -6.34242 -3.23202 -0.00800259 -0.279286 -0.058248 0.958406 1 3.00927e-21 3.00927e-21 3.93804e-09 -2.62768e-10 -1.14289e-09 1 3.00927e-21 3.93804e-09 -2.62768e-10 -1.14289e-09 1 3.93804e-09 -2.62768e-10 -1.14289e-09 5603.87 -141.865 -2998.29 3698.59 142.38 5590.55 +EDGE_SE3:QUAT 1878 1928 -5.409 0.0228986 -3.63239 0.0930279 -0.0233077 -0.0486736 0.9942 1 2.0463e-19 2.0463e-19 -2.72468e-08 8.34668e-09 -2.75975e-10 1 2.0463e-19 -2.72468e-08 8.34668e-09 -2.75975e-10 1 -2.72468e-08 8.34668e-09 -2.75975e-10 3969.47 -5.52548 -129.499 3999.31 3.40442 3994.61 +EDGE_SE3:QUAT 1877 1928 -5.62559 6.44058 -3.47029 0.0196759 -0.0638087 0.169806 0.983213 1 9.75002e-19 9.75002e-19 7.82988e-09 -2.62704e-08 5.45286e-08 1 9.75002e-19 7.82988e-09 -2.62704e-08 5.45286e-08 1 7.82988e-09 -2.62704e-08 5.45286e-08 4069.05 12.5529 -536.077 3984.22 -46.0107 3955.26 +EDGE_SE3:QUAT 1878 1927 -6.02047 -6.01808 -3.2065 0.0327142 -0.123065 -0.0434587 0.990907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4237.66 -35.4782 -1013.1 3944.24 37.682 4234.38 +EDGE_SE3:QUAT 1879 1929 -4.91222 0.0868387 -3.3678 -0.0756028 0.178472 0.0895352 0.976942 1 8.1852e-19 8.1852e-19 -1.82742e-08 5.33398e-08 -2.31306e-10 1 8.1852e-19 -1.82742e-08 5.33398e-08 -2.31306e-10 1 -1.82742e-08 5.33398e-08 -2.31306e-10 4591.63 -0.703874 1683.96 3862.29 30.3904 4582.42 +EDGE_SE3:QUAT 1878 1929 -5.99246 6.19344 -2.98289 0.0298367 0.0514626 -0.0610448 0.996361 1 6.01853e-20 6.01853e-20 6.19136e-09 -7.33979e-10 -1.35269e-08 1 6.01853e-20 6.19136e-09 -7.33979e-10 -1.35269e-08 1 6.19136e-09 -7.33979e-10 -1.35269e-08 4043.24 2.54686 435.211 3988.23 -11.8018 4031.89 +EDGE_SE3:QUAT 1879 1928 -5.41675 -6.47864 -2.98627 -0.11881 -0.113093 -0.00972348 0.986407 1 1.92593e-19 1.92593e-19 2.80985e-08 4.98825e-10 -3.19507e-09 1 1.92593e-19 2.80985e-08 4.98825e-10 -3.19507e-09 1 2.80985e-08 4.98825e-10 -3.19507e-09 4153.7 60.2704 -940.679 3952.82 -33.5567 4209.78 +EDGE_SE3:QUAT 1880 1930 -5.5394 0.10207 -3.31853 -0.124176 -0.0689251 -0.0334988 0.989296 1 1.92593e-19 1.92593e-19 -2.77629e-08 4.40297e-10 2.10408e-09 1 1.92593e-19 -2.77629e-08 4.40297e-10 2.10408e-09 1 -2.77629e-08 4.40297e-10 2.10408e-09 4026.1 35.629 -599.049 3978.76 -5.39944 4083.29 +EDGE_SE3:QUAT 1879 1930 -6.2208 6.32071 -3.32358 -0.147819 -0.0956986 -0.00756092 0.984344 1 7.52316e-22 7.52316e-22 -1.65529e-10 -2.63501e-10 1.73912e-09 1 7.52316e-22 -1.65529e-10 -2.63501e-10 1.73912e-09 1 -1.65529e-10 -2.63501e-10 1.73912e-09 4058.49 61.0952 -777.829 3968.32 -30.3038 4145.67 +EDGE_SE3:QUAT 1880 1929 -5.72873 -6.25211 -3.68235 -0.145106 0.0255587 -0.0985019 0.984169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3915.06 2.27591 26.9705 3999.99 1.42802 3960.47 +EDGE_SE3:QUAT 1881 1931 -5.21606 0.376214 -3.37908 0.0457363 0.0220503 -0.0182221 0.998544 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.27 4.11918 186.111 3997.79 -1.15252 4007.31 +EDGE_SE3:QUAT 1880 1931 -6.07085 6.01512 -3.18883 -0.126954 0.00925265 0.028671 0.991451 1 7.70372e-19 7.70372e-19 5.50596e-08 1.41189e-09 8.97381e-10 1 7.70372e-19 5.50596e-08 1.41189e-09 8.97381e-10 1 5.50596e-08 1.41189e-09 8.97381e-10 3938.82 -8.10082 115.433 3999 1.31557 4000 +EDGE_SE3:QUAT 1881 1930 -5.44476 -6.37105 -3.35845 0.100675 0.0631197 -0.0977981 0.988087 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.36 21.6461 620.708 3975.38 -20.2722 4055.64 +EDGE_SE3:QUAT 1882 1932 -5.64983 -0.291502 -3.34557 -0.122731 -0.0838137 -0.151724 0.977186 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4128.7 23.7074 -891.014 3951.43 46.6187 4096.87 +EDGE_SE3:QUAT 1881 1932 -5.83044 6.24735 -3.67462 0.0233387 -0.23505 -0.0684438 0.96929 1 4.81482e-20 4.81482e-20 1.50586e-08 -1.37864e-09 -3.55154e-09 1 4.81482e-20 1.50586e-08 -1.37864e-09 -3.55154e-09 1 1.50586e-08 -1.37864e-09 -3.55154e-09 5002.99 -158.177 -2243.1 3803.56 162.372 4986.43 +EDGE_SE3:QUAT 1882 1931 -5.65001 -6.6085 -3.37144 0.0137831 -0.00607542 0.127319 0.991747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.4 -0.319782 -68.2609 3999.67 -4.74794 3936.32 +EDGE_SE3:QUAT 1883 1933 -5.31792 -0.0352512 -3.20413 -0.170799 -0.00740835 -0.0527039 0.983867 1 4.81482e-20 4.81482e-20 -3.42413e-10 -2.34898e-09 1.36651e-08 1 4.81482e-20 -3.42413e-10 -2.34898e-09 1.36651e-08 1 -3.42413e-10 -2.34898e-09 1.36651e-08 3889.64 16.5078 -162.447 3997.7 3.94958 3995.22 +EDGE_SE3:QUAT 1882 1933 -5.76516 6.29492 -3.15531 -0.0324661 0.220389 -0.0165684 0.974731 1 8.1852e-19 8.1852e-19 -1.30921e-08 5.4602e-08 -9.2395e-10 1 8.1852e-19 -1.30921e-08 5.4602e-08 -9.2395e-10 1 -1.30921e-08 5.4602e-08 -9.2395e-10 4889.54 -76.4506 2091.38 3811.92 -74.5057 4892.66 +EDGE_SE3:QUAT 1883 1932 -5.69689 -6.14751 -3.29289 0.0566016 -0.068353 0.123095 0.988419 1 4.81482e-20 4.81482e-20 -1.38842e-08 -1.62736e-09 1.12095e-09 1 4.81482e-20 -1.38842e-08 -1.62736e-09 1.12095e-09 1 -1.38842e-08 -1.62736e-09 1.12095e-09 4083.55 -2.21387 -628.536 3975.84 -34.4084 4035.75 +EDGE_SE3:QUAT 1884 1934 -5.14163 -0.270211 -3.10537 -0.0217001 -0.166242 -0.0173811 0.985693 1 1.20371e-20 1.20371e-20 7.24213e-09 -7.97495e-11 -1.22537e-09 1 1.20371e-20 7.24213e-09 -7.97495e-11 -1.22537e-09 1 7.24213e-09 -7.97495e-11 -1.22537e-09 4482.46 7.48452 -1473.76 3888.91 0.0440014 4483.14 +EDGE_SE3:QUAT 1883 1934 -6.0415 6.03985 -3.46669 0.103856 0.154089 0.0308834 0.982098 1 9.62965e-19 9.62965e-19 -2.49091e-08 -5.63023e-08 2.40398e-09 1 9.62965e-19 -2.49091e-08 -5.63023e-08 2.40398e-09 1 -2.49091e-08 -5.63023e-08 2.40398e-09 4321.83 98.6899 1262.56 3924.87 85.195 4361.16 +EDGE_SE3:QUAT 1884 1933 -5.71961 -6.29947 -2.73787 -0.126856 0.124866 0.029818 0.983579 1 7.70372e-19 7.70372e-19 1.32059e-10 5.46245e-08 6.84592e-09 1 7.70372e-19 1.32059e-10 5.46245e-08 6.84592e-09 1 1.32059e-10 5.46245e-08 6.84592e-09 4208.99 -68.2959 1080.82 3938.27 -34.5561 4269.81 +EDGE_SE3:QUAT 1885 1935 -5.25852 0.0155489 -3.41512 -0.051218 -0.0853375 0.0568238 0.993411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4094.23 26.993 -655.843 3976.33 -28.0039 4091.81 +EDGE_SE3:QUAT 1884 1935 -5.74787 6.1956 -3.36797 0.148267 0.0472412 -0.0335346 0.987249 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3957.37 31.5687 428.237 3988.85 2.12148 4040.81 +EDGE_SE3:QUAT 1885 1934 -5.98148 -6.55532 -3.61103 0.0198111 0.0824905 -0.194742 0.977179 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4112.35 -26.8806 684.659 3976.37 -68.5204 3962.22 +EDGE_SE3:QUAT 1886 1936 -5.17882 0.259538 -3.19881 -0.0430399 -0.0116188 0.172695 0.983966 1 4.81482e-20 4.81482e-20 -1.36549e-08 -2.40156e-09 -5.20123e-11 1 4.81482e-20 -1.36549e-08 -2.40156e-09 -5.20123e-11 1 -1.36549e-08 -2.40156e-09 -5.20123e-11 3992.35 -0.622404 -1.24711 3999.95 2.5831 3880.47 +EDGE_SE3:QUAT 1885 1936 -5.84806 6.49143 -3.306 0.128758 0.00580929 0.0875567 0.987786 1 1.92593e-19 1.92593e-19 4.64814e-10 -3.54728e-09 -2.74217e-08 1 1.92593e-19 4.64814e-10 -3.54728e-09 -2.74217e-08 1 4.64814e-10 -3.54728e-09 -2.74217e-08 3935.15 -8.51948 -88.3303 3998.89 -5.70847 3970.8 +EDGE_SE3:QUAT 1886 1935 -5.63735 -6.28503 -3.28819 -0.0330224 -0.00292515 -0.0367895 0.998773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.99 0.68865 -37.8738 3999.89 0.770795 3994.94 +EDGE_SE3:QUAT 1887 1937 -5.25932 -0.0673475 -3.52084 0.0352149 -0.077077 -0.0309557 0.995922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4086.97 -15.7396 -613.368 3978.07 14.9657 4088.1 +EDGE_SE3:QUAT 1886 1937 -5.69346 6.37218 -3.27589 0.0406481 -0.0877133 -0.0122582 0.995241 1 2.40741e-19 2.40741e-19 -1.34787e-08 2.78966e-08 1.14806e-11 1 2.40741e-19 -1.34787e-08 2.78966e-08 1.14806e-11 1 -1.34787e-08 2.78966e-08 1.14806e-11 4116.46 -17.8975 -712.337 3970.45 12.358 4122.47 +EDGE_SE3:QUAT 1887 1936 -5.51629 -6.30264 -3.04449 0.155653 -0.0335413 -0.157241 0.97464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3900.84 10.9314 35.4838 3998.83 -11.0426 3898.86 +EDGE_SE3:QUAT 1888 1938 -5.32596 0.174419 -3.41732 0.0664039 -0.0183872 0.125657 0.989678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.78 -6.83658 -242.362 3995.53 -16.1072 3951.26 +EDGE_SE3:QUAT 1887 1938 -5.86833 6.19555 -3.2398 -0.108 -0.175442 0.0993376 0.973493 1 1.92593e-19 1.92593e-19 -4.2119e-09 -4.3233e-09 2.83682e-08 1 1.92593e-19 -4.2119e-09 -4.3233e-09 2.83682e-08 1 -4.2119e-09 -4.3233e-09 2.83682e-08 4350.55 157.059 -1324.23 3936.4 -155.825 4357.74 +EDGE_SE3:QUAT 1888 1937 -5.64136 -6.28624 -3.35464 0.0393225 -0.176987 0.0742522 0.98062 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4565.94 24.4654 -1617.36 3871.79 -45.4644 4550.08 +EDGE_SE3:QUAT 1889 1939 -5.07242 0.223601 -3.45333 -0.105844 0.0484 -0.00331942 0.993199 1 2.52778e-19 2.52778e-19 2.78286e-08 -1.49015e-08 6.74208e-09 1 2.52778e-19 2.78286e-08 -1.49015e-08 6.74208e-09 1 2.78286e-08 -1.49015e-08 6.74208e-09 3990.85 -20.5552 379.408 3991.74 -6.43073 4035.62 +EDGE_SE3:QUAT 1888 1939 -5.76775 6.23718 -3.16821 -0.113763 0.0331446 0.100976 0.987807 1 1.92593e-19 1.92593e-19 2.75514e-08 2.54324e-09 1.51713e-09 1 1.92593e-19 2.75514e-08 2.54324e-09 1.51713e-09 1 2.75514e-08 2.54324e-09 1.51713e-09 3986.63 -20.2544 395.642 3988.75 16.7516 3997.61 +EDGE_SE3:QUAT 1889 1938 -5.76817 -6.00625 -3.28152 0.0329253 -0.0532648 -0.0686291 0.995675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4034.96 -10.7966 -398.584 3991.03 15.7266 4020.46 +EDGE_SE3:QUAT 1890 1940 -5.42125 -0.359117 -3.37604 0.0430829 0.00840573 -0.06304 0.997045 1 3.00927e-21 3.00927e-21 2.1545e-10 3.4594e-09 -1.44655e-10 1 3.00927e-21 2.1545e-10 3.4594e-09 -1.44655e-10 1 2.1545e-10 3.4594e-09 -1.44655e-10 3995.01 2.1682 99.1853 3999.26 -3.32916 3986.53 +EDGE_SE3:QUAT 1889 1940 -5.98667 6.17462 -3.27167 0.0392517 -0.0231473 0.046509 0.997878 1 6.01853e-20 6.01853e-20 -6.04613e-11 -6.41094e-09 1.41234e-08 1 6.01853e-20 -6.04613e-11 -6.41094e-09 1.41234e-08 1 -6.04613e-11 -6.41094e-09 1.41234e-08 4004.46 -3.50492 -206.518 3997.2 -4.39531 4001.97 +EDGE_SE3:QUAT 1890 1939 -5.89077 -5.97495 -2.80096 -0.00798407 0.120483 -0.00118024 0.992683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4242.41 -5.11731 1014.67 3941.99 -3.67748 4242.66 +EDGE_SE3:QUAT 1891 1941 -5.19549 0.0843934 -3.29703 0.0596822 -0.0537894 -0.0211049 0.996544 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.63 -14.0047 -416.393 3989.88 8.40097 4041.09 +EDGE_SE3:QUAT 1890 1941 -5.66953 6.11332 -3.17434 0.0703933 -0.0170307 0.0635396 0.995348 1 4.81482e-20 4.81482e-20 3.56181e-10 -9.40848e-10 -1.38285e-08 1 4.81482e-20 3.56181e-10 -9.40848e-10 -1.38285e-08 1 3.56181e-10 -9.40848e-10 -1.38285e-08 3988.95 -6.51628 -188.182 3997.43 -5.72877 3992.62 +EDGE_SE3:QUAT 1891 1940 -5.38492 -6.47284 -3.07337 0.0770001 0.0232715 -0.0935818 0.992357 1 1.20371e-20 1.20371e-20 6.18113e-10 6.88873e-09 -4.95857e-10 1 1.20371e-20 6.18113e-10 6.88873e-09 -4.95857e-10 1 6.18113e-10 6.88873e-09 -4.95857e-10 3994.12 9.29184 268.939 3994.74 -12.1621 3982.81 +EDGE_SE3:QUAT 1892 1942 -5.14839 0.0320784 -3.6118 -0.133898 0.0892309 -0.070735 0.984432 1 7.70372e-19 7.70372e-19 -5.52274e-08 5.21985e-09 -3.70308e-09 1 7.70372e-19 -5.52274e-08 5.21985e-09 -3.70308e-09 1 -5.52274e-08 5.21985e-09 -3.70308e-09 4011.51 -48.8548 585.475 3985.68 -39.6231 4063.21 +EDGE_SE3:QUAT 1891 1942 -5.92854 6.48706 -3.09113 0.0358711 0.0123595 0.106465 0.993592 1 5.11575e-20 5.11575e-20 1.34184e-08 4.93334e-09 -6.88847e-11 1 5.11575e-20 1.34184e-08 4.93334e-09 -6.88847e-11 1 1.34184e-08 4.93334e-09 -6.88847e-11 3995.45 0.793558 51.5606 3999.94 1.95184 3955.26 +EDGE_SE3:QUAT 1892 1941 -5.36334 -6.04372 -3.10388 0.0486247 -0.0944793 0.054709 0.992832 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4148.05 -8.85018 -809.256 3961.42 -13.0264 4145.54 +EDGE_SE3:QUAT 1893 1943 -4.95404 -0.0765379 -3.45393 -0.0475312 0.0152231 0.0311921 0.998267 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3995.79 -3.23749 139.107 3998.7 1.93871 4000.93 +EDGE_SE3:QUAT 1892 1943 -5.95063 6.11043 -3.18645 -0.00383348 -0.0200149 0.0561338 0.998215 1 1.27894e-20 1.27894e-20 -1.3421e-09 -7.02423e-09 -8.2492e-12 1 1.27894e-20 -1.3421e-09 -7.02423e-09 -8.2492e-12 1 -1.3421e-09 -7.02423e-09 -8.2492e-12 4006.09 0.82413 -156.99 3998.51 -4.42887 3993.55 +EDGE_SE3:QUAT 1893 1942 -5.52506 -6.39371 -3.42225 0.0385486 0.014987 -0.0545855 0.997652 1 4.81482e-20 4.81482e-20 1.38542e-08 -7.40138e-10 2.6461e-10 1 4.81482e-20 1.38542e-08 -7.40138e-10 2.6461e-10 1 1.38542e-08 -7.40138e-10 2.6461e-10 3999.25 2.55348 144.452 3998.57 -3.89693 3993.28 +EDGE_SE3:QUAT 1894 1944 -5.15105 -0.184654 -3.29991 -0.00255589 0.086695 0.0724468 0.993594 1 1.88079e-22 1.88079e-22 -8.74902e-10 -6.43737e-11 -7.58555e-11 1 1.88079e-22 -8.74902e-10 -6.43737e-11 -7.58555e-11 1 -8.74902e-10 -6.43737e-11 -7.58555e-11 4121.82 12.5144 708.68 3970.99 27.1967 4100.85 +EDGE_SE3:QUAT 1893 1944 -5.92616 6.07332 -3.32082 -0.00818444 0.0385324 0.149265 0.988012 1 1.88079e-22 1.88079e-22 8.59646e-10 1.2971e-10 3.41331e-11 1 1.88079e-22 8.59646e-10 1.2971e-10 3.41331e-11 1 8.59646e-10 1.2971e-10 3.41331e-11 4024.25 4.22275 314.143 3994.4 23.6275 3935.4 +EDGE_SE3:QUAT 1894 1943 -5.76121 -6.2646 -2.86926 -0.0390798 0.0254796 -0.146184 0.988157 1 8.30557e-19 8.30557e-19 -1.34169e-08 1.1397e-08 -5.47515e-08 1 8.30557e-19 -1.34169e-08 1.1397e-08 -5.47515e-08 1 -1.34169e-08 1.1397e-08 -5.47515e-08 3997.9 -3.21984 129.384 3999.47 -7.96642 3918.53 +EDGE_SE3:QUAT 1895 1945 -5.43817 0.0746979 -3.15962 0.230416 0.001229 -0.0536502 0.971611 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3792.93 22.8982 152.038 3997.64 -4.11378 3993.79 +EDGE_SE3:QUAT 1894 1945 -5.97612 6.30314 -2.96295 -0.0275204 0.0748202 -0.0147909 0.996707 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4086.27 -10.7862 604.286 3978.3 -8.45854 4088.42 +EDGE_SE3:QUAT 1895 1944 -5.68272 -5.86521 -3.01997 0.147347 0.0258293 -0.0604969 0.986895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3936.19 23.3814 305.803 3993.32 -5.85992 4008.4 +EDGE_SE3:QUAT 1896 1946 -5.48235 0.131589 -3.21251 0.00662379 -0.0366716 0.00759876 0.999277 1 4.81482e-20 4.81482e-20 -9.89745e-11 1.38678e-08 -8.44118e-11 1 4.81482e-20 -9.89745e-11 1.38678e-08 -8.44118e-11 1 -9.89745e-11 1.38678e-08 -8.44118e-11 4021.51 -0.744969 -295.329 3994.6 -0.922839 4021.46 +EDGE_SE3:QUAT 1895 1946 -5.60899 6.21087 -3.3708 -0.00569916 -0.0299489 -0.0147844 0.999426 1 1.27894e-20 1.27894e-20 -1.83726e-09 -6.9098e-09 1.88668e-11 1 1.27894e-20 -1.83726e-09 -6.9098e-09 1.88668e-11 1 -1.83726e-09 -6.9098e-09 1.88668e-11 4014.37 0.373318 -241.277 3996.38 1.67876 4013.63 +EDGE_SE3:QUAT 1896 1945 -5.83583 -5.64283 -3.19586 0.10401 0.0510566 0.00616616 0.993246 1 1.95602e-19 1.95602e-19 2.78737e-08 8.31577e-10 4.8202e-09 1 1.95602e-19 2.78737e-08 8.31577e-10 4.8202e-09 1 2.78737e-08 8.31577e-10 4.8202e-09 3995.83 21.3423 397.469 3990.99 7.50768 4038.95 +EDGE_SE3:QUAT 1897 1947 -5.36216 0.0567657 -3.70098 -0.0451375 0.0081287 -0.102129 0.993713 1 2.40929e-19 2.40929e-19 1.36672e-08 -3.55616e-09 2.75239e-08 1 2.40929e-19 1.36672e-08 -3.55616e-09 2.75239e-08 1 1.36672e-08 -3.55616e-09 2.75239e-08 3991.78 0.207249 8.95427 4000 0.498099 3958.21 +EDGE_SE3:QUAT 1896 1947 -5.71569 6.28333 -3.49175 0.0758603 0.0836852 0.258635 0.959349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.02 29.873 372.463 4000.71 42.2719 3763.47 +EDGE_SE3:QUAT 1897 1946 -5.46386 -5.85812 -3.3704 0.0133332 0.0819793 -0.0633247 0.994531 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4111.14 -5.87557 678.158 3972.87 -20.8244 4095.81 +EDGE_SE3:QUAT 1898 1948 -5.05214 0.164301 -2.76411 -0.00266006 0.180257 -0.0117162 0.983546 1 3.00927e-21 3.00927e-21 -3.64931e-09 5.02343e-11 -6.68361e-10 1 3.00927e-21 -3.64931e-09 5.02343e-11 -6.68361e-10 1 -3.64931e-09 5.02343e-11 -6.68361e-10 4574.66 -13.6617 1621.43 3870.35 -15.2781 4574.14 +EDGE_SE3:QUAT 1897 1948 -5.93618 5.88721 -3.27276 -0.0279999 -0.189233 -0.0424886 0.980613 1 7.70372e-19 7.70372e-19 -1.91677e-09 -5.44523e-08 -7.2589e-10 1 7.70372e-19 -1.91677e-09 -5.44523e-08 -7.2589e-10 1 -1.91677e-09 -5.44523e-08 -7.2589e-10 4646.94 -10.3646 -1738.65 3855.2 22.3143 4642.85 +EDGE_SE3:QUAT 1898 1947 -5.26206 -5.80329 -3.25822 -0.110787 -0.0021894 -0.117821 0.986833 1 1.95602e-19 1.95602e-19 -2.78109e-08 -2.45556e-10 4.01247e-10 1 1.95602e-19 -2.78109e-08 -2.45556e-10 4.01247e-10 1 -2.78109e-08 -2.45556e-10 4.01247e-10 3957.6 11.5399 -171.035 3996.99 12.375 3951.17 +EDGE_SE3:QUAT 1899 1949 -5.61937 0.09798 -2.73389 -0.249683 0.0620375 -0.0459273 0.965246 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3774.43 -35.1223 317.681 3998.67 -18.2959 4015.36 +EDGE_SE3:QUAT 1898 1949 -5.93777 5.64638 -3.55401 0.0560691 0.00833484 0.0932437 0.994028 1 1.92593e-19 1.92593e-19 6.26577e-11 -1.57211e-09 -2.75894e-08 1 1.92593e-19 6.26577e-11 -1.57211e-09 -2.75894e-08 1 6.26577e-11 -1.57211e-09 -2.75894e-08 3987.32 -0.497556 3.2517 3999.98 -0.836692 3965.11 +EDGE_SE3:QUAT 1899 1948 -6.02824 -6.25715 -3.03075 -0.0768605 0.00583966 -0.0743998 0.994245 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.36 1.74206 -22.1804 3999.87 1.6863 3977.85 +EDGE_SE3:QUAT 1900 1950 -5.372 0.0899537 -3.0465 -0.0123151 0.17098 -0.0142124 0.985095 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4509.13 -23.7689 1516.17 3884.14 -24.1242 4508.93 +EDGE_SE3:QUAT 1899 1950 -5.72996 5.92394 -3.16469 0.0428913 -0.0198911 -0.00947996 0.998837 1 5.11575e-20 5.11575e-20 1.39379e-08 -3.05281e-10 -3.73187e-09 1 5.11575e-20 1.39379e-08 -3.05281e-10 -3.73187e-09 1 1.39379e-08 -3.05281e-10 -3.73187e-09 3998.56 -3.36303 -153.989 3998.57 1.11176 4005.56 +EDGE_SE3:QUAT 1900 1949 -5.51662 -6.07 -3.12497 0.0180443 0.0129921 0.131959 0.991006 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000 0.881815 72.958 3999.79 4.17288 3931.65 +EDGE_SE3:QUAT 1901 1951 -5.52206 -0.112958 -3.51601 -0.0738568 -0.120536 -0.0227254 0.989697 1 1.92593e-19 1.92593e-19 -2.83178e-08 1.43168e-10 3.5058e-09 1 1.92593e-19 -2.83178e-08 1.43168e-10 3.5058e-09 1 -2.83178e-08 1.43168e-10 3.5058e-09 4227.61 35.4525 -1029.54 3941.16 -14.7395 4247.37 +EDGE_SE3:QUAT 1900 1951 -5.77374 5.9544 -3.27572 0.20321 0.120279 -0.0780849 0.968577 1 4.81482e-20 4.81482e-20 2.03166e-09 2.72415e-09 1.39796e-08 1 4.81482e-20 2.03166e-09 2.72415e-09 1.39796e-08 1 2.03166e-09 2.72415e-09 1.39796e-08 4147.14 107.572 1160.69 3931.27 40.1375 4287.93 +EDGE_SE3:QUAT 1901 1950 -5.75525 -6.21588 -2.88021 -0.0440092 -0.0339751 0.076903 0.995487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.23 6.40479 -228.732 3997.28 -9.26095 3989.32 +EDGE_SE3:QUAT 1902 1952 -5.71636 -0.166639 -3.41545 -0.134996 -0.118334 0.0206628 0.983538 1 9.62965e-19 9.62965e-19 5.45322e-08 3.02701e-08 -2.17156e-09 1 9.62965e-19 5.45322e-08 3.02701e-08 -2.17156e-09 1 5.45322e-08 3.02701e-08 -2.17156e-09 4130.32 76.5765 -924.695 3958.48 -54.6738 4201.5 +EDGE_SE3:QUAT 1901 1952 -5.66359 6.09914 -2.84014 -0.109257 -0.201466 -0.0445723 0.972362 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4721.44 97.5847 -1915.3 3837.35 -73.9051 4761.24 +EDGE_SE3:QUAT 1902 1951 -5.41805 -6.18651 -3.01054 -0.0321486 -0.0833421 -0.232666 0.968446 1 3.00927e-21 3.00927e-21 3.41522e-09 -8.12838e-10 -3.13241e-10 1 3.00927e-21 3.41522e-09 -8.12838e-10 -3.13241e-10 1 3.41522e-09 -8.12838e-10 -3.13241e-10 4121.27 -32.0137 -719.326 3975.25 85.734 3908.87 +EDGE_SE3:QUAT 1903 1953 -5.55802 0.147616 -3.2256 0.143828 0.0664733 -0.0511814 0.98604 1 7.70372e-19 7.70372e-19 -5.53755e-08 1.71339e-09 -4.38448e-09 1 7.70372e-19 -5.53755e-08 1.71339e-09 -4.38448e-09 1 -5.53755e-08 1.71339e-09 -4.38448e-09 4009.16 41.3997 613.491 3977.31 2.06871 4081.43 +EDGE_SE3:QUAT 1902 1953 -5.68928 5.80354 -3.423 -0.0490166 0.0259791 0.11428 0.991898 1 1.92593e-19 1.92593e-19 1.0102e-09 -1.16607e-09 2.75941e-08 1 1.92593e-19 1.0102e-09 -1.16607e-09 2.75941e-08 1 1.0102e-09 -1.16607e-09 2.75941e-08 4008.55 -4.36866 270.789 3994.95 15.5962 3965.92 +EDGE_SE3:QUAT 1903 1952 -5.55087 -6.23803 -3.42172 0.148784 -0.022427 -0.0789488 0.985458 1 7.73381e-19 7.73381e-19 5.49862e-08 -1.13741e-09 -4.09852e-10 1 7.73381e-19 5.49862e-08 -1.13741e-09 -4.09852e-10 1 5.49862e-08 -1.13741e-09 -4.09852e-10 3911.12 1.07716 -33.4526 4000.03 -0.408694 3974.74 +EDGE_SE3:QUAT 1904 1954 -5.43857 0.399089 -2.97938 -0.0277226 -0.0501785 0.0413893 0.997497 1 4.81482e-20 4.81482e-20 6.14972e-10 -1.38413e-08 -4.43035e-10 1 4.81482e-20 6.14972e-10 -1.38413e-08 -4.43035e-10 1 6.14972e-10 -1.38413e-08 -4.43035e-10 4034.45 7.84677 -389.255 3991.05 -9.75186 4030.67 +EDGE_SE3:QUAT 1903 1954 -5.92474 5.96293 -3.27509 -0.215788 0.0704441 0.0809564 0.970525 1 1.92593e-19 1.92593e-19 -1.23715e-09 2.70027e-08 5.68802e-09 1 1.92593e-19 -1.23715e-09 2.70027e-08 5.68802e-09 1 -1.23715e-09 2.70027e-08 5.68802e-09 3948.14 -77.1844 746.307 3967.22 -6.28434 4108.18 +EDGE_SE3:QUAT 1904 1953 -5.91001 -5.85105 -3.2111 -0.124559 -0.0222389 -0.0968941 0.987219 1 1.92593e-19 1.92593e-19 -2.74861e-08 2.46551e-09 1.2531e-09 1 1.92593e-19 -2.74861e-08 2.46551e-09 1.2531e-09 1 -2.74861e-08 2.46551e-09 1.2531e-09 3962.28 19.7734 -315.761 3992.29 13.8681 3986.79 +EDGE_SE3:QUAT 1905 1955 -5.40534 -0.0451729 -3.39785 -0.0206651 0.138896 -0.159817 0.977108 1 9.62965e-19 9.62965e-19 3.52237e-08 -8.69406e-09 5.97134e-08 1 9.62965e-19 3.52237e-08 -8.69406e-09 5.97134e-08 1 3.52237e-08 -8.69406e-09 5.97134e-08 4274.47 -85.357 1087.66 3948.34 -110.875 4174.02 +EDGE_SE3:QUAT 1904 1955 -5.86914 5.85767 -3.47438 -0.129302 -0.143317 -0.0450677 0.980158 1 7.82409e-19 7.82409e-19 5.58696e-08 -1.3203e-09 -1.59061e-09 1 7.82409e-19 5.58696e-08 -1.3203e-09 -1.59061e-09 1 5.58696e-08 -1.3203e-09 -1.59061e-09 4310 76.9239 -1284.35 3915.49 -39.6567 4368.75 +EDGE_SE3:QUAT 1905 1954 -5.39267 -5.95195 -3.24789 -0.0802647 0.145185 -0.00430664 0.986134 1 1.92593e-19 1.92593e-19 -2.85492e-08 8.23067e-10 -4.12544e-09 1 1.92593e-19 -2.85492e-08 8.23067e-10 -4.12544e-09 1 -2.85492e-08 8.23067e-10 -4.12544e-09 4323.6 -62.7122 1232.74 3921.7 -47.4209 4349.3 +EDGE_SE3:QUAT 1906 1956 -5.43149 0.17423 -3.06112 -0.0873013 -0.0525061 0.0619235 0.992868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.79 17.7248 -350.31 3993.94 -14.7606 4014.94 +EDGE_SE3:QUAT 1905 1956 -5.78884 5.78818 -3.36153 -0.058238 -0.0799986 0.0144569 0.994987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4086.3 21.951 -639.91 3976.3 -13.8293 4099.03 +EDGE_SE3:QUAT 1906 1955 -5.73036 -5.9317 -3.06604 -0.152841 -0.124101 -0.194414 0.960959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4336.78 15.3446 -1381.97 3897.83 78.8289 4279.04 +EDGE_SE3:QUAT 1907 1957 -5.11673 -0.111477 -2.9244 -0.23414 0.129311 -0.116485 0.956498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3866.17 -85.1907 615.465 4002.13 -76.7952 4031.18 +EDGE_SE3:QUAT 1906 1957 -5.87182 6.18721 -3.39776 0.0272469 -0.101649 -0.0010582 0.994447 1 1.20371e-20 1.20371e-20 -7.04561e-09 4.74948e-11 7.18669e-10 1 1.20371e-20 -7.04561e-09 4.74948e-11 7.18669e-10 1 -7.04561e-09 4.74948e-11 7.18669e-10 4167.07 -12.9967 -842.063 3958.99 7.58572 4170.03 +EDGE_SE3:QUAT 1907 1956 -5.7052 -5.85319 -2.72716 0.0844198 -0.0784144 -0.237926 0.964425 1 9.62965e-19 9.62965e-19 -2.84716e-08 1.318e-08 5.45225e-08 1 9.62965e-19 -2.84716e-08 1.318e-08 5.45225e-08 1 -2.84716e-08 1.318e-08 5.45225e-08 3996.49 -25.0089 -336.067 4000.38 34.4766 3798.56 +EDGE_SE3:QUAT 1908 1958 -5.78212 0.239475 -3.56775 0.356487 0.0281349 -0.0808603 0.930369 1 1.92593e-19 1.92593e-19 2.08493e-09 9.76579e-09 2.60523e-08 1 1.92593e-19 2.08493e-09 9.76579e-09 2.60523e-08 1 2.08493e-09 9.76579e-09 2.60523e-08 3553.72 103.805 505.449 3983.78 3.31877 4035.89 +EDGE_SE3:QUAT 1907 1958 -5.91635 5.84241 -3.01824 -0.0415693 -0.024604 0.108901 0.992878 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.81 3.44471 -139.071 3999.2 -6.90668 3957.29 +EDGE_SE3:QUAT 1908 1957 -5.73142 -5.86921 -3.21623 0.0777694 0.0540119 0.185946 0.977987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.52 12.2844 236.802 3999.3 18.4657 3874.41 +EDGE_SE3:QUAT 1909 1959 -5.33926 0.0510347 -2.9403 0.0320131 0.066384 0.0263705 0.996932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4064.22 11.5137 527.207 3983.54 10.5589 4065.53 +EDGE_SE3:QUAT 1908 1959 -5.77973 5.75624 -3.47994 -0.0426209 0.0203214 0.135975 0.989586 1 4.81482e-20 4.81482e-20 1.37556e-08 1.86138e-09 4.30665e-10 1 4.81482e-20 1.37556e-08 1.86138e-09 4.30665e-10 1 1.37556e-08 1.86138e-09 4.30665e-10 4005.48 -3.0005 226.988 3996.37 16.2696 3938.79 +EDGE_SE3:QUAT 1909 1958 -5.75691 -6.07824 -2.97853 0.14739 -0.187342 -0.129689 0.962476 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4269.39 -198.665 -1254.78 3967.31 196.921 4289.01 +EDGE_SE3:QUAT 1910 1960 -5.55625 0.0598845 -3.03105 0.144372 0.0324729 -0.0215948 0.988755 1 7.70372e-19 7.70372e-19 -5.50331e-08 6.37304e-10 -2.07452e-09 1 7.70372e-19 -5.50331e-08 6.37304e-10 -2.07452e-09 1 -5.50331e-08 6.37304e-10 -2.07452e-09 3937.51 21.2345 289.834 3994.85 1.10947 4019.02 +EDGE_SE3:QUAT 1909 1960 -5.8482 5.94042 -3.5659 0.158001 -0.0362575 0.122148 0.979184 1 4.81482e-20 4.81482e-20 -1.46363e-09 1.36158e-08 -2.01907e-09 1 4.81482e-20 -1.46363e-09 1.36158e-08 -2.01907e-09 1 -1.46363e-09 1.36158e-08 -2.01907e-09 3962.4 -37.081 -506.617 3981.12 -23.5857 4002.57 +EDGE_SE3:QUAT 1910 1959 -5.69124 -5.9684 -2.95238 0.107803 -0.137397 -0.0908835 0.980429 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4184.82 -95.5123 -991.47 3959.44 92.712 4198.26 +EDGE_SE3:QUAT 1911 1961 -5.32259 -0.0215327 -3.50625 -0.171713 0.11404 0.149851 0.966982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4235.94 -57.6926 1242.65 3913.7 29.3816 4264.06 +EDGE_SE3:QUAT 1910 1961 -6.03801 5.84375 -2.88197 0.21488 0.0767489 0.0580681 0.971887 1 1.92593e-19 1.92593e-19 1.23999e-09 6.26096e-09 2.71293e-08 1 1.92593e-19 1.23999e-09 6.26096e-09 2.71293e-08 1 1.23999e-09 6.26096e-09 2.71293e-08 3858.7 45.505 425.819 3995.74 28.995 4029.91 +EDGE_SE3:QUAT 1911 1960 -5.93142 -6.09937 -3.01153 0.219719 -0.00648504 -0.0160039 0.97541 1 1.88079e-22 1.88079e-22 -1.49522e-11 -8.46015e-10 1.90657e-10 1 1.88079e-22 -1.49522e-11 -8.46015e-10 1.90657e-10 1 -1.49522e-11 -8.46015e-10 1.90657e-10 3806.85 0.881356 -7.3164 4000 -0.0422137 3998.93 +EDGE_SE3:QUAT 1912 1962 -5.37533 -0.194048 -3.32662 -0.22973 -0.0381504 -0.119868 0.965091 1 7.70372e-19 7.70372e-19 5.41986e-08 -5.09707e-09 -4.85824e-09 1 7.70372e-19 5.41986e-08 -5.09707e-09 -4.85824e-09 1 5.41986e-08 -5.09707e-09 -4.85824e-09 3876.88 70.3442 -604.882 3973.58 18.045 4030.51 +EDGE_SE3:QUAT 1911 1962 -5.3701 6.01884 -3.10308 0.150736 0.0628568 0.210263 0.963907 1 7.70372e-19 7.70372e-19 -3.98507e-10 9.07233e-09 5.34846e-08 1 7.70372e-19 -3.98507e-10 9.07233e-09 5.34846e-08 1 -3.98507e-10 9.07233e-09 5.34846e-08 3905.92 -1.86541 87.8157 4000.8 -4.20563 3819.96 +EDGE_SE3:QUAT 1912 1961 -5.73371 -6.19649 -2.98464 -0.00802518 0.0697582 -0.104871 0.992004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4073.24 -14.2018 547.259 3983.23 -30.6985 4029.51 +EDGE_SE3:QUAT 1913 1963 -5.3739 -0.217596 -3.18258 -0.0420106 0.0200935 0.023173 0.998646 1 1.20371e-20 1.20371e-20 1.52434e-10 -2.85246e-10 6.93591e-09 1 1.20371e-20 1.52434e-10 -2.85246e-10 6.93591e-09 1 1.52434e-10 -2.85246e-10 6.93591e-09 4000.33 -3.46047 172.149 3998.09 1.59323 4005.24 +EDGE_SE3:QUAT 1912 1963 -5.64523 5.73839 -3.30537 -0.0184915 -0.0102083 0.0393575 0.999002 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.95 0.72792 -72.7316 3999.7 -1.41256 3995.12 +EDGE_SE3:QUAT 1913 1962 -5.72327 -5.94802 -3.02907 0.295072 -0.0767289 -0.0614519 0.950405 1 3.08149e-18 3.08149e-18 -1.05854e-07 1.05389e-08 3.081e-09 1 3.08149e-18 -1.05854e-07 1.05389e-08 3.081e-09 1 -1.05854e-07 1.05389e-08 3.081e-09 3674.93 -38.2563 -326.271 4001.87 24.5268 4008.09 +EDGE_SE3:QUAT 1914 1964 -5.30525 0.27847 -2.99766 0.141942 -0.149231 -0.0761681 0.975593 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4186.2 -122.134 -1069.94 3957.54 111.903 4243.59 +EDGE_SE3:QUAT 1913 1964 -5.74542 5.8854 -3.08893 -0.056718 0.0441545 0.00192346 0.997412 1 1.17549e-23 1.17549e-23 9.59749e-12 -1.23583e-11 2.17127e-10 1 1.17549e-23 9.59749e-12 -1.23583e-11 2.17127e-10 1 9.59749e-12 -1.23583e-11 2.17127e-10 4018.44 -10.1872 355.255 3992.33 -2.33015 4031.29 +EDGE_SE3:QUAT 1914 1963 -5.51539 -6.02837 -2.80163 -0.13599 -0.144559 -0.0535229 0.978644 1 7.70372e-19 7.70372e-19 5.69816e-08 -7.9572e-10 -8.92744e-09 1 7.70372e-19 5.69816e-08 -7.9572e-10 -8.92744e-09 1 5.69816e-08 -7.9572e-10 -8.92744e-09 4318.92 79.5284 -1313.78 3911.92 -38.6485 4381.44 +EDGE_SE3:QUAT 1915 1965 -5.22701 -0.103785 -3.01899 0.0783535 0.103385 0.00798106 0.991518 1 1.92593e-19 1.92593e-19 -2.81023e-08 -6.9345e-10 -2.85677e-09 1 1.92593e-19 -2.81023e-08 -6.9345e-10 -2.85677e-09 1 -2.81023e-08 -6.9345e-10 -2.85677e-09 4145.32 38.5557 841.686 3960.64 24.3178 4169.62 +EDGE_SE3:QUAT 1914 1965 -6.09836 5.6236 -3.31964 0.162461 0.00655449 0.0578307 0.984997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3895 -7.99803 -60.4005 3999.39 -2.78653 3987.19 +EDGE_SE3:QUAT 1915 1964 -6.02475 -5.83798 -3.25967 0.070973 0.0782712 -0.0897143 0.990347 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4101.88 11.7486 709.444 3969.31 -22.4426 4089.83 +EDGE_SE3:QUAT 1916 1966 -5.27215 -0.0550451 -2.90971 -0.242019 0.184326 -0.0723972 0.949847 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4084.36 -215.062 1186.05 3986.44 -199.919 4297.69 +EDGE_SE3:QUAT 1915 1966 -5.72452 6.15158 -3.06675 0.215732 0.0878103 -0.0476405 0.971329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3967.7 86.1604 799.466 3966.98 28.35 4144.78 +EDGE_SE3:QUAT 1916 1965 -5.77162 -5.83695 -3.25941 -0.135063 0.00983051 -0.0165169 0.990651 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3927.63 -2.74819 50.0315 3999.92 -0.495308 3999.51 +EDGE_SE3:QUAT 1917 1967 -5.49158 0.0205048 -3.19738 0.0285492 0.00746192 0.196589 0.980042 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.63 -0.47362 -9.38322 3999.93 -3.24699 3845.3 +EDGE_SE3:QUAT 1916 1967 -6.04732 5.90511 -3.23606 -0.196302 0.0522525 0.318886 0.925768 1 9.62965e-19 9.62965e-19 4.55388e-08 4.20974e-08 1.2519e-08 1 9.62965e-19 4.55388e-08 4.20974e-08 1.2519e-08 1 4.55388e-08 4.20974e-08 1.2519e-08 4120.99 -30.2456 1094.24 3921.19 161.656 3868.38 +EDGE_SE3:QUAT 1917 1966 -5.87633 -5.9373 -2.91136 0.0253532 -0.227797 -0.278911 0.932563 1 3.08149e-18 3.08149e-18 -2.07316e-08 1.86853e-08 1.1205e-07 1 3.08149e-18 -2.07316e-08 1.86853e-08 1.1205e-07 1 -2.07316e-08 1.86853e-08 1.1205e-07 4616.69 -362.737 -1702.48 3984.9 374.582 4308.09 +EDGE_SE3:QUAT 1918 1968 -5.25048 0.259951 -3.10762 0.0322364 0.079893 -0.120692 0.988945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4110.89 -8.73768 688.078 3972.49 -39.6284 4056.78 +EDGE_SE3:QUAT 1917 1968 -5.67838 5.9095 -2.9385 0.00457327 0.074624 0.0305591 0.996733 1 1.20371e-20 1.20371e-20 5.20597e-10 6.46435e-11 6.99352e-09 1 1.20371e-20 5.20597e-10 6.46435e-11 6.99352e-09 1 5.20597e-10 6.46435e-11 6.99352e-09 4089.74 5.63485 606.096 3978.08 10.414 4086.09 +EDGE_SE3:QUAT 1918 1967 -5.30055 -6.00147 -2.96965 0.0178951 -0.043615 -0.218045 0.974799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4017.95 -9.59906 -279.728 3997.16 28.9433 3829.06 +EDGE_SE3:QUAT 1919 1969 -5.40989 0.106336 -3.45595 -0.0139702 0.0626476 -0.146048 0.987193 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4052.7 -15.6985 465.991 3988.87 -35.5244 3968.16 +EDGE_SE3:QUAT 1918 1969 -5.85382 6.22736 -3.05685 0.0319758 0.108872 -0.0543264 0.992055 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4200.2 -0.103348 926.775 3950.75 -18.6112 4192.49 +EDGE_SE3:QUAT 1919 1968 -6.07208 -5.68104 -2.9485 -0.0906637 0.0871956 -0.101326 0.986869 1 7.70372e-19 7.70372e-19 5.53461e-08 -6.5533e-09 3.66791e-09 1 7.70372e-19 5.53461e-08 -6.5533e-09 3.66791e-09 1 5.53461e-08 -6.5533e-09 3.66791e-09 4048.14 -39.8854 577.199 3985.39 -41.457 4039.95 +EDGE_SE3:QUAT 1920 1970 -5.97202 0.0581314 -3.21766 0.0317237 -0.0973144 -0.0340615 0.994165 1 2.40741e-19 2.40741e-19 -1.51877e-08 -2.70084e-08 2.41962e-09 1 2.40741e-19 -1.51877e-08 -2.70084e-08 2.41962e-09 1 -1.51877e-08 -2.70084e-08 2.41962e-09 4145.44 -21.4877 -787.553 3964.65 21.9536 4144.82 +EDGE_SE3:QUAT 1919 1970 -5.92917 5.73577 -2.77653 -0.175937 0.123697 0.18639 0.958647 1 7.70372e-19 7.70372e-19 -5.62967e-08 -8.13563e-09 -1.01772e-08 1 7.70372e-19 -5.62967e-08 -8.13563e-09 -1.01772e-08 1 -5.62967e-08 -8.13563e-09 -1.01772e-08 4326.51 -41.9909 1417.39 3892.1 58.5596 4311.36 +EDGE_SE3:QUAT 1920 1969 -5.93737 -5.90578 -3.05839 0.00656643 0.0443108 0.0747592 0.996195 1 2.43751e-19 2.43751e-19 -3.61295e-09 -1.44536e-08 -2.77209e-08 1 2.43751e-19 -3.61295e-09 -1.44536e-08 -2.77209e-08 1 -3.61295e-09 -1.44536e-08 -2.77209e-08 4029.85 4.58281 347.855 3992.85 13.455 4007.67 +EDGE_SE3:QUAT 1921 1971 -5.41818 0.254283 -3.06712 -0.0264279 0.116764 0.104796 0.987262 1 1.95602e-19 1.95602e-19 6.34124e-09 -2.70497e-08 3.7923e-10 1 1.95602e-19 6.34124e-09 -2.70497e-08 3.7923e-10 1 6.34124e-09 -2.70497e-08 3.7923e-10 4233.68 22.7718 1000.9 3945.11 51.026 4192.54 +EDGE_SE3:QUAT 1920 1971 -6.01132 5.65109 -3.30793 0.130887 0.042637 0.0823051 0.987054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3941.01 11.9264 201.654 3998.95 9.11437 3982.44 +EDGE_SE3:QUAT 1921 1970 -5.88634 -5.64343 -2.87231 -0.0836671 0.120599 -0.0238146 0.988883 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4196.68 -54.7856 974.408 3949.97 -42.7831 4222.41 +EDGE_SE3:QUAT 1922 1972 -5.11801 -0.191454 -2.70662 0.0769679 0.205962 0.153475 0.96338 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4525.04 232.803 1583.98 3928.9 240.597 4454.52 +EDGE_SE3:QUAT 1921 1972 -6.09128 5.6427 -3.0341 0.133351 -0.0303706 -0.0642129 0.98852 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3932.97 -7.09784 -133.703 3999.59 4.3784 3987.61 +EDGE_SE3:QUAT 1922 1971 -5.97799 -5.99252 -3.11043 -0.0396212 0.0440897 -0.0984448 0.993375 1 4.81482e-20 4.81482e-20 -1.41458e-09 -1.3781e-08 -6.60976e-10 1 4.81482e-20 -1.41458e-09 -1.3781e-08 -6.60976e-10 1 -1.41458e-09 -1.3781e-08 -6.60976e-10 4016.23 -9.36045 301.554 3995.34 -15.6925 3983.75 +EDGE_SE3:QUAT 1923 1973 -5.64818 -0.0648937 -3.22836 0.0425153 -0.20371 -0.123027 0.97034 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4635.17 -185.596 -1727.92 3887.16 195.867 4581.85 +EDGE_SE3:QUAT 1922 1973 -5.98771 6.08179 -3.14155 -0.0331101 -0.0485389 0.186663 0.980665 1 9.62965e-20 9.62965e-20 1.10097e-08 1.62471e-08 2.19484e-10 1 9.62965e-20 1.10097e-08 1.62471e-08 2.19484e-10 1 1.10097e-08 1.62471e-08 2.19484e-10 4017.07 11.5895 -296.083 3996.76 -26.4376 3882.09 +EDGE_SE3:QUAT 1923 1972 -5.62464 -5.40038 -3.26501 0.0680975 0.0245985 -0.0424296 0.996472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.62 7.47763 230.142 3996.46 -3.88234 4005.97 +EDGE_SE3:QUAT 1924 1974 -5.72869 0.100921 -3.02056 0.0596113 0.00250168 -0.0479273 0.997067 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.48 1.91008 53.9984 3999.74 -1.5187 3991.51 +EDGE_SE3:QUAT 1923 1974 -5.87459 5.83622 -3.42603 0.110911 -0.142584 0.0472117 0.982415 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4323.85 -60.6106 -1277.28 3914.64 26.6455 4364.14 +EDGE_SE3:QUAT 1924 1973 -5.83773 -5.62218 -2.82335 0.0986505 0.190308 -0.159707 0.96361 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4734.18 -57.5115 1921.08 3836.14 -103.756 4671.08 +EDGE_SE3:QUAT 1925 1975 -5.3902 0.195262 -3.44477 -0.000475353 0.0234077 -0.0107822 0.999668 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.77 -0.186879 187.526 3997.81 -1.02288 4008.31 +EDGE_SE3:QUAT 1924 1975 -6.12638 5.46839 -3.22623 -0.0772483 0.0891131 0.045792 0.991965 1 3.85186e-19 3.85186e-19 -2.89172e-08 2.664e-08 -7.36073e-10 1 3.85186e-19 -2.89172e-08 2.664e-08 -7.36073e-10 1 -2.89172e-08 2.664e-08 -7.36073e-10 4119.52 -23.0454 770.841 3964.81 2.89826 4135 +EDGE_SE3:QUAT 1925 1974 -5.79555 -5.66613 -2.95105 0.20793 0.0496706 -0.0799946 0.973601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3907.06 59.2713 572.91 3978.87 -3.49464 4054.41 +EDGE_SE3:QUAT 1926 1976 -5.59028 0.116294 -3.17158 0.00426384 -0.00761341 -0.0684639 0.997615 1 1.50463e-21 1.50463e-21 -1.84965e-09 -1.61168e-09 2.12059e-11 1 1.50463e-21 -1.84965e-09 -1.61168e-09 2.12059e-11 1 -1.84965e-09 -1.61168e-09 2.12059e-11 4000.74 -0.204936 -56.9954 3999.81 1.91264 3982.06 +EDGE_SE3:QUAT 1925 1976 -5.83207 5.60718 -3.19103 -0.0567011 -0.285189 0.102468 0.95129 1 7.70372e-19 7.70372e-19 -6.18345e-08 -1.02489e-08 1.70014e-08 1 7.70372e-19 -6.18345e-08 -1.02489e-08 1.70014e-08 1 -6.18345e-08 -1.02489e-08 1.70014e-08 5436.31 421.49 -2811.31 3796.02 -420.559 5407.17 +EDGE_SE3:QUAT 1926 1975 -5.28172 -5.6819 -3.25177 0.0800388 -0.0170729 -0.233137 0.968994 1 1.92593e-19 1.92593e-19 -2.68975e-08 6.46156e-09 -5.87724e-10 1 1.92593e-19 -2.68975e-08 6.46156e-09 -5.87724e-10 1 -2.68975e-08 6.46156e-09 -5.87724e-10 3975.07 6.67964 90.5486 3998.21 -19.7128 3783.28 +EDGE_SE3:QUAT 1927 1977 -5.94081 0.185167 -2.98209 -0.0674661 -0.153327 -0.139286 0.975981 1 4.81482e-20 4.81482e-20 1.43161e-08 -1.81924e-09 -2.42585e-09 1 4.81482e-20 1.43161e-08 -1.81924e-09 -2.42585e-09 1 1.43161e-08 -1.81924e-09 -2.42585e-09 4440.65 -36.7106 -1430.43 3897.37 80.9004 4381.25 +EDGE_SE3:QUAT 1926 1977 -6.18717 5.6459 -3.14047 0.0345798 -0.0884394 -0.0745292 0.992687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4109.38 -25.8881 -685.516 3974.21 33.249 4091.94 +EDGE_SE3:QUAT 1927 1976 -5.80858 -5.52692 -3.25038 0.0799596 -0.106992 -0.0344881 0.990439 1 2.40741e-19 2.40741e-19 -2.94861e-08 2.74059e-09 1.68621e-08 1 2.40741e-19 -2.94861e-08 2.74059e-09 1.68621e-08 1 -2.94861e-08 2.74059e-09 1.68621e-08 4144.45 -46.2167 -842.234 3962.21 37.3674 4165.27 +EDGE_SE3:QUAT 1928 1978 -5.09616 -0.226885 -2.42526 0.0703136 0.00799011 -0.0843857 0.993917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.55 5.08206 133.55 3998.5 -6.2615 3975.84 +EDGE_SE3:QUAT 1927 1978 -5.46809 5.39257 -2.91371 -0.126132 -0.00438587 0.166022 0.978012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3946.02 -17.1638 211.682 3994.71 23.4497 3899.4 +EDGE_SE3:QUAT 1928 1977 -5.53476 -5.66536 -2.6525 -0.0313804 -0.137503 -0.0122253 0.989929 1 3.00927e-21 3.00927e-21 -4.97663e-10 -1.05128e-10 3.57037e-09 1 3.00927e-21 -4.97663e-10 -1.05128e-10 3.57037e-09 1 -4.97663e-10 -1.05128e-10 3.57037e-09 4318.45 16.173 -1180.47 3924.11 -7.02813 4321.79 +EDGE_SE3:QUAT 1929 1979 -5.70405 0.075712 -3.07675 -0.0624272 -0.0323186 -0.0114412 0.997461 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.1 8.18766 -266.588 3995.58 -0.0877797 4017.16 +EDGE_SE3:QUAT 1928 1979 -6.30165 5.92354 -3.33554 -0.0156341 0.0574385 -0.206016 0.976736 1 1.20371e-20 1.20371e-20 -6.81151e-09 1.4573e-09 -3.21845e-10 1 1.20371e-20 -6.81151e-09 1.4573e-09 -3.21845e-10 1 -6.81151e-09 1.4573e-09 -3.21845e-10 4037.55 -16.246 395.688 3993.53 -40.6272 3868.75 +EDGE_SE3:QUAT 1929 1978 -5.78223 -5.34375 -2.93903 0.0179952 0.00225767 -0.126443 0.991808 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.18 0.410726 44.6344 3999.83 -3.37812 3936.53 +EDGE_SE3:QUAT 1930 1980 -5.61077 0.129224 -3.00596 -0.0135074 -0.0995116 0.0725925 0.992293 1 1.92593e-19 1.92593e-19 -2.72744e-09 -7.99427e-10 2.8075e-08 1 1.92593e-19 -2.72744e-09 -7.99427e-10 2.8075e-08 1 -2.72744e-09 -7.99427e-10 2.8075e-08 4154.75 23.4213 -803.846 3963.91 -35.2026 4134.4 +EDGE_SE3:QUAT 1929 1980 -5.95159 5.47767 -3.24622 -0.0935881 -0.122234 0.206005 0.966365 1 9.62965e-19 9.62965e-19 -3.11895e-08 -1.42438e-08 5.64171e-08 1 9.62965e-19 -3.11895e-08 -1.42438e-08 5.64171e-08 1 -3.11895e-08 -1.42438e-08 5.64171e-08 4075.99 75.842 -687.169 3991.88 -88.3379 3941.28 +EDGE_SE3:QUAT 1930 1979 -5.9131 -6.02924 -3.1074 0.242785 0.136752 -0.0974497 0.955436 1 1.92593e-19 1.92593e-19 4.85103e-09 6.52543e-09 2.80159e-08 1 1.92593e-19 4.85103e-09 6.52543e-09 2.80159e-08 1 4.85103e-09 6.52543e-09 2.80159e-08 4199.81 154.79 1390.15 3910.75 73.0194 4397.6 +EDGE_SE3:QUAT 1931 1981 -5.66593 0.217337 -3.07788 0.0703076 -0.0216826 0.126671 0.989212 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.77 -7.88632 -274.735 3994.37 -18.0078 3954.36 +EDGE_SE3:QUAT 1930 1981 -5.63695 5.80025 -3.14638 -0.0501989 0.161187 -0.00875738 0.985608 1 4.81482e-20 4.81482e-20 -1.44167e-08 3.80467e-10 -2.33107e-09 1 4.81482e-20 -1.44167e-08 3.80467e-10 -2.33107e-09 1 -1.44167e-08 3.80467e-10 -2.33107e-09 4432.23 -51.0016 1401.76 3900.17 -42.986 4442 +EDGE_SE3:QUAT 1931 1980 -5.74247 -5.40073 -2.93043 0.0102417 0.151486 -0.153295 0.976446 1 3.00927e-21 3.00927e-21 -3.54771e-09 5.7239e-10 -5.3511e-10 1 3.00927e-21 -3.54771e-09 5.7239e-10 -5.3511e-10 1 -3.54771e-09 5.7239e-10 -5.3511e-10 4376.8 -84.4312 1285.2 3923.63 -116.072 4283.23 +EDGE_SE3:QUAT 1932 1982 -5.77935 0.317827 -2.95799 -0.0479788 -0.0490188 0.155044 0.985523 1 4.81482e-20 4.81482e-20 -1.37129e-08 -2.22094e-09 4.40629e-10 1 4.81482e-20 -1.37129e-08 -2.22094e-09 4.40629e-10 1 -1.37129e-08 -2.22094e-09 4.40629e-10 4011.31 11.9811 -289.813 3996.78 -21.9374 3924.36 +EDGE_SE3:QUAT 1931 1982 -5.83537 6.00612 -3.07782 -0.157661 0.0248591 0.0888569 0.983173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3931.57 -29.1793 356.553 3990.32 12.219 3999.42 +EDGE_SE3:QUAT 1932 1981 -5.64881 -5.59225 -2.64752 -0.0113972 -0.00283249 0.107299 0.994157 1 3.00927e-21 3.00927e-21 -3.44918e-09 -3.72396e-10 1.16221e-12 1 3.00927e-21 -3.44918e-09 -3.72396e-10 1.16221e-12 1 -3.44918e-09 -3.72396e-10 1.16221e-12 3999.49 0.0200625 -7.70429 4000 -0.144297 3953.96 +EDGE_SE3:QUAT 1933 1983 -5.41265 0.0498768 -2.93584 0.0318547 0.0939032 0.205101 0.973705 1 7.70372e-19 7.70372e-19 4.08306e-09 3.81143e-09 5.47448e-08 1 7.70372e-19 4.08306e-09 3.81143e-09 5.47448e-08 1 4.08306e-09 3.81143e-09 5.47448e-08 4094.48 44.8547 638.122 3984.95 71.5832 3930.27 +EDGE_SE3:QUAT 1932 1983 -5.90597 5.46483 -3.18458 0.227759 0.0220752 -0.0517486 0.972091 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3814.67 37.8936 300.426 3993.64 -2.40246 4011.46 +EDGE_SE3:QUAT 1933 1982 -6.01945 -5.93215 -2.97635 -0.124469 0.00829796 0.0732279 0.989483 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3945.17 -12.3774 172.502 3997.39 6.60048 3985.69 +EDGE_SE3:QUAT 1934 1984 -5.62765 0.161058 -2.97784 -0.0116354 0.0996643 -0.189115 0.976815 1 1.20371e-20 1.20371e-20 6.89616e-09 -1.3775e-09 6.20822e-10 1 1.20371e-20 6.89616e-09 -1.3775e-09 6.20822e-10 1 6.89616e-09 -1.3775e-09 6.20822e-10 4134.83 -46.2661 749.169 3975.2 -78.1605 3992.32 +EDGE_SE3:QUAT 1933 1984 -6.09735 5.67671 -2.95737 -0.213144 0.115645 0.123251 0.962292 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4175.64 -103.807 1248.87 3916.67 -13.9949 4296.6 +EDGE_SE3:QUAT 1934 1983 -5.67101 -5.68546 -2.97019 -0.0506029 0.0147239 -0.0741834 0.995851 1 4.81482e-20 4.81482e-20 -1.38223e-08 1.04532e-09 -9.72384e-11 1 4.81482e-20 -1.38223e-08 1.04532e-09 -9.72384e-11 1 -1.38223e-08 1.04532e-09 -9.72384e-11 3990.98 -1.60716 71.5641 3999.82 -2.21017 3979.21 +EDGE_SE3:QUAT 1935 1985 -5.86027 -0.115511 -3.12756 0.095808 -0.0711417 -0.00132095 0.992853 1 1.92593e-19 1.92593e-19 -4.15802e-10 -2.75541e-08 2.69127e-09 1 1.92593e-19 -4.15802e-10 -2.75541e-08 2.69127e-09 1 -4.15802e-10 -2.75541e-08 2.69127e-09 4042.76 -28.7329 -569.451 3981.43 12.0645 4079.47 +EDGE_SE3:QUAT 1934 1985 -6.1729 5.35397 -2.98941 -0.163941 0.0338879 0.116743 0.978951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3949.69 -38.1732 485.604 3982.48 21.2856 4002.69 +EDGE_SE3:QUAT 1935 1984 -6.06708 -5.83126 -2.92531 -0.0271255 0.000153693 -0.180476 0.983205 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.76 0.900327 -56.2832 3999.65 6.8284 3870.42 +EDGE_SE3:QUAT 1936 1986 -5.55572 0.0462881 -2.90896 0.119241 0.00346388 0.0222375 0.99261 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.1 -0.90734 -4.40603 3999.99 -0.169458 3998 +EDGE_SE3:QUAT 1935 1986 -6.03282 5.66394 -2.92846 -0.000798306 -0.134767 0.161487 0.977629 1 7.82409e-19 7.82409e-19 -1.43361e-08 -3.7887e-09 5.71081e-08 1 7.82409e-19 -1.43361e-08 -3.7887e-09 5.71081e-08 1 -1.43361e-08 -3.7887e-09 5.71081e-08 4280.81 73.2692 -1096.81 3944.38 -104.595 4176.5 +EDGE_SE3:QUAT 1936 1985 -5.75823 -5.51146 -2.87005 0.0901736 -0.0391384 -0.164467 0.981472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3970.13 -4.29188 -122.549 4000.14 5.70656 3894.46 +EDGE_SE3:QUAT 1937 1987 -5.48107 -0.23882 -2.68005 -0.145833 -0.00633839 -0.105867 0.983608 1 9.62965e-19 9.62965e-19 -5.36794e-08 9.46399e-09 -2.53256e-08 1 9.62965e-19 -5.36794e-08 9.46399e-09 -2.53256e-08 1 -5.36794e-08 9.46399e-09 -2.53256e-08 3927.36 19.8462 -230.273 3994.95 13.4599 3967.59 +EDGE_SE3:QUAT 1936 1987 -6.22298 5.63396 -2.973 0.171364 0.0201483 -0.130163 0.976364 1 7.70372e-19 7.70372e-19 -5.44892e-08 6.47248e-09 -3.45617e-09 1 7.70372e-19 -5.44892e-08 6.47248e-09 -3.45617e-09 1 -5.44892e-08 6.47248e-09 -3.45617e-09 3923.58 37.0125 414.091 3985.72 -24.5664 3973.28 +EDGE_SE3:QUAT 1937 1986 -5.49423 -5.53868 -2.90626 0.010673 0.104714 -0.0365008 0.993775 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4182.26 -4.98561 874.219 3955.95 -14.8557 4177.39 +EDGE_SE3:QUAT 1938 1988 -5.8145 -0.0582989 -2.92979 -0.0146065 -0.025704 -0.0140911 0.999464 1 3.00927e-21 3.00927e-21 9.06579e-11 4.82738e-11 -3.47228e-09 1 3.00927e-21 9.06579e-11 4.82738e-11 -3.47228e-09 1 9.06579e-11 4.82738e-11 -3.47228e-09 4009.98 1.31073 -208.471 3997.28 1.24808 4010.04 +EDGE_SE3:QUAT 1937 1988 -6.10943 5.62974 -3.0653 0.0889021 0.112053 0.125452 0.981734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4103.24 63.6517 749.786 3977.63 69.309 4071.9 +EDGE_SE3:QUAT 1938 1987 -5.91065 -5.2262 -2.88461 -0.112183 -0.0584074 -0.239007 0.962746 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4085.58 6.61268 -752.635 3963.91 86.5526 3907.42 +EDGE_SE3:QUAT 1939 1989 -5.43265 -0.317635 -3.02114 0.01346 -0.0228957 -0.11534 0.992971 1 2.0463e-19 2.0463e-19 2.71947e-10 7.3997e-09 2.74556e-08 1 2.0463e-19 2.71947e-10 7.3997e-09 2.74556e-08 1 2.71947e-10 7.3997e-09 2.74556e-08 4005.74 -2.24038 -161.211 3998.63 9.05161 3953.26 +EDGE_SE3:QUAT 1938 1989 -5.89258 5.67977 -2.91313 -0.110861 0.103969 -0.149011 0.977086 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.07 -55.754 601.012 3989.77 -60.3869 3997.41 +EDGE_SE3:QUAT 1939 1988 -5.93409 -5.8145 -3.01982 0.156818 -0.0773604 0.203625 0.963307 1 7.70372e-19 7.70372e-19 -5.50556e-08 -9.89878e-09 7.4274e-09 1 7.70372e-19 -5.50556e-08 -9.89878e-09 7.4274e-09 1 -5.50556e-08 -9.89878e-09 7.4274e-09 4127.66 -31.5421 -980.686 3939.96 -74.0641 4060.17 +EDGE_SE3:QUAT 1940 1990 -5.7645 0.232152 -2.99877 0.0775501 -0.0212488 0.0662592 0.994557 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.96 -8.55194 -229.332 3996.25 -6.93863 3995.46 +EDGE_SE3:QUAT 1939 1990 -5.88077 5.39985 -3.07892 -0.0139997 0.0460724 0.0893615 0.994835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.38 2.06638 382.074 3991.13 16.8693 4004.23 +EDGE_SE3:QUAT 1940 1989 -5.61037 -5.45768 -3.31903 0.0154269 0.134899 -0.0803057 0.987479 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4309.64 -28.0896 1157.09 3928.38 -48.2109 4284.8 +EDGE_SE3:QUAT 1941 1991 -5.66644 -0.111799 -2.57368 0.0400817 0.186846 0.0310708 0.981079 1 7.70372e-19 7.70372e-19 2.72182e-09 -5.44201e-08 3.06333e-09 1 7.70372e-19 2.72182e-09 -5.44201e-08 3.06333e-09 1 2.72182e-09 -5.44201e-08 3.06333e-09 4595.92 75.9486 1665.03 3869.44 74.4459 4598.49 +EDGE_SE3:QUAT 1940 1991 -5.59468 5.3084 -3.14205 -0.00776798 -0.108477 0.177656 0.978065 1 1.20371e-20 1.20371e-20 -6.93315e-09 -1.3011e-09 6.99334e-10 1 1.20371e-20 -6.93315e-09 -1.3011e-09 6.99334e-10 1 -6.93315e-09 -1.3011e-09 6.99334e-10 4168.48 51.8345 -839.343 3967.71 -83.8378 4042.48 +EDGE_SE3:QUAT 1941 1990 -5.79331 -5.3608 -2.67527 0.118483 -0.0291772 -0.00471463 0.992516 1 3.00927e-21 3.00927e-21 -9.4668e-11 4.13332e-10 3.44886e-09 1 3.00927e-21 -9.4668e-11 4.13332e-10 3.44886e-09 1 -9.4668e-11 4.13332e-10 3.44886e-09 3956.17 -13.1502 -222.448 3997.22 2.78148 4012.24 +EDGE_SE3:QUAT 1942 1992 -6.02923 -0.424649 -2.77023 -0.114408 0.111535 0.0745464 0.984334 1 1.92593e-19 1.92593e-19 2.81653e-08 1.39582e-09 3.56913e-09 1 1.92593e-19 2.81653e-08 1.39582e-09 3.56913e-09 1 2.81653e-08 1.39582e-09 3.56913e-09 4194.67 -41.2964 1024.45 3940.48 2.56846 4224.8 +EDGE_SE3:QUAT 1941 1992 -6.0774 5.38794 -3.22731 0.027272 0.0339954 -0.005687 0.999034 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.79 3.63769 274.635 3995.32 -0.0241884 4018.64 +EDGE_SE3:QUAT 1942 1991 -5.75961 -5.10071 -2.83249 0.131032 0.147993 -0.229949 0.952918 1 1.54074e-18 1.54074e-18 6.76687e-08 4.16671e-08 8.11422e-09 1 1.54074e-18 6.76687e-08 4.16671e-08 8.11422e-09 1 6.76687e-08 4.16671e-08 8.11422e-09 4496.27 -52.585 1606.51 3878.37 -140.897 4353.44 +EDGE_SE3:QUAT 1943 1993 -5.67341 -0.20126 -2.55362 -0.0315902 -0.0925572 -0.118575 0.988117 1 1.92593e-19 1.92593e-19 -2.75286e-09 -2.59563e-10 2.79499e-08 1 1.92593e-19 -2.75286e-09 -2.59563e-10 2.79499e-08 1 -2.75286e-09 -2.59563e-10 2.79499e-08 4148.15 -13.3458 -794.804 3964.07 44.9702 4095.9 +EDGE_SE3:QUAT 1942 1993 -5.77378 5.49368 -3.22536 -0.138698 -0.0744347 0.0697172 0.98507 1 1.15556e-18 1.15556e-18 5.40415e-08 3.63939e-08 -2.62708e-08 1 1.15556e-18 5.40415e-08 3.63939e-08 -2.62708e-08 1 5.40415e-08 3.63939e-08 -2.62708e-08 3975.38 36.7977 -463.466 3991.41 -28.05 4032.89 +EDGE_SE3:QUAT 1943 1992 -5.75054 -5.86238 -2.51768 0.0750036 0.0781265 -0.0651578 0.99198 1 1.92593e-19 1.92593e-19 2.79341e-08 -1.50637e-09 2.43437e-09 1 1.92593e-19 2.79341e-08 -1.50637e-09 2.43437e-09 1 2.79341e-08 -1.50637e-09 2.43437e-09 4093.86 17.2441 692.221 3970.86 -11.82 4099.38 +EDGE_SE3:QUAT 1944 1994 -5.53323 0.0169691 -2.72087 -0.0193928 0.114648 -0.0142461 0.993115 1 1.92593e-19 1.92593e-19 5.31579e-10 2.75622e-08 6.44942e-10 1 1.92593e-19 5.31579e-10 2.75622e-08 6.44942e-10 1 5.31579e-10 2.75622e-08 6.44942e-10 4215.29 -15.305 956.13 3948.28 -14.2252 4215.98 +EDGE_SE3:QUAT 1943 1994 -6.02697 5.26097 -2.74765 -0.00181119 -0.158605 0.0346736 0.986731 1 4.81482e-20 4.81482e-20 -2.3094e-09 -1.94754e-10 1.44162e-08 1 4.81482e-20 -2.3094e-09 -1.94754e-10 1.44162e-08 1 -2.3094e-09 -1.94754e-10 1.44162e-08 4432.67 25.231 -1384.9 3900.75 -31.7109 4427.88 +EDGE_SE3:QUAT 1944 1993 -5.73174 -5.06169 -3.07058 0.221035 -0.106744 -0.0266662 0.96904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3936.21 -91.3806 -740.386 3981.05 60.1242 4128.79 +EDGE_SE3:QUAT 1945 1995 -5.70169 0.0202217 -3.14898 -0.155465 0.0890199 -0.0617538 0.981882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.04 -52.6894 576.854 3986.85 -39.2821 4065.46 +EDGE_SE3:QUAT 1944 1995 -5.8351 5.34556 -3.05052 0.0931141 0.0717643 0.185746 0.97554 1 1.92593e-19 1.92593e-19 2.71686e-08 5.48897e-09 8.72442e-10 1 1.92593e-19 2.71686e-08 5.48897e-09 8.72442e-10 1 2.71686e-08 5.48897e-09 8.72442e-10 3991.27 22.9352 335.295 3998.41 29.8245 3887.94 +EDGE_SE3:QUAT 1945 1994 -5.61748 -5.54422 -3.25128 -0.199502 0.0589614 -0.0127633 0.978039 1 1.20371e-20 1.20371e-20 3.43191e-10 -1.41124e-09 6.82434e-09 1 1.20371e-20 3.43191e-10 -1.41124e-09 6.82434e-09 1 3.43191e-10 -1.41124e-09 6.82434e-09 3883.69 -41.9183 417.416 3992.41 -16.6842 4042.25 +EDGE_SE3:QUAT 1946 1996 -5.41253 -0.0291444 -2.64144 0.010401 -0.290376 -0.0629052 0.954786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5734.86 -227.849 -3154.79 3691.24 226.831 5719.46 +EDGE_SE3:QUAT 1945 1996 -6.11098 5.27448 -2.83143 0.0367806 -0.0442301 0.149158 0.987139 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4036.19 0.873245 -410.271 3989.59 -30.485 3952.61 +EDGE_SE3:QUAT 1946 1995 -5.67794 -5.62635 -2.70092 0.20836 -0.180916 0.0343966 0.960558 1 6.77085e-21 6.77085e-21 9.98308e-10 -1.17321e-09 -5.36019e-09 1 6.77085e-21 9.98308e-10 -1.17321e-09 -5.36019e-09 1 9.98308e-10 -1.17321e-09 -5.36019e-09 4398.37 -198.443 -1617.61 3899.88 157.849 4567.29 +EDGE_SE3:QUAT 1947 1997 -5.71039 -0.234476 -2.97886 -0.0111939 -0.0445816 0.0217571 0.998706 1 3.00927e-21 3.00927e-21 3.47854e-09 7.95485e-11 -1.53389e-10 1 3.00927e-21 3.47854e-09 7.95485e-11 -1.53389e-10 1 3.47854e-09 7.95485e-11 -1.53389e-10 4030.9 3.05988 -355.821 3992.26 -4.47073 4029.51 +EDGE_SE3:QUAT 1946 1997 -5.95988 5.11896 -2.96813 0.176967 0.0583168 -0.0161961 0.982354 1 7.52316e-22 7.52316e-22 1.0538e-10 3.08068e-10 1.71679e-09 1 7.52316e-22 1.0538e-10 3.08068e-10 1.71679e-09 1 1.0538e-10 3.08068e-10 1.71679e-09 3932.59 43.4485 484.574 3987.28 11.4315 4056.81 +EDGE_SE3:QUAT 1947 1996 -5.69679 -5.08671 -3.06303 -0.12997 -0.0536243 -0.0888583 0.986071 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4009.07 31.1502 -560.051 3979.39 13.9332 4045.06 +EDGE_SE3:QUAT 1948 1998 -5.47657 -0.0238708 -2.97579 -0.123908 -0.15715 -0.101637 0.974485 1 1.15556e-18 1.15556e-18 2.71534e-08 4.95697e-08 2.88981e-08 1 1.15556e-18 2.71534e-08 4.95697e-08 2.88981e-08 1 2.71534e-08 4.95697e-08 2.88981e-08 4450.6 44.5556 -1520.14 3882.93 4.55512 4470.69 +EDGE_SE3:QUAT 1947 1998 -5.96388 5.66373 -3.15448 -0.137908 -0.0170446 -0.0880495 0.986376 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3942.34 20.3682 -275.383 3993.88 11.1538 3987.41 +EDGE_SE3:QUAT 1948 1997 -5.92981 -5.45892 -2.62981 0.0141309 0.0429315 -0.0080415 0.998946 1 7.52316e-22 7.52316e-22 -7.51098e-11 -2.34873e-11 -1.73935e-09 1 7.52316e-22 -7.51098e-11 -2.34873e-11 -1.73935e-09 1 -7.51098e-11 -2.34873e-11 -1.73935e-09 4029.07 2.14093 346.938 3992.56 -0.789436 4029.61 +EDGE_SE3:QUAT 1949 1999 -5.53104 0.133516 -2.97321 0.0134861 0.11802 -0.0988072 0.987991 1 1.17549e-21 1.17549e-21 2.20466e-09 -2.19572e-10 2.64098e-10 1 1.17549e-21 2.20466e-09 -2.19572e-10 2.64098e-10 1 2.20466e-09 -2.19572e-10 2.64098e-10 4232.94 -27.9767 994.618 3946.27 -51.6839 4194.61 +EDGE_SE3:QUAT 1948 1999 -5.63484 5.12141 -3.03802 -0.0177782 -0.116475 0.0866586 0.989246 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4209.91 38.1578 -943.125 3952.61 -52.0471 4181.13 +EDGE_SE3:QUAT 1949 1998 -5.69403 -5.12119 -2.76562 0.0126678 0.072052 0.0125699 0.997241 1 3.00927e-21 3.00927e-21 3.49591e-09 5.09605e-11 2.51291e-10 1 3.00927e-21 3.49591e-09 5.09605e-11 2.51291e-10 1 3.49591e-09 5.09605e-11 2.51291e-10 4083.08 5.49748 584.706 3979.48 5.47977 4083.09 +EDGE_SE3:QUAT 1950 2000 -5.56361 -0.0839157 -3.14064 -0.0455072 0.209455 -0.0299295 0.9763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4769.38 -102.792 1927.59 3837.53 -100.665 4774.08 +EDGE_SE3:QUAT 1949 2000 -6.66197 5.09212 -2.61078 0.233164 0.151302 0.0250307 0.960269 1 1.54074e-18 1.54074e-18 -5.00559e-08 -5.84901e-08 6.86755e-09 1 1.54074e-18 -5.00559e-08 -5.84901e-08 6.86755e-09 1 -5.00559e-08 -5.84901e-08 6.86755e-09 4063.2 161.862 1100.1 3965.17 130.021 4278.16 +EDGE_SE3:QUAT 1950 1999 -5.7465 -5.33035 -2.75239 0.0426499 -0.0488764 -0.0706528 0.99539 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4023.61 -10.8866 -353.157 3993.16 14.3771 4010.92 +EDGE_SE3:QUAT 1951 2001 -5.6398 -0.163561 -3.13307 0.00927954 -0.0160952 0.218586 0.975641 1 7.52316e-22 7.52316e-22 -1.69361e-09 -3.79093e-10 3.21397e-11 1 7.52316e-22 -1.69361e-09 -3.79093e-10 3.21397e-11 1 -1.69361e-09 -3.79093e-10 3.21397e-11 4004.79 0.959906 -143.37 3998.87 -16.1877 3814.01 +EDGE_SE3:QUAT 1950 2001 -6.23354 5.46285 -2.82595 -0.0443128 -0.111859 -0.0620883 0.990792 1 4.81482e-20 4.81482e-20 1.65659e-09 4.42042e-10 -1.41263e-08 1 4.81482e-20 1.65659e-09 4.42042e-10 -1.41263e-08 1 1.65659e-09 4.42042e-10 -1.41263e-08 4212.96 3.6841 -965.43 3946.78 19.4986 4205.39 +EDGE_SE3:QUAT 1951 2000 -5.74476 -5.45607 -2.90869 -0.00716688 0.123201 0.0101715 0.992304 1 7.52316e-22 7.52316e-22 1.77535e-09 1.55327e-11 2.20622e-10 1 7.52316e-22 1.77535e-09 1.55327e-11 2.20622e-10 1 1.77535e-09 1.55327e-11 2.20622e-10 4254.54 -0.337574 1041.1 3939.2 3.33577 4254.33 +EDGE_SE3:QUAT 1952 2002 -5.76985 0.0546793 -3.12402 -0.0376988 0.127675 0.0927539 0.986749 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4284.54 16.3551 1115.87 3932.09 44.7435 4255.81 +EDGE_SE3:QUAT 1951 2002 -5.96414 5.3963 -3.11487 -0.134165 -0.0372506 0.0119718 0.990186 1 1.20371e-20 1.20371e-20 -2.27442e-10 -9.41505e-10 6.88685e-09 1 1.20371e-20 -2.27442e-10 -9.41505e-10 6.88685e-09 1 -2.27442e-10 -9.41505e-10 6.88685e-09 3946.36 18.2157 -271.891 3996.1 -5.50657 4017.79 +EDGE_SE3:QUAT 1952 2001 -5.71059 -4.86651 -3.03923 0.0529575 0.0539876 -0.100625 0.992046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4048.8 5.31866 493.903 3984.58 -22.0896 4019.52 +EDGE_SE3:QUAT 1953 2003 -5.70127 0.347249 -2.86924 -0.161488 0.0520757 -0.0316518 0.984991 1 4.81482e-20 4.81482e-20 -5.44539e-10 2.3013e-09 -1.37198e-08 1 4.81482e-20 -5.44539e-10 2.3013e-09 -1.37198e-08 1 -5.44539e-10 2.3013e-09 -1.37198e-08 3924.35 -27.6115 341.22 3994.91 -12.9663 4024.66 +EDGE_SE3:QUAT 1952 2003 -5.90542 5.06578 -2.78077 0.0979782 -0.0534328 0.0498171 0.992504 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4019.37 -21.2221 -484.378 3985.2 -4.71234 4047.84 +EDGE_SE3:QUAT 1953 2002 -6.0686 -5.39291 -2.46015 0.162297 -0.048676 -0.129568 0.976986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3895.95 -3.67336 -118.521 4000.5 3.62163 3934.16 +EDGE_SE3:QUAT 1954 2004 -5.55714 -0.0549004 -2.68253 -0.0723659 -0.0261524 0.0438591 0.99607 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.15 6.19588 -169.269 3998.55 -4.30153 3999.41 +EDGE_SE3:QUAT 1953 2004 -5.87243 5.22577 -2.93341 0.0649868 -0.126177 -0.0706836 0.98735 1 1.92593e-19 1.92593e-19 -3.26211e-09 2.41353e-09 2.81873e-08 1 1.92593e-19 -3.26211e-09 2.41353e-09 2.81873e-08 1 -3.26211e-09 2.41353e-09 2.81873e-08 4212.25 -62.2968 -984.874 3951.6 63.3819 4209.16 +EDGE_SE3:QUAT 1954 2003 -5.60981 -5.25054 -3.00829 0.0619935 -0.0310215 -0.182272 0.980801 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.58 -2.85923 -102.074 4000.06 5.20888 3869.06 +EDGE_SE3:QUAT 1955 2005 -5.58607 0.081455 -2.95209 -0.0668168 0.136755 -0.0563759 0.98674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4263.2 -68.2856 1097.23 3939.79 -66.2721 4268.35 +EDGE_SE3:QUAT 1954 2005 -6.22933 5.35178 -2.91826 0.143709 -0.11357 0.0261934 0.982733 1 3.00927e-21 3.00927e-21 4.14798e-10 -5.0448e-10 -3.50525e-09 1 3.00927e-21 4.14798e-10 -5.0448e-10 -3.50525e-09 1 4.14798e-10 -5.0448e-10 -3.50525e-09 4140.37 -71.121 -970.382 3950.38 34.8065 4220.23 +EDGE_SE3:QUAT 1955 2004 -5.72138 -5.29418 -2.71588 0.0287704 0.10993 -0.294566 0.948851 1 1.20371e-20 1.20371e-20 -6.75564e-09 2.10609e-09 -7.61033e-10 1 1.20371e-20 -6.75564e-09 2.10609e-09 -7.61033e-10 1 -6.75564e-09 2.10609e-09 -7.61033e-10 4189.37 -77.5527 899.977 3973.4 -141.02 3845.61 +EDGE_SE3:QUAT 1956 2006 -5.83318 -0.0594392 -2.73087 -0.110212 0.0427695 0.0667543 0.990741 1 4.81482e-20 4.81482e-20 7.81709e-10 -1.45172e-09 1.3827e-08 1 4.81482e-20 7.81709e-10 -1.45172e-09 1.3827e-08 1 7.81709e-10 -1.45172e-09 1.3827e-08 3996.07 -21.3476 425.632 3987.99 8.57215 4026.83 +EDGE_SE3:QUAT 1955 2006 -5.84427 5.22181 -2.50614 0.0825699 -0.163076 -0.0248644 0.982838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4403.44 -89.5827 -1381.59 3908.04 78.9267 4428.24 +EDGE_SE3:QUAT 1956 2005 -5.74409 -5.19997 -2.78787 -0.0662893 -0.137256 0.00399158 0.988307 1 9.75002e-19 9.75002e-19 2.8199e-08 5.60095e-08 -7.14134e-09 1 9.75002e-19 2.8199e-08 5.60095e-08 -7.14134e-09 1 2.8199e-08 5.60095e-08 -7.14134e-09 4295.17 48.0324 -1161.4 3928.37 -35.2057 4312.68 +EDGE_SE3:QUAT 1957 2007 -5.48579 0.107212 -2.76941 0.0683702 -0.0944266 0.0993741 0.988197 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4155.56 -7.3108 -853.047 3957.11 -30.2937 4134.76 +EDGE_SE3:QUAT 1956 2007 -6.10548 5.36593 -2.63969 -0.0150947 -0.024659 0.172033 0.984667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.27 2.91681 -158.132 3998.92 -12.6787 3887.8 +EDGE_SE3:QUAT 1957 2006 -6.08369 -5.43909 -2.90869 -0.174901 -0.0462131 -0.186996 0.96556 1 7.70372e-19 7.70372e-19 -5.45063e-08 9.0964e-09 5.86432e-09 1 7.70372e-19 -5.45063e-08 9.0964e-09 5.86432e-09 1 -5.45063e-08 9.0964e-09 5.86432e-09 4005.98 47.8052 -734.153 3961.14 55.1951 3988.47 +EDGE_SE3:QUAT 1958 2008 -5.5547 0.310551 -2.73143 0.0142904 -0.00931801 0.035402 0.999228 1 4.81482e-20 4.81482e-20 1.43e-10 -1.88746e-10 -1.38699e-08 1 4.81482e-20 1.43e-10 -1.88746e-10 -1.38699e-08 1 1.43e-10 -1.88746e-10 -1.38699e-08 4000.8 -0.506432 -80.4762 3999.58 -1.4272 3996.6 +EDGE_SE3:QUAT 1957 2008 -5.92744 5.31834 -2.96315 0.0737119 -0.0170343 0.0383177 0.996398 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.36 -6.27241 -168.898 3998.03 -2.73205 4001.22 +EDGE_SE3:QUAT 1958 2007 -5.65723 -4.87485 -2.68255 -0.0586493 0.0445547 -0.115206 0.990607 1 1.92593e-19 1.92593e-19 8.23447e-10 -1.87739e-09 2.75564e-08 1 1.92593e-19 8.23447e-10 -1.87739e-09 2.75564e-08 1 8.23447e-10 -1.87739e-09 2.75564e-08 4003.86 -10.6962 267.996 3996.92 -15.773 3964.53 +EDGE_SE3:QUAT 1959 2009 -5.94867 0.148053 -2.76658 0.119209 0.152837 0.128694 0.972557 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4188.33 125.022 1025.69 3967.46 126.319 4178.92 +EDGE_SE3:QUAT 1958 2009 -5.92672 5.12529 -2.76616 0.0834466 -0.0457933 -0.0401869 0.994648 1 1.92593e-19 1.92593e-19 2.7697e-08 -1.32027e-09 -1.06632e-09 1 1.92593e-19 2.7697e-08 -1.32027e-09 -1.06632e-09 1 2.7697e-08 -1.32027e-09 -1.06632e-09 3998.03 -14.7925 -323.22 3994.42 9.79603 4019.42 +EDGE_SE3:QUAT 1959 2008 -5.53675 -5.23217 -2.96019 0.0811418 0.128017 0.133615 0.979375 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4160.46 81.7637 887.263 3969.16 90.1402 4115.38 +EDGE_SE3:QUAT 1960 2010 -5.80748 0.362028 -2.75937 -0.0377079 -0.0275719 -0.031196 0.998421 1 7.22224e-20 7.22224e-20 1.38743e-08 6.27411e-09 6.77528e-09 1 7.22224e-20 1.38743e-08 6.27411e-09 6.77528e-09 1 1.38743e-08 6.27411e-09 6.77528e-09 4008.02 3.91793 -234.609 3996.48 3.0021 4009.82 +EDGE_SE3:QUAT 1959 2010 -6.21574 5.17408 -2.80505 -0.155608 -0.0680137 0.144556 0.974815 1 4.81482e-20 4.81482e-20 -2.20379e-09 1.34975e-08 2.34428e-09 1 4.81482e-20 -2.20379e-09 1.34975e-08 2.34428e-09 1 -2.20379e-09 1.34975e-08 2.34428e-09 3915.14 16.6679 -244.205 4000.44 -16.2601 3928.41 +EDGE_SE3:QUAT 1960 2009 -5.73817 -5.25338 -2.47899 0.128958 0.0129682 -0.260081 0.956849 1 1.92593e-19 1.92593e-19 2.67507e-08 -6.94846e-09 2.09835e-09 1 1.92593e-19 2.67507e-08 -6.94846e-09 2.09835e-09 1 2.67507e-08 -6.94846e-09 2.09835e-09 3987.05 23.89 477.71 3979.83 -72.2559 3783 +EDGE_SE3:QUAT 1961 2011 -5.35019 0.0847051 -2.64849 0.0725867 -0.0630012 0.279745 0.955251 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4095.36 17.1318 -692.976 3974.1 -99.7307 3803.41 +EDGE_SE3:QUAT 1960 2011 -6.06279 5.26813 -2.63105 0.0913468 0.20585 -0.00206662 0.974309 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4721.06 123.657 1893.97 3844.8 110.436 4754.42 +EDGE_SE3:QUAT 1961 2010 -5.90705 -5.35565 -2.43422 0.157619 -0.0559475 -0.333143 0.927923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3901.13 35.8775 214.152 3986.98 -75.9817 3556.57 +EDGE_SE3:QUAT 1962 2012 -5.64112 0.0355303 -2.82609 0.0748712 -0.0875253 0.0682599 0.990997 1 3.85186e-19 3.85186e-19 -2.95435e-08 2.59622e-08 9.54967e-10 1 3.85186e-19 -2.95435e-08 2.59622e-08 9.54967e-10 1 -2.95435e-08 2.59622e-08 9.54967e-10 4122.62 -17.5581 -775.491 3964.01 -13.2862 4126.4 +EDGE_SE3:QUAT 1961 2012 -6.30313 5.0439 -2.39212 -0.0192521 0.0282844 0.111514 0.993174 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.87 0.0106663 248.376 3996.13 13.9477 3965.61 +EDGE_SE3:QUAT 1962 2011 -5.78984 -5.09319 -2.92011 -0.169915 -0.110789 0.0221681 0.97896 1 7.70372e-19 7.70372e-19 5.54882e-08 3.35249e-09 -5.46825e-09 1 7.70372e-19 5.54882e-08 3.35249e-09 -5.46825e-09 1 5.54882e-08 3.35249e-09 -5.46825e-09 4049.45 82.5203 -829.899 3969.37 -55.798 4162.97 +EDGE_SE3:QUAT 1963 2013 -5.55926 0.0106586 -2.72411 0.00226115 0.0812185 0.115388 0.989992 1 1.92593e-19 1.92593e-19 2.20684e-09 5.91303e-10 2.78315e-08 1 1.92593e-19 2.20684e-09 5.91303e-10 2.78315e-08 1 2.20684e-09 5.91303e-10 2.78315e-08 4102.22 19.0183 647.682 3976.86 39.9792 4048.98 +EDGE_SE3:QUAT 1962 2013 -6.1569 5.21974 -2.66006 -0.116123 0.0726492 0.109888 0.98446 1 3.85186e-19 3.85186e-19 -3.03166e-08 2.47961e-08 8.31436e-11 1 3.85186e-19 -3.03166e-08 2.47961e-08 8.31436e-11 1 -3.03166e-08 2.47961e-08 8.31436e-11 4075.63 -28.0115 732.375 3966.3 24.2784 4081.27 +EDGE_SE3:QUAT 1963 2012 -5.84509 -4.95802 -2.16642 0.082384 -0.050515 -0.126357 0.987266 1 8.1852e-19 8.1852e-19 -3.18794e-10 -1.88474e-08 -5.36394e-08 1 8.1852e-19 -3.18794e-10 -1.88474e-08 -5.36394e-08 1 -3.18794e-10 -1.88474e-08 -5.36394e-08 3990.08 -13.5469 -267.666 3997.64 17.0377 3953.36 +EDGE_SE3:QUAT 1964 2014 -5.89865 0.161489 -2.79976 -0.0409409 0.171466 0.0831334 0.980822 1 2.0463e-19 2.0463e-19 1.24461e-08 1.52846e-10 3.03045e-08 1 2.0463e-19 1.24461e-08 1.52846e-10 3.03045e-08 1 1.24461e-08 1.52846e-10 3.03045e-08 4530.24 28.014 1560.8 3879.37 51.695 4509.3 +EDGE_SE3:QUAT 1963 2014 -6.1017 4.84359 -3.05412 -0.00554837 -0.00706027 0.281925 0.959394 1 7.52316e-22 7.52316e-22 1.66434e-09 4.89216e-10 -5.09264e-12 1 7.52316e-22 1.66434e-09 4.89216e-10 -5.09264e-12 1 1.66434e-09 4.89216e-10 -5.09264e-12 4000.11 0.217138 -32.105 4000 -3.31517 3682.31 +EDGE_SE3:QUAT 1964 2013 -5.82694 -5.02414 -2.83175 0.145132 0.0641916 -0.030391 0.98686 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.28 39.9094 558.604 3981.82 7.41978 4072.84 +EDGE_SE3:QUAT 1965 2015 -5.78185 -0.293457 -2.55322 -0.0411493 -0.101595 0.0903226 0.989862 1 4.81482e-20 4.81482e-20 -1.39888e-08 -1.41726e-09 1.29967e-09 1 4.81482e-20 -1.39888e-08 -1.41726e-09 1.29967e-09 1 -1.39888e-08 -1.41726e-09 1.29967e-09 4139.51 38.2735 -779.161 3968.36 -47.4735 4113.65 +EDGE_SE3:QUAT 1964 2015 -5.96799 5.2187 -2.66507 -0.0297032 -0.0675495 -0.0306644 0.996802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4073.17 5.2268 -559.191 3980.98 5.62108 4072.94 +EDGE_SE3:QUAT 1965 2014 -5.80007 -4.81497 -2.49599 -0.323167 0.120376 0.0584606 0.936833 1 3.8639e-18 3.8639e-18 1.10452e-07 4.66107e-08 3.95277e-08 1 3.8639e-18 1.10452e-07 4.66107e-08 3.95277e-08 1 1.10452e-07 4.66107e-08 3.95277e-08 3860.35 -187.27 1091.31 3961.98 -104.752 4264.42 +EDGE_SE3:QUAT 1966 2016 -5.59521 0.338809 -2.52424 -0.0531358 0.050036 0.0282886 0.996932 1 9.62965e-20 9.62965e-20 1.42293e-08 -1.35169e-08 3.44665e-11 1 9.62965e-20 1.42293e-08 -1.35169e-08 3.44665e-11 1 1.42293e-08 -1.35169e-08 3.44665e-11 4032.37 -9.78091 420.207 3989.02 2.73946 4040.46 +EDGE_SE3:QUAT 1965 2016 -6.0179 5.05754 -2.87883 0.00860148 -0.0791804 0.127532 0.988631 1 4.70198e-23 4.70198e-23 -4.34243e-10 -5.61308e-11 3.4599e-11 1 4.70198e-23 -4.34243e-10 -5.61308e-11 3.4599e-11 1 -4.34243e-10 -5.61308e-11 3.4599e-11 4101.16 16.8771 -645.096 3976.89 -42.5092 4036.4 +EDGE_SE3:QUAT 1966 2015 -5.80695 -5.06613 -3.02376 0.0991734 0.0286857 -0.301713 0.947793 1 1.92593e-19 1.92593e-19 -2.65621e-08 8.16637e-09 -2.23774e-09 1 1.92593e-19 -2.65621e-08 8.16637e-09 -2.23774e-09 1 -2.65621e-08 8.16637e-09 -2.23774e-09 4031.16 6.451 541.093 3979.08 -91.6107 3706.38 +EDGE_SE3:QUAT 1967 2017 -5.42888 -0.0863278 -2.64494 -0.0397853 0.167547 -0.105351 0.979411 1 4.81482e-20 4.81482e-20 -1.43123e-08 1.82532e-09 -2.25207e-09 1 4.81482e-20 -1.43123e-08 1.82532e-09 -2.25207e-09 1 -1.43123e-08 1.82532e-09 -2.25207e-09 4421.86 -108.625 1377.53 3915.25 -119.912 4383.79 +EDGE_SE3:QUAT 1966 2017 -6.07612 4.65554 -2.82802 0.0578134 0.0569274 0.236518 0.968234 1 7.70372e-19 7.70372e-19 -1.30402e-09 -4.32731e-09 -5.38559e-08 1 7.70372e-19 -1.30402e-09 -4.32731e-09 -5.38559e-08 1 -1.30402e-09 -4.32731e-09 -5.38559e-08 4001.74 13.8036 257.57 3999.6 24.91 3791.35 +EDGE_SE3:QUAT 1967 2016 -5.92882 -5.22541 -3.03713 0.0716756 -0.126361 -0.0991666 0.984409 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4189.21 -71.7515 -940.864 3959.27 76.6543 4170.43 +EDGE_SE3:QUAT 1968 2018 -5.61055 0.412602 -3.02123 -0.10553 -0.00136581 -0.0382377 0.99368 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3956.26 3.91549 -58.7489 3999.66 1.33936 3994.95 +EDGE_SE3:QUAT 1967 2018 -6.32657 4.86791 -2.83946 -0.013256 0.00461149 0.0190961 0.999719 1 3.76158e-21 3.76158e-21 3.50155e-09 -1.66843e-09 -4.93531e-12 1 3.76158e-21 3.50155e-09 -1.66843e-09 -4.93531e-12 1 3.50155e-09 -1.66843e-09 -4.93531e-12 3999.69 -0.260157 39.9023 3999.9 0.383003 3998.94 +EDGE_SE3:QUAT 1968 2017 -5.52342 -4.45198 -2.67716 0.116746 0.039456 0.188937 0.974226 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3943.56 -2.90765 36.0957 4000 -5.30982 3855.28 +EDGE_SE3:QUAT 1969 2019 -5.55445 0.111801 -2.37467 0.00945934 0.0814525 -0.0145659 0.996526 1 1.98612e-19 1.98612e-19 3.42486e-09 -2.76808e-08 3.99079e-09 1 1.98612e-19 3.42486e-09 -2.76808e-08 3.99079e-09 1 3.42486e-09 -2.76808e-08 3.99079e-09 4108.42 0.982283 668.526 3973.34 -3.65314 4107.93 +EDGE_SE3:QUAT 1968 2019 -5.99301 5.0266 -2.94892 0.0522195 0.0325692 0.148859 0.986941 1 4.81482e-20 4.81482e-20 -1.37071e-08 -2.10616e-09 -2.1611e-10 1 4.81482e-20 -1.37071e-08 -2.10616e-09 -2.1611e-10 1 -1.37071e-08 -2.10616e-09 -2.1611e-10 3995.09 5.13794 159.152 3999.28 10.0129 3917.36 +EDGE_SE3:QUAT 1969 2018 -5.76646 -4.84213 -2.5999 -0.0444678 0.0891799 0.0168252 0.99488 1 2.40741e-19 2.40741e-19 -1.42848e-08 2.74891e-08 -1.04244e-10 1 2.40741e-19 -1.42848e-08 2.74891e-08 -1.04244e-10 1 -1.42848e-08 2.74891e-08 -1.04244e-10 4124.97 -14.5375 741.069 3967.63 -2.18407 4131.75 +EDGE_SE3:QUAT 1970 2020 -5.82967 0.304044 -2.82536 -0.157662 -0.0656332 0.0380804 0.984573 1 8.1852e-19 8.1852e-19 5.41929e-08 1.68347e-08 -5.36961e-10 1 8.1852e-19 5.41929e-08 1.68347e-08 -5.36961e-10 1 5.41929e-08 1.68347e-08 -5.36961e-10 3947.47 36.3195 -437.24 3991.61 -20.533 4041.1 +EDGE_SE3:QUAT 1969 2020 -6.17113 4.66312 -2.90793 0.0256646 0.0391883 0.0587911 0.997171 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.97 5.72784 294.824 3994.97 9.46148 4007.77 +EDGE_SE3:QUAT 1970 2019 -6.0969 -5.1143 -2.76453 0.0467298 -0.051302 -0.0355855 0.996954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.2 -11.303 -391.455 3991.1 9.76075 4032.87 +EDGE_SE3:QUAT 1971 2021 -5.61436 -0.0743676 -2.7118 -0.0584537 -0.0106876 0.0304647 0.997768 1 5.11575e-20 5.11575e-20 -1.37392e-08 -3.89892e-09 -1.07e-10 1 5.11575e-20 -1.37392e-08 -3.89892e-09 -1.07e-10 1 -1.37392e-08 -3.89892e-09 -1.07e-10 3987.33 1.70174 -63.6451 3999.81 -0.961875 3997.29 +EDGE_SE3:QUAT 1970 2021 -6.11228 5.24886 -2.75424 -0.0840038 0.173473 -0.0358125 0.980596 1 4.81482e-20 4.81482e-20 -2.40963e-09 1.49934e-09 -1.44138e-08 1 4.81482e-20 -2.40963e-09 1.49934e-09 -1.44138e-08 1 -2.40963e-09 1.49934e-09 -1.44138e-08 4453.92 -108.407 1470.32 3900.4 -100.081 4477.02 +EDGE_SE3:QUAT 1971 2020 -5.81932 -5.23223 -2.54402 -0.0960846 0.0822997 -0.0175838 0.991809 1 3.97223e-19 3.97223e-19 -2.82588e-08 -2.72828e-08 2.01596e-09 1 3.97223e-19 -2.82588e-08 -2.72828e-08 2.01596e-09 1 -2.82588e-08 -2.72828e-08 2.01596e-09 4063.6 -35.2431 642.186 3977.3 -21.0048 4099.29 +EDGE_SE3:QUAT 1972 2022 -5.46177 -0.035977 -2.84547 0.0685089 -0.00981803 -0.113626 0.99111 1 1.92593e-19 1.92593e-19 2.75082e-08 -3.1612e-09 1.65422e-10 1 1.92593e-19 2.75082e-08 -3.1612e-09 1.65422e-10 1 2.75082e-08 -3.1612e-09 1.65422e-10 3981.04 1.63697 15.8422 3999.86 -2.71108 3948.17 +EDGE_SE3:QUAT 1971 2022 -5.96238 5.30211 -2.98207 0.0224291 -0.0375887 -0.0860044 0.995333 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.8 -5.57971 -275.162 3995.78 12.2737 3989.23 +EDGE_SE3:QUAT 1972 2021 -5.92054 -5.40279 -2.29281 0.0703241 0.0791217 0.0678571 0.992063 1 3.85186e-19 3.85186e-19 2.5911e-08 -5.9673e-11 -2.5911e-08 1 3.85186e-19 2.5911e-08 -5.9673e-11 -2.5911e-08 1 2.5911e-08 -5.9673e-11 -2.5911e-08 4061.36 29.5153 576.044 3982.7 29.1124 4062.73 +EDGE_SE3:QUAT 1973 2023 -5.64176 -0.334158 -2.97709 0.0261019 0.0568746 -0.059323 0.996275 1 6.01853e-20 6.01853e-20 7.79311e-09 -1.25868e-10 1.43387e-08 1 6.01853e-20 7.79311e-09 -1.25868e-10 1.43387e-08 1 7.79311e-09 -1.25868e-10 1.43387e-08 4053.27 1.56092 476.59 3986.03 -12.6186 4041.92 +EDGE_SE3:QUAT 1972 2023 -6.25126 5.08113 -2.7667 -0.0959658 -0.0251984 -0.0263482 0.994717 1 1.20371e-20 1.20371e-20 -2.06698e-10 -6.5781e-10 6.91364e-09 1 1.20371e-20 -2.06698e-10 -6.5781e-10 6.91364e-09 1 -2.06698e-10 -6.5781e-10 6.91364e-09 3976.27 11.0395 -229.457 3996.58 1.36536 4010.33 +EDGE_SE3:QUAT 1973 2022 -5.7987 -5.05597 -2.87073 0.153698 -0.00191393 -0.144069 0.977557 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3918.73 23.7647 244.368 3993.35 -22.0295 3930.19 +EDGE_SE3:QUAT 1974 2024 -5.62248 -0.0881144 -2.65411 0.145877 0.130054 -0.0844516 0.977074 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4266 66.8293 1236.26 3918.3 12.7582 4322.6 +EDGE_SE3:QUAT 1973 2024 -6.24743 4.80503 -2.41995 0.0644192 0.0367497 0.231623 0.969974 1 1.20371e-20 1.20371e-20 1.62713e-09 -6.72576e-09 5.14059e-10 1 1.20371e-20 1.62713e-09 -6.72576e-09 5.14059e-10 1 1.62713e-09 -6.72576e-09 5.14059e-10 3984.51 2.59166 96.3597 4000.37 3.74471 3786.52 +EDGE_SE3:QUAT 1974 2023 -5.62602 -5.006 -2.59611 0.101156 0.0767111 -0.0304958 0.99144 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4063.71 31.0204 655.402 3974.6 5.05574 4100.92 +EDGE_SE3:QUAT 1975 2025 -5.83777 -0.187894 -2.52429 -0.0681333 0.101996 -0.0504116 0.991168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4131.69 -41.0913 789.971 3966.78 -37.7282 4140.1 +EDGE_SE3:QUAT 1974 2025 -6.02117 5.13924 -2.68467 -0.176395 0.0177541 0.0992362 0.979143 1 7.70372e-19 7.70372e-19 -5.45502e-08 -4.84907e-09 -2.82081e-09 1 7.70372e-19 -5.45502e-08 -4.84907e-09 -2.82081e-09 1 -5.45502e-08 -4.84907e-09 -2.82081e-09 3903.41 -32.9433 340.269 3990.44 14.4962 3988.48 +EDGE_SE3:QUAT 1975 2024 -5.64167 -4.73379 -2.63662 0.117109 0.0884776 -0.0171257 0.989022 1 1.93345e-19 1.93345e-19 2.80643e-08 3.1448e-10 4.28411e-09 1 1.93345e-19 2.80643e-08 3.1448e-10 4.28411e-09 1 2.80643e-08 3.1448e-10 4.28411e-09 4076.92 43.6393 737.876 3969.36 16.6378 4130.6 +EDGE_SE3:QUAT 1976 2026 -5.79021 0.0351533 -2.17371 -0.135019 -0.0511551 -0.0757556 0.986618 1 3.27408e-18 3.27408e-18 1.08542e-07 -1.02339e-08 1.98867e-08 1 3.27408e-18 1.08542e-07 -1.02339e-08 1.98867e-08 1 1.08542e-07 -1.02339e-08 1.98867e-08 3994.38 32.0412 -524.086 3982.06 9.29404 4044.35 +EDGE_SE3:QUAT 1975 2026 -6.14514 5.39205 -2.22845 -0.211582 -0.131978 0.0956704 0.963671 1 1.73334e-18 1.73334e-18 -5.47254e-08 -4.82752e-08 5.21364e-08 1 1.73334e-18 -5.47254e-08 -4.82752e-08 5.21364e-08 1 -5.47254e-08 -4.82752e-08 5.21364e-08 3951.24 102.056 -746.329 3991.77 -89.5107 4093.7 +EDGE_SE3:QUAT 1976 2025 -5.80607 -5.31618 -2.51122 -0.16012 0.00178209 -0.0732645 0.984373 1 3.08149e-18 3.08149e-18 -1.09335e-07 7.78237e-09 2.3795e-09 1 3.08149e-18 -1.09335e-07 7.78237e-09 2.3795e-09 1 -1.09335e-07 7.78237e-09 2.3795e-09 3900.82 13.4973 -124.368 3998.21 5.76054 3981.9 +EDGE_SE3:QUAT 1977 2027 -5.58196 -0.0518926 -2.53368 -0.000538693 -0.183283 0.0882751 0.979089 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4580.28 83.3341 -1630.34 3876.41 -98.2855 4549.11 +EDGE_SE3:QUAT 1976 2027 -5.94683 4.92936 -2.70095 -0.00878037 0.125579 0.130898 0.983371 1 3.00927e-21 3.00927e-21 3.522e-09 4.76137e-10 4.42276e-10 1 3.00927e-21 3.522e-09 4.76137e-10 4.42276e-10 1 3.522e-09 4.76137e-10 4.42276e-10 4257.76 47.5958 1048.36 3943.88 76.3953 4189.54 +EDGE_SE3:QUAT 1977 2026 -5.88419 -5.25582 -2.55267 -0.146415 0.10357 -0.091093 0.97956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4013.94 -62.6726 644.093 3985.61 -55.0607 4066.5 +EDGE_SE3:QUAT 1978 2028 -5.57459 -0.241232 -2.8666 -0.0508601 0.00163402 0.0781108 0.995645 1 1.92593e-19 1.92593e-19 -2.64168e-10 1.38755e-09 -2.76377e-08 1 1.92593e-19 -2.64168e-10 1.38755e-09 -2.76377e-08 1 -2.64168e-10 1.38755e-09 -2.76377e-08 3990.5 -1.86447 60.3122 3999.64 2.92744 3976.44 +EDGE_SE3:QUAT 1977 2028 -6.30366 4.95006 -2.71237 0.0930435 0.0387102 0.0773255 0.9919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.92 10.4401 217.665 3998.1 9.29143 3987.63 +EDGE_SE3:QUAT 1978 2027 -5.68106 -5.45982 -2.6351 -0.0235839 0.0899917 0.0122115 0.995588 1 3.00927e-21 3.00927e-21 3.19023e-10 -7.6685e-11 3.51149e-09 1 3.00927e-21 3.19023e-10 -7.6685e-11 3.51149e-09 1 3.19023e-10 -7.6685e-11 3.51149e-09 4131.62 -7.05186 743.827 3967.34 0.138372 4133.24 +EDGE_SE3:QUAT 1979 2029 -5.53242 -0.0966988 -2.80643 0.0380318 0.00507223 0.0123781 0.999187 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.52 0.632281 34.8394 3999.93 0.222424 3999.69 +EDGE_SE3:QUAT 1978 2029 -5.69392 5.10597 -2.91211 0.070054 -0.0633819 0.00862033 0.99549 1 1.92593e-19 1.92593e-19 -2.78584e-08 8.59206e-12 1.78996e-09 1 1.92593e-19 -2.78584e-08 8.59206e-12 1.78996e-09 1 -2.78584e-08 8.59206e-12 1.78996e-09 4046.34 -18.1015 -517.919 3983.95 4.64739 4065.67 +EDGE_SE3:QUAT 1979 2028 -6.0416 -5.32162 -2.6612 0.0203484 -0.0585127 -0.0061867 0.99806 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.25 -5.48071 -471.854 3986.48 3.2 4054.75 +EDGE_SE3:QUAT 1980 2030 -5.81057 0.196344 -2.6174 -0.0174316 0.0149725 0.0789963 0.99661 1 1.20371e-20 1.20371e-20 6.91934e-09 5.44783e-10 1.21661e-10 1 1.20371e-20 6.91934e-09 5.44783e-10 1.21661e-10 1 6.91934e-09 5.44783e-10 1.21661e-10 4003.34 -0.710272 135.204 3998.8 5.44319 3979.6 +EDGE_SE3:QUAT 1979 2030 -5.88715 5.12168 -2.50169 0.0109778 -0.0281491 0.122219 0.992043 1 7.52316e-22 7.52316e-22 1.72397e-09 2.11627e-10 -5.20793e-11 1 7.52316e-22 1.72397e-09 2.11627e-10 -5.20793e-11 1 1.72397e-09 2.11627e-10 -5.20793e-11 4013.49 1.20076 -236.818 3996.61 -14.5976 3954.22 +EDGE_SE3:QUAT 1980 2029 -5.91907 -4.82385 -2.44389 0.143405 -0.000335221 -0.0898777 0.985574 1 1.95602e-19 1.95602e-19 3.97402e-10 4.99597e-10 2.78625e-08 1 1.95602e-19 3.97402e-10 4.99597e-10 2.78625e-08 1 3.97402e-10 4.99597e-10 2.78625e-08 3922.72 13.9686 149.334 3997.55 -8.31807 3972.66 +EDGE_SE3:QUAT 1981 2031 -5.62464 0.206072 -2.28812 -0.157416 -0.208253 -0.0301668 0.964853 1 1.20371e-20 1.20371e-20 1.57568e-09 1.21113e-09 -7.34319e-09 1 1.20371e-20 1.57568e-09 1.21113e-09 -7.34319e-09 1 1.57568e-09 1.21113e-09 -7.34319e-09 4691.72 188.363 -1946.63 3850.44 -162.845 4787.2 +EDGE_SE3:QUAT 1980 2031 -6.16488 4.87918 -2.81171 0.0854644 0.10288 0.127672 0.982757 1 1.92593e-19 1.92593e-19 2.7662e-08 4.10511e-09 2.13443e-09 1 1.92593e-19 2.7662e-08 4.10511e-09 2.13443e-09 1 2.7662e-08 4.10511e-09 2.13443e-09 4081.39 53.6822 677.321 3981.6 60.0429 4045.4 +EDGE_SE3:QUAT 1981 2030 -6.0896 -4.9199 -2.60216 -0.167353 0.0782559 -0.105006 0.97716 1 1.92593e-19 1.92593e-19 1.03703e-09 -5.05847e-09 2.72438e-08 1 1.92593e-19 1.03703e-09 -5.05847e-09 2.72438e-08 1 1.03703e-09 -5.05847e-09 2.72438e-08 3922.53 -34.1275 384.314 3997.22 -28.83 3990.45 +EDGE_SE3:QUAT 1982 2032 -5.83269 -0.101761 -2.35014 -0.0388854 -0.121573 -0.0416926 0.990944 1 4.81482e-20 4.81482e-20 -1.4186e-08 4.75159e-10 1.77687e-09 1 4.81482e-20 -1.4186e-08 4.75159e-10 1.77687e-09 1 -1.4186e-08 4.75159e-10 1.77687e-09 4249.63 7.28555 -1043.11 3938.84 10.0932 4248.72 +EDGE_SE3:QUAT 1981 2032 -6.10071 4.84744 -2.37578 -0.0327414 -0.240854 0.00821786 0.969974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5104.34 79.3549 -2379.83 3773.2 -77.2132 5108.36 +EDGE_SE3:QUAT 1982 2031 -5.38864 -4.56459 -2.38905 -0.00151616 -0.0730807 -0.0734111 0.994619 1 1.92781e-19 1.92781e-19 -1.16218e-09 1.95239e-10 2.78388e-08 1 1.92781e-19 -1.16218e-09 1.95239e-10 2.78388e-08 1 -1.16218e-09 1.95239e-10 2.78388e-08 4085.81 -9.12119 -592.141 3979.45 22.7191 4064.26 +EDGE_SE3:QUAT 1983 2033 -5.58055 -0.000936011 -2.53136 -0.0245385 -0.0850974 -0.0111865 0.996008 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4116.95 7.24864 -701.211 3970.8 -0.21822 4118.86 +EDGE_SE3:QUAT 1982 2033 -6.44423 4.86211 -3.03996 0.0535564 0.0304205 -0.0584733 0.996387 1 4.81482e-20 4.81482e-20 5.04944e-10 6.92066e-10 1.38614e-08 1 4.81482e-20 5.04944e-10 6.92066e-10 1.38614e-08 1 5.04944e-10 6.92066e-10 1.38614e-08 4007.97 6.2724 279.788 3994.83 -7.13347 4005.77 +EDGE_SE3:QUAT 1983 2032 -5.65146 -4.95144 -2.66478 0.266813 0.0357628 0.167205 0.948459 1 3.08149e-18 3.08149e-18 1.05433e-07 1.79382e-08 -6.22526e-09 1 3.08149e-18 1.05433e-07 1.79382e-08 -6.22526e-09 1 1.05433e-07 1.79382e-08 -6.22526e-09 3724.35 -58.7874 -255.867 3987.6 -35.7815 3897.28 +EDGE_SE3:QUAT 1984 2034 -5.60448 0.148149 -2.74125 0.125853 -0.157393 -0.0627958 0.977469 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4269.13 -125.911 -1201.85 3940.95 115.549 4316.71 +EDGE_SE3:QUAT 1983 2034 -6.09646 4.87565 -2.75031 0.0132994 -0.0966534 0.0123399 0.995153 1 2.0463e-19 2.0463e-19 -7.31389e-09 2.75513e-08 3.76491e-10 1 2.0463e-19 -7.31389e-09 2.75513e-08 3.76491e-10 1 -7.31389e-09 2.75513e-08 3.76491e-10 4153.73 -2.95206 -800.995 3962.45 -2.30341 4153.83 +EDGE_SE3:QUAT 1984 2033 -5.67011 -4.92578 -2.50307 -0.0290747 -0.0142919 0.0761176 0.996572 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.48 1.37613 -86.7815 3999.64 -3.05081 3978.68 +EDGE_SE3:QUAT 1985 2035 -5.84516 0.0393672 -2.74784 0.106386 0.054903 -0.190111 0.974436 1 7.70372e-19 7.70372e-19 -5.03764e-09 -4.44621e-09 -5.48349e-08 1 7.70372e-19 -5.03764e-09 -4.44621e-09 -5.48349e-08 1 -5.03764e-09 -4.44621e-09 -5.48349e-08 4060.47 13.7576 661.272 3971.1 -57.8427 3961.17 +EDGE_SE3:QUAT 1984 2035 -6.30415 4.71264 -2.66988 -0.0766229 0.0104648 -0.0905172 0.992888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.32 1.09664 -0.498165 3999.95 1.29822 3967.03 +EDGE_SE3:QUAT 1985 2034 -5.99181 -4.85055 -2.38902 -0.093493 0.057342 -0.105838 0.988316 1 3.85186e-19 3.85186e-19 2.65399e-08 -3.13332e-10 -2.65399e-08 1 3.85186e-19 2.65399e-08 -3.13332e-10 -2.65399e-08 1 2.65399e-08 -3.13332e-10 -2.65399e-08 3991.33 -18.7951 328.867 3995.87 -20.003 3981.49 +EDGE_SE3:QUAT 1986 2036 -5.8423 0.0765821 -2.4772 0.188258 0.0539376 0.169777 0.965829 1 7.70372e-19 7.70372e-19 8.36705e-10 -1.08475e-08 -5.35806e-08 1 7.70372e-19 8.36705e-10 -1.08475e-08 -5.35806e-08 1 8.36705e-10 -1.08475e-08 -5.35806e-08 3853.55 -10.6695 22.2419 3999.55 -9.48723 3880.02 +EDGE_SE3:QUAT 1985 2036 -5.80227 4.49604 -2.85727 -0.0870336 0.161084 0.146824 0.97207 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4503.26 31.0304 1555.42 3881.07 80.6867 4447.33 +EDGE_SE3:QUAT 1986 2035 -6.11787 -4.68468 -2.66225 -0.0711888 0.122931 -0.0117258 0.989789 1 1.20371e-20 1.20371e-20 -8.56927e-10 5.45498e-10 -7.07515e-09 1 1.20371e-20 -8.56927e-10 5.45498e-10 -7.07515e-09 1 -8.56927e-10 5.45498e-10 -7.07515e-09 4223.19 -46.1541 1016.47 3944.22 -33.906 4242.91 +EDGE_SE3:QUAT 1987 2037 -5.82507 0.251556 -2.89924 -0.0932562 -0.0107739 -0.0824261 0.992166 1 1.92593e-19 1.92593e-19 -2.75644e-08 2.19562e-09 7.14023e-10 1 1.92593e-19 -2.75644e-08 2.19562e-09 7.14023e-10 1 -2.75644e-08 2.19562e-09 7.14023e-10 3972.72 8.87257 -175.836 3997.43 7.65529 3980.34 +EDGE_SE3:QUAT 1986 2037 -6.22171 4.5748 -2.54794 -0.141088 -0.00811539 0.0972853 0.985172 1 7.70372e-19 7.70372e-19 -5.47004e-08 -5.31135e-09 -1.07745e-09 1 7.70372e-19 -5.47004e-08 -5.31135e-09 -1.07745e-09 1 -5.47004e-08 -5.31135e-09 -1.07745e-09 3922.13 -10.8192 99.4373 3998.51 7.35599 3963.9 +EDGE_SE3:QUAT 1987 2036 -5.87973 -4.82442 -2.35063 -0.0301519 0.276243 -0.127289 0.952144 1 3.08149e-18 3.08149e-18 -1.85547e-08 -1.05023e-07 -1.24809e-08 1 3.08149e-18 -1.85547e-08 -1.05023e-07 -1.24809e-08 1 -1.85547e-08 -1.05023e-07 -1.24809e-08 5359.59 -388.626 2704.99 3801.3 -388.609 5298.42 +EDGE_SE3:QUAT 1988 2038 -5.72781 -0.243681 -2.58642 0.0636907 -0.0523606 0.13818 0.986969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4049.27 -5.2585 -516.637 3982.92 -33.2484 3989.13 +EDGE_SE3:QUAT 1987 2038 -5.97679 4.73865 -2.92585 -0.0747261 0.0103783 0.057869 0.995469 1 1.92593e-19 1.92593e-19 -2.76451e-08 -1.54672e-09 -5.22257e-10 1 1.92593e-19 -2.76451e-08 -1.54672e-09 -5.22257e-10 1 -2.76451e-08 -1.54672e-09 -5.22257e-10 3982.06 -5.31058 133.652 3998.61 3.94408 3991 +EDGE_SE3:QUAT 1988 2037 -5.42749 -4.74336 -2.75471 -0.00245771 0.0503086 -0.0755926 0.995866 1 1.93345e-19 1.93345e-19 -3.11289e-09 4.13347e-10 -2.78643e-08 1 1.93345e-19 -3.11289e-09 4.13347e-10 -2.78643e-08 1 -3.11289e-09 4.13347e-10 -2.78643e-08 4039.62 -5.06102 400.211 3990.49 -15.6017 4016.79 +EDGE_SE3:QUAT 1989 2039 -5.32677 -0.193427 -2.90048 0.107272 -0.00284034 -0.0291763 0.993797 1 1.92593e-19 1.92593e-19 2.75835e-08 -8.07977e-10 9.57765e-11 1 1.92593e-19 2.75835e-08 -8.07977e-10 9.57765e-11 1 2.75835e-08 -8.07977e-10 9.57765e-11 3953.99 1.48037 14.9456 3999.95 -0.401646 3996.61 +EDGE_SE3:QUAT 1988 2039 -6.32887 4.59431 -3.04422 0.22661 0.0570059 0.115326 0.965452 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3794.05 0.537007 110.951 4000.95 2.40035 3946.26 +EDGE_SE3:QUAT 1989 2038 -5.59004 -5.01092 -2.67938 0.0499908 0.129782 0.0488658 0.989075 1 4.81482e-20 4.81482e-20 -1.41714e-08 -9.10624e-10 -1.76788e-09 1 4.81482e-20 -1.41714e-08 -9.10624e-10 -1.76788e-09 1 -1.41714e-08 -9.10624e-10 -1.76788e-09 4252.09 50.8929 1057.02 3941.42 50.6678 4252.53 +EDGE_SE3:QUAT 1990 2040 -5.83816 -0.0238069 -2.50901 -0.0215571 -0.063101 0.00487211 0.997762 1 1.20371e-20 1.20371e-20 -6.97861e-09 -5.34558e-11 4.39426e-10 1 1.20371e-20 -6.97861e-09 -5.34558e-11 4.39426e-10 1 -6.97861e-09 -5.34558e-11 4.39426e-10 4062.19 6.19575 -510.207 3984.25 -3.38349 4063.96 +EDGE_SE3:QUAT 1989 2040 -6.2884 4.99782 -3.03253 -0.0264948 -0.0246439 0.0431345 0.998414 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.54 2.9358 -183.014 3998.05 -4.21075 4000.91 +EDGE_SE3:QUAT 1990 2039 -6.12206 -4.7972 -2.39508 -0.00832302 0.0796996 -0.0557926 0.995222 1 3.00927e-21 3.00927e-21 3.49622e-09 -2.03177e-10 2.74871e-10 1 3.00927e-21 3.49622e-09 -2.03177e-10 2.74871e-10 1 3.49622e-09 -2.03177e-10 2.74871e-10 4100.45 -11.4356 642.71 3975.89 -20.3189 4088.28 +EDGE_SE3:QUAT 1991 2041 -5.33331 0.000993581 -2.57633 -0.0473322 0.0985588 7.63888e-05 0.994005 1 4.81482e-20 4.81482e-20 1.40667e-08 -1.32745e-10 1.38848e-09 1 4.81482e-20 1.40667e-08 -1.32745e-10 1.38848e-09 1 1.40667e-08 -1.32745e-10 1.38848e-09 4150.01 -21.1816 813.11 3961.88 -11.4878 4158.97 +EDGE_SE3:QUAT 1990 2041 -5.91045 4.87682 -2.65131 -0.018029 -0.118459 0.0423728 0.991891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4226.58 25.0871 -981.578 3946.59 -30.1435 4220.7 +EDGE_SE3:QUAT 1991 2040 -5.81424 -4.94513 -2.78347 -0.10436 0.00163549 -0.0179045 0.994377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3956.44 0.883702 -9.38995 3999.98 0.151103 3998.73 +EDGE_SE3:QUAT 1992 2042 -5.75801 0.327649 -2.18203 -0.0591572 0.106488 -0.0583874 0.990834 1 1.92593e-19 1.92593e-19 2.77334e-09 -2.05849e-09 2.80672e-08 1 1.92593e-19 2.77334e-09 -2.05849e-09 2.80672e-08 1 2.77334e-09 -2.05849e-09 2.80672e-08 4151 -42.0332 829.24 3963.55 -41.8855 4151.36 +EDGE_SE3:QUAT 1991 2042 -5.99816 4.5661 -2.42445 -0.245682 0.146013 -0.00506717 0.958277 1 4.81482e-20 4.81482e-20 1.80061e-09 -3.71478e-09 1.37982e-08 1 4.81482e-20 1.80061e-09 -3.71478e-09 1.37982e-08 1 1.80061e-09 -3.71478e-09 1.37982e-08 4044.79 -163.185 1110.41 3961.82 -123.051 4286.13 +EDGE_SE3:QUAT 1992 2041 -5.81549 -4.68994 -2.28145 0.0498741 0.0352315 -0.250706 0.966136 1 3.17778e-18 3.17778e-18 1.07828e-08 7.00393e-09 -1.07437e-07 1 3.17778e-18 1.07828e-08 7.00393e-09 -1.07437e-07 1 1.07828e-08 7.00393e-09 -1.07437e-07 4029.96 -2.44726 402.399 3990.09 -53.8832 3788.5 +EDGE_SE3:QUAT 1993 2043 -5.85018 0.148334 -2.39404 -0.033387 -0.0745669 0.174105 0.981332 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4058.14 26.6599 -505.969 3989.11 -46.8749 3941.34 +EDGE_SE3:QUAT 1992 2043 -6.2121 4.49992 -2.63058 -0.1282 0.0313848 0.105436 0.985628 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3974.2 -24.1895 404.209 3987.99 17.7418 3995.47 +EDGE_SE3:QUAT 1993 2042 -5.93575 -4.69422 -2.28861 0.00193902 0.0618758 -0.096073 0.993447 1 4.89006e-20 4.89006e-20 3.96335e-10 -1.3955e-08 -3.17601e-11 1 4.89006e-20 3.96335e-10 -1.3955e-08 -3.17601e-11 1 3.96335e-10 -1.3955e-08 -3.17601e-11 4060.78 -8.40288 496.894 3985.65 -24.5773 4023.88 +EDGE_SE3:QUAT 1994 2044 -5.54471 -0.0865035 -2.77795 -0.0503206 -0.00819526 -0.121604 0.991268 1 1.92593e-19 1.92593e-19 -5.56722e-10 -1.30159e-09 2.75291e-08 1 1.92593e-19 -5.56722e-10 -1.30159e-09 2.75291e-08 1 -5.56722e-10 -1.30159e-09 2.75291e-08 3994.4 3.37529 -136.614 3998.45 9.49838 3945.38 +EDGE_SE3:QUAT 1993 2044 -5.91115 4.44448 -2.4001 -0.0578966 0.173122 0.264579 0.946929 1 7.70372e-19 7.70372e-19 1.44987e-08 -5.26174e-08 2.19756e-09 1 7.70372e-19 1.44987e-08 -5.26174e-08 2.19756e-09 1 1.44987e-08 -5.26174e-08 2.19756e-09 4542.48 178.426 1591.95 3914.14 235.768 4275.88 +EDGE_SE3:QUAT 1994 2043 -6.12533 -4.93785 -2.55806 -0.0790521 -0.0463046 -0.0698286 0.993343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4021.65 13.8106 -434.858 3987.69 11.0444 4027.15 +EDGE_SE3:QUAT 1995 2045 -6.02268 -0.115236 -2.63112 0.0732892 0.043972 -0.105859 0.990701 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4026.25 10.5456 440.287 3987.12 -20.5386 4002.92 +EDGE_SE3:QUAT 1994 2045 -6.47528 4.45109 -2.79067 -0.0906651 0.102947 0.0264549 0.990193 1 1.92593e-19 1.92593e-19 -2.81112e-08 -2.1868e-10 -3.00865e-09 1 1.92593e-19 -2.81112e-08 -2.1868e-10 -3.00865e-09 1 -2.81112e-08 -2.1868e-10 -3.00865e-09 4150.39 -37.209 875.612 3956.44 -12.2877 4180.48 +EDGE_SE3:QUAT 1995 2044 -5.7439 -4.55534 -2.2473 -0.106961 -0.0380007 -0.0468061 0.992434 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3986.34 18.4517 -360.127 3991.53 4.13636 4023.34 +EDGE_SE3:QUAT 1996 2046 -5.85235 0.113321 -2.63808 0.0571499 -0.00319212 -0.0505145 0.997082 1 9.62994e-20 9.62994e-20 -1.37957e-08 1.60313e-09 1.3795e-08 1 9.62994e-20 -1.37957e-08 1.60313e-09 1.3795e-08 1 -1.37957e-08 1.60313e-09 1.3795e-08 3986.92 0.595063 9.19409 3999.97 -0.526033 3989.78 +EDGE_SE3:QUAT 1995 2046 -6.02481 4.58153 -2.40359 0.0538539 0.139553 0.162645 0.97528 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4226.71 96.6082 1007.57 3961.25 114.367 4132.5 +EDGE_SE3:QUAT 1996 2045 -5.8481 -4.47008 -2.35659 -0.0327702 0.0126655 0.0418022 0.998508 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.14 -1.81163 117.4 3999.07 2.41091 3996.45 +EDGE_SE3:QUAT 1997 2047 -5.54208 0.130305 -2.63216 -0.0577175 0.0676911 -0.105489 0.990434 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4039.04 -22.2026 461.777 3989.65 -28.8513 4007.85 +EDGE_SE3:QUAT 1996 2047 -6.10635 4.57587 -2.37946 -0.00954041 -0.0731402 0.173183 0.982124 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4073.12 23.0261 -547.654 3985.5 -49.7061 3953.52 +EDGE_SE3:QUAT 1997 2046 -5.46557 -4.60917 -2.45894 0.152979 0.0738222 -0.0614653 0.983549 1 1.01111e-18 1.01111e-18 -5.51922e-08 -2.32202e-08 1.28833e-08 1 1.01111e-18 -5.51922e-08 -2.32202e-08 1.28833e-08 1 -5.51922e-08 -2.32202e-08 1.28833e-08 4024.18 48.8029 696.772 3971 2.33127 4102.68 +EDGE_SE3:QUAT 1998 2048 -5.55841 0.0230523 -2.89878 0.0195643 -0.00189331 0.0504198 0.998535 1 1.20371e-20 1.20371e-20 6.92888e-09 3.49088e-10 -2.67308e-11 1 1.20371e-20 6.92888e-09 3.49088e-10 -2.67308e-11 1 6.92888e-09 3.49088e-10 -2.67308e-11 3998.65 -0.290358 -26.8954 3999.94 -0.772674 3990.01 +EDGE_SE3:QUAT 1997 2048 -6.55733 4.66008 -2.71325 0.0292998 -0.098183 -0.0790373 0.991592 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4140.37 -30.0384 -772.106 3967.58 39.6034 4118.82 +EDGE_SE3:QUAT 1998 2047 -6.26297 -4.72047 -2.15853 -0.0689165 -0.160056 -0.172724 0.969432 1 8.1852e-19 8.1852e-19 -4.06944e-09 3.03863e-09 -5.46758e-08 1 8.1852e-19 -4.06944e-09 3.03863e-09 -5.46758e-08 1 -4.06944e-09 3.03863e-09 -5.46758e-08 4489.39 -68.2862 -1513.96 3891.85 118.525 4389.05 +EDGE_SE3:QUAT 1999 2049 -5.74076 -0.217645 -2.56162 -0.106043 -0.0727538 -0.167104 0.977516 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4102.57 13.6113 -783.68 3961.67 53.905 4035.85 +EDGE_SE3:QUAT 1998 2049 -5.94534 4.56517 -2.64906 0.103794 -0.198342 0.239703 0.944685 1 8.1852e-19 8.1852e-19 -8.42678e-10 -3.45001e-09 -5.48354e-08 1 8.1852e-19 -8.42678e-10 -3.45001e-09 -5.48354e-08 1 -8.42678e-10 -3.45001e-09 -5.48354e-08 4838.17 178.094 -2074.04 3840.63 -234.118 4651.43 +EDGE_SE3:QUAT 1999 2048 -6.0652 -4.96577 -2.37991 0.017999 0.0278375 -0.0128337 0.999368 1 3.00927e-21 3.00927e-21 -9.82478e-11 -6.01381e-11 -3.47277e-09 1 3.00927e-21 -9.82478e-11 -6.01381e-11 -3.47277e-09 1 -9.82478e-11 -6.01381e-11 -3.47277e-09 4011.43 1.81394 225.941 3996.81 -1.12511 4012.06 +EDGE_SE3:QUAT 2000 2050 -5.42382 -0.146872 -2.56876 0.00405157 -0.0288671 -0.0752604 0.996738 1 7.52316e-22 7.52316e-22 1.73183e-09 -1.31382e-10 -4.85269e-11 1 7.52316e-22 1.73183e-09 -1.31382e-10 -4.85269e-11 1 1.73183e-09 -1.31382e-10 -4.85269e-11 4012.65 -1.91628 -225.943 3996.96 8.58285 3990.06 +EDGE_SE3:QUAT 1999 2050 -5.88008 4.60724 -2.40615 0.00169072 -0.0407756 0.12967 0.990717 1 8.19273e-19 8.19273e-19 -2.13927e-09 -1.44688e-08 5.51223e-08 1 8.19273e-19 -2.13927e-09 -1.44688e-08 5.51223e-08 1 -2.13927e-09 -1.44688e-08 5.51223e-08 4025.8 4.84399 -322.416 3994.1 -21.079 3958.56 +EDGE_SE3:QUAT 2000 2049 -5.77655 -5.00955 -2.37705 0.17551 0.0498203 0.0818945 0.9798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3886.38 14.684 207.761 3999.54 10.0949 3982.77 +EDGE_SE3:QUAT 2001 2051 -5.59175 -0.0342234 -2.33167 -0.168093 -0.0561221 -0.16612 0.970051 1 7.70372e-19 7.70372e-19 5.9156e-09 8.02989e-09 -5.48231e-08 1 7.70372e-19 5.9156e-09 8.02989e-09 -5.48231e-08 1 5.9156e-09 8.02989e-09 -5.48231e-08 4025.67 46.4073 -761.864 3960.28 45.1468 4028.31 +EDGE_SE3:QUAT 2000 2051 -6.4696 4.25073 -2.67439 -0.106342 0.0305965 0.208128 0.971822 1 4.81482e-20 4.81482e-20 -2.75011e-09 1.35156e-08 1.18255e-09 1 4.81482e-20 -2.75011e-09 1.35156e-08 1.18255e-09 1 -2.75011e-09 1.35156e-08 1.18255e-09 4012.44 -15.9265 488.463 3982.09 52.9563 3884.41 +EDGE_SE3:QUAT 2001 2050 -5.95782 -4.55566 -2.4013 -0.105637 -0.00319708 -0.0982205 0.989537 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3960.43 9.45747 -147.76 3997.83 8.71526 3966.48 +EDGE_SE3:QUAT 2002 2052 -5.66437 -0.119938 -2.58808 -0.0751301 0.0963277 -0.195999 0.972965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.51 -46.5317 553.056 3992.21 -60.8717 3919.42 +EDGE_SE3:QUAT 2001 2052 -6.19704 4.31958 -2.38563 -0.183689 -0.0695969 0.0796583 0.977276 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3894.48 31.8208 -353.012 3997.3 -22.8119 4004.07 +EDGE_SE3:QUAT 2002 2051 -5.89464 -4.60424 -2.59421 0.255756 -0.047516 0.0583544 0.963808 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3805.02 -69.6569 -521.418 3984.18 6.65754 4053.05 +EDGE_SE3:QUAT 2003 2053 -6.12848 0.174115 -2.57878 0.110698 0.099478 -0.0758227 0.985952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4150.22 35.8145 914.918 3951.18 -7.18015 4176.24 +EDGE_SE3:QUAT 2002 2053 -6.15608 4.84663 -2.67856 0.103321 -0.0661229 -0.00796267 0.992416 1 1.92593e-19 1.92593e-19 2.77737e-08 -6.02785e-10 -1.76412e-09 1 1.92593e-19 2.77737e-08 -6.02785e-10 -1.76412e-09 1 2.77737e-08 -6.02785e-10 -1.76412e-09 4023.24 -28.4436 -517.87 3984.9 12.6565 4065.69 +EDGE_SE3:QUAT 2003 2052 -6.39699 -4.67059 -2.27028 -0.0966978 -0.0436071 -0.0300047 0.993905 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.6 17.7403 -381.252 3990.9 0.904795 4032.4 +EDGE_SE3:QUAT 2004 2054 -5.885 0.0849002 -2.0029 0.0860056 0.0204448 0.0232491 0.995813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3975.14 5.75818 137.863 3999 2.17481 4002.56 +EDGE_SE3:QUAT 2003 2054 -6.19481 4.26915 -2.35037 -0.0463086 0.0539579 -0.106279 0.991791 1 4.81482e-20 4.81482e-20 1.38216e-08 -1.55204e-09 5.94461e-10 1 4.81482e-20 1.38216e-08 -1.55204e-09 5.94461e-10 1 1.38216e-08 -1.55204e-09 5.94461e-10 4024.59 -14.0051 366.633 3993.33 -21.3137 3987.99 +EDGE_SE3:QUAT 2004 2053 -5.81192 -4.50113 -2.50091 -0.149977 0.299492 -0.0927296 0.937664 1 3.85186e-18 3.85186e-18 -7.07729e-09 -1.17606e-07 3.4193e-08 1 3.85186e-18 -7.07729e-09 -1.17606e-07 3.4193e-08 1 -7.07729e-09 -1.17606e-07 3.4193e-08 5216.32 -613.437 2639.84 3929.14 -617.736 5271.9 +EDGE_SE3:QUAT 2005 2055 -5.82632 0.214749 -2.29785 -0.107649 -0.133862 -0.0305938 0.984661 1 1.92593e-19 1.92593e-19 2.83993e-08 -4.51066e-11 -3.9582e-09 1 1.92593e-19 2.83993e-08 -4.51066e-11 -3.9582e-09 1 2.83993e-08 -4.51066e-11 -3.9582e-09 4269.07 60.6711 -1166.69 3927.95 -31.109 4311.68 +EDGE_SE3:QUAT 2004 2055 -6.53402 4.83352 -1.99269 0.00461248 -0.00455859 0.107657 0.994167 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.35 -0.0335312 -41.7524 3999.89 -2.3406 3954.08 +EDGE_SE3:QUAT 2005 2054 -6.12502 -4.40393 -2.48785 0.0783334 0.00772037 -0.145283 0.986254 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3984.39 7.87675 193.806 3996.6 -16.5662 3924.51 +EDGE_SE3:QUAT 2006 2056 -5.74575 0.144819 -2.77758 0.0352533 -0.139532 0.189605 0.971256 1 3.00927e-21 3.00927e-21 3.51648e-09 6.77872e-10 -5.16026e-10 1 3.00927e-21 3.51648e-09 6.77872e-10 -5.16026e-10 1 3.51648e-09 6.77872e-10 -5.16026e-10 4338.03 76.1612 -1220.6 3931.16 -122.903 4199.2 +EDGE_SE3:QUAT 2005 2056 -6.38789 4.80976 -2.76582 -0.053715 -0.15788 0.13937 0.976097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4323.58 117.509 -1207.02 3941.5 -131.538 4257.42 +EDGE_SE3:QUAT 2006 2055 -5.85952 -4.19059 -2.46397 -0.0453264 -0.00389277 -0.10679 0.99324 1 4.81482e-20 4.81482e-20 -1.37872e-08 1.4715e-09 1.86064e-10 1 4.81482e-20 -1.37872e-08 1.4715e-09 1.86064e-10 1 -1.37872e-08 1.4715e-09 1.86064e-10 3993.64 2.20402 -88.1228 3999.3 5.63406 3956.24 +EDGE_SE3:QUAT 2007 2057 -5.42054 -0.2199 -2.59162 -0.0825197 0.0570435 0.0207723 0.994739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4029.05 -18.8957 477.855 3986.13 -1.73723 4054.56 +EDGE_SE3:QUAT 2006 2057 -5.94151 4.81227 -2.48989 -0.00327183 0.0187697 0.0603288 0.997997 1 1.20371e-20 1.20371e-20 4.18055e-10 -6.92503e-09 -6.85945e-12 1 1.20371e-20 4.18055e-10 -6.92503e-09 -6.85945e-12 1 4.18055e-10 -6.92503e-09 -6.85945e-12 4005.72 0.269876 151.892 3998.57 4.58631 3991.2 +EDGE_SE3:QUAT 2007 2056 -6.1455 -4.62231 -2.43335 0.0396546 -0.0778905 -0.169457 0.981654 1 4.81482e-20 4.81482e-20 1.37397e-08 -2.47663e-09 -8.3552e-10 1 4.81482e-20 1.37397e-08 -2.47663e-09 -8.3552e-10 1 1.37397e-08 -2.47663e-09 -8.3552e-10 4060.22 -29.2944 -522.033 3988.59 47.9504 3951.65 +EDGE_SE3:QUAT 2008 2058 -5.38851 -0.408224 -2.33771 0.00760861 0.00188794 -0.158192 0.987377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.97 0.0872189 28.7423 3999.93 -2.63712 3900.1 +EDGE_SE3:QUAT 2007 2058 -6.31181 4.52054 -2.55357 -0.0770537 0.0729092 -0.180263 0.977881 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.25 -25.733 388.456 3996.17 -35.7092 3906.02 +EDGE_SE3:QUAT 2008 2057 -5.86872 -4.53077 -2.49132 0.0379722 0.000271439 -0.109717 0.993237 1 4.81482e-20 4.81482e-20 -1.3785e-08 1.51808e-09 -1.18528e-10 1 4.81482e-20 -1.3785e-08 1.51808e-09 -1.18528e-10 1 -1.3785e-08 1.51808e-09 -1.18528e-10 3994.83 1.2299 51.6809 3999.71 -3.72554 3952.45 +EDGE_SE3:QUAT 2009 2059 -5.80224 -0.0711231 -2.5993 0.108419 -0.178084 0.150951 0.966305 1 9.62965e-19 9.62965e-19 3.56873e-08 -5.03274e-08 -2.93307e-09 1 9.62965e-19 3.56873e-08 -5.03274e-08 -2.93307e-09 1 3.56873e-08 -5.03274e-08 -2.93307e-09 4638.51 24.3023 -1792.42 3849.91 -75.5774 4594.38 +EDGE_SE3:QUAT 2008 2059 -6.51113 4.17244 -2.69912 0.0136637 0.249215 0.300934 0.920404 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4757.91 472.68 1913.92 4011.61 474.096 4396.41 +EDGE_SE3:QUAT 2009 2058 -5.89355 -4.44566 -2.67166 -0.0677453 0.0757036 -0.0534288 0.993391 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4059.66 -26.209 564.403 3982.76 -23.8371 4066.6 +EDGE_SE3:QUAT 2010 2060 -5.77267 0.118666 -2.15933 -0.0717144 -0.0424586 0.11436 0.989937 1 3.85186e-19 3.85186e-19 2.82063e-08 5.5394e-09 -2.82063e-08 1 3.85186e-19 2.82063e-08 5.5394e-09 -2.82063e-08 1 2.82063e-08 5.5394e-09 -2.82063e-08 3992.65 10.0393 -233.474 3997.96 -13.2498 3960.91 +EDGE_SE3:QUAT 2009 2060 -6.09126 4.47556 -2.56073 0.00396693 0.0327345 -0.0330581 0.998909 1 1.88079e-22 1.88079e-22 8.68295e-10 -2.85705e-11 2.86195e-11 1 1.88079e-22 8.68295e-10 -2.85705e-11 2.86195e-11 1 8.68295e-10 -2.85705e-11 2.86195e-11 4017.29 -0.330536 264.016 3995.68 -4.31636 4012.98 +EDGE_SE3:QUAT 2010 2059 -5.87046 -4.49538 -2.2714 0.0980544 0.148098 -0.0928959 0.979705 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4395.08 25.0377 1386.54 3899.16 -17.0295 4399.02 +EDGE_SE3:QUAT 2011 2061 -5.97921 0.096645 -2.43845 -0.069681 0.185391 -0.0436995 0.979217 1 1.92593e-19 1.92593e-19 2.9043e-08 -2.18131e-09 5.22231e-09 1 1.92593e-19 2.9043e-08 -2.18131e-09 5.22231e-09 1 2.9043e-08 -2.18131e-09 5.22231e-09 4542.85 -115.478 1601.86 3884.46 -111.281 4554.63 +EDGE_SE3:QUAT 2010 2061 -6.19348 4.86806 -2.75368 -0.0713966 0.0451306 0.05522 0.994895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.68 -12.1501 407.614 3989.32 7.6968 4028.88 +EDGE_SE3:QUAT 2011 2060 -5.78706 -4.64808 -2.33722 0.0768699 -0.0281778 -0.0636358 0.994609 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3982.95 -6.29436 -163.881 3998.82 5.49756 3990.39 +EDGE_SE3:QUAT 2012 2062 -5.58568 -0.20631 -2.40147 0.0990803 -0.0704397 0.152322 0.980826 1 3.85186e-19 3.85186e-19 -3.14981e-08 2.34091e-08 6.37226e-10 1 3.85186e-19 -3.14981e-08 2.34091e-08 6.37226e-10 1 -3.14981e-08 2.34091e-08 6.37226e-10 4091.63 -13.6779 -736.493 3965.94 -45.8735 4038.09 +EDGE_SE3:QUAT 2011 2062 -6.32288 4.57936 -2.08502 0.11487 -0.0336292 0.15048 0.981341 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.47 -20.8818 -463.544 3984.1 -32.8744 3961.68 +EDGE_SE3:QUAT 2012 2061 -5.85948 -4.70691 -2.48079 -0.0931796 0.145389 -0.214031 0.961442 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4135.35 -111.972 854.558 3989.15 -125.136 3986.85 +EDGE_SE3:QUAT 2013 2063 -5.74637 -0.0460024 -2.54864 0.11476 0.0869428 -0.122244 0.982002 1 3.85186e-19 3.85186e-19 2.47488e-08 -5.48724e-09 -2.47488e-08 1 3.85186e-19 2.47488e-08 -5.48724e-09 -2.47488e-08 1 2.47488e-08 -5.48724e-09 -2.47488e-08 4127.44 26.0344 868.52 3954.26 -31.7312 4120.35 +EDGE_SE3:QUAT 2012 2063 -5.85434 4.74438 -2.54381 -0.0221462 0.0929901 -0.120374 0.988116 1 1.92593e-19 1.92593e-19 -2.38887e-09 1.25067e-09 -2.7852e-08 1 1.92593e-19 -2.38887e-09 1.25067e-09 -2.7852e-08 1 -2.38887e-09 1.25067e-09 -2.7852e-08 4121.33 -31.9247 713.344 3973.67 -49.9682 4065.33 +EDGE_SE3:QUAT 2013 2062 -5.79056 -4.39856 -2.43401 -0.0509067 0.117114 -0.10631 0.986099 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4176.38 -56.9838 884.993 3962.12 -67.1828 4141.54 +EDGE_SE3:QUAT 2014 2064 -5.69974 0.134273 -2.70278 0.0186701 -0.0170229 0.0696109 0.997254 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.28 -0.888436 -150.866 3998.51 -5.28488 3986.29 +EDGE_SE3:QUAT 2013 2064 -5.99402 4.51717 -2.34841 0.0187387 0.0190765 0.0363579 0.998981 1 6.01853e-20 6.01853e-20 -1.21355e-11 7.21061e-09 1.37333e-08 1 6.01853e-20 -1.21355e-11 7.21061e-09 1.37333e-08 1 -1.21355e-11 7.21061e-09 1.37333e-08 4003.79 1.62047 144.218 3998.76 2.72928 3999.9 +EDGE_SE3:QUAT 2014 2063 -5.79878 -4.7144 -2.31435 -0.057673 0.0651349 -0.281197 0.955698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.95 -17.1519 273.169 4000.97 -29.3732 3699.97 +EDGE_SE3:QUAT 2015 2065 -5.85503 0.246962 -2.37207 0.113593 0.130666 0.0203777 0.984687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4207.79 77.6574 1051.45 3945.15 59.409 4257.75 +EDGE_SE3:QUAT 2014 2065 -5.95108 4.58165 -2.4278 0.136406 -0.0818578 0.310143 0.937285 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4203.07 25.1848 -1091.97 3936.01 -161.697 3892.74 +EDGE_SE3:QUAT 2015 2064 -6.07232 -4.34462 -2.55804 0.0924295 -0.0689157 -0.170965 0.978508 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.17 -22.0958 -335.437 3997.77 28.3617 3909.43 +EDGE_SE3:QUAT 2016 2066 -6.00318 0.00156011 -2.45919 0.0237396 0.00487023 -0.134153 0.990664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3999.14 0.814323 75.6544 3999.53 -5.86666 3929.41 +EDGE_SE3:QUAT 2015 2066 -6.39293 4.32174 -2.24162 0.0150498 0.0994518 0.0729545 0.99225 1 1.20371e-20 1.20371e-20 7.01774e-09 5.47457e-10 6.79541e-10 1 1.20371e-20 7.01774e-09 5.47457e-10 6.79541e-10 1 7.01774e-09 5.47457e-10 6.79541e-10 4153.74 24.0846 801.603 3964.19 35.5979 4133.35 +EDGE_SE3:QUAT 2016 2065 -6.00026 -4.21238 -2.11326 0.0574393 0.00542179 -0.0868098 0.994553 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3989.32 3.24376 102.143 3999.09 -5.12222 3972.37 +EDGE_SE3:QUAT 2017 2067 -5.54314 0.101223 -2.67163 0.0547113 -0.0385723 0.0989174 0.992841 1 1.92593e-19 1.92593e-19 2.76748e-08 2.63288e-09 -1.34863e-09 1 1.92593e-19 2.76748e-08 2.63288e-09 -1.34863e-09 1 2.76748e-08 2.63288e-09 -1.34863e-09 4021.91 -6.13081 -370.105 3990.97 -17.0219 3994.74 +EDGE_SE3:QUAT 2016 2067 -6.46493 4.50475 -2.51945 -0.0740301 0.0987282 0.239957 0.962909 1 1.92593e-19 1.92593e-19 2.75085e-08 6.52895e-09 3.46733e-09 1 1.92593e-19 2.75085e-08 6.52895e-09 3.46733e-09 1 2.75085e-08 6.52895e-09 3.46733e-09 4201.59 37.0201 971.787 3952.12 113.314 3993.2 +EDGE_SE3:QUAT 2017 2066 -5.99134 -4.62565 -2.3962 0.111669 0.127682 -0.12124 0.978023 1 1.92593e-19 1.92593e-19 -2.8336e-08 2.71516e-09 -4.30035e-09 1 1.92593e-19 -2.8336e-08 2.71516e-09 -4.30035e-09 1 -2.8336e-08 2.71516e-09 -4.30035e-09 4300.42 21.8094 1234.85 3916.46 -34.1544 4291.51 +EDGE_SE3:QUAT 2018 2068 -5.94153 -0.172348 -2.49893 0.139372 0.00307365 -0.0568158 0.988604 1 3.0845e-18 3.0845e-18 1.09989e-07 -2.5411e-09 1.58566e-09 1 3.0845e-18 1.09989e-07 -2.5411e-09 1.58566e-09 1 1.09989e-07 -2.5411e-09 1.58566e-09 3925.53 10.1794 117.446 3998.66 -3.73921 3990.31 +EDGE_SE3:QUAT 2017 2068 -5.9196 4.47843 -2.56821 0.00751514 -0.218993 0.0153467 0.975577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4894.43 10.5827 -2092.62 3808.11 -13.4742 4893.72 +EDGE_SE3:QUAT 2018 2067 -5.84592 -4.84392 -2.19541 0.0150508 0.123135 -0.118773 0.985142 1 1.93768e-19 1.93768e-19 1.09116e-09 2.7609e-08 1.30751e-10 1 1.93768e-19 1.09116e-09 2.7609e-08 1.30751e-10 1 1.09116e-09 2.7609e-08 1.30751e-10 4253.52 -37.8631 1040.43 3942.99 -65.9954 4198 +EDGE_SE3:QUAT 2019 2069 -5.43246 -0.0705129 -2.57965 -0.139703 0.0196843 -0.0358633 0.989348 1 7.73381e-19 7.73381e-19 -5.47957e-08 5.64896e-09 -7.98836e-12 1 7.73381e-19 -5.47957e-08 5.64896e-09 -7.98836e-12 1 -5.47957e-08 5.64896e-09 -7.98836e-12 3923.98 -5.17155 93.2907 3999.75 -1.89542 3996.9 +EDGE_SE3:QUAT 2018 2069 -6.24619 4.17102 -2.37571 -0.0393725 0.0448074 0.152465 0.986507 1 8.66668e-19 8.66668e-19 -1.27963e-08 1.02659e-08 5.46427e-08 1 8.66668e-19 -1.27963e-08 1.02659e-08 5.46427e-08 1 -1.27963e-08 1.02659e-08 5.46427e-08 4037.47 0.673537 420.471 3989.04 31.9138 3950.69 +EDGE_SE3:QUAT 2019 2068 -5.63046 -4.17563 -2.29547 -0.142291 -0.0130142 -0.0624056 0.98777 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3929.33 16.349 -205.774 3996.58 5.70935 3994.73 +EDGE_SE3:QUAT 2020 2070 -5.97643 0.127113 -2.54583 0.0116358 -0.103463 -0.033008 0.994017 1 3.00927e-21 3.00927e-21 3.52307e-09 -1.28174e-10 -3.62987e-10 1 3.00927e-21 3.52307e-09 -1.28174e-10 -3.62987e-10 1 3.52307e-09 -1.28174e-10 -3.62987e-10 4173.62 -14.339 -852.647 3958.35 18.7367 4169.81 +EDGE_SE3:QUAT 2019 2070 -6.022 4.03461 -2.19947 0.0682944 0.0435939 0.0648346 0.994601 1 4.81482e-20 4.81482e-20 9.7652e-10 -1.37976e-08 1.02093e-09 1 4.81482e-20 9.7652e-10 -1.37976e-08 1.02093e-09 1 9.7652e-10 -1.37976e-08 1.02093e-09 4002.5 11.7581 292.387 3995.64 11.3985 4004.34 +EDGE_SE3:QUAT 2020 2069 -6.28964 -4.11854 -2.40629 0.12679 0.0603233 -0.0735226 0.98736 1 1.92593e-19 1.92593e-19 -2.76998e-08 1.58595e-09 -2.14177e-09 1 1.92593e-19 -2.76998e-08 1.58595e-09 -2.14177e-09 1 -2.76998e-08 1.58595e-09 -2.14177e-09 4020.57 32.3763 589.419 3977.96 -8.62703 4063.25 +EDGE_SE3:QUAT 2021 2071 -5.92182 0.201238 -2.30643 0.0132033 0.0593874 0.0212897 0.997921 1 6.31946e-20 6.31946e-20 3.57762e-09 1.40394e-08 6.95851e-09 1 6.31946e-20 3.57762e-09 1.40394e-08 6.95851e-09 1 3.57762e-09 1.40394e-08 6.95851e-09 4055.4 5.06701 477.024 3986.24 6.37395 4054.29 +EDGE_SE3:QUAT 2020 2071 -6.09461 4.34273 -2.15144 0.20174 -0.0348614 0.0478406 0.977649 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3872.28 -39.7304 -376.982 3990.9 -0.229038 4025.92 +EDGE_SE3:QUAT 2021 2070 -5.88501 -4.48984 -2.19389 -0.209094 0.0505755 0.0196878 0.976388 1 3.00927e-21 3.00927e-21 1.89148e-10 -7.26448e-10 3.40777e-09 1 3.00927e-21 1.89148e-10 -7.26448e-10 3.40777e-09 1 1.89148e-10 -7.26448e-10 3.40777e-09 3870.96 -45.7831 430.639 3990.26 -10.0099 4044.29 +EDGE_SE3:QUAT 2022 2072 -5.79923 0.0477005 -2.20333 0.128375 0.0675637 -0.00181322 0.98942 1 3.08149e-18 3.08149e-18 1.10836e-07 1.74221e-09 7.36908e-09 1 3.08149e-18 1.10836e-07 1.74221e-09 7.36908e-09 1 1.10836e-07 1.74221e-09 7.36908e-09 4005.2 35.7704 538.152 3983.94 13.5451 4071.11 +EDGE_SE3:QUAT 2021 2072 -6.07871 3.72768 -2.05408 0.0187631 -0.0841082 0.137048 0.986809 1 1.95602e-19 1.95602e-19 -7.24589e-09 2.69157e-08 4.35159e-10 1 1.95602e-19 -7.24589e-09 2.69157e-08 4.35159e-10 1 -7.24589e-09 2.69157e-08 4.35159e-10 4118.37 17.8696 -702.473 3972.62 -48.7312 4044.65 +EDGE_SE3:QUAT 2022 2071 -5.9673 -4.33048 -2.04847 -0.02583 -0.0744224 -0.0159843 0.996764 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4088.74 6.17367 -611.557 3977.49 1.61833 4090.39 +EDGE_SE3:QUAT 2023 2073 -5.89289 -0.231447 -2.49991 -0.0318157 0.122605 0.0580207 0.990247 1 1.20371e-20 1.20371e-20 -7.09249e-09 -3.70705e-10 -8.97628e-10 1 1.20371e-20 -7.09249e-09 -3.70705e-10 -8.97628e-10 1 -7.09249e-09 -3.70705e-10 -8.97628e-10 4256.71 3.62482 1054.06 3937.91 23.0116 4247.29 +EDGE_SE3:QUAT 2022 2073 -6.17361 4.27664 -2.55514 -0.116433 -0.117062 0.139816 0.976315 1 9.62965e-19 9.62965e-19 3.13242e-10 -3.52886e-08 5.0966e-08 1 9.62965e-19 3.13242e-10 -3.52886e-08 5.0966e-08 1 3.13242e-10 -3.52886e-08 5.0966e-08 4065.94 72.0176 -710.321 3984.86 -75.0823 4041.97 +EDGE_SE3:QUAT 2023 2072 -5.61167 -4.20754 -2.45811 0.0122977 0.0103093 -0.0039813 0.999863 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.12 0.502269 83.0728 3999.57 -0.134207 4001.66 +EDGE_SE3:QUAT 2024 2074 -5.72654 0.111995 -2.54122 -0.229328 0.29334 0.164299 0.913436 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 6214.38 -280.795 3947 3617.05 -295.293 6316.77 +EDGE_SE3:QUAT 2023 2074 -6.66341 4.16764 -2.01555 -0.251795 -0.0299458 -0.0106926 0.967258 1 1.88079e-22 1.88079e-22 2.72546e-11 2.18687e-10 -8.40688e-10 1 1.88079e-22 2.72546e-11 2.18687e-10 -8.40688e-10 1 2.72546e-11 2.18687e-10 -8.40688e-10 3761.82 31.7719 -248.943 3997.09 -4.58115 4014.97 +EDGE_SE3:QUAT 2024 2073 -5.88315 -4.30423 -2.13679 0.0168628 -0.00595334 -0.034361 0.999249 1 1.20371e-20 1.20371e-20 -6.93404e-09 2.39712e-10 3.31544e-11 1 1.20371e-20 -6.93404e-09 2.39712e-10 3.31544e-11 1 -6.93404e-09 2.39712e-10 3.31544e-11 3999.27 -0.3453 -40.5788 3999.91 0.668196 3995.69 +EDGE_SE3:QUAT 2025 2075 -5.90737 -0.086734 -2.14357 0.0573702 -0.270975 0.11311 0.954195 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 5548.44 150.457 -2947.04 3708.05 -154.842 5510.43 +EDGE_SE3:QUAT 2024 2075 -6.1141 4.05297 -2.82965 -0.0882537 0.0334861 0.153512 0.983628 1 1.92593e-19 1.92593e-19 2.7452e-08 4.06823e-09 1.62284e-09 1 1.92593e-19 2.7452e-08 4.06823e-09 1.62284e-09 1 2.7452e-08 4.06823e-09 1.62284e-09 4011.86 -12.441 419.261 3987.38 31.7279 3948.75 +EDGE_SE3:QUAT 2025 2074 -5.74706 -4.48053 -2.27958 0.00526498 0.0215878 -0.0414262 0.998894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.54 -0.00862051 175.161 3998.09 -3.60091 4000.79 +EDGE_SE3:QUAT 2026 2076 -5.96548 -0.168222 -2.31653 -0.129651 -0.0840004 0.00542083 0.98798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4039.26 46.3419 -661.469 3976.63 -23.4429 4106.38 +EDGE_SE3:QUAT 2025 2076 -6.44955 4.5918 -2.36333 -0.0178921 -0.0826619 -0.00432216 0.996408 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4110.54 5.77241 -678.073 3972.64 -1.46671 4111.74 +EDGE_SE3:QUAT 2026 2075 -5.72006 -4.01025 -2.48898 0.0350657 0.0761459 -0.0781756 0.993409 1 1.20371e-20 1.20371e-20 6.98192e-09 -5.17014e-10 5.66191e-10 1 1.20371e-20 6.98192e-09 -5.17014e-10 5.66191e-10 1 6.98192e-09 -5.17014e-10 5.66191e-10 4098.05 0.262191 650.024 3974.62 -22.0058 4078.52 +EDGE_SE3:QUAT 2027 2077 -5.99069 -0.117023 -1.99683 -0.0958509 0.0756567 -0.101205 0.987343 1 3.85186e-19 3.85186e-19 2.90854e-08 -6.28664e-09 2.90854e-08 1 3.85186e-19 2.90854e-08 -6.28664e-09 2.90854e-08 1 2.90854e-08 -6.28664e-09 2.90854e-08 4018.68 -31.5443 476.78 3990.44 -32.2417 4014.46 +EDGE_SE3:QUAT 2026 2077 -6.12106 4.34416 -2.43285 0.0884658 -0.0419215 0.0411593 0.994345 1 8.66668e-19 8.66668e-19 -5.5229e-08 1.07629e-08 -1.23425e-08 1 8.66668e-19 -5.5229e-08 1.07629e-08 -1.23425e-08 1 -5.5229e-08 1.07629e-08 -1.23425e-08 4003.91 -15.5176 -377.123 3990.9 -3.69313 4028.44 +EDGE_SE3:QUAT 2027 2076 -5.895 -4.63864 -1.98451 -0.0235451 -0.000979654 -0.047109 0.998612 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3997.89 0.294617 -21.0908 3999.96 0.598159 3991.23 +EDGE_SE3:QUAT 2028 2078 -5.96818 -0.290398 -2.27559 -0.0748396 0.0163059 0.049661 0.995825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.07 -6.55502 173.558 3997.85 3.92606 3997.61 +EDGE_SE3:QUAT 2027 2078 -6.30525 4.31543 -2.01322 -0.0535466 -0.129943 0.178981 0.973763 1 1.92593e-19 1.92593e-19 2.76991e-08 5.62296e-09 -2.87218e-09 1 1.92593e-19 2.76991e-08 5.62296e-09 -2.87218e-09 1 2.76991e-08 5.62296e-09 -2.87218e-09 4181.77 86.022 -903.483 3970.72 -105.899 4065.1 +EDGE_SE3:QUAT 2028 2077 -6.02865 -4.23894 -2.28676 0.0444931 0.176898 -0.106962 0.977388 1 1.20371e-20 1.20371e-20 7.26276e-09 -7.23889e-10 1.35308e-09 1 1.20371e-20 7.26276e-09 -7.23889e-10 1.35308e-09 1 7.26276e-09 -7.23889e-10 1.35308e-09 4572.24 -49.3496 1630.1 3872.63 -77.4474 4534.4 +EDGE_SE3:QUAT 2029 2079 -6.01511 -0.00957518 -2.36107 -0.0676672 0.123288 0.0852634 0.986383 1 4.81482e-20 4.81482e-20 -1.41728e-08 -1.00955e-09 -1.89965e-09 1 4.81482e-20 -1.41728e-08 -1.00955e-09 -1.89965e-09 1 -1.41728e-08 -1.00955e-09 -1.89965e-09 4266.59 -7.61638 1104.98 3931.92 26.8044 4255.83 +EDGE_SE3:QUAT 2028 2079 -6.0284 3.74659 -2.3225 0.0637511 -0.035385 -0.0464379 0.996257 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.74 -8.64201 -245.751 3996.75 7.02123 4006.37 +EDGE_SE3:QUAT 2029 2078 -6.0028 -3.88728 -2.46996 -0.0875126 -0.124098 -0.145168 0.977685 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4293.78 -7.21548 -1184.72 3923.67 62.6665 4240.12 +EDGE_SE3:QUAT 2030 2080 -5.92971 0.0893737 -2.38793 0.00978783 0.0222637 -0.0422408 0.998811 1 4.81482e-20 4.81482e-20 -3.1962e-10 -1.09502e-10 -1.38758e-08 1 4.81482e-20 -3.1962e-10 -1.09502e-10 -1.38758e-08 1 -3.1962e-10 -1.09502e-10 -1.38758e-08 4007.96 0.383138 182.902 3997.9 -3.79371 4001.21 +EDGE_SE3:QUAT 2029 2080 -6.4214 4.21602 -2.18778 0.00379703 0.129177 0.237523 0.962747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4226.31 92.1447 980.164 3966.61 133.5 4000.7 +EDGE_SE3:QUAT 2030 2079 -5.90836 -4.01572 -2.38509 0.187477 0.033267 -0.119736 0.974376 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3923.7 47.8675 515.949 3980.03 -21.5789 4006.95 +EDGE_SE3:QUAT 2031 2081 -5.84922 -0.320743 -2.40794 -0.0746631 -0.123931 -0.000803192 0.989478 1 1.92593e-19 1.92593e-19 -5.01531e-10 2.74589e-08 2.13203e-09 1 1.92593e-19 -5.01531e-10 2.74589e-08 2.13203e-09 1 -5.01531e-10 2.74589e-08 2.13203e-09 4231.06 44.6671 -1038.11 3941.46 -28.9039 4253.36 +EDGE_SE3:QUAT 2030 2081 -5.994 4.01254 -2.06607 0.00712457 -0.0363756 0.0634899 0.997294 1 4.89006e-20 4.89006e-20 -8.58552e-10 -1.39504e-08 9.85728e-11 1 4.89006e-20 -8.58552e-10 -1.39504e-08 9.85728e-11 1 -8.58552e-10 -1.39504e-08 9.85728e-11 4021.59 0.999535 -296.06 3994.62 -9.33767 4005.67 +EDGE_SE3:QUAT 2031 2080 -6.25344 -3.95171 -2.17636 0.0509318 0.0154476 -0.159499 0.985762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.93 3.98763 214.726 3996.48 -18.9341 3909.55 +EDGE_SE3:QUAT 2032 2082 -5.56571 -0.124822 -2.1324 0.167663 -0.0601002 -0.07426 0.981205 1 8.1852e-19 8.1852e-19 -5.58828e-08 -8.56658e-09 4.1798e-09 1 8.1852e-19 -5.58828e-08 -8.56658e-09 4.1798e-09 1 -5.58828e-08 -8.56658e-09 4.1798e-09 3910.6 -25.2511 -311.008 3997.43 17.4085 4000.99 +EDGE_SE3:QUAT 2031 2082 -6.06331 4.0965 -2.28056 -0.0500104 -0.0323385 0.200703 0.97784 1 6.01853e-20 6.01853e-20 -1.21672e-08 -9.60229e-09 -2.70228e-10 1 6.01853e-20 -1.21672e-08 -9.60229e-09 -2.70228e-10 1 -1.21672e-08 -9.60229e-09 -2.70228e-10 3993.34 3.80822 -125.121 3999.94 -8.471 3842.22 +EDGE_SE3:QUAT 2032 2081 -5.97797 -4.33585 -2.05024 0.0112451 -0.0573716 0.0707585 0.995779 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4054.11 3.06295 -470.587 3986.63 -16.3859 4034.59 +EDGE_SE3:QUAT 2033 2083 -5.59569 0.189901 -2.03405 -0.122991 0.0566547 -0.0609084 0.988915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3970.11 -23.4239 353.338 3994.59 -16.5518 4015.78 +EDGE_SE3:QUAT 2032 2083 -6.24472 4.16206 -2.0174 -0.022512 0.140323 -0.138389 0.980128 1 7.70372e-19 7.70372e-19 -8.32453e-09 -5.43135e-08 -3.44161e-09 1 7.70372e-19 -8.32453e-09 -5.43135e-08 -3.44161e-09 1 -8.32453e-09 -5.43135e-08 -3.44161e-09 4288.04 -79.9064 1116.14 3942.79 -101.587 4213.46 +EDGE_SE3:QUAT 2033 2082 -5.98074 -4.14401 -2.41188 -0.0985147 0.100045 -0.177559 0.974042 1 1.92593e-19 1.92593e-19 -2.72889e-08 5.50631e-09 -1.58702e-09 1 1.92593e-19 -2.72889e-08 5.50631e-09 -1.58702e-09 1 -2.72889e-08 5.50631e-09 -1.58702e-09 4033.1 -49.7387 550.443 3993.02 -58.4714 3945.81 +EDGE_SE3:QUAT 2034 2084 -5.95732 0.167702 -2.29784 -0.060233 -0.115619 -0.104362 0.985958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4238.03 -3.21303 -1036.4 3939.68 40.4578 4208.98 +EDGE_SE3:QUAT 2033 2084 -6.3735 4.41493 -2.31639 -0.0447484 0.0519068 0.100413 0.992583 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4045.77 -3.30132 467.092 3986.29 21.5029 4013.45 +EDGE_SE3:QUAT 2034 2083 -6.33738 -4.0689 -2.08223 0.0794027 0.0879663 -0.113954 0.986393 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4136.67 9.9236 821.166 3959.66 -34.1801 4109.95 +EDGE_SE3:QUAT 2035 2085 -5.7798 -0.150605 -2.2252 -0.00348552 0.162349 -0.0420486 0.985831 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4453.33 -33.3147 1420.95 3896.89 -40.7887 4446.31 +EDGE_SE3:QUAT 2034 2085 -6.56743 4.15504 -2.13074 0.0777469 -0.0634634 -0.0014608 0.99495 1 3.00927e-21 3.00927e-21 2.18434e-10 -2.74743e-10 -3.47946e-09 1 3.00927e-21 2.18434e-10 -2.74743e-10 -3.47946e-09 1 2.18434e-10 -2.74743e-10 -3.47946e-09 4039.5 -20.6723 -508.695 3984.8 7.92991 4063.67 +EDGE_SE3:QUAT 2035 2084 -6.12407 -4.44258 -1.98097 0.14877 -0.0997273 -0.111043 0.977544 1 7.70372e-19 7.70372e-19 -5.48053e-08 7.70347e-09 3.33896e-09 1 7.70372e-19 -5.48053e-08 7.70347e-09 3.33896e-09 1 -5.48053e-08 7.70347e-09 3.33896e-09 3988.4 -55.5716 -567.638 3991 51.1221 4027.61 +EDGE_SE3:QUAT 2036 2086 -5.87049 -0.0185586 -2.35066 -0.134245 0.044085 -0.150781 0.978417 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3928.17 -1.6931 94.3612 4000.37 -1.60842 3909.32 +EDGE_SE3:QUAT 2035 2086 -5.75472 4.32554 -1.95853 0.00776783 -0.0264361 0.153364 0.987786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.68 1.87743 -218.715 3997.25 -16.935 3917.84 +EDGE_SE3:QUAT 2036 2085 -5.99614 -3.92956 -2.15634 0.068897 0.0715819 -0.055369 0.993511 1 1.92593e-19 1.92593e-19 2.79044e-08 -1.27894e-09 2.19508e-09 1 1.92593e-19 2.79044e-08 -1.27894e-09 2.19508e-09 1 2.79044e-08 -1.27894e-09 2.19508e-09 4076.34 15.4489 624.912 3976.08 -8.97774 4083.06 +EDGE_SE3:QUAT 2037 2087 -5.76105 -0.0588617 -2.46447 -0.0185528 -0.13789 0.0378101 0.989552 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4313.8 31.587 -1166.22 3927.07 -35.5496 4309.46 +EDGE_SE3:QUAT 2036 2087 -6.13801 4.3355 -2.16674 0.0582113 0.0317954 0.109082 0.991817 1 1.20371e-20 1.20371e-20 -7.78243e-10 6.87974e-09 -4.4261e-10 1 1.20371e-20 -7.78243e-10 6.87974e-09 -4.4261e-10 1 -7.78243e-10 6.87974e-09 -4.4261e-10 3993.73 5.78342 173.234 3998.85 8.8231 3959.69 +EDGE_SE3:QUAT 2037 2086 -6.13029 -4.19022 -1.79588 -0.251745 0.0196953 -0.151461 0.955665 1 3.8639e-18 3.8639e-18 1.04181e-07 -2.27887e-08 4.8586e-08 1 3.8639e-18 1.04181e-07 -2.27887e-08 4.8586e-08 1 1.04181e-07 -2.27887e-08 4.8586e-08 3763.27 55.0248 -294.73 3987.65 30.778 3925.01 +EDGE_SE3:QUAT 2038 2088 -5.9117 -0.14876 -2.55026 -0.0314983 0.113772 -0.0469531 0.991897 1 4.81482e-20 4.81482e-20 -1.56485e-09 6.12664e-10 -1.41139e-08 1 4.81482e-20 -1.56485e-09 6.12664e-10 -1.41139e-08 1 -1.56485e-09 6.12664e-10 -1.41139e-08 4200.38 -31.3733 926.954 3952.69 -34.5232 4195.53 +EDGE_SE3:QUAT 2037 2088 -6.52289 3.85305 -2.45646 -0.00420833 -0.124163 0.13013 0.983683 1 2.0463e-19 2.0463e-19 -3.27911e-09 -2.82509e-08 -1.77442e-10 1 2.0463e-19 -3.27911e-09 -2.82509e-08 -1.77442e-10 1 -3.27911e-09 -2.82509e-08 -1.77442e-10 4241 52.0541 -1011.35 3948.67 -77.3156 4173.34 +EDGE_SE3:QUAT 2038 2087 -6.04283 -3.93032 -2.41144 -0.189464 0.0223306 0.0075797 0.981604 1 1.88079e-22 1.88079e-22 -2.04466e-11 1.64386e-10 -8.52361e-10 1 1.88079e-22 -2.04466e-11 1.64386e-10 -8.52361e-10 1 -2.04466e-11 1.64386e-10 -8.52361e-10 3865.07 -17.8817 186.288 3998.1 -1.74561 4008.43 +EDGE_SE3:QUAT 2039 2089 -5.65238 0.081504 -2.14703 0.0047696 0.0320591 0.0114053 0.99941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4016.31 0.899676 256.677 3995.92 1.59588 4015.88 +EDGE_SE3:QUAT 2038 2089 -6.43608 3.99481 -2.20133 -0.0921592 0.144269 -0.0775156 0.982183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4249.39 -95.5721 1102.83 3945.68 -92.9983 4259.33 +EDGE_SE3:QUAT 2039 2088 -5.6889 -3.81655 -2.02065 -0.0865434 0.00712599 -0.244141 0.965844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3977.68 10.2878 -191.187 3995.41 33.296 3769.22 +EDGE_SE3:QUAT 2040 2090 -5.67483 0.166235 -2.2901 -0.0849688 -0.221394 -0.153965 0.959197 1 9.62965e-19 9.62965e-19 3.71317e-08 4.94167e-08 -6.38715e-09 1 9.62965e-19 3.71317e-08 4.94167e-08 -6.38715e-09 1 3.71317e-08 4.94167e-08 -6.38715e-09 5002.04 -106.65 -2277.39 3793.72 136.735 4936.09 +EDGE_SE3:QUAT 2039 2090 -6.21583 3.93852 -2.32344 -0.00435114 0.0294432 -0.124291 0.991799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.45 -2.89782 224.27 3997.19 -13.8944 3950.73 +EDGE_SE3:QUAT 2040 2089 -6.47835 -4.06208 -1.9324 0.0281801 -0.0117848 -0.244226 0.969237 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.61 0.284759 -6.5888 3999.98 -2.90908 3761.2 +EDGE_SE3:QUAT 2041 2091 -5.83397 0.160193 -2.46001 0.0588936 0.11868 0.0341642 0.990596 1 1.92593e-19 1.92593e-19 -2.82416e-08 -1.40083e-09 -3.2327e-09 1 1.92593e-19 -2.82416e-08 -1.40083e-09 -3.2327e-09 1 -2.82416e-08 -1.40083e-09 -3.2327e-09 4205.23 43.8423 961.563 3950.24 38.8505 4214.44 +EDGE_SE3:QUAT 2040 2091 -6.51373 3.81036 -2.30338 -0.104574 -0.0198247 0.064745 0.992209 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3957.44 2.63517 -74.5461 3999.91 -1.84048 3984.42 +EDGE_SE3:QUAT 2041 2090 -5.83541 -3.77905 -2.2029 -0.0985332 0.0557859 -0.0861342 0.989828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.68 -19.273 335.417 3995.28 -17.9861 3997.84 +EDGE_SE3:QUAT 2042 2092 -5.92044 0.00740024 -2.30434 -0.0421533 0.0335638 0.0117754 0.998478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.69 -5.56914 274.832 3995.29 0.465968 4018.24 +EDGE_SE3:QUAT 2041 2092 -6.07797 4.02335 -2.25342 0.145511 0.126832 -0.0965716 0.976429 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4261.93 60.4137 1227.8 3918.31 2.21115 4309.32 +EDGE_SE3:QUAT 2042 2091 -5.99332 -4.19262 -2.71931 -0.00984588 -0.0270658 -0.212494 0.976738 1 1.22251e-20 1.22251e-20 2.32158e-09 6.59338e-09 -4.07778e-11 1 1.22251e-20 2.32158e-09 6.59338e-09 -4.07778e-11 1 2.32158e-09 6.59338e-09 -4.07778e-11 4012.45 -2.97183 -227.022 3997.29 24.4871 3832.23 +EDGE_SE3:QUAT 2043 2093 -5.93404 -0.00171089 -2.40796 -0.0699514 0.0103075 -0.170564 0.982806 1 9.62965e-19 9.62965e-19 -2.80484e-08 8.78134e-10 5.49438e-08 1 9.62965e-19 -2.80484e-08 8.78134e-10 5.49438e-08 1 -2.80484e-08 8.78134e-10 5.49438e-08 3980.82 3.83196 -61.6451 3999.23 9.43021 3884.02 +EDGE_SE3:QUAT 2042 2093 -6.24195 3.61781 -2.40325 0.0906685 0.0933855 -0.0175438 0.991338 1 3.88195e-19 3.88195e-19 2.76984e-08 2.71917e-08 -3.28631e-09 1 3.88195e-19 2.76984e-08 2.71917e-08 -3.28631e-09 1 2.76984e-08 2.71917e-08 -3.28631e-09 4114.28 34.9836 781.223 3965.05 12.7862 4145.93 +EDGE_SE3:QUAT 2043 2092 -6.23066 -4.10532 -2.2065 0.145964 -0.0719206 0.172973 0.971392 1 7.70372e-19 7.70372e-19 5.51596e-08 8.36324e-09 -6.50015e-09 1 7.70372e-19 5.51596e-08 8.36324e-09 -6.50015e-09 1 5.51596e-08 8.36324e-09 -6.50015e-09 4091.84 -33.2763 -862.703 3952.42 -53.6955 4057.39 +EDGE_SE3:QUAT 2044 2094 -5.95123 0.123039 -2.04246 0.0922824 0.0202926 0.0125152 0.995447 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3971.29 6.65116 146.61 3998.81 1.67041 4004.73 +EDGE_SE3:QUAT 2043 2094 -6.43686 4.09835 -2.04577 0.207757 0.0253947 -0.192982 0.958619 1 7.70372e-19 7.70372e-19 -5.54026e-09 -1.03237e-08 -5.3928e-08 1 7.70372e-19 -5.54026e-09 -1.03237e-08 -5.3928e-08 1 -5.54026e-09 -1.03237e-08 -5.3928e-08 3927.31 63.3367 652.023 3965.01 -55.4707 3951 +EDGE_SE3:QUAT 2044 2093 -5.81995 -3.9295 -2.04381 -0.131168 0.0263954 -0.0801527 0.987762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3932.25 -2.64834 79.4248 4000.02 -1.97761 3975.37 +EDGE_SE3:QUAT 2045 2095 -6.09999 -0.0783311 -2.44462 0.0687772 0.0897536 -0.0295681 0.993146 1 9.75002e-19 9.75002e-19 5.59121e-08 2.61407e-08 -3.55536e-09 1 9.75002e-19 5.59121e-08 2.61407e-08 -3.55536e-09 1 5.59121e-08 2.61407e-08 -3.55536e-09 4120.33 22.4124 759.235 3966.09 2.15421 4135.76 +EDGE_SE3:QUAT 2044 2095 -5.99144 3.7795 -2.10423 -0.0104097 -0.059255 -0.0513579 0.996867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4057.44 -1.85015 -484.602 3985.74 12.0424 4047.32 +EDGE_SE3:QUAT 2045 2094 -6.14836 -4.19607 -2.12941 0.0585092 0.186767 -0.105045 0.975018 1 2.40741e-19 2.40741e-19 -2.04604e-08 7.29186e-10 -3.21735e-08 1 2.40741e-19 -2.04604e-08 7.29186e-10 -3.21735e-08 1 -2.04604e-08 7.29186e-10 -3.21735e-08 4653.38 -39.2456 1764.47 3854.04 -68.0873 4622.94 +EDGE_SE3:QUAT 2046 2096 -5.7114 0.0687705 -2.24967 -0.00273935 -0.0621389 -0.088808 0.994105 1 1.88079e-22 1.88079e-22 -8.68931e-10 7.79329e-11 5.38781e-11 1 1.88079e-22 -8.68931e-10 7.79329e-11 5.38781e-11 1 -8.68931e-10 7.79329e-11 5.38781e-11 4061.72 -7.62737 -500.811 3985.3 22.8432 4030.2 +EDGE_SE3:QUAT 2045 2096 -6.1733 4.00108 -2.4708 -0.131292 0.161281 -0.212571 0.954759 1 1.54074e-18 1.54074e-18 -5.88981e-08 2.55242e-08 -5.88981e-08 1 1.54074e-18 -5.88981e-08 2.55242e-08 -5.88981e-08 1 -5.88981e-08 2.55242e-08 -5.88981e-08 4098.14 -132.151 856.704 4000.45 -138.069 3986.35 +EDGE_SE3:QUAT 2046 2095 -6.16734 -3.83367 -2.15104 0.0870774 -0.181127 0.112064 0.973166 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4626.8 9.57398 -1749.47 3854.28 -47.0129 4606.9 +EDGE_SE3:QUAT 2047 2097 -5.93143 -0.194145 -1.77415 0.0121962 -0.0448351 -0.0451635 0.997898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.36 -4.31064 -353.238 3992.5 8.65739 4022.79 +EDGE_SE3:QUAT 2046 2097 -6.18717 4.01075 -2.1438 0.0957463 -0.0224264 0.00330489 0.995148 1 4.70198e-23 4.70198e-23 -9.83084e-12 4.15436e-11 4.32022e-10 1 4.70198e-23 -9.83084e-12 4.15436e-11 4.32022e-10 1 -9.83084e-12 4.15436e-11 4.32022e-10 3971.51 -8.6943 -181.047 3998.02 0.875711 4008.13 +EDGE_SE3:QUAT 2047 2096 -5.83357 -3.85748 -2.08617 -0.238591 0.0637434 -0.191939 0.949827 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3764.29 34.3048 -76.806 3995.24 27.6742 3844.63 +EDGE_SE3:QUAT 2048 2098 -5.9877 0.176301 -2.2341 -0.0923488 -0.123471 0.107691 0.982155 1 1.92593e-19 1.92593e-19 2.78018e-09 3.39708e-09 -2.78793e-08 1 1.92593e-19 2.78018e-09 3.39708e-09 -2.78793e-08 1 2.78018e-09 3.39708e-09 -2.78793e-08 4145.09 75.9145 -867.692 3968.44 -78.443 4132.82 +EDGE_SE3:QUAT 2047 2098 -6.11046 3.95743 -2.20725 -0.137114 0.0131803 0.140514 0.98045 1 7.70372e-19 7.70372e-19 5.46051e-08 7.3405e-09 2.78372e-09 1 7.70372e-19 5.46051e-08 7.3405e-09 2.78372e-09 1 5.46051e-08 7.3405e-09 2.78372e-09 3950.2 -23.6393 326.888 3990.55 24.4275 3946.43 +EDGE_SE3:QUAT 2048 2097 -5.85849 -4.08542 -2.17686 -0.0165288 0.007242 -0.0615648 0.99794 1 7.52316e-22 7.52316e-22 -1.07162e-10 -1.73113e-09 -3.00015e-11 1 7.52316e-22 -1.07162e-10 -1.73113e-09 -3.00015e-11 1 -1.07162e-10 -1.73113e-09 -3.00015e-11 3999.42 -0.394487 45.4088 3999.9 -1.28385 3985.35 +EDGE_SE3:QUAT 2049 2099 -6.18969 -0.132152 -2.19276 -0.0863136 -0.11855 0.0578083 0.987499 1 9.62965e-19 9.62965e-19 -5.39667e-08 -3.18771e-08 3.1814e-09 1 9.62965e-19 -5.39667e-08 -3.18771e-08 3.1814e-09 1 -5.39667e-08 -3.18771e-08 3.1814e-09 4166.59 61.7753 -908.388 3959.01 -56.4284 4183.02 +EDGE_SE3:QUAT 2048 2099 -6.29672 3.61343 -2.24292 0.0392752 0.0183611 -0.158388 0.986425 1 1.20371e-20 1.20371e-20 -1.08707e-09 -6.84661e-09 2.19302e-10 1 1.20371e-20 -1.08707e-09 -6.84661e-09 2.19302e-10 1 -1.08707e-09 -6.84661e-09 2.19302e-10 4005.26 2.293 215.022 3996.72 -18.3461 3911.08 +EDGE_SE3:QUAT 2049 2098 -5.7923 -3.8637 -2.15568 0.0738981 -0.0587051 -0.0407974 0.9947 1 4.81482e-20 4.81482e-20 -6.83973e-10 -1.37989e-08 1.09499e-09 1 4.81482e-20 -6.83973e-10 -1.37989e-08 1.09499e-09 1 -6.83973e-10 -1.37989e-08 1.09499e-09 4024.35 -18.9813 -432.594 3989.7 14.2332 4039.53 +EDGE_SE3:QUAT 2050 2100 -6.2291 0.0351545 -2.08472 0.0224631 -0.0624066 0.0146639 0.99769 1 2.07639e-19 2.07639e-19 7.52982e-09 -2.76816e-08 -3.35244e-09 1 2.07639e-19 7.52982e-09 -2.76816e-08 -3.35244e-09 1 7.52982e-09 -2.76816e-08 -3.35244e-09 4061.92 -4.56233 -509.732 3984.17 -1.73648 4063.07 +EDGE_SE3:QUAT 2049 2100 -6.28228 4.02725 -2.50365 0.0456977 0.192356 0.00662197 0.980238 1 1.20371e-20 1.20371e-20 1.42868e-09 3.89622e-10 7.33967e-09 1 1.20371e-20 1.42868e-09 3.89622e-10 7.33967e-09 1 1.42868e-09 3.89622e-10 7.33967e-09 4647.62 62.8955 1747.64 3856.69 56.5421 4655.8 +EDGE_SE3:QUAT 2050 2099 -5.81979 -4.03371 -2.10247 -0.0858398 0.107135 -0.0849586 0.986882 1 3.85186e-19 3.85186e-19 2.53703e-08 2.04358e-11 -2.53703e-08 1 3.85186e-19 2.53703e-08 2.04358e-11 -2.53703e-08 1 2.53703e-08 2.04358e-11 -2.53703e-08 4114.01 -55.2049 772.268 3971.9 -55.0525 4114.61 +EDGE_SE3:QUAT 2051 2101 -6.3236 0.195869 -2.23065 0.0783967 0.0195247 0.0385118 0.995987 1 2.52778e-19 2.52778e-19 2.75543e-08 9.15869e-09 1.36418e-08 1 2.52778e-19 2.75543e-08 9.15869e-09 1.36418e-08 1 2.75543e-08 9.15869e-09 1.36418e-08 3978.88 4.39148 118.424 3999.34 2.51682 3997.53 +EDGE_SE3:QUAT 2050 2101 -6.20094 4.02824 -2.15382 -0.0707951 -0.0670878 0.125408 0.987299 1 1.92593e-19 1.92593e-19 -2.7552e-08 -3.7556e-09 1.29857e-09 1 1.92593e-19 -2.7552e-08 -3.7556e-09 1.29857e-09 1 -2.7552e-08 -3.7556e-09 1.29857e-09 4022.57 23.2239 -417.645 3992.72 -29.8326 3979.71 +EDGE_SE3:QUAT 2051 2100 -6.05776 -3.78059 -2.01656 0.00816781 0.0210855 -0.0473407 0.998623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4007.2 0.189543 173.021 3998.12 -4.05646 3998.51 +EDGE_SE3:QUAT 2052 2102 -5.74602 0.0616866 -2.33117 -0.0626667 0.129995 -0.0160662 0.989402 1 1.92593e-19 1.92593e-19 2.83898e-08 -9.51848e-10 3.6376e-09 1 1.92593e-19 2.83898e-08 -9.51848e-10 3.6376e-09 1 2.83898e-08 -9.51848e-10 3.6376e-09 4258 -46.5799 1081.58 3937.41 -37.0117 4272.67 +EDGE_SE3:QUAT 2051 2102 -6.18654 4.08366 -2.302 -0.0239377 0.0420764 0.0178576 0.998668 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4026.99 -3.42537 343.498 3992.67 2.09016 4028.01 +EDGE_SE3:QUAT 2052 2101 -6.28434 -4.14297 -1.93834 0.0370142 -0.181145 -0.00780384 0.982729 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4569.89 -47.8115 -1622.52 3871.85 42.667 4575.13 +EDGE_SE3:QUAT 2053 2103 -5.85052 -0.150241 -1.85311 0.0615709 0.101104 0.0727358 0.990301 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4126.24 41.6753 765.722 3969.63 43.73 4120.25 +EDGE_SE3:QUAT 2052 2103 -6.12891 4.07641 -1.95605 -0.00310913 0.0680235 0.146137 0.986918 1 3.00927e-21 3.00927e-21 3.45529e-09 5.14965e-10 2.31069e-10 1 3.00927e-21 3.45529e-09 5.14965e-10 2.31069e-10 1 3.45529e-09 5.14965e-10 2.31069e-10 4071.69 15.3212 540.517 3984.21 40.7761 3986.31 +EDGE_SE3:QUAT 2053 2102 -6.03474 -3.95892 -2.00329 0.140787 0.0556313 -0.184998 0.97101 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.35 29.8832 735.405 3963.25 -56.7926 3992.73 +EDGE_SE3:QUAT 2054 2104 -6.12363 0.181701 -2.01607 -0.056646 -0.0254609 -0.075446 0.995214 1 2.40741e-19 2.40741e-19 1.29064e-08 -2.45731e-09 2.72117e-08 1 2.40741e-19 1.29064e-08 -2.45731e-09 2.72117e-08 1 1.29064e-08 -2.45731e-09 2.72117e-08 4003.04 6.02495 -252.941 3995.61 8.99026 3993.11 +EDGE_SE3:QUAT 2053 2104 -6.5516 3.97487 -2.14996 -0.0958448 -0.139877 0.0514549 0.984175 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4245.81 85.2951 -1100.62 3942.44 -77.0462 4271.96 +EDGE_SE3:QUAT 2054 2103 -6.04641 -3.80015 -2.00331 -0.033149 0.00664351 -0.292827 0.955568 1 1.92781e-19 1.92781e-19 2.67786e-08 -7.29288e-09 -3.35519e-10 1 1.92781e-19 2.67786e-08 -7.29288e-09 -3.35519e-10 1 2.67786e-08 -7.29288e-09 -3.35519e-10 3996.28 1.5789 -63.3708 3999.33 15.2842 3657.68 +EDGE_SE3:QUAT 2055 2105 -5.83764 -0.0860458 -1.84159 -0.133969 0.103241 -0.0635839 0.98354 1 9.62965e-19 9.62965e-19 -5.29503e-08 3.23306e-08 -4.6675e-10 1 9.62965e-19 -5.29503e-08 3.23306e-08 -4.6675e-10 1 -5.29503e-08 3.23306e-08 -4.6675e-10 4051.02 -62.5809 713.571 3977.97 -51.1803 4106.64 +EDGE_SE3:QUAT 2054 2105 -6.40353 4.05922 -2.3888 -0.148738 -0.045223 0.109279 0.981779 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3915.96 7.73033 -152.288 4000.08 -6.69024 3956.69 +EDGE_SE3:QUAT 2055 2104 -6.16128 -3.6106 -1.98464 -0.228708 0.0153465 -0.110478 0.967084 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3796.51 32.0101 -179.3 3995.06 14.6475 3956.91 +EDGE_SE3:QUAT 2056 2106 -6.05671 -0.00923209 -2.13017 -0.113224 0.064001 -0.0824564 0.988071 1 1.92593e-19 1.92593e-19 -2.64281e-09 -2.73926e-08 -3.40919e-09 1 1.92593e-19 -2.64281e-09 -2.73926e-08 -3.40919e-09 1 -2.64281e-09 -2.73926e-08 -3.40919e-09 3985.55 -25.6781 388.401 3993.82 -22.1809 4009.63 +EDGE_SE3:QUAT 2055 2106 -6.22057 3.99385 -1.8653 -0.0543794 0.110366 0.26114 0.957428 1 1.20371e-20 1.20371e-20 -6.85381e-09 -1.82654e-09 -8.77291e-10 1 1.20371e-20 -6.85381e-09 -1.82654e-09 -8.77291e-10 1 -6.85381e-09 -1.82654e-09 -8.77291e-10 4227.68 64.1872 1007.71 3955.68 135.104 3966.73 +EDGE_SE3:QUAT 2056 2105 -5.91935 -4.21299 -2.08422 -0.0399638 0.0146487 -0.10075 0.994001 1 4.81482e-20 4.81482e-20 -1.37964e-08 1.4105e-09 -8.73827e-11 1 4.81482e-20 -1.37964e-08 1.4105e-09 -8.73827e-11 1 -1.37964e-08 1.4105e-09 -8.73827e-11 3994.67 -1.23988 67.1874 3999.86 -2.63419 3960.45 +EDGE_SE3:QUAT 2057 2107 -6.10256 0.124651 -2.18165 -0.0322238 -0.0848056 0.148893 0.984683 1 4.81482e-20 4.81482e-20 -1.38225e-08 -2.191e-09 9.98986e-10 1 4.81482e-20 -1.38225e-08 -2.191e-09 9.98986e-10 1 -1.38225e-08 -2.191e-09 9.98986e-10 4086.14 32.0212 -608.732 3982.58 -51.094 4001.62 +EDGE_SE3:QUAT 2056 2107 -6.00885 3.603 -2.04305 -0.0436017 -0.0443233 0.140438 0.988135 1 9.62965e-20 9.62965e-20 1.17446e-08 1.57117e-08 3.33552e-10 1 9.62965e-20 1.17446e-08 1.57117e-08 3.33552e-10 1 1.17446e-08 1.57117e-08 3.33552e-10 4010.49 9.85623 -271.429 3996.89 -18.746 3939.2 +EDGE_SE3:QUAT 2057 2106 -6.62016 -3.71369 -1.8929 0.0326362 0.0841482 -0.0361109 0.995264 1 2.0463e-19 2.0463e-19 -7.87e-09 -2.74105e-08 1.398e-10 1 2.0463e-19 -7.87e-09 -2.74105e-08 1.398e-10 1 -7.87e-09 -2.74105e-08 1.398e-10 4115.74 5.87423 703.145 3970.51 -7.8259 4114.78 +EDGE_SE3:QUAT 2058 2108 -5.85919 0.176084 -1.73736 0.0772147 -0.00247919 -0.192164 0.978317 1 1.95602e-19 1.95602e-19 -2.6512e-08 8.67915e-09 -9.94776e-10 1 1.95602e-19 -2.6512e-08 8.67915e-09 -9.94776e-10 1 -2.6512e-08 8.67915e-09 -9.94776e-10 3981.36 7.30627 154.592 3997.23 -20.2186 3857.5 +EDGE_SE3:QUAT 2057 2108 -6.4678 4.04672 -2.15127 0.0501556 -0.22046 0.130457 0.96533 1 7.70372e-19 7.70372e-19 -1.39581e-08 -4.86577e-10 5.97103e-08 1 7.70372e-19 -1.39581e-08 -4.86577e-10 5.97103e-08 1 -1.39581e-08 -4.86577e-10 5.97103e-08 4939.21 120.037 -2167.54 3809.72 -142.338 4881.2 +EDGE_SE3:QUAT 2058 2107 -5.84402 -4.2034 -2.21767 0.152652 0.132129 -0.0519822 0.978027 1 1.54074e-18 1.54074e-18 5.71171e-08 5.37582e-08 1.8501e-10 1 1.54074e-18 5.71171e-08 5.37582e-08 1.8501e-10 1 5.71171e-08 5.37582e-08 1.8501e-10 4235.88 84.7932 1193.61 3926.58 39.4399 4318.28 +EDGE_SE3:QUAT 2059 2109 -5.89457 -0.226077 -1.88177 -0.0813395 -0.0538254 -0.133513 0.986236 1 7.70372e-19 7.70372e-19 4.08037e-09 3.62672e-09 -5.52689e-08 1 7.70372e-19 4.08037e-09 3.62672e-09 -5.52689e-08 1 4.08037e-09 3.62672e-09 -5.52689e-08 4048.41 11.057 -553.304 3980.05 32.5435 4003.57 +EDGE_SE3:QUAT 2058 2109 -6.48201 3.15858 -2.22932 0.00603182 0.0566601 0.2763 0.959381 1 1.20371e-20 1.20371e-20 6.68991e-09 1.94321e-09 3.11851e-10 1 1.20371e-20 6.68991e-09 1.94321e-09 3.11851e-10 1 6.68991e-09 1.94321e-09 3.11851e-10 4036.38 18.3839 386.012 3995.55 51.8661 3731.16 +EDGE_SE3:QUAT 2059 2108 -6.21469 -3.90053 -2.08211 0.12747 0.0337798 -0.0920602 0.986983 1 1.92593e-19 1.92593e-19 1.54457e-09 3.33476e-09 2.75335e-08 1 1.92593e-19 1.54457e-09 3.33476e-09 2.75335e-08 1 1.54457e-09 3.33476e-09 2.75335e-08 3974.82 24.1249 402.91 3988.4 -14.2067 4005.91 +EDGE_SE3:QUAT 2060 2110 -5.90648 -0.380699 -2.39572 0.0555457 0.0206953 0.144674 0.987702 1 4.81482e-20 4.81482e-20 1.37084e-08 2.02813e-09 5.28948e-11 1 4.81482e-20 1.37084e-08 2.02813e-09 5.28948e-11 1 1.37084e-08 2.02813e-09 5.28948e-11 3988.41 1.25754 64.6882 4000 2.37198 3917.02 +EDGE_SE3:QUAT 2059 2110 -6.26375 3.7768 -1.6641 -0.0444851 -0.00527283 0.0230873 0.998729 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.3 0.577766 -29.7206 3999.96 -0.31271 3998.08 +EDGE_SE3:QUAT 2060 2109 -5.87906 -3.47211 -1.76229 0.125642 -0.153489 -0.0519438 0.978753 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4263.19 -117.697 -1189.44 3939.58 105.065 4315.54 +EDGE_SE3:QUAT 2061 2111 -5.67788 0.0379647 -1.97966 -0.13598 0.165209 -0.000716447 0.976839 1 1.20371e-20 1.20371e-20 -1.16086e-09 1.05492e-09 -7.15264e-09 1 1.20371e-20 -1.16086e-09 1.05492e-09 -7.15264e-09 1 -1.16086e-09 1.05492e-09 -7.15264e-09 4371.06 -123.084 1406.72 3910.35 -98.5217 4445.02 +EDGE_SE3:QUAT 2060 2111 -6.06015 3.6431 -1.97228 0.114664 -0.0224914 0.16806 0.978827 1 4.81482e-20 4.81482e-20 2.20845e-09 -1.36046e-08 1.40349e-09 1 4.81482e-20 2.20845e-09 -1.36046e-08 1.40349e-09 1 2.20845e-09 -1.36046e-08 1.40349e-09 3985.57 -19.5565 -397.811 3987.27 -34.7911 3925.19 +EDGE_SE3:QUAT 2061 2110 -5.90747 -3.67452 -1.91072 0.00995136 0.239418 -0.0182268 0.970695 1 7.52316e-22 7.52316e-22 -1.90231e-09 3.01019e-11 -4.69568e-10 1 7.52316e-22 -1.90231e-09 3.01019e-11 -4.69568e-10 1 -1.90231e-09 3.01019e-11 -4.69568e-10 5104.24 -14.4348 2374.6 3770.6 -17.0045 5103.3 +EDGE_SE3:QUAT 2062 2112 -6.10632 -0.452601 -1.89285 0.0107788 0.0280427 -0.0656786 0.997388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.95 -0.0347772 232.019 3996.64 -7.54694 3996.16 +EDGE_SE3:QUAT 2061 2112 -6.28114 3.5434 -2.46446 -0.132068 0.0034068 -0.0910232 0.987047 1 7.73381e-19 7.73381e-19 -5.45039e-08 8.35255e-09 1.59111e-09 1 7.73381e-19 -5.45039e-08 8.35255e-09 1.59111e-09 1 -5.45039e-08 8.35255e-09 1.59111e-09 3933.04 10.6015 -115.649 3998.35 7.12603 3969.66 +EDGE_SE3:QUAT 2062 2111 -5.93368 -4.0076 -1.9594 0.089588 0.0285273 -0.0844937 0.991978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3992.37 12.7846 314.918 3992.96 -11.7315 3995.91 +EDGE_SE3:QUAT 2063 2113 -5.84045 0.0117146 -1.88403 -0.0251819 -0.00674923 -0.162005 0.986446 1 1.50463e-20 1.50463e-20 7.40731e-09 2.30181e-09 -2.48903e-11 1 1.50463e-20 7.40731e-09 2.30181e-09 -2.48903e-11 1 7.40731e-09 2.30181e-09 -2.48903e-11 3999.91 0.960189 -99.9746 3999.22 9.29159 3897.47 +EDGE_SE3:QUAT 2062 2113 -6.34413 3.67088 -2.05258 -0.0382 -0.0817145 0.0791635 0.992772 1 2.40741e-19 2.40741e-19 -1.15483e-08 -2.87497e-08 -3.7743e-10 1 2.40741e-19 -1.15483e-08 -2.87497e-08 -3.7743e-10 1 -1.15483e-08 -2.87497e-08 -3.7743e-10 4088.55 24.1429 -621.892 3978.94 -31.3255 4069.32 +EDGE_SE3:QUAT 2063 2112 -6.52678 -4.21932 -2.03786 0.0340642 -0.0970544 -0.148472 0.983553 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4115.97 -41.9054 -706.066 3976.88 61.6158 4032.44 +EDGE_SE3:QUAT 2064 2114 -5.96667 -0.0106513 -1.94403 -0.080291 0.177062 0.0558304 0.979329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4560.02 -37.7114 1639.03 3868.45 -12.2516 4573.33 +EDGE_SE3:QUAT 2063 2114 -6.3038 4.05777 -1.99246 0.183113 -0.0920665 -0.0507388 0.977455 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3951.96 -61.4854 -596.408 3987 42.4713 4075.78 +EDGE_SE3:QUAT 2064 2113 -6.16299 -3.73864 -1.77537 -0.104463 0.0793809 -0.0416386 0.990481 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4038.75 -36.5201 580.578 3982.65 -26.1929 4075.47 +EDGE_SE3:QUAT 2065 2115 -5.9671 0.102757 -1.97968 0.0206529 0.0976021 0.0785802 0.991903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4143.9 26.5276 777.036 3966.71 37.8294 4120.91 +EDGE_SE3:QUAT 2064 2115 -6.2919 3.57257 -1.98333 0.0090353 0.0292646 0.0752737 0.996692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.24 2.46199 224.565 3997.04 8.5712 3989.9 +EDGE_SE3:QUAT 2065 2114 -5.99568 -3.69544 -1.64848 -0.131486 -0.0300325 0.155569 0.978574 1 7.70372e-19 7.70372e-19 5.43093e-08 8.76901e-09 6.96738e-10 1 7.70372e-19 5.43093e-08 8.76901e-09 6.96738e-10 1 5.43093e-08 8.76901e-09 6.96738e-10 3929.09 -6.54561 13.3979 3999.42 7.76304 3901.44 +EDGE_SE3:QUAT 2066 2116 -6.01428 0.134321 -2.25401 -0.0207639 0.000645705 -0.0261202 0.999443 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.27 0.0365364 -1.34644 4000 0.0459591 3997.27 +EDGE_SE3:QUAT 2065 2116 -5.99824 4.12726 -2.414 0.0955446 0.126101 0.122929 0.979724 1 7.70372e-19 7.70372e-19 -5.43209e-09 -7.18904e-09 -5.56002e-08 1 7.70372e-19 -5.43209e-09 -7.18904e-09 -5.56002e-08 1 -5.43209e-09 -7.18904e-09 -5.56002e-08 4138.81 81.1155 858.85 3971.58 85.3927 4114.88 +EDGE_SE3:QUAT 2066 2115 -5.95766 -3.52857 -2.11851 0.012173 0.0103069 -0.11981 0.992669 1 1.92593e-19 1.92593e-19 3.58278e-10 2.60265e-10 2.75605e-08 1 1.92593e-19 3.58278e-10 2.60265e-10 2.75605e-08 1 3.58278e-10 2.60265e-10 2.75605e-08 4001.8 0.22453 98.0575 3999.37 -6.15448 3944.98 +EDGE_SE3:QUAT 2067 2117 -5.84296 -0.281542 -2.21937 0.128595 0.127127 0.0370443 0.982817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4158.87 84.432 975.849 3955.59 67.4843 4219.53 +EDGE_SE3:QUAT 2066 2117 -6.52234 3.36703 -2.1076 0.0261995 -0.0962624 -0.0434106 0.994064 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4142.9 -20.8395 -777.068 3965.64 24.2514 4138.11 +EDGE_SE3:QUAT 2067 2116 -6.0063 -3.65695 -2.20443 -0.112162 0.0270263 0.0466135 0.992228 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.4 -15.4528 274.844 3994.85 4.02259 4010.03 +EDGE_SE3:QUAT 2068 2118 -5.86984 -0.0742077 -2.02765 -0.0610364 0.151685 0.0560082 0.984951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4402.15 -15.9843 1357.28 3903.09 8.41079 4404.51 +EDGE_SE3:QUAT 2067 2118 -6.41734 3.78439 -1.94094 0.0701978 -0.0541963 0.0920577 0.991797 1 2.40741e-19 2.40741e-19 -2.89179e-08 1.1419e-08 1.01118e-09 1 2.40741e-19 -2.89179e-08 1.1419e-08 1.01118e-09 1 -2.89179e-08 1.1419e-08 1.01118e-09 4044.06 -10.9638 -509.45 3983.35 -18.9866 4029.87 +EDGE_SE3:QUAT 2068 2117 -6.16588 -3.62202 -1.90053 -0.167201 0.0346515 -0.0639977 0.983233 1 7.82409e-19 7.82409e-19 5.4111e-08 -1.08139e-08 -5.53323e-10 1 7.82409e-19 5.4111e-08 -1.08139e-08 -5.53323e-10 1 5.4111e-08 -1.08139e-08 -5.53323e-10 3892.34 -8.34841 138.16 3999.79 -4.72783 3987.78 +EDGE_SE3:QUAT 2069 2119 -6.39944 0.229211 -2.13257 0.0552483 0.0579448 0.0445291 0.995795 1 4.81482e-20 4.81482e-20 1.39003e-08 7.11358e-10 7.31582e-10 1 4.81482e-20 1.39003e-08 7.11358e-10 7.31582e-10 1 1.39003e-08 7.11358e-10 7.31582e-10 4034.46 15.3508 434.748 3989.33 13.7875 4038.74 +EDGE_SE3:QUAT 2068 2119 -6.13399 3.31401 -2.03727 -0.0877751 -0.0927346 0.23222 0.964246 1 7.70372e-19 7.70372e-19 2.28625e-09 6.78163e-09 -5.38421e-08 1 7.70372e-19 2.28625e-09 6.78163e-09 -5.38421e-08 1 2.28625e-09 6.78163e-09 -5.38421e-08 4013.31 38.5491 -438.977 3999.21 -50.0709 3828.42 +EDGE_SE3:QUAT 2069 2118 -5.90742 -3.31662 -2.28751 0.0767793 -0.0784284 0.0558862 0.992386 1 1.92593e-19 1.92593e-19 2.41224e-09 -1.9283e-09 -2.79405e-08 1 1.92593e-19 2.41224e-09 -1.9283e-09 -2.79405e-08 1 2.41224e-09 -1.9283e-09 -2.79405e-08 4091.38 -19.321 -687.885 3971.34 -7.91487 4102.46 +EDGE_SE3:QUAT 2070 2120 -6.21053 -0.0633654 -1.63756 0.0502282 0.0971672 -0.133987 0.984928 1 4.81482e-20 4.81482e-20 1.39791e-08 -1.79185e-09 1.51536e-09 1 4.81482e-20 1.39791e-08 -1.79185e-09 1.51536e-09 1 1.39791e-08 -1.79185e-09 1.51536e-09 4170.17 -11.449 868.155 3957.2 -52.3736 4108.45 +EDGE_SE3:QUAT 2069 2120 -6.47456 3.45711 -2.03556 0.161553 0.0504677 0.0979861 0.98069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3903.87 12.5069 196.308 3999.76 9.84367 3969.86 +EDGE_SE3:QUAT 2070 2119 -6.0757 -3.57705 -1.79795 -0.0526039 0.031192 -0.042755 0.997212 1 4.81482e-20 4.81482e-20 1.38603e-08 -6.376e-10 3.67027e-10 1 4.81482e-20 1.38603e-08 -6.376e-10 3.67027e-10 1 1.38603e-08 -6.376e-10 3.67027e-10 4001.13 -6.45669 221.43 3997.28 -5.59554 4004.88 +EDGE_SE3:QUAT 2071 2121 -6.31115 -0.114323 -1.76897 0.061656 -0.118031 -0.00325417 0.991089 1 1.95602e-19 1.95602e-19 -9.20243e-10 -2.72747e-08 5.31743e-09 1 1.95602e-19 -9.20243e-10 -2.72747e-08 5.31743e-09 1 -9.20243e-10 -2.72747e-08 5.31743e-09 4213.27 -35.8378 -982.928 3946.58 23.6422 4228.44 +EDGE_SE3:QUAT 2070 2121 -6.81276 3.31205 -1.75449 0.257996 -0.160253 -0.0103777 0.952706 1 7.70372e-19 7.70372e-19 5.10774e-09 5.26417e-08 -1.51943e-08 1 7.70372e-19 5.10774e-09 5.26417e-08 -1.51943e-08 1 5.10774e-09 5.26417e-08 -1.51943e-08 4062.92 -192.869 -1197.98 3963.7 155.913 4328.73 +EDGE_SE3:QUAT 2071 2120 -6.16931 -3.51208 -1.59348 -0.0696576 -0.0225645 -0.0251814 0.996998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3990.6 6.88838 -200.475 3997.38 1.61559 4007.48 +EDGE_SE3:QUAT 2072 2122 -5.97059 -0.030168 -2.56492 -0.188006 -0.0212595 0.146878 0.970891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3862.39 -25.7863 163.161 3995.2 19.9476 3917.48 +EDGE_SE3:QUAT 2071 2122 -6.08904 3.49319 -1.88244 -0.0638947 0.00488229 0.120935 0.99059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.66 -4.57775 129.674 3998.44 9.40986 3945.49 +EDGE_SE3:QUAT 2072 2121 -6.20454 -3.49402 -1.84879 0.0258279 -0.0332497 -0.156676 0.986752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4008.06 -5.37418 -208.603 3998.13 15.4318 3912.54 +EDGE_SE3:QUAT 2073 2123 -6.0379 0.22034 -2.22442 -0.177747 0.077544 -0.026132 0.980668 1 2.40741e-19 2.40741e-19 5.5926e-10 2.97613e-08 -8.64673e-09 1 2.40741e-19 5.5926e-10 2.97613e-08 -8.64673e-09 1 5.5926e-10 2.97613e-08 -8.64673e-09 3945.76 -51.5203 543.328 3987.08 -28.3758 4069.4 +EDGE_SE3:QUAT 2072 2123 -6.38054 3.36452 -1.95574 0.0800076 0.0202995 0.0382151 0.995855 1 1.92593e-19 1.92593e-19 2.76537e-08 1.13823e-09 3.85534e-10 1 1.92593e-19 2.76537e-08 1.13823e-09 3.85534e-10 1 2.76537e-08 1.13823e-09 3.85534e-10 3978.19 4.71597 124.054 3999.27 2.66059 3997.96 +EDGE_SE3:QUAT 2073 2122 -6.02802 -3.42081 -2.496 -0.0162101 0.0588062 -0.0747741 0.995333 1 1.20371e-20 1.20371e-20 -6.95108e-09 5.38826e-10 -3.88818e-10 1 1.20371e-20 -6.95108e-09 5.38826e-10 -3.88818e-10 1 -6.95108e-09 5.38826e-10 -3.88818e-10 4050.43 -9.7179 456.762 3987.96 -18.7274 4029.12 +EDGE_SE3:QUAT 2074 2124 -6.30587 -0.00784763 -2.14607 -0.0146977 0.136584 -0.00686185 0.990496 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4314.15 -13.6291 1165.88 3925.83 -11.9918 4314.82 +EDGE_SE3:QUAT 2073 2124 -5.78765 3.75178 -2.30476 0.0720108 0.157271 -0.115464 0.978135 1 4.81482e-20 4.81482e-20 -1.43787e-08 1.42854e-09 -2.48035e-09 1 4.81482e-20 -1.43787e-08 1.42854e-09 -2.48035e-09 1 -1.43787e-08 1.42854e-09 -2.48035e-09 4459.68 -17.2486 1467.21 3890.75 -56.7545 4427.09 +EDGE_SE3:QUAT 2074 2123 -6.10747 -3.58594 -1.63558 0.0168979 -0.0168346 0.12027 0.992455 1 3.00927e-21 3.00927e-21 3.44592e-09 4.15656e-10 -7.07455e-11 1 3.00927e-21 3.44592e-09 4.15656e-10 -7.07455e-11 1 3.44592e-09 4.15656e-10 -7.07455e-11 4004.93 -0.343411 -156.084 3998.42 -9.70251 3948.21 +EDGE_SE3:QUAT 2075 2125 -5.6946 0.347958 -2.00552 0.0172236 0.0598278 0.0560734 0.996484 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.29 8.83805 469.995 3987.02 14.9653 4041.9 +EDGE_SE3:QUAT 2074 2125 -6.59775 3.69854 -1.84926 0.0375756 0.0649414 -0.0428061 0.996262 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4067.28 6.15836 545.041 3981.8 -8.2342 4065.6 +EDGE_SE3:QUAT 2075 2124 -5.93204 -3.92275 -1.7897 -0.110107 0.0932222 -0.068319 0.987177 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4053.97 -48.1859 649.809 3980.39 -41.4341 4083.79 +EDGE_SE3:QUAT 2076 2126 -5.89019 -0.357423 -1.82606 0.0150274 -0.120471 0.138986 0.982824 1 7.52316e-22 7.52316e-22 -1.75657e-09 -2.49298e-10 2.14318e-10 1 7.52316e-22 -1.75657e-09 -2.49298e-10 2.14318e-10 1 -1.75657e-09 -2.49298e-10 2.14318e-10 4240.27 43.4908 -1011.43 3947.38 -75.6305 4163.91 +EDGE_SE3:QUAT 2075 2126 -6.35367 3.41941 -1.76555 -0.0671326 -0.0470717 -0.0955974 0.992038 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4032.01 9.56292 -450.624 3986.76 18.5113 4013.48 +EDGE_SE3:QUAT 2076 2125 -6.25481 -3.16925 -2.1351 0.00929452 -0.0215117 -0.130907 0.991118 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4005.51 -1.91478 -153.41 3998.77 9.75499 3937.31 +EDGE_SE3:QUAT 2077 2127 -6.05497 -0.0468846 -2.19734 0.0695604 0.0695607 0.0439448 0.994179 1 1.92593e-19 1.92593e-19 2.7825e-08 1.50118e-09 1.74772e-09 1 1.92593e-19 2.7825e-08 1.50118e-09 1.74772e-09 1 2.7825e-08 1.50118e-09 1.74772e-09 4047.41 23.1116 521.311 3985.03 18.9986 4059.04 +EDGE_SE3:QUAT 2076 2127 -6.42831 3.52636 -1.86411 -0.0214727 -0.200035 -0.0425415 0.978629 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4731.04 -21.6724 -1862.43 3839.23 31.6002 4725.65 +EDGE_SE3:QUAT 2077 2126 -5.97184 -3.282 -2.13642 0.222453 -0.0421889 -0.222831 0.948199 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3810.83 52.3879 267.528 3985.58 -52.4814 3810.16 +EDGE_SE3:QUAT 2078 2128 -6.08139 -0.0560443 -1.81457 0.0431883 0.0158223 -0.00594938 0.998924 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3996.72 2.78477 129.417 3998.95 -0.119889 4004.04 +EDGE_SE3:QUAT 2077 2128 -6.3541 3.29161 -1.94547 0.059664 0.00360845 -0.0694493 0.995793 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3987.22 2.70142 77.9811 3999.45 -3.18014 3982.16 +EDGE_SE3:QUAT 2078 2127 -6.23287 -3.34582 -1.97876 -0.0743387 -0.155103 -0.164525 0.971261 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4462.23 -51.8771 -1473.81 3894.28 103.141 4376.06 +EDGE_SE3:QUAT 2079 2129 -5.92656 0.141562 -2.08426 -0.0328301 -0.0137361 -0.0687435 0.996999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4000.29 1.94393 -136.065 3998.71 4.77893 3985.7 +EDGE_SE3:QUAT 2078 2129 -5.94856 3.66557 -2.18198 -0.0254807 0.0375133 -0.0924663 0.994683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4015.35 -5.97939 268.815 3996.07 -12.8199 3983.75 +EDGE_SE3:QUAT 2079 2128 -6.11704 -3.61409 -1.83444 -0.0779399 -0.00982772 -0.0442013 0.995929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.19 4.96546 -118.903 3998.93 2.57566 3995.67 +EDGE_SE3:QUAT 2080 2130 -5.83627 -0.0062531 -2.09587 -0.209903 -0.0387237 -0.00379086 0.976948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3846.15 31.4753 -300.264 3995.63 -6.7807 4022.33 +EDGE_SE3:QUAT 2079 2130 -6.67179 3.57751 -1.97558 -0.0485772 0.170139 -0.0985392 0.979277 1 1.92593e-19 1.92593e-19 4.55147e-09 -2.49482e-09 2.86535e-08 1 1.92593e-19 4.55147e-09 -2.49482e-09 2.86535e-08 1 4.55147e-09 -2.49482e-09 2.86535e-08 4428.89 -114.167 1395.39 3913.92 -122.598 4399.49 +EDGE_SE3:QUAT 2080 2129 -6.23095 -3.68747 -1.78357 -0.0283151 0.0524237 -0.0864379 0.994474 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4034.02 -10.5443 387.884 3991.68 -18.3682 4007.34 +EDGE_SE3:QUAT 2081 2131 -5.97798 0.055837 -1.94691 -0.0353833 -0.0385943 -0.0845181 0.995045 1 4.81482e-20 4.81482e-20 1.38597e-08 -1.14009e-09 -6.118e-10 1 4.81482e-20 1.38597e-08 -1.14009e-09 -6.118e-10 1 1.38597e-08 -1.14009e-09 -6.118e-10 4024.15 2.79093 -342.891 3992.49 13.7041 4000.59 +EDGE_SE3:QUAT 2080 2131 -6.49503 3.45668 -2.16213 0.0233983 0.167074 0.195728 0.966038 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4381.08 146.502 1298.39 3941.49 173.296 4230.03 +EDGE_SE3:QUAT 2081 2130 -5.99005 -3.31981 -2.12971 -0.0352641 -0.155768 -0.0610058 0.985277 1 9.62965e-20 9.62965e-20 1.20764e-08 -1.01888e-09 1.20764e-08 1 9.62965e-20 1.20764e-08 -1.01888e-09 1.20764e-08 1 1.20764e-08 -1.01888e-09 1.20764e-08 4426.59 -10.2222 -1382.94 3900.46 29.7805 4416.68 +EDGE_SE3:QUAT 2082 2132 -6.1909 -0.130467 -1.95843 -0.00413673 0.0201954 0.160747 0.98678 1 1.88079e-22 1.88079e-22 8.56627e-10 1.39514e-10 1.7765e-11 1 1.88079e-22 8.56627e-10 1.39514e-10 1.7765e-11 1 8.56627e-10 1.39514e-10 1.7765e-11 4006.6 1.28177 163.424 3998.5 13.1945 3903.31 +EDGE_SE3:QUAT 2081 2132 -6.27302 3.56946 -1.70289 -0.0294421 0.0296451 0.0261096 0.998786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.68 -3.12322 246.663 3996.15 2.62868 4012.42 +EDGE_SE3:QUAT 2082 2131 -6.17475 -3.20488 -1.94801 -0.225224 0.0269219 0.108061 0.967922 1 1.92593e-19 1.92593e-19 1.9807e-09 -6.00998e-09 2.70649e-08 1 1.92593e-19 1.9807e-09 -6.00998e-09 2.70649e-08 1 1.9807e-09 -6.00998e-09 2.70649e-08 3853.21 -58.3919 482.759 3982.04 16.036 4009.4 +EDGE_SE3:QUAT 2083 2133 -5.81745 -0.241465 -1.5461 0.17628 0.0141977 0.185448 0.966609 1 7.70372e-19 7.70372e-19 -5.37648e-08 -9.93751e-09 2.82767e-09 1 7.70372e-19 -5.37648e-08 -9.93751e-09 2.82767e-09 1 -5.37648e-08 -9.93751e-09 2.82767e-09 3890.67 -33.5363 -273.498 3989.99 -35.531 3877.41 +EDGE_SE3:QUAT 2082 2133 -6.44383 3.98501 -1.96622 0.00239344 -0.035847 0.0810397 0.996063 1 2.40741e-19 2.40741e-19 -1.29998e-10 1.39187e-08 -2.76701e-08 1 2.40741e-19 -1.29998e-10 1.39187e-08 -2.76701e-08 1 -1.29998e-10 1.39187e-08 -2.76701e-08 4020.54 2.16771 -287.562 3995.02 -11.729 3994.3 +EDGE_SE3:QUAT 2083 2132 -6.11785 -3.59948 -1.73738 -0.012068 0.00861977 0.135006 0.990734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001.28 -0.209246 86.4182 3999.5 6.20506 3928.95 +EDGE_SE3:QUAT 2084 2134 -6.40075 0.0836463 -2.03934 -0.00148893 0.18417 0.0366431 0.98221 1 7.52316e-22 7.52316e-22 1.8276e-09 7.20698e-11 3.41919e-10 1 7.52316e-22 1.8276e-09 7.20698e-11 3.41919e-10 1 1.8276e-09 7.20698e-11 3.41919e-10 4601.19 33.61 1663.2 3865.95 40.2314 4595.83 +EDGE_SE3:QUAT 2083 2134 -6.36572 3.03035 -2.30642 0.198822 0.0217322 0.096915 0.97499 1 1.92593e-19 1.92593e-19 -4.99289e-10 5.52883e-09 2.70595e-08 1 1.92593e-19 -4.99289e-10 5.52883e-09 2.70595e-08 1 -4.99289e-10 5.52883e-09 2.70595e-08 3841.34 -14.3276 -62.472 3998.71 -7.01711 3961.89 +EDGE_SE3:QUAT 2084 2133 -6.19069 -3.12231 -1.79445 0.0309969 -0.0376398 0.0140361 0.998712 1 1.50463e-20 1.50463e-20 -7.084e-09 2.29337e-11 3.74256e-09 1 1.50463e-20 -7.084e-09 2.29337e-11 3.74256e-09 1 -7.084e-09 2.29337e-11 3.74256e-09 4019.64 -4.3683 -307.404 3994.12 -1.11315 4022.7 +EDGE_SE3:QUAT 2085 2135 -6.15156 0.231746 -1.92774 -0.148362 -0.0237132 -0.0728881 0.985958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3935.72 24.1407 -311.33 3992.78 8.40916 4002.51 +EDGE_SE3:QUAT 2084 2135 -6.69924 3.76892 -1.93651 0.0371684 -0.0375968 0.0404698 0.997781 1 9.62965e-20 9.62965e-20 1.44138e-08 -1.33239e-08 -8.87832e-11 1 9.62965e-20 1.44138e-08 -1.33239e-08 -8.87832e-11 1 1.44138e-08 -1.33239e-08 -8.87832e-11 4019.79 -4.62347 -319.258 3993.54 -5.29103 4018.76 +EDGE_SE3:QUAT 2085 2134 -5.88281 -3.32681 -2.06493 -0.146838 0.0107281 -0.0746554 0.986281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3913.82 6.74019 -46.817 3999.47 3.42279 3977.78 +EDGE_SE3:QUAT 2086 2136 -6.00932 0.192595 -1.96886 0.134755 -0.0878347 0.0061011 0.986959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.29 -50.5332 -711.961 3972.62 23.2565 4122.77 +EDGE_SE3:QUAT 2085 2136 -5.98525 3.36899 -1.77301 0.046216 0.230734 0.0408909 0.971058 1 4.81482e-20 4.81482e-20 1.50185e-08 1.06216e-09 3.47112e-09 1 4.81482e-20 1.50185e-08 1.06216e-09 3.47112e-09 1 1.50185e-08 1.06216e-09 3.47112e-09 4953.63 145.674 2185.14 3808.87 145.136 4955.48 +EDGE_SE3:QUAT 2086 2135 -5.78279 -3.92913 -1.76473 0.076292 0.0999746 -0.140702 0.982032 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4186.84 -1.99727 940.855 3949.14 -53.1574 4130.93 +EDGE_SE3:QUAT 2087 2137 -5.95108 -0.0378646 -1.96939 0.132923 0.0995383 -0.0352346 0.985486 1 1.20371e-20 1.20371e-20 7.46471e-10 9.1056e-10 6.99162e-09 1 1.20371e-20 7.46471e-10 9.1056e-10 6.99162e-09 1 7.46471e-10 9.1056e-10 6.99162e-09 4107.57 55.0611 863.01 3958.59 18.7923 4173.28 +EDGE_SE3:QUAT 2086 2137 -6.67495 3.11147 -1.6884 -0.0726607 0.104886 0.00867783 0.991788 1 4.70198e-23 4.70198e-23 -4.65821e-11 3.21315e-11 -4.3987e-10 1 4.70198e-23 -4.65821e-11 3.21315e-11 -4.3987e-10 1 -4.65821e-11 3.21315e-11 -4.3987e-10 4161.31 -33.0465 873.487 3956.84 -16.1035 4182.12 +EDGE_SE3:QUAT 2087 2136 -5.96675 -3.12064 -2.43987 -0.0442481 -0.14559 0.005229 0.988341 1 8.1852e-19 8.1852e-19 1.32776e-08 5.51263e-08 5.58216e-10 1 8.1852e-19 1.32776e-08 5.51263e-08 5.58216e-10 1 1.32776e-08 5.51263e-08 5.58216e-10 4349.86 36.7494 -1248.48 3917.46 -28.7881 4357.58 +EDGE_SE3:QUAT 2088 2138 -5.82373 -0.0412822 -1.89792 -0.155677 0.0323784 -0.0716594 0.984673 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3905.82 -5.90362 116.271 3999.93 -3.72187 3982.22 +EDGE_SE3:QUAT 2087 2138 -6.44278 3.26921 -1.98739 -0.0707728 0.0389736 0.074523 0.993941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4014.34 -10.5276 372.797 3990.79 11.459 4012.16 +EDGE_SE3:QUAT 2088 2137 -6.22739 -3.02594 -1.73344 0.125279 -0.0875077 -0.224361 0.96245 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3955.21 -24.3947 -305.611 4002.4 27.465 3816.64 +EDGE_SE3:QUAT 2089 2139 -5.68452 -0.264268 -1.59953 -0.0232863 -0.0751344 0.063009 0.994908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4083 15.4688 -589.93 3980.06 -22.4864 4069.29 +EDGE_SE3:QUAT 2088 2139 -6.4249 3.18636 -1.74905 0.0777047 0.272583 -0.131059 0.949992 1 2.40741e-19 2.40741e-19 6.36438e-09 -2.02329e-09 -2.67247e-08 1 2.40741e-19 6.36438e-09 -2.02329e-09 -2.67247e-08 1 6.36438e-09 -2.02329e-09 -2.67247e-08 5613.01 -151.114 3037.92 3697.34 -155.726 5568.45 +EDGE_SE3:QUAT 2089 2138 -5.95299 -3.38154 -2.1851 -0.201952 -0.0540617 -0.00506212 0.977889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3880.9 43.1049 -422.24 3991.28 -12.8226 4043.94 +EDGE_SE3:QUAT 2090 2140 -5.95859 0.220736 -2.07928 -0.0775318 0.0840594 0.0547121 0.991932 1 1.92593e-19 1.92593e-19 -2.79821e-08 -1.17761e-09 -2.57065e-09 1 1.92593e-19 -2.79821e-08 -1.17761e-09 -2.57065e-09 1 -2.79821e-08 -1.17761e-09 -2.57065e-09 4106.86 -20.714 735.457 3967.57 7.03698 4118.93 +EDGE_SE3:QUAT 2089 2140 -6.32031 3.47347 -2.07086 -0.0772787 0.0679247 -0.0385739 0.993945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4039.61 -23.8341 508.211 3985.81 -17.7058 4057.54 +EDGE_SE3:QUAT 2090 2139 -5.94223 -3.14743 -1.94779 0.0960445 -0.0368106 -0.00994007 0.994646 1 2.43751e-19 2.43751e-19 2.75603e-08 -1.4608e-08 -3.06522e-09 1 2.43751e-19 2.75603e-08 -1.4608e-08 -3.06522e-09 1 2.75603e-08 -1.4608e-08 -3.06522e-09 3982.61 -13.6846 -280.131 3995.52 4.28805 4019.12 +EDGE_SE3:QUAT 2091 2141 -5.86592 -0.0624009 -1.85018 0.023505 0.0387216 0.179668 0.982684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4012.65 7.27922 245.656 3997.53 20.9603 3885.74 +EDGE_SE3:QUAT 2090 2141 -6.44125 3.09765 -2.12557 -0.000677762 -0.0647572 0.00997086 0.997851 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4067.91 1.20967 -525.585 3983.25 -2.80537 4067.51 +EDGE_SE3:QUAT 2091 2140 -5.86629 -3.43352 -1.73879 0.0447889 -0.0423336 -0.00568134 0.998083 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.11 -7.89041 -336.624 3993.12 2.87861 4028 +EDGE_SE3:QUAT 2092 2142 -6.39927 0.125209 -2.12187 0.137896 0.0431687 0.0248283 0.989194 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3945.6 20.4401 295.858 3995.72 8.43369 4019.2 +EDGE_SE3:QUAT 2091 2142 -6.25453 3.37216 -2.1816 -0.122333 0.165431 0.201154 0.957708 1 7.70372e-19 7.70372e-19 1.18699e-08 -3.12131e-09 5.75088e-08 1 7.70372e-19 1.18699e-08 -3.12131e-09 5.75088e-08 1 1.18699e-08 -3.12131e-09 5.75088e-08 4588.91 52.1894 1737.02 3860.79 123.217 4486.92 +EDGE_SE3:QUAT 2092 2141 -6.36938 -3.46666 -1.98315 -0.0133139 0.0967171 -0.0972911 0.990456 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4142.32 -27.2486 769.896 3967.73 -43.5823 4105.17 +EDGE_SE3:QUAT 2093 2143 -5.82281 0.284845 -2.14414 -0.0905091 -0.0513478 0.0281795 0.994172 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.5 18.5376 -377.49 3992.18 -10.3293 4032.09 +EDGE_SE3:QUAT 2092 2143 -5.86428 3.0906 -1.86578 0.0573329 -0.217118 0.0317602 0.973943 1 1.20371e-20 1.20371e-20 -1.68229e-09 3.71399e-10 7.47569e-09 1 1.20371e-20 -1.68229e-09 3.71399e-10 7.47569e-09 1 -1.68229e-09 3.71399e-10 7.47569e-09 4878.19 -44.905 -2088.03 3809.81 33.3108 4887.31 +EDGE_SE3:QUAT 2093 2142 -5.79994 -3.05588 -1.85638 0.0882144 0.0721242 0.0343865 0.992892 1 1.92593e-19 1.92593e-19 1.30255e-09 -2.7544e-08 2.60395e-09 1 1.92593e-19 1.30255e-09 -2.7544e-08 2.60395e-09 1 1.30255e-09 -2.7544e-08 2.60395e-09 4040.64 28.3049 540.857 3984.12 19.5121 4067.04 +EDGE_SE3:QUAT 2094 2144 -5.93343 -0.516848 -1.74858 0.0351107 0.0165977 -0.212925 0.976296 1 1.20371e-20 1.20371e-20 6.78418e-09 -1.46922e-09 2.06132e-10 1 1.20371e-20 6.78418e-09 -1.46922e-09 2.06132e-10 1 6.78418e-09 -1.46922e-09 2.06132e-10 4006.07 1.12316 211.159 3996.89 -24.94 3829.66 +EDGE_SE3:QUAT 2093 2144 -6.26926 3.31359 -1.71986 -0.14653 0.0168197 0.0720983 0.986432 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3929.95 -20.3414 254.806 3994.87 7.81767 3995.04 +EDGE_SE3:QUAT 2094 2143 -6.31424 -3.43036 -1.86041 -0.0103479 0.0305404 -0.154228 0.987509 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4011.3 -4.0009 217.271 3997.63 -16.3752 3916.59 +EDGE_SE3:QUAT 2095 2145 -5.64655 0.0857815 -1.89721 0.0058196 -0.0433273 -0.0123398 0.998968 1 5.19098e-20 5.19098e-20 -1.71086e-09 1.39099e-08 3.4581e-09 1 5.19098e-20 -1.71086e-09 1.39099e-08 3.4581e-09 1 -1.71086e-09 1.39099e-08 3.4581e-09 4029.9 -1.59004 -347.926 3992.55 2.4504 4029.43 +EDGE_SE3:QUAT 2094 2145 -6.66448 3.07169 -1.66877 0.0263508 -0.30196 0.0346069 0.952328 1 1.20371e-20 1.20371e-20 2.57418e-09 -6.6404e-11 -8.09328e-09 1 1.20371e-20 2.57418e-09 -6.6404e-11 -8.09328e-09 1 2.57418e-09 -6.6404e-11 -8.09328e-09 5994.38 30.9695 -3460.82 3634 -28.2984 5992.37 +EDGE_SE3:QUAT 2095 2144 -5.58251 -3.46932 -1.70498 0.161094 0.0518375 -0.0794862 0.982366 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3971.62 41.9184 555.627 3979.87 -7.98757 4050.16 +EDGE_SE3:QUAT 2096 2146 -6.05956 0.161374 -1.9364 -0.103353 0.0615676 0.0430824 0.991802 1 9.62965e-19 9.62965e-19 5.63892e-08 -2.58731e-08 1.12717e-09 1 9.62965e-19 5.63892e-08 -2.58731e-08 1.12717e-09 1 5.63892e-08 -2.58731e-08 1.12717e-09 4030.28 -25.6047 545.438 3981.71 1.53192 4065.58 +EDGE_SE3:QUAT 2095 2146 -6.22196 3.20309 -1.77873 -0.126812 0.206718 0.159955 0.95687 1 9.62965e-19 9.62965e-19 2.32525e-08 5.70525e-08 1.07391e-08 1 9.62965e-19 2.32525e-08 5.70525e-08 1.07391e-08 1 2.32525e-08 5.70525e-08 1.07391e-08 4907.22 31.9555 2197.94 3797.3 77.0857 4869.2 +EDGE_SE3:QUAT 2096 2145 -5.79182 -3.29178 -1.91581 -0.0896255 -0.031159 -0.0165462 0.99535 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3985.34 11.7969 -264.926 3995.62 -0.0486122 4016.37 +EDGE_SE3:QUAT 2097 2147 -5.82641 -0.0615974 -2.03617 -0.0582224 0.0123173 -0.0194374 0.998038 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3988.22 -2.38091 84.4636 3999.61 -0.943913 4000.27 +EDGE_SE3:QUAT 2096 2147 -6.28647 3.34795 -1.72115 -0.0243882 -0.255351 0.0656441 0.964309 1 3.12964e-18 3.12964e-18 -5.43932e-09 -1.08268e-07 -3.24381e-09 1 3.12964e-18 -5.43932e-09 -1.08268e-07 -3.24381e-09 1 -5.43932e-09 -1.08268e-07 -3.24381e-09 5226.88 192.343 -2535.48 3768.84 -194.604 5212.02 +EDGE_SE3:QUAT 2097 2146 -6.03812 -3.39227 -1.65845 0.00188487 -0.080928 0.0354022 0.996089 1 4.70198e-23 4.70198e-23 4.37718e-10 1.56283e-11 -3.55317e-11 1 4.70198e-23 4.37718e-10 1.56283e-11 -3.55317e-11 1 4.37718e-10 1.56283e-11 -3.55317e-11 4106.73 5.07578 -662.098 3973.99 -12.223 4101.73 +EDGE_SE3:QUAT 2098 2148 -6.05318 0.384762 -1.76829 0.0274655 0.327291 0.0939185 0.939844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 6251.84 520.989 3755.98 3687.66 513.256 6219.57 +EDGE_SE3:QUAT 2097 2148 -6.38801 3.09337 -1.83244 0.0489811 -0.117534 0.0991489 0.986892 1 1.92593e-19 1.92593e-19 -2.49739e-09 2.74161e-08 -7.15571e-10 1 1.92593e-19 -2.49739e-09 2.74161e-08 -7.15571e-10 1 -2.49739e-09 2.74161e-08 -7.15571e-10 4243.34 8.40021 -1037.22 3939.98 -41.3437 4213.62 +EDGE_SE3:QUAT 2098 2147 -6.44943 -2.97789 -1.35797 0.0513371 0.0609614 -0.125774 0.988852 1 2.40741e-19 2.40741e-19 -1.18499e-08 2.65663e-09 2.67105e-08 1 2.40741e-19 -1.18499e-08 2.65663e-09 2.67105e-08 1 -1.18499e-08 2.65663e-09 2.67105e-08 4066.56 1.55936 560.934 3980.59 -32.521 4013.83 +EDGE_SE3:QUAT 2099 2149 -5.96041 0.299651 -1.95731 -0.0380773 0.0735684 0.0268177 0.996202 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4085.44 -8.69564 610.993 3977.45 3.48894 4088.37 +EDGE_SE3:QUAT 2098 2149 -6.32252 3.73947 -1.59462 -0.2148 0.0481873 0.0251493 0.975144 1 7.82409e-19 7.82409e-19 -5.40701e-08 -1.63681e-09 3.77571e-09 1 7.82409e-19 -5.40701e-08 -1.63681e-09 3.77571e-09 1 -5.40701e-08 -1.63681e-09 3.77571e-09 3860.33 -46.7283 426.103 3990.23 -8.65775 4042.36 +EDGE_SE3:QUAT 2099 2148 -6.03019 -2.82924 -1.58295 0.00655118 -0.0453654 -0.163705 0.985444 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4028.1 -8.42559 -337.73 3994.19 27.7419 3921.07 +EDGE_SE3:QUAT 2100 2150 -5.88918 0.154716 -1.35396 -0.192157 0.210781 0.00779448 0.958429 1 4.81482e-20 4.81482e-20 2.98291e-09 -3.14349e-09 1.4515e-08 1 4.81482e-20 2.98291e-09 -3.14349e-09 1.4515e-08 1 2.98291e-09 -3.14349e-09 1.4515e-08 4584.35 -253.25 1862.29 3884.54 -229.57 4731.8 +EDGE_SE3:QUAT 2099 2150 -6.48032 3.30597 -1.70027 0.2827 0.175085 -0.054866 0.941497 1 3.8639e-18 3.8639e-18 1.1061e-07 6.03862e-08 1.23554e-08 1 3.8639e-18 1.1061e-07 6.03862e-08 1.23554e-08 1 1.1061e-07 6.03862e-08 1.23554e-08 4231.37 257.093 1584.63 3924.61 199.784 4539 +EDGE_SE3:QUAT 2100 2149 -5.55418 -3.14368 -1.55127 0.0511241 -0.0781689 0.0183417 0.995459 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4091.96 -14.8949 -648.18 3974.9 1.54562 4101.07 +EDGE_SE3:QUAT 2101 2151 -6.08329 -0.634163 -2.24699 -0.0216379 -0.0417634 0.139558 0.989096 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4018.89 7.74957 -289.529 3995.85 -20.1764 3942.86 +EDGE_SE3:QUAT 2100 2151 -6.15483 2.79689 -1.4882 -0.0796762 -0.090551 0.191163 0.97412 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4035.08 40.5267 -503.475 3993.8 -52.9146 3914.3 +EDGE_SE3:QUAT 2101 2150 -6.20589 -2.9062 -1.88225 -0.164559 0.0831516 0.0076518 0.982826 1 7.71124e-19 7.71124e-19 5.5458e-08 -1.4135e-09 6.29321e-09 1 7.71124e-19 5.5458e-08 -1.4135e-09 6.29321e-09 1 5.5458e-08 -1.4135e-09 6.29321e-09 4000.47 -57.4488 668.713 3976.85 -25.0846 4108.56 +EDGE_SE3:QUAT 2102 2152 -5.90368 0.0147362 -1.42733 -0.152116 0.0436973 0.234085 0.959247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4037.72 -30.8457 740.319 3960.61 81.711 3911.1 +EDGE_SE3:QUAT 2101 2152 -6.31734 3.10107 -1.40113 -0.00231515 -0.170669 0.00833437 0.98529 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4509.82 9.04351 -1516.35 3883.65 -10.1757 4509.57 +EDGE_SE3:QUAT 2102 2151 -5.89533 -2.92904 -1.87881 -0.0131369 -0.0784132 -0.0299945 0.996383 1 3.00927e-21 3.00927e-21 -3.50051e-09 9.93571e-11 2.77695e-10 1 3.00927e-21 -3.50051e-09 9.93571e-11 2.77695e-10 1 -3.50051e-09 9.93571e-11 2.77695e-10 4100.77 -0.0845522 -645.088 3975.09 8.3087 4097.86 +EDGE_SE3:QUAT 2103 2153 -5.92433 0.115199 -1.70436 -0.018626 -0.0443093 -0.0622966 0.9969 1 4.81482e-20 4.81482e-20 -8.44582e-10 -1.3836e-08 -1.80849e-10 1 4.81482e-20 -8.44582e-10 -1.3836e-08 -1.80849e-10 1 -8.44582e-10 -1.3836e-08 -1.80849e-10 4032.35 0.420037 -368.889 3991.57 10.925 4018.21 +EDGE_SE3:QUAT 2102 2153 -6.4821 3.35465 -1.58899 0.03524 0.0226157 -0.0544177 0.99764 1 4.81482e-20 4.81482e-20 -1.38629e-08 7.33011e-10 -3.64872e-10 1 4.81482e-20 -1.38629e-08 7.33011e-10 -3.64872e-10 1 -1.38629e-08 7.33011e-10 -3.64872e-10 4005.32 2.92823 203.226 3997.28 -5.24206 3998.44 +EDGE_SE3:QUAT 2103 2152 -6.25235 -3.03269 -1.74837 -0.0848059 0.185307 -0.125269 0.970967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4421.54 -174.97 1418.39 3930.35 -180.343 4387.54 +EDGE_SE3:QUAT 2104 2154 -5.99507 -0.180664 -1.70664 0.0368934 -0.210706 0.131436 0.96797 1 2.70834e-20 2.70834e-20 1.10939e-08 1.46277e-09 -2.43985e-09 1 2.70834e-20 1.10939e-08 1.46277e-09 -2.43985e-09 1 1.10939e-08 1.46277e-09 -2.43985e-09 4829.29 124.936 -2008.93 3832.65 -147.983 4765.63 +EDGE_SE3:QUAT 2103 2154 -6.31168 2.95307 -1.49362 0.0128076 0.0900642 -0.136235 0.986491 1 1.93442e-19 1.93442e-19 1.93056e-09 2.76361e-08 1.6619e-10 1 1.93442e-19 1.93056e-09 2.76361e-08 1.6619e-10 1 1.93056e-09 2.76361e-08 1.6619e-10 4132.65 -22.7409 742.314 3970.02 -52.3948 4059.06 +EDGE_SE3:QUAT 2104 2153 -6.09176 -3.03455 -2.05549 -0.134518 -0.147925 -0.113423 0.973221 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4400.93 46.122 -1455.41 3890.56 10.8654 4421.85 +EDGE_SE3:QUAT 2105 2155 -5.67707 -0.0868067 -1.84952 -0.0771442 0.0273516 -0.0486445 0.995457 1 1.20371e-20 1.20371e-20 -3.63071e-10 -6.90607e-09 -5.51751e-10 1 1.20371e-20 -3.63071e-10 -6.90607e-09 -5.51751e-10 1 -3.63071e-10 -6.90607e-09 -5.51751e-10 3983.47 -6.64609 171.496 3998.57 -4.76986 3997.81 +EDGE_SE3:QUAT 2104 2155 -6.49563 3.16602 -1.93466 -0.180281 0.0986167 0.0726778 0.975957 1 7.70372e-19 7.70372e-19 -1.89159e-09 5.42935e-08 9.35169e-09 1 7.70372e-19 -1.89159e-09 5.42935e-08 9.35169e-09 1 -1.89159e-09 5.42935e-08 9.35169e-09 4081.46 -76.5794 943.994 3950.55 -16.2614 4190.34 +EDGE_SE3:QUAT 2105 2154 -6.15517 -2.90788 -1.4627 -0.155843 0.00939378 -0.165187 0.973826 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3913.67 24.4566 -229.467 3993.24 26.1126 3901.67 +EDGE_SE3:QUAT 2106 2156 -6.22873 0.236185 -1.58969 0.0704644 0.00987467 -0.00209204 0.997463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3981.75 2.83743 80.2009 3999.6 0.0848547 4001.59 +EDGE_SE3:QUAT 2105 2156 -6.43917 3.05404 -2.00664 0.0902646 -0.0326063 0.142522 0.985128 1 2.40741e-19 2.40741e-19 -2.93566e-08 9.92538e-09 4.88678e-10 1 2.40741e-19 -2.93566e-08 9.92538e-09 4.88678e-10 1 -2.93566e-08 9.92538e-09 4.88678e-10 4007.67 -13.2955 -405.483 3988.13 -28.111 3959.01 +EDGE_SE3:QUAT 2106 2155 -6.28226 -3.12125 -1.6484 -0.0615649 0.0286482 -0.0282655 0.997291 1 6.01853e-20 6.01853e-20 1.36394e-08 -7.35878e-09 -9.22483e-11 1 6.01853e-20 1.36394e-08 -7.35878e-09 -9.22483e-11 1 1.36394e-08 -7.35878e-09 -9.22483e-11 3995.53 -6.67515 207.229 3997.58 -3.886 4007.5 +EDGE_SE3:QUAT 2107 2157 -6.44864 0.240925 -1.5668 0.00598202 0.0437569 -0.089655 0.994993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.06 -3.13176 354.654 3992.46 -15.9751 3999.05 +EDGE_SE3:QUAT 2106 2157 -6.38055 2.8384 -2.05076 -0.0103101 0.093459 0.00852052 0.995533 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4143.42 -2.48237 772.067 3964.97 1.33501 4143.56 +EDGE_SE3:QUAT 2107 2156 -6.40254 -2.96195 -1.88137 0.124735 -0.0149555 -0.226485 0.965879 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3946.66 19.0988 216.476 3993.26 -36.8429 3803.72 +EDGE_SE3:QUAT 2108 2158 -5.85062 -0.238311 -1.76674 -0.0518197 -0.0668543 -0.0714094 0.993854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4072.69 7.45411 -583.796 3978.99 16.0028 4063.04 +EDGE_SE3:QUAT 2107 2158 -6.39359 3.16502 -1.63721 0.0142375 -0.0423576 0.208635 0.976972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4030.27 7.22197 -354.009 3993.46 -37.4686 3856.97 +EDGE_SE3:QUAT 2108 2157 -5.9087 -3.2844 -1.81066 -0.202185 -0.0705535 -0.0943736 0.972233 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3979.71 71.5795 -771.657 3963.76 1.74143 4107.6 +EDGE_SE3:QUAT 2109 2159 -6.14298 -0.0974313 -1.21432 0.0524844 0.00218097 0.0818809 0.995257 1 4.83363e-20 4.83363e-20 -1.38832e-08 -2.69985e-10 4.37992e-11 1 4.83363e-20 -1.38832e-08 -2.69985e-10 4.37992e-11 1 -1.38832e-08 -2.69985e-10 4.37992e-11 3989.2 -1.33187 -34.0452 3999.84 -2.09149 3973.4 +EDGE_SE3:QUAT 2108 2159 -6.58723 2.9231 -1.63235 -0.0686444 -0.100293 0.0718062 0.989986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4117.56 43.1996 -751.724 3971.07 -43.7728 4115.79 +EDGE_SE3:QUAT 2109 2158 -6.2459 -2.68988 -1.97507 0.0293889 -0.0477841 -0.106024 0.99278 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4025.19 -9.76877 -340.137 3993.9 18.9795 3983.68 +EDGE_SE3:QUAT 2110 2160 -6.01438 0.116009 -1.71543 -0.116754 0.119792 -0.0108612 0.98585 1 1.92593e-19 1.92593e-19 -2.81213e-08 1.11978e-09 -3.24585e-09 1 1.92593e-19 -2.81213e-08 1.11978e-09 -3.24585e-09 1 -2.81213e-08 1.11978e-09 -3.24585e-09 4166.95 -67.9512 967.131 3952.12 -46.7911 4221.01 +EDGE_SE3:QUAT 2109 2160 -6.48429 3.13941 -1.75137 -0.0655725 -0.0430784 -0.0648473 0.994806 1 4.81482e-20 4.81482e-20 -7.09149e-10 -8.32605e-10 1.38725e-08 1 4.81482e-20 -7.09149e-10 -8.32605e-10 1.38725e-08 1 -7.09149e-10 -8.32605e-10 1.38725e-08 4021.3 10.1621 -394.562 3989.9 9.97 4021.68 +EDGE_SE3:QUAT 2110 2159 -6.01555 -2.85794 -1.55229 0.0388373 0.116343 0.00764732 0.99242 1 1.92593e-19 1.92593e-19 -4.73262e-10 2.75419e-08 -1.15797e-09 1 1.92593e-19 -4.73262e-10 2.75419e-08 -1.15797e-09 1 -4.73262e-10 2.75419e-08 -1.15797e-09 4216.67 24.1181 969.759 3947.24 17.5846 4222.47 +EDGE_SE3:QUAT 2111 2161 -5.84379 -0.238433 -1.91668 -0.22619 -0.125399 -0.0528417 0.964531 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4095.65 130.908 -1136.41 3940.9 -69.0589 4289.13 +EDGE_SE3:QUAT 2110 2161 -6.48461 2.82137 -1.7114 -0.0236191 0.0782505 0.0290491 0.99623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4099.87 -3.69094 647.171 3974.87 6.4072 4098.73 +EDGE_SE3:QUAT 2111 2160 -6.2303 -2.89785 -1.52264 -0.183001 0.0107733 0.0493445 0.981814 1 6.01853e-20 6.01853e-20 -9.25779e-11 -4.29835e-09 -1.48979e-08 1 6.01853e-20 -9.25779e-11 -4.29835e-09 -1.48979e-08 1 -9.25779e-11 -4.29835e-09 -1.48979e-08 3874.61 -19.8894 187.783 3997.13 3.59502 3998.82 +EDGE_SE3:QUAT 2112 2162 -5.957 -0.00406792 -1.43539 -0.170673 0.139609 -0.0317539 0.97487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4143.84 -117.551 1054.82 3954.96 -93.3968 4256.32 +EDGE_SE3:QUAT 2111 2162 -6.1919 2.74537 -1.79911 -0.0426862 -0.0468198 0.0613841 0.996101 1 1.92593e-19 1.92593e-19 -1.14326e-09 -1.34519e-09 2.7748e-08 1 1.92593e-19 -1.14326e-09 -1.34519e-09 2.7748e-08 1 -1.14326e-09 -1.34519e-09 2.7748e-08 4021.71 10.0199 -342.06 3993.47 -12.3187 4013.93 +EDGE_SE3:QUAT 2112 2161 -6.37604 -2.74324 -1.52105 -0.0206478 0.0869922 0.0724129 0.993359 1 2.0463e-19 2.0463e-19 -8.94248e-09 2.70838e-08 -4.04466e-10 1 2.0463e-19 -8.94248e-09 2.70838e-08 -4.04466e-10 1 -8.94248e-09 2.70838e-08 -4.04466e-10 4126.7 5.9019 728.102 3968.91 24.6616 4107.43 +EDGE_SE3:QUAT 2113 2163 -5.88878 0.030802 -1.66387 0.0889741 -0.113755 -0.0145874 0.989409 1 9.75002e-19 9.75002e-19 -5.61036e-08 3.01285e-08 1.06264e-08 1 9.75002e-19 -5.61036e-08 3.01285e-08 1.06264e-08 1 -5.61036e-08 3.01285e-08 1.06264e-08 4170.43 -50.7074 -921.639 3954.49 35.6858 4201.25 +EDGE_SE3:QUAT 2112 2163 -6.31933 2.75664 -1.45216 -0.0550191 -0.114536 0.270281 0.95436 1 1.92593e-19 1.92593e-19 -7.93303e-09 2.63629e-08 2.99796e-09 1 1.92593e-19 -7.93303e-09 2.63629e-08 2.99796e-09 1 -7.93303e-09 2.63629e-08 2.99796e-09 4087.49 70.1558 -650.827 3995.9 -94.5238 3807.39 +EDGE_SE3:QUAT 2113 2162 -6.29618 -2.76437 -1.91491 0.019135 0.099878 -0.0838302 0.991277 1 3.00927e-21 3.00927e-21 -3.51164e-09 2.89195e-10 -3.60098e-10 1 3.00927e-21 -3.51164e-09 2.89195e-10 -3.60098e-10 1 -3.51164e-09 2.89195e-10 -3.60098e-10 4167.65 -12.6837 839.672 3959.78 -34.2187 4141 +EDGE_SE3:QUAT 2114 2164 -5.88859 -0.221504 -1.67923 -0.0569606 0.128353 0.15851 0.977321 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4304.03 36.4278 1169.87 3928.97 84.9684 4216.51 +EDGE_SE3:QUAT 2113 2164 -6.64284 2.88949 -1.7291 -0.0296369 -0.0156337 0.0952642 0.994888 1 3.00927e-21 3.00927e-21 3.3324e-10 -3.45145e-09 -1.11275e-10 1 3.00927e-21 3.3324e-10 -3.45145e-09 -1.11275e-10 1 3.3324e-10 -3.45145e-09 -1.11275e-10 3998.45 1.49319 -89.5715 3999.65 -3.81202 3965.67 +EDGE_SE3:QUAT 2114 2163 -6.24601 -2.84511 -1.49188 -0.0303938 0.0291417 0.131572 0.990412 1 9.62965e-20 9.62965e-20 -1.55798e-08 1.19419e-08 -1.98631e-10 1 9.62965e-20 -1.55798e-08 1.19419e-08 -1.98631e-10 1 -1.55798e-08 1.19419e-08 -1.98631e-10 4015.15 -0.92217 275.449 3995.11 18.4205 3949.6 +EDGE_SE3:QUAT 2115 2165 -5.93866 -0.107247 -1.79275 0.101341 0.0622934 0.0717467 0.990304 1 1.92593e-19 1.92593e-19 1.27769e-09 3.06584e-09 2.76255e-08 1 1.92593e-19 1.27769e-09 3.06584e-09 2.76255e-08 1 1.27769e-09 3.06584e-09 2.76255e-08 3998.81 24.2897 403.116 3992.53 20.6339 4019.3 +EDGE_SE3:QUAT 2114 2165 -6.33681 2.94734 -1.66775 0.155554 0.0243499 0.0880704 0.983592 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3902.54 -2.48547 24.5247 3999.99 -1.26867 3968.3 +EDGE_SE3:QUAT 2115 2164 -6.33543 -2.60878 -1.69678 -0.0711048 -0.0843748 -0.0143687 0.99379 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4098.68 24.2779 -699.813 3971.3 -7.3962 4118.07 +EDGE_SE3:QUAT 2116 2166 -5.84939 0.328368 -1.64502 -0.0780827 0.113913 -0.10358 0.984986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4135.17 -61.5506 816.213 3969.83 -65.9192 4116.65 +EDGE_SE3:QUAT 2115 2166 -6.6138 2.87019 -1.48593 0.137643 -0.0336773 0.193016 0.970909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4001 -28.5648 -565.491 3975.68 -52.7733 3927.76 +EDGE_SE3:QUAT 2116 2165 -6.04806 -2.82658 -1.63037 -0.103783 -0.0227753 -0.20169 0.973669 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.53 15.8044 -415.554 3986.27 45.3355 3878.9 +EDGE_SE3:QUAT 2117 2167 -6.22335 -0.0862006 -1.54487 0.0236969 0.11523 0.0326641 0.992519 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4213.06 23.6982 952.676 3949.28 25.5591 4211.03 +EDGE_SE3:QUAT 2116 2167 -6.41088 2.5703 -1.5018 -0.264476 0.00934886 0.190502 0.945343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3814.66 -93.47 641.175 3962.12 54.0264 3949.28 +EDGE_SE3:QUAT 2117 2166 -5.79247 -2.96589 -1.54539 -0.0267316 0.0655098 -0.138175 0.987877 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4051.42 -18.4017 469.763 3989.04 -34.7189 3977.91 +EDGE_SE3:QUAT 2118 2168 -6.11849 -0.0677265 -1.49682 0.0118588 -0.299906 0.0204939 0.953675 1 1.20371e-20 1.20371e-20 -2.54012e-09 1.29861e-12 8.0717e-09 1 1.20371e-20 -2.54012e-09 1.29861e-12 8.0717e-09 1 -2.54012e-09 1.29861e-12 8.0717e-09 5949.79 30.8181 -3406.65 3640.21 -29.5666 5948.67 +EDGE_SE3:QUAT 2117 2168 -6.64344 2.87731 -1.41319 0.0313311 -0.057323 0.0228453 0.997602 1 1.20371e-20 1.20371e-20 -6.96966e-09 -1.35157e-10 4.09347e-10 1 1.20371e-20 -6.96966e-09 -1.35157e-10 4.09347e-10 1 -6.96966e-09 -1.35157e-10 4.09347e-10 4050.97 -5.81155 -471.802 3986.33 -3.02977 4052.81 +EDGE_SE3:QUAT 2118 2167 -6.16728 -2.93924 -1.44253 0.10489 0.00636192 -0.203589 0.973401 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3976.39 15.4674 295.845 3991.62 -36.5141 3854.6 +EDGE_SE3:QUAT 2119 2169 -5.89934 -0.0188211 -1.45521 0.124818 -0.0699604 -0.0707355 0.987179 1 4.81482e-20 4.81482e-20 1.19906e-09 1.36825e-08 -1.86404e-09 1 4.81482e-20 1.19906e-09 1.36825e-08 -1.86404e-09 1 1.19906e-09 1.36825e-08 -1.86404e-09 3985.24 -31.908 -441.183 3991.77 25.0981 4027.54 +EDGE_SE3:QUAT 2118 2169 -6.35461 2.98641 -1.44136 0.0817312 -0.156701 0.197179 0.964305 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4486.14 74.578 -1521.39 3892.69 -134.642 4357.34 +EDGE_SE3:QUAT 2119 2168 -6.03763 -2.64469 -1.32887 0.0346552 -0.0538259 -0.102961 0.992623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.48 -12.5421 -383.19 3992.3 21.4109 3993.88 +EDGE_SE3:QUAT 2120 2170 -6.10401 0.118268 -1.6208 -0.053294 -0.167284 0.174149 0.968942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4340.39 146.234 -1240.46 3948.4 -163.843 4230.44 +EDGE_SE3:QUAT 2119 2170 -6.84522 3.07695 -2.05205 -0.107289 0.0510175 0.0924011 0.988609 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.69 -22.3654 521.859 3981.99 16.6873 4032.58 +EDGE_SE3:QUAT 2120 2169 -6.06798 -2.58186 -1.59018 -0.0274259 -0.0332331 -0.0231717 0.998803 1 1.20371e-20 1.20371e-20 -6.94678e-09 1.4859e-10 2.39402e-10 1 1.20371e-20 -6.94678e-09 1.4859e-10 2.39402e-10 1 -6.94678e-09 1.4859e-10 2.39402e-10 4015.69 3.19244 -274.11 3995.28 2.47908 4016.55 +EDGE_SE3:QUAT 2121 2171 -6.11021 0.016219 -1.41591 0.137766 -0.0823116 0.212299 0.963937 1 1.92593e-19 1.92593e-19 -2.75583e-08 -5.31261e-09 3.70055e-09 1 1.92593e-19 -2.75583e-08 -5.31261e-09 3.70055e-09 1 -2.75583e-08 -5.31261e-09 3.70055e-09 4154.08 -15.4453 -988.854 3940.91 -84.0579 4049.72 +EDGE_SE3:QUAT 2120 2171 -6.13605 2.9657 -1.68947 -0.0937701 0.0732705 0.0468896 0.991786 1 3.85186e-19 3.85186e-19 2.87876e-08 -2.66211e-08 -1.68147e-10 1 3.85186e-19 2.87876e-08 -2.66211e-08 -1.68147e-10 1 2.87876e-08 -2.66211e-08 -1.68147e-10 4065.8 -25.7396 643.589 3974.89 2.37528 4092.18 +EDGE_SE3:QUAT 2121 2170 -6.15291 -2.654 -1.44597 0.0895051 0.141769 0.0139356 0.985747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4290.98 70.7157 1181.82 3929.01 55.6759 4322.25 +EDGE_SE3:QUAT 2122 2172 -5.90332 -0.03569 -1.97544 0.0516571 0.00922416 0.0357082 0.997984 1 9.62965e-20 9.62965e-20 1.39268e-08 1.23055e-09 1.39268e-08 1 9.62965e-20 1.39268e-08 1.23055e-09 1.39268e-08 1 1.39268e-08 1.23055e-09 1.39268e-08 3989.97 1.17342 51.2835 3999.88 0.843169 3995.54 +EDGE_SE3:QUAT 2121 2172 -6.56473 2.66133 -1.78382 -0.00669694 0.0846335 0.277295 0.957027 1 1.92593e-19 1.92593e-19 7.77314e-09 -2.65405e-08 1.10476e-09 1 1.92593e-19 7.77314e-09 -2.65405e-08 1.10476e-09 1 7.77314e-09 -2.65405e-08 1.10476e-09 4097.56 42.5203 634.437 3986.54 90.6754 3790.17 +EDGE_SE3:QUAT 2122 2171 -6.33494 -2.49359 -1.53084 0.0669384 0.0669221 0.0273248 0.995135 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4047.62 20.5404 516.309 3984.81 14.0585 4062.56 +EDGE_SE3:QUAT 2123 2173 -5.95529 0.0221792 -1.53481 0.0932682 0.0370411 -0.064208 0.992878 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.11 15.4075 364.83 3991.08 -8.34919 4016.41 +EDGE_SE3:QUAT 2122 2173 -6.30177 2.83303 -1.60831 0.00375107 -0.073063 0.158688 0.984615 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4082.24 19.1417 -579.761 3982.34 -47.7034 3981.57 +EDGE_SE3:QUAT 2123 2172 -6.07498 -2.99195 -1.40479 -0.0423355 0.0824298 -6.38557e-05 0.995697 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4103.18 -15.276 673.471 3973.23 -7.13414 4110.35 +EDGE_SE3:QUAT 2124 2174 -5.87526 0.406192 -1.69762 0.0632815 -0.0926968 -0.0374365 0.992976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4111.7 -32.0685 -726.206 3970.86 27.1786 4122.11 +EDGE_SE3:QUAT 2123 2174 -6.2769 2.60726 -1.84046 -0.107382 0.146108 -0.0342291 0.982828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4273.94 -93.3333 1176.32 3934.42 -79.6491 4315.37 +EDGE_SE3:QUAT 2124 2173 -6.09235 -2.89341 -1.71034 -0.0401153 0.0623988 -0.0408924 0.996406 1 4.81482e-20 4.81482e-20 8.20186e-10 -6.34721e-10 1.39272e-08 1 4.81482e-20 8.20186e-10 -6.34721e-10 1.39272e-08 1 8.20186e-10 -6.34721e-10 1.39272e-08 4051.01 -13.5441 482.858 3986.48 -13.6672 4050.76 +EDGE_SE3:QUAT 2125 2175 -6.04167 0.0232744 -1.84467 0.247483 0.0473506 -0.0876582 0.963756 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3843.19 76.6871 602.667 3976.72 -1.6062 4057.44 +EDGE_SE3:QUAT 2124 2175 -6.28138 2.78277 -1.68726 0.186244 -0.089633 0.0491142 0.977173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.66 -73.8296 -814.321 3964 21.7978 4149.76 +EDGE_SE3:QUAT 2125 2174 -5.91212 -3.03163 -1.50665 0.0734836 -0.0540042 -0.138818 0.98611 1 2.40741e-19 2.40741e-19 2.54227e-08 -1.773e-08 3.25863e-10 1 2.40741e-19 2.54227e-08 -1.773e-08 3.25863e-10 1 2.54227e-08 -1.773e-08 3.25863e-10 3999.61 -15.0087 -296.279 3997 20.7368 3944.13 +EDGE_SE3:QUAT 2126 2176 -5.99288 -0.096714 -1.42925 -0.0846102 -0.146753 -0.00927242 0.985504 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4337.44 60.5178 -1264.25 3917.34 -41.4144 4365.73 +EDGE_SE3:QUAT 2125 2176 -6.21565 2.61577 -1.68492 0.0389839 -0.0687809 0.191101 0.978381 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4087.77 13.3966 -619.875 3978.66 -59.128 3947.76 +EDGE_SE3:QUAT 2126 2175 -6.36295 -3.01356 -1.54565 -0.0283108 -0.0892648 -0.119041 0.988463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4136.88 -13.3535 -761.57 3966.97 43.8688 4083.41 +EDGE_SE3:QUAT 2127 2177 -6.43297 0.0121953 -1.36521 -0.0121728 -0.0560547 0.00371383 0.998347 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4050.01 3.12895 -452.734 3987.49 -1.79804 4050.55 +EDGE_SE3:QUAT 2126 2177 -6.43228 2.73538 -1.59065 0.00321791 0.0774472 0.00265831 0.996988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4097.64 1.47622 632.68 3976.02 1.37092 4097.66 +EDGE_SE3:QUAT 2127 2176 -5.82769 -2.71929 -1.82317 -0.169366 0.0236241 -0.0209176 0.985048 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3890.01 -10.5784 139.194 3999.25 -2.73423 4003 +EDGE_SE3:QUAT 2128 2178 -6.09345 -0.149374 -1.82503 0.0793358 -0.0229897 -0.0388073 0.995827 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3980.04 -5.60932 -145.133 3998.96 3.28033 3999.19 +EDGE_SE3:QUAT 2127 2178 -6.42433 2.42878 -1.16372 0.122674 0.0267182 0.0973309 0.987301 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3940.21 1.23397 64.8488 4000.07 1.13829 3962.52 +EDGE_SE3:QUAT 2128 2177 -6.5753 -2.49563 -1.64776 0.00361256 -0.0138969 -0.169298 0.98546 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4002.4 -0.840626 -99.2768 3999.51 8.08845 3887.81 +EDGE_SE3:QUAT 2129 2179 -6.18598 -0.115605 -1.84456 -0.0240664 -0.140875 -0.0375422 0.989023 1 7.82409e-19 7.82409e-19 -8.93187e-09 -5.46805e-08 2.45219e-10 1 7.82409e-19 -8.93187e-09 -5.46805e-08 2.45219e-10 1 -8.93187e-09 -5.46805e-08 2.45219e-10 4340.29 -2.1294 -1219.76 3919.51 15.0432 4336.97 +EDGE_SE3:QUAT 2128 2179 -6.4727 2.75309 -1.68934 -0.0246687 -0.0774667 -0.10238 0.991418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4101.96 -7.38378 -654.586 3974.89 32.2112 4062.47 +EDGE_SE3:QUAT 2129 2178 -6.23943 -2.62941 -1.42978 -0.117576 0.122757 -0.087489 0.981556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4118.72 -79.8389 854.756 3969.96 -74.9448 4143.4 +EDGE_SE3:QUAT 2130 2180 -6.09195 -0.0655146 -1.59424 0.0605471 -0.034891 0.0454859 0.996518 1 4.81482e-20 4.81482e-20 5.56787e-10 -7.97377e-10 -1.38712e-08 1 4.81482e-20 5.56787e-10 -7.97377e-10 -1.38712e-08 1 5.56787e-10 -7.97377e-10 -1.38712e-08 4009.41 -8.29374 -311.405 3993.71 -5.31391 4015.8 +EDGE_SE3:QUAT 2129 2180 -6.27488 2.53415 -1.81107 0.159747 0.0770423 0.0465987 0.983043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3961.07 44.6382 508.635 3989.15 28.7793 4054.46 +EDGE_SE3:QUAT 2130 2179 -6.20484 -2.61649 -1.68396 0.083814 -0.119638 0.11053 0.983079 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4258.74 -8.05979 -1109.09 3931.2 -37.3202 4237.97 +EDGE_SE3:QUAT 2131 2181 -6.08393 -0.119281 -1.26989 -0.0355954 0.0853237 -0.0748258 0.992902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4100.29 -24.6827 657.851 3976.23 -31.7834 4082.96 +EDGE_SE3:QUAT 2130 2181 -6.21664 2.47272 -1.53516 0.00675151 -0.108503 -0.0375691 0.993363 1 4.81482e-20 4.81482e-20 -1.52969e-09 2.15803e-10 1.41147e-08 1 4.81482e-20 -1.52969e-09 2.15803e-10 1.41147e-08 1 -1.52969e-09 2.15803e-10 1.41147e-08 4192.69 -14.5543 -899.283 3954 20.9647 4187.23 +EDGE_SE3:QUAT 2131 2180 -6.32022 -2.21892 -1.46795 -0.0608674 -0.0446645 0.100695 0.992049 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4004.18 11.0834 -277.836 3996.48 -14.8536 3978.44 +EDGE_SE3:QUAT 2132 2182 -6.37389 0.0536592 -1.1447 0.093478 -0.0650581 -0.134464 0.984352 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3994.88 -22.0059 -352.321 3996.08 25.8988 3957.51 +EDGE_SE3:QUAT 2131 2182 -5.9859 2.60351 -1.29413 -0.0308738 0.114993 0.080004 0.989658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4226.73 10.6371 987.583 3945.25 34.6317 4204.94 +EDGE_SE3:QUAT 2132 2181 -5.85911 -2.64234 -1.38427 0.0370831 -0.105862 -0.063883 0.991634 1 4.81482e-20 4.81482e-20 1.4052e-08 -1.03578e-09 -1.41454e-09 1 4.81482e-20 1.4052e-08 -1.03578e-09 -1.41454e-09 1 1.4052e-08 -1.03578e-09 -1.41454e-09 4163.94 -34.0944 -840.645 3961.59 39.3677 4153.11 +EDGE_SE3:QUAT 2133 2183 -6.43401 -0.00173554 -1.08361 0.048811 0.127192 0.0110594 0.990615 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4256.48 34.931 1065.28 3938.04 27.0712 4265.52 +EDGE_SE3:QUAT 2132 2183 -6.53681 2.36327 -1.67993 0.0245819 -0.0699808 0.0784687 0.994153 1 2.0463e-19 2.0463e-19 4.92611e-09 9.09531e-10 2.73745e-08 1 2.0463e-19 4.92611e-09 9.09531e-10 2.73745e-08 1 4.92611e-09 9.09531e-10 2.73745e-08 4082.28 2.26782 -588.206 3979.22 -21.4339 4060.07 +EDGE_SE3:QUAT 2133 2182 -6.43311 -2.54809 -1.6224 0.114862 0.0450135 0.0362732 0.991698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3970.09 18.0305 304.023 3995.42 9.60353 4017.6 +EDGE_SE3:QUAT 2134 2184 -6.05539 -0.356444 -1.69674 -0.0196833 -0.00942754 0.139396 0.989996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3998.83 0.407758 -40.6968 3999.96 -2.03746 3922.65 +EDGE_SE3:QUAT 2133 2184 -6.38725 2.94279 -1.05999 0.0521397 -0.124252 0.139467 0.981016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4279.97 27.085 -1117.15 3933.43 -70.0599 4213.04 +EDGE_SE3:QUAT 2134 2183 -6.06702 -2.60743 -1.41926 -0.117292 -0.0152205 0.109587 0.986915 1 1.92781e-19 1.92781e-19 -2.72956e-08 -3.9118e-09 -4.0585e-10 1 1.92781e-19 -2.72956e-08 -3.9118e-09 -4.0585e-10 1 -2.72956e-08 -3.9118e-09 -4.0585e-10 3944.6 -5.14637 34.5235 3999.52 4.81006 3951.59 +EDGE_SE3:QUAT 2135 2185 -6.02618 -0.123866 -1.68179 -0.0371539 0.0845309 -0.0362594 0.995068 1 1.92593e-19 1.92593e-19 -1.19357e-09 -2.76112e-08 -1.21458e-09 1 1.92593e-19 -1.19357e-09 -2.76112e-08 -1.21458e-09 1 -1.19357e-09 -2.76112e-08 -1.21458e-09 4104.61 -19.454 672.837 3973.98 -19.2857 4104.87 +EDGE_SE3:QUAT 2134 2185 -6.09349 2.54561 -1.63908 -0.120234 0.0114128 0.177511 0.97668 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3968.81 -20.0031 335.744 3989.81 33.8252 3900.59 +EDGE_SE3:QUAT 2135 2184 -6.15782 -2.56379 -1.34698 0.187467 -0.0784255 -0.101721 0.973837 1 1.92593e-19 1.92593e-19 9.33318e-10 -5.60039e-09 -2.71364e-08 1 1.92593e-19 9.33318e-10 -5.60039e-09 -2.71364e-08 1 9.33318e-10 -5.60039e-09 -2.71364e-08 3889.57 -33.553 -362.449 3998.49 27.1573 3988.75 +EDGE_SE3:QUAT 2136 2186 -5.98841 0.214462 -1.60796 -0.156803 -0.0332944 -0.00579463 0.987051 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3919.57 21.1597 -268.371 3995.98 -3.48297 4017.79 +EDGE_SE3:QUAT 2135 2186 -6.213 2.89366 -1.28021 -0.0548083 -0.0406956 0.0788871 0.994543 1 4.81482e-20 4.81482e-20 -1.38335e-08 -1.15581e-09 4.35397e-10 1 4.81482e-20 -1.38335e-08 -1.15581e-09 4.35397e-10 1 -1.38335e-08 -1.15581e-09 4.35397e-10 4006.07 9.36966 -270.348 3996.31 -11.7197 3993.2 +EDGE_SE3:QUAT 2136 2185 -6.26198 -2.40773 -1.3378 0.174685 -0.140552 0.0435885 0.973566 1 4.81482e-20 4.81482e-20 -2.13062e-09 2.45433e-09 1.41265e-08 1 4.81482e-20 -2.13062e-09 2.45433e-09 1.41265e-08 1 -2.13062e-09 2.45433e-09 1.41265e-08 4239.13 -111.157 -1255.09 3924.05 64.7105 4353.59 +EDGE_SE3:QUAT 2137 2187 -6.09732 0.234205 -1.56454 0.0961292 0.0147891 0.016805 0.995117 1 1.20371e-20 1.20371e-20 -7.83651e-11 -6.70546e-10 -6.90707e-09 1 1.20371e-20 -7.83651e-11 -6.70546e-10 -6.90707e-09 1 -7.83651e-11 -6.70546e-10 -6.90707e-09 3965.39 4.41833 97.4038 3999.52 1.13772 4001.23 +EDGE_SE3:QUAT 2136 2187 -6.30856 2.61035 -1.20517 -0.0534952 -0.149263 0.235079 0.958956 1 4.04445e-18 4.04445e-18 5.37756e-08 -3.17989e-08 -1.19231e-07 1 4.04445e-18 5.37756e-08 -3.17989e-08 -1.19231e-07 1 5.37756e-08 -3.17989e-08 -1.19231e-07 4212.42 125.497 -980.13 3979.72 -149.24 4002.81 +EDGE_SE3:QUAT 2137 2186 -6.46427 -2.5057 -1.17523 -0.0856353 0.092725 0.00838976 0.991967 1 4.23178e-22 4.23178e-22 1.22856e-10 -1.13285e-10 1.31337e-09 1 4.23178e-22 1.22856e-10 -1.13285e-10 1.31337e-09 1 1.22856e-10 -1.13285e-10 1.31337e-09 4112.05 -33.9647 765.193 3966.61 -15.0134 4141.1 +EDGE_SE3:QUAT 2138 2188 -6.03955 0.0617027 -1.23866 0.0361095 -0.0677845 -0.00754228 0.997018 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4068.1 -11.1543 -546.474 3982.14 6.17646 4073.09 +EDGE_SE3:QUAT 2137 2188 -6.64461 2.59131 -1.614 -0.00569071 0.0143844 -0.0334643 0.99932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4003.04 -0.479802 112.67 3999.22 -1.90271 3998.69 +EDGE_SE3:QUAT 2138 2187 -5.97793 -2.45654 -1.29395 -0.119562 0.0712254 0.176981 0.974325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4099.53 -18.4324 809.052 3958.66 58.0951 4031.42 +EDGE_SE3:QUAT 2139 2189 -6.1277 -0.0947567 -1.93973 0.13925 -0.130389 0.0560192 0.980036 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4245.65 -72.3513 -1182.12 3926.27 28.6426 4310.66 +EDGE_SE3:QUAT 2138 2189 -6.1038 2.64156 -1.25054 0.135533 -0.105401 0.0735686 0.9824 1 1.01111e-18 1.01111e-18 5.55958e-08 -2.30726e-08 1.05259e-08 1 1.01111e-18 5.55958e-08 -2.30726e-08 1.05259e-08 1 5.55958e-08 -2.30726e-08 1.05259e-08 4154.17 -52.7559 -981.264 3945.29 3.71726 4206 +EDGE_SE3:QUAT 2139 2188 -6.34881 -2.44207 -1.50737 0.0304095 0.0384198 -0.0394001 0.998021 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4022.12 3.54573 322.442 3993.45 -5.38208 4019.61 +EDGE_SE3:QUAT 2140 2190 -6.18066 0.264316 -1.19883 -0.0272403 -0.106564 -0.0716321 0.991348 1 1.92593e-19 1.92593e-19 -3.10708e-09 -3.44176e-10 2.8184e-08 1 1.92593e-19 -3.10708e-09 -3.44176e-10 2.8184e-08 1 -3.10708e-09 -3.44176e-10 2.8184e-08 4192.72 -7.41816 -906.118 3953.1 28.5482 4175.16 +EDGE_SE3:QUAT 2139 2190 -6.37838 2.12029 -1.53823 -0.0168509 0.0532098 0.141617 0.988347 1 3.00927e-21 3.00927e-21 -3.45043e-09 -4.9084e-10 -1.94774e-10 1 3.00927e-21 -3.45043e-09 -4.9084e-10 -1.94774e-10 1 -3.45043e-09 -4.9084e-10 -1.94774e-10 4047.98 6.51306 445.933 3988.51 31.7072 3968.89 +EDGE_SE3:QUAT 2140 2189 -5.93184 -2.4764 -1.69202 0.0536753 -0.0609762 -0.0466743 0.995602 1 9.62965e-20 9.62965e-20 -1.31672e-08 1.45567e-08 -5.33094e-11 1 9.62965e-20 -1.31672e-08 1.45567e-08 -5.33094e-11 1 -1.31672e-08 1.45567e-08 -5.33094e-11 4040.43 -16.2574 -458.985 3988.12 15.2015 4043.24 +EDGE_SE3:QUAT 2141 2191 -6.45205 -0.0107397 -1.34414 -0.0714431 0.057628 0.0689226 0.99339 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4046.27 -13.3182 520.998 3982.84 12.3693 4047.69 +EDGE_SE3:QUAT 2140 2191 -6.46201 2.19729 -1.28682 0.0390529 0.0465721 0.0932711 0.993784 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4020.06 10.1066 325.055 3994.47 16.3426 3991.36 +EDGE_SE3:QUAT 2141 2190 -5.88257 -2.5253 -0.934816 0.0416626 -0.263818 -0.146307 0.952501 1 3.85186e-18 3.85186e-18 -6.38434e-09 -1.13148e-07 -4.57125e-08 1 3.85186e-18 -6.38434e-09 -1.13148e-07 -4.57125e-08 1 -6.38434e-09 -1.13148e-07 -4.57125e-08 5130.91 -388.694 -2419.93 3850.19 390.665 5052.24 +EDGE_SE3:QUAT 2142 2192 -5.81885 -0.00329667 -1.09432 -0.0792315 -0.178681 -0.283058 0.938975 1 1.20371e-20 1.20371e-20 7.06637e-09 -2.0519e-09 -1.44826e-09 1 1.20371e-20 7.06637e-09 -2.0519e-09 -1.44826e-09 1 7.06637e-09 -2.0519e-09 -1.44826e-09 4621.74 -202.08 -1734.05 3902.22 266.482 4326.36 +EDGE_SE3:QUAT 2141 2192 -6.36368 2.06286 -1.6917 -0.0911329 0.0343502 -0.110157 0.989131 1 1.92593e-19 1.92593e-19 -3.61799e-10 2.68197e-09 -2.74712e-08 1 1.92593e-19 -3.61799e-10 2.68197e-09 -2.74712e-08 1 -3.61799e-10 2.68197e-09 -2.74712e-08 3971.72 -6.07987 147.477 3999.53 -6.86173 3956.4 +EDGE_SE3:QUAT 2142 2191 -6.26608 -2.67174 -1.33406 0.0771913 -0.0677643 -0.0802774 0.991466 1 2.40741e-19 2.40741e-19 2.64473e-08 -1.62744e-08 -2.81925e-10 1 2.40741e-19 2.64473e-08 -1.62744e-08 -2.81925e-10 1 2.64473e-08 -1.62744e-08 -2.81925e-10 4028.73 -24.472 -462.648 3989.48 24.9025 4026.79 +EDGE_SE3:QUAT 2143 2193 -6.33647 -0.074254 -1.20504 0.136693 0.175723 -0.08576 0.971124 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4553.77 77.0738 1705.68 3861.79 33.5913 4599.09 +EDGE_SE3:QUAT 2142 2193 -6.58472 2.68599 -1.36461 -0.0541041 -0.14803 0.128412 0.979117 1 1.92593e-19 1.92593e-19 2.81891e-08 4.30659e-09 -3.67104e-09 1 1.92593e-19 2.81891e-08 4.30659e-09 -3.67104e-09 1 2.81891e-08 4.30659e-09 -3.67104e-09 4284.87 99.2897 -1130.21 3945.55 -112.08 4230.62 +EDGE_SE3:QUAT 2143 2192 -6.16774 -2.33307 -1.75009 0.0217342 0.0160192 0.0943446 0.995173 1 3.00927e-21 3.00927e-21 3.29546e-10 -3.45249e-09 8.45321e-11 1 3.00927e-21 3.29546e-10 -3.45249e-09 8.45321e-11 1 3.29546e-10 -3.45249e-09 8.45321e-11 4000.69 1.42677 101.946 3999.49 4.49855 3966.97 +EDGE_SE3:QUAT 2144 2194 -6.12585 -0.197592 -1.56794 0.0553751 -0.118603 0.0422066 0.990498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4234.23 -17.0004 -1023.13 3940.91 -4.21325 4239.37 +EDGE_SE3:QUAT 2143 2194 -6.53388 2.41353 -1.61655 -0.0011376 0.172553 0.106936 0.979178 1 7.82409e-19 7.82409e-19 9.29455e-10 5.51509e-08 -8.23589e-10 1 7.82409e-19 9.29455e-10 5.51509e-08 -8.23589e-10 1 9.29455e-10 5.51509e-08 -8.23589e-10 4503.6 85.5398 1506.1 3893.77 104.97 4457.86 +EDGE_SE3:QUAT 2144 2193 -6.08405 -2.43113 -1.20261 0.0038619 -0.107399 -0.0326119 0.993673 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4189.71 -11.4342 -891.691 3954.54 17.4242 4185.52 +EDGE_SE3:QUAT 2145 2195 -6.12077 0.26033 -1.25296 -0.027915 0.0849712 0.0837579 0.992464 1 1.20371e-20 1.20371e-20 -6.99456e-09 -5.64575e-10 -6.22817e-10 1 1.20371e-20 -6.99456e-09 -5.64575e-10 -6.22817e-10 1 -6.99456e-09 -5.64575e-10 -6.22817e-10 4122.35 4.89835 719.46 3969.56 27.5388 4097.4 +EDGE_SE3:QUAT 2144 2195 -5.839 2.2565 -1.37592 0.0520503 0.143294 0.0685405 0.985931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4302.33 70.4731 1162.49 3933.03 73.6325 4294.38 +EDGE_SE3:QUAT 2145 2194 -6.3282 -2.65561 -1.60304 -0.0833777 0.0915315 0.0525401 0.990914 1 1.92593e-19 1.92593e-19 -1.03714e-09 2.75225e-08 2.07475e-09 1 1.92593e-19 -1.03714e-09 2.75225e-08 2.07475e-09 1 -1.03714e-09 2.75225e-08 2.07475e-09 4126.67 -25.059 801.192 3962.08 4.18255 4143.44 +EDGE_SE3:QUAT 2146 2196 -6.11261 0.184771 -1.39396 0.0358141 -0.166304 0.14011 0.975412 1 3.00927e-21 3.00927e-21 -3.59311e-09 -5.00541e-10 6.24792e-10 1 3.00927e-21 -3.59311e-09 -5.00541e-10 6.24792e-10 1 -3.59311e-09 -5.00541e-10 6.24792e-10 4493.9 75.819 -1498.4 3894.17 -109.688 4420.51 +EDGE_SE3:QUAT 2145 2196 -6.50496 2.32954 -1.56935 0.130881 -0.0763554 -0.0310001 0.987967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4006.7 -40.6051 -554.322 3984.68 24.6263 4071.37 +EDGE_SE3:QUAT 2146 2195 -6.11584 -2.95048 -1.38443 -0.114887 0.033622 0.111743 0.986501 1 1.92593e-19 1.92593e-19 2.75281e-08 2.83205e-09 1.59971e-09 1 1.92593e-19 2.75281e-08 2.83205e-09 1.59971e-09 1 2.75281e-08 2.83205e-09 1.59971e-09 3989.28 -20.8949 414.613 3987.55 19.9802 3992.13 +EDGE_SE3:QUAT 2147 2197 -6.46198 0.131016 -1.2928 0.09128 0.0220425 0.0712485 0.993029 1 1.95602e-19 1.95602e-19 -2.73123e-08 -5.50199e-09 8.79305e-11 1 1.95602e-19 -2.73123e-08 -5.50199e-09 8.79305e-11 1 -2.73123e-08 -5.50199e-09 8.79305e-11 3968.76 3.46799 95.4304 3999.76 2.87868 3981.78 +EDGE_SE3:QUAT 2146 2197 -6.08453 2.54739 -1.50432 0.0721838 -0.0523722 0.0499519 0.994762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4031.98 -13.8601 -462.822 3986.48 -6.69319 4042.84 +EDGE_SE3:QUAT 2147 2196 -6.001 -2.38368 -1.4923 0.0744268 -0.090034 0.139277 0.983339 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4150.72 -0.832247 -849.702 3957.57 -48.7025 4095.29 +EDGE_SE3:QUAT 2148 2198 -5.95441 -0.17049 -1.42582 -0.0340691 0.0757336 -0.209714 0.97423 1 3.85186e-19 3.85186e-19 -2.12438e-08 3.30553e-08 2.0795e-10 1 3.85186e-19 -2.12438e-08 3.30553e-08 2.0795e-10 1 -2.12438e-08 3.30553e-08 2.0795e-10 4053.01 -29.1242 486.668 3991.74 -52.4655 3881.73 +EDGE_SE3:QUAT 2147 2198 -6.70787 2.03875 -1.78842 0.0401164 -0.167249 0.0123912 0.98502 1 4.81482e-20 4.81482e-20 -1.44848e-08 1.35003e-11 2.46592e-09 1 4.81482e-20 -1.44848e-08 1.35003e-11 2.46592e-09 1 -1.44848e-08 1.35003e-11 2.46592e-09 4483.89 -29.185 -1483.83 3888.22 19.1303 4489.72 +EDGE_SE3:QUAT 2148 2197 -6.03845 -2.04539 -1.26226 -0.036631 -0.0329012 -0.00811882 0.998754 1 7.52316e-22 7.52316e-22 5.80761e-11 6.28872e-11 -1.73641e-09 1 7.52316e-22 5.80761e-11 6.28872e-11 -1.73641e-09 1 5.80761e-11 6.28872e-11 -1.73641e-09 4012.41 4.75404 -267.265 3995.56 0.126965 4017.51 +EDGE_SE3:QUAT 2149 2199 -6.29151 0.0934634 -1.52214 -0.0413571 -0.0340673 0.000676077 0.998563 1 9.62965e-20 9.62965e-20 1.38414e-08 1.39064e-08 1.04448e-10 1 9.62965e-20 1.38414e-08 1.39064e-08 1.04448e-10 1 1.38414e-08 1.39064e-08 1.04448e-10 4011.65 5.71727 -272.6 3995.44 -1.24571 4018.49 +EDGE_SE3:QUAT 2148 2199 -6.72408 2.39779 -1.26861 -0.0916859 -0.0384267 0.00156898 0.995045 1 7.52316e-22 7.52316e-22 -6.52238e-11 -1.60187e-10 1.7311e-09 1 7.52316e-22 -6.52238e-11 -1.60187e-10 1.7311e-09 1 -6.52238e-11 -1.60187e-10 1.7311e-09 3989.24 14.0871 -303.322 3994.58 -3.43337 4022.86 +EDGE_SE3:QUAT 2149 2198 -6.2467 -2.09832 -1.19062 -0.00642948 0.106323 -0.0870453 0.990493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4179.47 -27.3584 866.529 3958.78 -43.7247 4149.32 diff --git a/examples/module/pgo/data/sphere_g2o.g2o b/examples/module/pgo/data/sphere_g2o.g2o new file mode 100644 index 0000000..f7643e6 --- /dev/null +++ b/examples/module/pgo/data/sphere_g2o.g2o @@ -0,0 +1,12299 @@ +VERTEX_SE3:QUAT 0 -0.125664 -1.53894e-17 99.9999 0.706662 4.32706e-17 0.707551 -4.3325e-17 +VERTEX_SE3:QUAT 1 -0.250786 -0.0328449 99.981 0.705413 0.0432253 0.705946 -0.0465295 +VERTEX_SE3:QUAT 2 -0.384479 -0.102155 99.9722 0.701473 0.0869233 0.701311 -0.0924285 +VERTEX_SE3:QUAT 3 -0.488061 -0.195958 99.9833 0.689802 0.131752 0.698923 -0.135355 +VERTEX_SE3:QUAT 4 -0.577441 -0.319656 99.9749 0.683889 0.173189 0.684097 -0.185235 +VERTEX_SE3:QUAT 5 -0.626233 -0.455465 99.9639 0.675686 0.20944 0.672757 -0.216751 +VERTEX_SE3:QUAT 6 -0.653603 -0.602648 99.9579 0.658288 0.246239 0.662316 -0.259541 +VERTEX_SE3:QUAT 7 -0.660457 -0.786874 99.9504 0.637158 0.294767 0.642758 -0.306601 +VERTEX_SE3:QUAT 8 -0.618421 -0.981472 99.946 0.627982 0.330033 0.615145 -0.343967 +VERTEX_SE3:QUAT 9 -0.575668 -1.15736 99.9408 0.601927 0.362809 0.592794 -0.393253 +VERTEX_SE3:QUAT 10 -0.47692 -1.34096 99.9362 0.574097 0.399746 0.566487 -0.435554 +VERTEX_SE3:QUAT 11 -0.334869 -1.49407 99.9083 0.548034 0.426931 0.538043 -0.477387 +VERTEX_SE3:QUAT 12 -0.152315 -1.64676 99.8848 -0.518965 -0.460068 -0.505645 0.513162 +VERTEX_SE3:QUAT 13 0.0828471 -1.77185 99.8702 -0.489516 -0.486895 -0.470679 0.549334 +VERTEX_SE3:QUAT 14 0.321525 -1.86696 99.8255 -0.451596 -0.510827 -0.435292 0.58791 +VERTEX_SE3:QUAT 15 0.582859 -1.94452 99.7839 -0.412004 -0.544589 -0.403826 0.608769 +VERTEX_SE3:QUAT 16 0.883238 -1.95252 99.744 -0.372324 -0.564041 -0.380507 0.631226 +VERTEX_SE3:QUAT 17 1.18775 -1.91094 99.7309 -0.331991 -0.579922 -0.348705 0.657173 +VERTEX_SE3:QUAT 18 1.50997 -1.8334 99.6984 -0.287826 -0.597032 -0.311572 0.680905 +VERTEX_SE3:QUAT 19 1.8256 -1.70483 99.6812 -0.248136 -0.621835 -0.267198 0.693076 +VERTEX_SE3:QUAT 20 2.12658 -1.52692 99.669 -0.183637 -0.642126 -0.229015 0.70817 +VERTEX_SE3:QUAT 21 2.40105 -1.2961 99.68 -0.146657 -0.645412 -0.194294 0.724006 +VERTEX_SE3:QUAT 22 2.68391 -1.01558 99.6684 -0.105138 -0.655187 -0.145632 0.733803 +VERTEX_SE3:QUAT 23 2.91855 -0.694584 99.6652 -0.057182 -0.664299 -0.099255 0.738638 +VERTEX_SE3:QUAT 24 3.1105 -0.327308 99.6652 -0.0169134 -0.666974 -0.0546239 0.742884 +VERTEX_SE3:QUAT 25 3.2543 0.0702852 99.6863 0.0374677 -0.670736 -0.0198094 0.740484 +VERTEX_SE3:QUAT 26 3.33659 0.51248 99.7065 0.0765176 -0.672032 0.027518 0.736044 +VERTEX_SE3:QUAT 27 3.3566 0.971217 99.7314 0.126636 -0.667994 0.074981 0.729469 +VERTEX_SE3:QUAT 28 3.33901 1.45235 99.7688 0.173646 -0.667189 0.11687 0.714875 +VERTEX_SE3:QUAT 29 3.24945 1.93048 99.7883 0.215488 -0.657402 0.159555 0.704223 +VERTEX_SE3:QUAT 30 3.10136 2.38806 99.8305 0.258519 -0.651712 0.20059 0.684253 +VERTEX_SE3:QUAT 31 2.86909 2.82129 99.8735 0.298063 -0.632345 0.241849 0.672909 +VERTEX_SE3:QUAT 32 2.59101 3.25307 99.9139 0.339166 -0.622062 0.275332 0.649767 +VERTEX_SE3:QUAT 33 2.22787 3.63948 99.9746 0.373085 -0.606334 0.30509 0.632525 +VERTEX_SE3:QUAT 34 1.8105 4.00537 100.015 0.415754 -0.581183 0.346013 0.607988 +VERTEX_SE3:QUAT 35 1.32992 4.3138 100.089 0.458394 -0.556104 0.382356 0.578297 +VERTEX_SE3:QUAT 36 0.805773 4.57549 100.161 0.487631 -0.536936 0.412347 0.551258 +VERTEX_SE3:QUAT 37 0.236984 4.79361 100.219 0.515112 -0.513901 0.449327 0.518334 +VERTEX_SE3:QUAT 38 -0.372745 4.91847 100.268 0.54971 -0.481749 0.480856 0.484267 +VERTEX_SE3:QUAT 39 -1.03279 4.95659 100.333 0.57783 -0.452171 0.511104 0.447691 +VERTEX_SE3:QUAT 40 -1.64883 4.9201 100.38 0.602475 -0.421273 0.539251 0.410805 +VERTEX_SE3:QUAT 41 -2.27661 4.78462 100.424 0.626431 -0.390256 0.563405 0.371294 +VERTEX_SE3:QUAT 42 -2.92284 4.56379 100.463 0.647235 -0.3602 0.588447 0.324151 +VERTEX_SE3:QUAT 43 -3.55649 4.26294 100.476 0.657436 -0.329256 0.616067 0.282543 +VERTEX_SE3:QUAT 44 -4.17832 3.88417 100.455 0.673296 -0.290578 0.635806 0.240809 +VERTEX_SE3:QUAT 45 -4.74997 3.41753 100.436 0.684276 -0.251892 0.654466 0.19998 +VERTEX_SE3:QUAT 46 -5.26523 2.87975 100.399 0.687548 -0.213299 0.675216 0.160822 +VERTEX_SE3:QUAT 47 -5.71191 2.27518 100.346 0.691853 -0.173888 0.690457 0.119879 +VERTEX_SE3:QUAT 48 -6.10514 1.59846 100.292 0.700544 -0.132931 0.69625 0.0824808 +VERTEX_SE3:QUAT 49 -6.42184 0.873476 100.232 0.708267 -0.0891035 0.699106 0.0408578 +VERTEX_SE3:QUAT 50 -6.62522 0.122139 100.173 0.713464 -0.0460351 0.699081 -0.0116336 +VERTEX_SE3:QUAT 51 -6.74266 -0.68575 100.116 0.711734 -0.00217364 0.70015 -0.0567422 +VERTEX_SE3:QUAT 52 -6.75702 -1.53433 100.048 0.708903 0.0392652 0.696926 -0.101037 +VERTEX_SE3:QUAT 53 -6.65842 -2.3904 99.9609 0.700891 0.0802255 0.693329 -0.147004 +VERTEX_SE3:QUAT 54 -6.4541 -3.22733 99.8675 0.691941 0.1258 0.682824 -0.197848 +VERTEX_SE3:QUAT 55 -6.13939 -4.05095 99.7578 0.678005 0.174025 0.669987 -0.247268 +VERTEX_SE3:QUAT 56 -5.68333 -4.81535 99.6555 0.664086 0.205356 0.652995 -0.300693 +VERTEX_SE3:QUAT 57 -5.12703 -5.5254 99.5181 0.645777 0.258324 0.6282 -0.348719 +VERTEX_SE3:QUAT 58 -4.46571 -6.16839 99.3861 0.619254 0.299323 0.604383 -0.402059 +VERTEX_SE3:QUAT 59 -3.69874 -6.70835 99.2549 0.59995 0.332372 0.581362 -0.43773 +VERTEX_SE3:QUAT 60 -2.85117 -7.14511 99.1195 0.571071 0.361792 0.564998 -0.473034 +VERTEX_SE3:QUAT 61 -1.9466 -7.47236 98.9735 -0.541049 -0.394519 -0.536636 0.513462 +VERTEX_SE3:QUAT 62 -0.996932 -7.69009 98.8158 -0.519563 -0.420646 -0.51121 0.540162 +VERTEX_SE3:QUAT 63 -0.0178757 -7.82916 98.6592 -0.479601 -0.447532 -0.484465 0.578785 +VERTEX_SE3:QUAT 64 0.992569 -7.8224 98.529 -0.443765 -0.476602 -0.44953 0.611429 +VERTEX_SE3:QUAT 65 1.99158 -7.67822 98.4091 -0.408213 -0.506507 -0.414541 0.636372 +VERTEX_SE3:QUAT 66 2.98678 -7.38528 98.2792 -0.370145 -0.524892 -0.382231 0.664364 +VERTEX_SE3:QUAT 67 3.97574 -6.96218 98.1539 -0.331049 -0.546174 -0.342197 0.689204 +VERTEX_SE3:QUAT 68 4.91054 -6.43458 98.0502 -0.289696 -0.560411 -0.305762 0.71311 +VERTEX_SE3:QUAT 69 5.79747 -5.76576 97.9733 -0.25561 -0.571935 -0.263435 0.733591 +VERTEX_SE3:QUAT 70 6.5771 -4.98538 97.8849 -0.212799 -0.58688 -0.22828 0.747112 +VERTEX_SE3:QUAT 71 7.27886 -4.12203 97.8066 -0.172275 -0.595525 -0.18603 0.762276 +VERTEX_SE3:QUAT 72 7.87479 -3.1424 97.7359 -0.12889 -0.600604 -0.132754 0.777842 +VERTEX_SE3:QUAT 73 8.33514 -2.0795 97.6617 -0.0790849 -0.593394 -0.0974749 0.795065 +VERTEX_SE3:QUAT 74 8.68166 -0.94083 97.6339 -0.0400429 -0.598999 -0.0511615 0.79811 +VERTEX_SE3:QUAT 75 8.88164 0.245122 97.5939 0.00831129 -0.597565 -0.00828116 0.801735 +VERTEX_SE3:QUAT 76 8.92997 1.44472 97.6008 0.0518612 -0.59569 0.0327454 0.800869 +VERTEX_SE3:QUAT 77 8.83763 2.66781 97.6392 0.103913 -0.59128 0.0749202 0.796227 +VERTEX_SE3:QUAT 78 8.56777 3.87632 97.7266 0.14969 -0.58234 0.114821 0.790752 +VERTEX_SE3:QUAT 79 8.16068 5.05845 97.8364 0.202358 -0.577975 0.155912 0.775041 +VERTEX_SE3:QUAT 80 7.58218 6.1822 97.9849 0.252754 -0.558366 0.187942 0.767477 +VERTEX_SE3:QUAT 81 6.88564 7.24249 98.1951 0.303919 -0.546103 0.228109 0.746573 +VERTEX_SE3:QUAT 82 6.02295 8.19037 98.4358 0.347756 -0.521616 0.268224 0.731463 +VERTEX_SE3:QUAT 83 5.04632 9.04191 98.7085 0.397271 -0.500917 0.307318 0.70485 +VERTEX_SE3:QUAT 84 3.93508 9.73016 99.0377 0.439148 -0.476502 0.345539 0.678747 +VERTEX_SE3:QUAT 85 2.75009 10.26 99.3848 0.487985 -0.45005 0.377197 0.645793 +VERTEX_SE3:QUAT 86 1.47294 10.6181 99.7644 0.518747 -0.433371 0.409574 0.61265 +VERTEX_SE3:QUAT 87 0.157582 10.8314 100.134 0.555786 -0.41958 0.432098 0.573014 +VERTEX_SE3:QUAT 88 -1.18654 10.882 100.499 0.587796 -0.396134 0.466187 0.52938 +VERTEX_SE3:QUAT 89 -2.54514 10.7371 100.847 0.622547 -0.369572 0.484959 0.490578 +VERTEX_SE3:QUAT 90 -3.88809 10.413 101.198 0.644065 -0.34361 0.511286 0.45354 +VERTEX_SE3:QUAT 91 -5.20014 9.92231 101.517 0.670954 -0.310891 0.533863 0.410071 +VERTEX_SE3:QUAT 92 -6.46493 9.26431 101.824 0.699283 -0.271627 0.549743 0.36743 +VERTEX_SE3:QUAT 93 -7.63078 8.42852 102.142 0.72418 -0.240012 0.56208 0.319412 +VERTEX_SE3:QUAT 94 -8.71028 7.44039 102.419 0.740759 -0.208612 0.582876 0.260791 +VERTEX_SE3:QUAT 95 -9.658 6.30408 102.639 0.749404 -0.182333 0.60278 0.204463 +VERTEX_SE3:QUAT 96 -10.4654 5.03391 102.768 0.757739 -0.1604 0.614725 0.149053 +VERTEX_SE3:QUAT 97 -11.1622 3.66486 102.795 0.763367 -0.127376 0.625424 0.0994509 +VERTEX_SE3:QUAT 98 -11.6843 2.21226 102.787 0.769986 -0.0969252 0.628455 0.0526439 +VERTEX_SE3:QUAT 99 -12.0658 0.679298 102.725 0.769303 -0.0587123 0.636181 -0.000425651 +VERTEX_SE3:QUAT 100 -12.2419 -0.897375 102.603 0.768875 -0.0305489 0.636651 -0.0507338 +VERTEX_SE3:QUAT 101 -12.2419 -2.48977 102.42 0.766257 -0.00389831 0.635232 -0.0965186 +VERTEX_SE3:QUAT 102 -12.0701 -4.07003 102.161 0.759186 0.0388178 0.634514 -0.139717 +VERTEX_SE3:QUAT 103 -11.7165 -5.63769 101.89 0.745637 0.0675141 0.634939 -0.190578 +VERTEX_SE3:QUAT 104 -11.1719 -7.15164 101.549 0.73355 0.0989521 0.627986 -0.240304 +VERTEX_SE3:QUAT 105 -10.4499 -8.59884 101.159 0.712268 0.130304 0.623217 -0.29546 +VERTEX_SE3:QUAT 106 -9.54814 -9.93979 100.706 0.69288 0.16532 0.611495 -0.344471 +VERTEX_SE3:QUAT 107 -8.45781 -11.1692 100.235 0.670566 0.194142 0.599007 -0.392226 +VERTEX_SE3:QUAT 108 -7.22723 -12.2431 99.7228 0.643029 0.226539 0.587086 -0.436491 +VERTEX_SE3:QUAT 109 -5.842 -13.1612 99.1913 0.61723 0.251748 0.565523 -0.485627 +VERTEX_SE3:QUAT 110 -4.36579 -13.8838 98.6294 -0.586218 -0.281622 -0.54124 0.533007 +VERTEX_SE3:QUAT 111 -2.7816 -14.3741 98.0387 -0.558069 -0.302849 -0.516713 0.574325 +VERTEX_SE3:QUAT 112 -1.11593 -14.6726 97.4325 -0.535292 -0.331024 -0.483384 0.608462 +VERTEX_SE3:QUAT 113 0.588067 -14.778 96.8072 -0.49926 -0.360446 -0.455036 0.643242 +VERTEX_SE3:QUAT 114 2.28469 -14.6435 96.2292 -0.464226 -0.384465 -0.421755 0.67735 +VERTEX_SE3:QUAT 115 3.98654 -14.2527 95.6284 -0.424358 -0.410843 -0.397341 0.702316 +VERTEX_SE3:QUAT 116 5.65556 -13.6687 95.1053 -0.383978 -0.42847 -0.371507 0.728668 +VERTEX_SE3:QUAT 117 7.25546 -12.8931 94.6309 -0.343537 -0.448096 -0.340074 0.752025 +VERTEX_SE3:QUAT 118 8.78618 -11.9003 94.2313 -0.300457 -0.466683 -0.30545 0.773714 +VERTEX_SE3:QUAT 119 10.1846 -10.7107 93.8725 -0.259256 -0.482124 -0.266271 0.793375 +VERTEX_SE3:QUAT 120 11.4485 -9.34108 93.5628 -0.217348 -0.486882 -0.218192 0.817373 +VERTEX_SE3:QUAT 121 12.5347 -7.78541 93.2624 -0.178001 -0.493767 -0.179789 0.831977 +VERTEX_SE3:QUAT 122 13.4556 -6.10435 93.0088 -0.122848 -0.493807 -0.141289 0.849176 +VERTEX_SE3:QUAT 123 14.1483 -4.32182 92.8434 -0.0818509 -0.491629 -0.105885 0.860459 +VERTEX_SE3:QUAT 124 14.6709 -2.43408 92.745 -0.0383728 -0.508206 -0.0679758 0.857691 +VERTEX_SE3:QUAT 125 14.9635 -0.471363 92.7466 0.0201908 -0.513908 -0.0280617 0.857149 +VERTEX_SE3:QUAT 126 15.0269 1.51215 92.8593 0.0702367 -0.513625 0.00891263 0.855089 +VERTEX_SE3:QUAT 127 14.8445 3.50829 93.0599 0.11831 -0.510492 0.0561896 0.849849 +VERTEX_SE3:QUAT 128 14.3869 5.46258 93.3301 0.157175 -0.515173 0.0985744 0.836765 +VERTEX_SE3:QUAT 129 13.7163 7.36568 93.6256 0.205665 -0.510589 0.137041 0.823542 +VERTEX_SE3:QUAT 130 12.8038 9.1582 94.0183 0.251503 -0.506919 0.173309 0.806067 +VERTEX_SE3:QUAT 131 11.687 10.8297 94.4849 0.292263 -0.498596 0.210122 0.788564 +VERTEX_SE3:QUAT 132 10.391 12.3801 94.9976 0.335259 -0.483928 0.255806 0.766797 +VERTEX_SE3:QUAT 133 8.87696 13.7336 95.5478 0.378732 -0.471662 0.289835 0.741682 +VERTEX_SE3:QUAT 134 7.20017 14.8936 96.1327 0.415922 -0.453701 0.328697 0.716326 +VERTEX_SE3:QUAT 135 5.37777 15.809 96.7442 0.451988 -0.44165 0.366293 0.682995 +VERTEX_SE3:QUAT 136 3.44089 16.4913 97.3733 0.488618 -0.42352 0.399398 0.649895 +VERTEX_SE3:QUAT 137 1.42121 16.9154 97.9861 0.520974 -0.400225 0.433364 0.616929 +VERTEX_SE3:QUAT 138 -0.679484 17.0607 98.607 0.550439 -0.375226 0.465646 0.582577 +VERTEX_SE3:QUAT 139 -2.7755 16.9643 99.222 0.573175 -0.354231 0.491806 0.551468 +VERTEX_SE3:QUAT 140 -4.87065 16.6297 99.807 0.601656 -0.326709 0.51768 0.513106 +VERTEX_SE3:QUAT 141 -6.92183 16.0345 100.414 0.630461 -0.29966 0.534133 0.47689 +VERTEX_SE3:QUAT 142 -8.91971 15.2002 101.017 0.660887 -0.267484 0.553898 0.429974 +VERTEX_SE3:QUAT 143 -10.7957 14.0734 101.611 0.679682 -0.236896 0.581754 0.37878 +VERTEX_SE3:QUAT 144 -12.546 12.6861 102.129 0.694767 -0.2039 0.606497 0.328459 +VERTEX_SE3:QUAT 145 -14.0719 11.0477 102.585 0.716234 -0.177647 0.615221 0.277405 +VERTEX_SE3:QUAT 146 -15.4338 9.24711 102.969 0.72791 -0.152354 0.628267 0.228509 +VERTEX_SE3:QUAT 147 -16.606 7.27552 103.256 0.735399 -0.124808 0.643622 0.171353 +VERTEX_SE3:QUAT 148 -17.5335 5.12739 103.46 0.739468 -0.0933352 0.654587 0.126455 +VERTEX_SE3:QUAT 149 -18.2246 2.88285 103.595 0.740232 -0.0665121 0.665131 0.0723368 +VERTEX_SE3:QUAT 150 -18.6816 0.564944 103.625 0.742727 -0.0273486 0.668627 0.023386 +VERTEX_SE3:QUAT 151 -18.8308 -1.80373 103.599 0.736799 0.00570804 0.675445 -0.0294941 +VERTEX_SE3:QUAT 152 -18.6962 -4.19355 103.476 0.736419 0.0333436 0.67078 -0.0814217 +VERTEX_SE3:QUAT 153 -18.2924 -6.57013 103.263 0.726381 0.0788144 0.669945 -0.131652 +VERTEX_SE3:QUAT 154 -17.5639 -8.86332 103.008 0.717182 0.110566 0.662981 -0.184072 +VERTEX_SE3:QUAT 155 -16.5531 -11.063 102.709 0.703616 0.140401 0.656932 -0.231631 +VERTEX_SE3:QUAT 156 -15.2948 -13.1349 102.336 0.68712 0.17501 0.645589 -0.283641 +VERTEX_SE3:QUAT 157 -13.7805 -15.0537 101.893 0.669202 0.209024 0.627859 -0.338039 +VERTEX_SE3:QUAT 158 -12.0172 -16.7254 101.385 0.651336 0.2386 0.606365 -0.388784 +VERTEX_SE3:QUAT 159 -10.0373 -18.1461 100.813 0.631888 0.266897 0.582954 -0.435485 +VERTEX_SE3:QUAT 160 -7.92343 -19.3123 100.198 0.609417 0.301248 0.554827 -0.479611 +VERTEX_SE3:QUAT 161 -5.6299 -20.1961 99.5275 -0.587474 -0.32751 -0.525304 0.521216 +VERTEX_SE3:QUAT 162 -3.2567 -20.775 98.8191 -0.564624 -0.349516 -0.495006 0.560364 +VERTEX_SE3:QUAT 163 -0.81822 -21.0434 98.0517 -0.537203 -0.373451 -0.465316 0.596178 +VERTEX_SE3:QUAT 164 1.63205 -21.0444 97.276 -0.500671 -0.401292 -0.438997 0.628947 +VERTEX_SE3:QUAT 165 4.11533 -20.7098 96.5323 -0.469619 -0.421388 -0.398462 0.665671 +VERTEX_SE3:QUAT 166 6.51208 -20.0549 95.7546 -0.431992 -0.431948 -0.358199 0.706043 +VERTEX_SE3:QUAT 167 8.80129 -19.0319 94.9438 -0.391944 -0.440367 -0.323525 0.740127 +VERTEX_SE3:QUAT 168 10.9503 -17.7208 94.1593 -0.353975 -0.453748 -0.287975 0.765432 +VERTEX_SE3:QUAT 169 12.9591 -16.1283 93.3909 -0.314202 -0.468606 -0.262054 0.782951 +VERTEX_SE3:QUAT 170 14.791 -14.3273 92.716 -0.271646 -0.48318 -0.220752 0.802505 +VERTEX_SE3:QUAT 171 16.4098 -12.2796 92.121 -0.223493 -0.497484 -0.19109 0.816116 +VERTEX_SE3:QUAT 172 17.821 -10.0157 91.6277 -0.176564 -0.503297 -0.14303 0.833702 +VERTEX_SE3:QUAT 173 18.9239 -7.57582 91.2016 -0.132858 -0.507076 -0.097468 0.846004 +VERTEX_SE3:QUAT 174 19.6963 -4.97592 90.8415 -0.0866862 -0.502764 -0.0505948 0.858577 +VERTEX_SE3:QUAT 175 20.1248 -2.26431 90.5652 -0.0481007 -0.501821 -0.0039219 0.863624 +VERTEX_SE3:QUAT 176 20.2311 0.499522 90.3394 -0.0110161 -0.505093 0.0444786 0.861848 +VERTEX_SE3:QUAT 177 20.0043 3.26105 90.1429 0.0345823 -0.4954 0.0925024 0.863033 +VERTEX_SE3:QUAT 178 19.4161 5.97712 90.0606 0.0684393 -0.481221 0.137679 0.863011 +VERTEX_SE3:QUAT 179 18.4987 8.62106 90.0102 0.110867 -0.466438 0.178745 0.859182 +VERTEX_SE3:QUAT 180 17.2845 11.1717 90.0725 0.153917 -0.462525 0.22675 0.843187 +VERTEX_SE3:QUAT 181 15.7363 13.5573 90.2023 0.192564 -0.452541 0.257579 0.831732 +VERTEX_SE3:QUAT 182 13.9747 15.7818 90.4392 0.232072 -0.433916 0.294102 0.819367 +VERTEX_SE3:QUAT 183 11.9724 17.8193 90.805 0.275896 -0.421541 0.330101 0.79826 +VERTEX_SE3:QUAT 184 9.75647 19.5749 91.255 0.31433 -0.405988 0.360062 0.778926 +VERTEX_SE3:QUAT 185 7.3493 21.1077 91.8017 0.35408 -0.386904 0.388421 0.757668 +VERTEX_SE3:QUAT 186 4.80418 22.3435 92.4803 0.39262 -0.371194 0.415912 0.731493 +VERTEX_SE3:QUAT 187 2.12174 23.3001 93.2509 0.429825 -0.349246 0.452071 0.699221 +VERTEX_SE3:QUAT 188 -0.654558 23.9002 94.0839 0.465233 -0.326072 0.482994 0.666297 +VERTEX_SE3:QUAT 189 -3.4786 24.1211 94.9683 0.491333 -0.305036 0.511382 0.635637 +VERTEX_SE3:QUAT 190 -6.32992 24.0263 95.8904 0.528525 -0.281105 0.541133 0.590607 +VERTEX_SE3:QUAT 191 -9.12273 23.5334 96.8314 0.553723 -0.257318 0.571805 0.547921 +VERTEX_SE3:QUAT 192 -11.8726 22.6528 97.7549 0.580521 -0.232838 0.59626 0.503245 +VERTEX_SE3:QUAT 193 -14.4825 21.4229 98.6555 0.606075 -0.202449 0.617934 0.45809 +VERTEX_SE3:QUAT 194 -16.9283 19.8581 99.5496 0.621287 -0.17279 0.641229 0.415898 +VERTEX_SE3:QUAT 195 -19.1752 18.0039 100.431 0.64379 -0.135174 0.655039 0.371734 +VERTEX_SE3:QUAT 196 -21.1569 15.8289 101.302 0.664301 -0.103995 0.667969 0.318914 +VERTEX_SE3:QUAT 197 -22.8517 13.3775 102.134 0.682807 -0.0688414 0.675298 0.2702 +VERTEX_SE3:QUAT 198 -24.2155 10.7143 102.93 0.701393 -0.0426044 0.67638 0.220778 +VERTEX_SE3:QUAT 199 -25.278 7.88905 103.665 0.707094 -0.0109507 0.686541 0.168996 +VERTEX_SE3:QUAT 200 -25.9905 4.90396 104.322 0.708285 0.0297733 0.696655 0.110076 +VERTEX_SE3:QUAT 201 -26.2793 1.8408 104.889 0.712181 0.0550409 0.697553 0.0564635 +VERTEX_SE3:QUAT 202 -26.2024 -1.29185 105.34 0.718682 0.0881704 0.689672 -0.00868077 +VERTEX_SE3:QUAT 203 -25.6997 -4.4135 105.641 0.718527 0.126913 0.680476 -0.0675685 +VERTEX_SE3:QUAT 204 -24.7696 -7.43672 105.822 0.714631 0.160427 0.670369 -0.119043 +VERTEX_SE3:QUAT 205 -23.4514 -10.3544 105.911 0.706518 0.195541 0.659602 -0.165895 +VERTEX_SE3:QUAT 206 -21.794 -13.1241 105.914 0.70509 0.219505 0.639822 -0.212822 +VERTEX_SE3:QUAT 207 -19.8595 -15.7145 105.803 0.697664 0.250825 0.620282 -0.256129 +VERTEX_SE3:QUAT 208 -17.6408 -18.0887 105.598 0.690424 0.275238 0.594468 -0.306866 +VERTEX_SE3:QUAT 209 -15.1503 -20.1867 105.224 0.667336 0.29986 0.577776 -0.361831 +VERTEX_SE3:QUAT 210 -12.4256 -21.9593 104.719 0.647656 0.318349 0.554174 -0.414833 +VERTEX_SE3:QUAT 211 -9.52153 -23.3888 104.054 0.62032 0.339714 0.537303 -0.45946 +VERTEX_SE3:QUAT 212 -6.47828 -24.4696 103.317 -0.595373 -0.359447 -0.510453 0.505735 +VERTEX_SE3:QUAT 213 -3.33189 -25.1503 102.473 -0.569101 -0.380348 -0.478559 0.549946 +VERTEX_SE3:QUAT 214 -0.12066 -25.4104 101.558 -0.540211 -0.396993 -0.444619 0.594039 +VERTEX_SE3:QUAT 215 3.08291 -25.2507 100.551 -0.51054 -0.410123 -0.410246 0.634702 +VERTEX_SE3:QUAT 216 6.22109 -24.6853 99.4676 -0.475885 -0.421521 -0.369885 0.677524 +VERTEX_SE3:QUAT 217 9.24585 -23.6745 98.3102 -0.444977 -0.436995 -0.323916 0.711413 +VERTEX_SE3:QUAT 218 12.1059 -22.249 97.0858 -0.40487 -0.446009 -0.280937 0.747148 +VERTEX_SE3:QUAT 219 14.7266 -20.4123 95.8446 -0.370271 -0.454232 -0.237334 0.774755 +VERTEX_SE3:QUAT 220 17.0861 -18.2325 94.6004 -0.331583 -0.45111 -0.199148 0.804297 +VERTEX_SE3:QUAT 221 19.1421 -15.7585 93.3713 -0.291585 -0.465082 -0.142926 0.823558 +VERTEX_SE3:QUAT 222 20.8252 -12.9706 92.1443 -0.241071 -0.466786 -0.101255 0.844833 +VERTEX_SE3:QUAT 223 22.1164 -9.94856 91.0242 -0.202361 -0.471744 -0.0574396 0.856276 +VERTEX_SE3:QUAT 224 23.0274 -6.72103 89.9867 -0.162703 -0.464531 -0.0141085 0.870367 +VERTEX_SE3:QUAT 225 23.5457 -3.37859 89.0224 -0.104598 -0.464788 0.0323685 0.878626 +VERTEX_SE3:QUAT 226 23.5753 0.0615722 88.2575 -0.0616034 -0.45749 0.0685502 0.884426 +VERTEX_SE3:QUAT 227 23.2474 3.53756 87.6492 -0.022399 -0.448716 0.114887 0.885976 +VERTEX_SE3:QUAT 228 22.4817 6.98472 87.1516 0.0173245 -0.440554 0.158855 0.88339 +VERTEX_SE3:QUAT 229 21.3292 10.3388 86.7645 0.0712981 -0.428723 0.194091 0.879455 +VERTEX_SE3:QUAT 230 19.7993 13.5605 86.5997 0.120262 -0.421907 0.232116 0.868132 +VERTEX_SE3:QUAT 231 17.8842 16.602 86.6509 0.16099 -0.417423 0.277533 0.850186 +VERTEX_SE3:QUAT 232 15.6093 19.4006 86.8016 0.196033 -0.409838 0.319868 0.831437 +VERTEX_SE3:QUAT 233 13.018 21.9298 87.0326 0.23609 -0.394419 0.359578 0.812034 +VERTEX_SE3:QUAT 234 10.1406 24.1386 87.3866 0.280058 -0.368024 0.398894 0.791839 +VERTEX_SE3:QUAT 235 7.01237 25.9654 87.933 0.313371 -0.35794 0.437475 0.763081 +VERTEX_SE3:QUAT 236 3.68383 27.3994 88.5531 0.349347 -0.335359 0.469668 0.738175 +VERTEX_SE3:QUAT 237 0.22551 28.4578 89.2943 0.38487 -0.317068 0.492648 0.71319 +VERTEX_SE3:QUAT 238 -3.31822 29.1613 90.1633 0.417422 -0.291773 0.533509 0.675274 +VERTEX_SE3:QUAT 239 -6.92283 29.3387 91.1016 0.45118 -0.258085 0.564392 0.64132 +VERTEX_SE3:QUAT 240 -10.5234 29.0515 92.1677 0.48497 -0.238421 0.593822 0.5961 +VERTEX_SE3:QUAT 241 -14.0191 28.2723 93.2523 0.515927 -0.209817 0.619379 0.553323 +VERTEX_SE3:QUAT 242 -17.3978 27.0289 94.3987 0.542922 -0.179404 0.646143 0.505519 +VERTEX_SE3:QUAT 243 -20.5596 25.2898 95.5821 0.568042 -0.153895 0.665459 0.459138 +VERTEX_SE3:QUAT 244 -23.4831 23.1727 96.7544 0.586871 -0.119116 0.684301 0.416085 +VERTEX_SE3:QUAT 245 -26.0938 20.6909 97.9603 0.602903 -0.0954956 0.703665 0.363654 +VERTEX_SE3:QUAT 246 -28.4216 17.8555 99.0714 0.626676 -0.0648448 0.711005 0.312322 +VERTEX_SE3:QUAT 247 -30.37 14.7353 100.157 0.64482 -0.0495094 0.717623 0.258403 +VERTEX_SE3:QUAT 248 -31.9498 11.3427 101.11 0.657845 -0.0163167 0.726659 0.197332 +VERTEX_SE3:QUAT 249 -33.0509 7.70866 101.967 0.662037 0.0119392 0.734803 0.147068 +VERTEX_SE3:QUAT 250 -33.7095 3.96143 102.726 0.670714 0.0344641 0.735446 0.0898588 +VERTEX_SE3:QUAT 251 -33.9313 0.11121 103.339 0.678856 0.0637549 0.730573 0.0367818 +VERTEX_SE3:QUAT 252 -33.6771 -3.76137 103.834 0.681487 0.0864545 0.726468 -0.0185683 +VERTEX_SE3:QUAT 253 -32.9882 -7.62979 104.161 0.683446 0.119577 0.716467 -0.0726445 +VERTEX_SE3:QUAT 254 -31.8219 -11.4089 104.375 0.684395 0.144523 0.703186 -0.127459 +VERTEX_SE3:QUAT 255 -30.2418 -15.0315 104.419 0.679749 0.17475 0.688401 -0.183051 +VERTEX_SE3:QUAT 256 -28.1946 -18.4606 104.288 0.67137 0.201786 0.671986 -0.238703 +VERTEX_SE3:QUAT 257 -25.7455 -21.6066 104.004 0.663461 0.223992 0.655268 -0.283321 +VERTEX_SE3:QUAT 258 -22.9965 -24.4914 103.603 0.646256 0.246736 0.639485 -0.335461 +VERTEX_SE3:QUAT 259 -19.9267 -27.0308 103.056 0.628116 0.263729 0.62032 -0.388742 +VERTEX_SE3:QUAT 260 -16.5861 -29.18 102.341 0.606693 0.285457 0.598621 -0.438282 +VERTEX_SE3:QUAT 261 -13.0208 -30.8941 101.492 0.580985 0.307312 0.579116 -0.482329 +VERTEX_SE3:QUAT 262 -9.26019 -32.1712 100.607 -0.55758 -0.331387 -0.548638 0.527526 +VERTEX_SE3:QUAT 263 -5.36273 -32.9485 99.6262 -0.538444 -0.355157 -0.514673 0.564849 +VERTEX_SE3:QUAT 264 -1.40744 -33.2515 98.5564 -0.512016 -0.382699 -0.48363 0.597898 +VERTEX_SE3:QUAT 265 2.56292 -33.0915 97.4935 -0.487335 -0.397665 -0.449781 0.634085 +VERTEX_SE3:QUAT 266 6.47945 -32.4541 96.371 -0.456651 -0.410427 -0.415244 0.671261 +VERTEX_SE3:QUAT 267 10.2888 -31.3289 95.1956 -0.418906 -0.418976 -0.377065 0.711898 +VERTEX_SE3:QUAT 268 13.9199 -29.6917 93.9928 -0.386396 -0.430193 -0.333443 0.744613 +VERTEX_SE3:QUAT 269 17.3018 -27.5826 92.7626 -0.349588 -0.441385 -0.291006 0.773488 +VERTEX_SE3:QUAT 270 20.3893 -25.0145 91.5296 -0.319061 -0.448244 -0.246991 0.797667 +VERTEX_SE3:QUAT 271 23.1374 -22.0848 90.295 -0.282291 -0.45484 -0.198931 0.820889 +VERTEX_SE3:QUAT 272 25.4599 -18.7767 89.0867 -0.234883 -0.46572 -0.155906 0.838826 +VERTEX_SE3:QUAT 273 27.3554 -15.1448 88.027 -0.203092 -0.458374 -0.109693 0.858262 +VERTEX_SE3:QUAT 274 28.8102 -11.2994 86.9655 -0.161661 -0.452358 -0.0683076 0.874398 +VERTEX_SE3:QUAT 275 29.7846 -7.26052 86.0267 -0.111216 -0.454011 -0.00974979 0.883974 +VERTEX_SE3:QUAT 276 30.1452 -3.07771 85.2195 -0.0673854 -0.45429 0.0459573 0.887112 +VERTEX_SE3:QUAT 277 29.8885 1.12795 84.5274 -0.0193619 -0.449945 0.0857469 0.888719 +VERTEX_SE3:QUAT 278 29.1515 5.3419 84.0494 0.0274749 -0.441944 0.127838 0.887462 +VERTEX_SE3:QUAT 279 27.9094 9.47037 83.7779 0.0681248 -0.44427 0.172897 0.876407 +VERTEX_SE3:QUAT 280 26.2019 13.4454 83.6227 0.113061 -0.434143 0.21452 0.867593 +VERTEX_SE3:QUAT 281 24.0323 17.2037 83.6748 0.146488 -0.426987 0.262702 0.852766 +VERTEX_SE3:QUAT 282 21.401 20.6641 83.791 0.184474 -0.418338 0.302959 0.836169 +VERTEX_SE3:QUAT 283 18.384 23.8467 84.0327 0.216273 -0.408323 0.344589 0.817164 +VERTEX_SE3:QUAT 284 15.0385 26.6627 84.3507 0.256004 -0.396654 0.379332 0.795761 +VERTEX_SE3:QUAT 285 11.3695 29.0841 84.8191 0.294983 -0.375719 0.417616 0.772928 +VERTEX_SE3:QUAT 286 7.44949 31.0548 85.4498 0.33716 -0.35484 0.461312 0.740002 +VERTEX_SE3:QUAT 287 3.28616 32.4261 86.205 0.378403 -0.342045 0.49838 0.701023 +VERTEX_SE3:QUAT 288 -1.01683 33.2378 87.0347 0.414829 -0.317121 0.535664 0.663638 +VERTEX_SE3:QUAT 289 -5.38866 33.4453 87.9277 0.450042 -0.29365 0.570884 0.620744 +VERTEX_SE3:QUAT 290 -9.74404 33.0229 88.9142 0.474906 -0.269897 0.606516 0.577719 +VERTEX_SE3:QUAT 291 -14.0105 32.0262 89.888 0.498625 -0.2401 0.638208 0.535178 +VERTEX_SE3:QUAT 292 -18.1288 30.4585 90.8864 0.519128 -0.217378 0.666532 0.488865 +VERTEX_SE3:QUAT 293 -22.0329 28.361 91.8335 0.540361 -0.180603 0.692269 0.442895 +VERTEX_SE3:QUAT 294 -25.6355 25.7501 92.8165 0.568663 -0.149614 0.70904 0.38923 +VERTEX_SE3:QUAT 295 -28.8065 22.6453 93.8047 0.585704 -0.12344 0.728739 0.332645 +VERTEX_SE3:QUAT 296 -31.5435 19.1086 94.7171 0.601663 -0.0900545 0.745761 0.271537 +VERTEX_SE3:QUAT 297 -33.7511 15.1794 95.5448 0.611421 -0.0536632 0.756903 0.22446 +VERTEX_SE3:QUAT 298 -35.4587 10.9705 96.3512 0.620747 -0.0290125 0.763921 0.173945 +VERTEX_SE3:QUAT 299 -36.698 6.57802 97.0657 0.626226 -0.00203153 0.77158 0.111809 +VERTEX_SE3:QUAT 300 -37.3303 2.03931 97.6241 0.634468 0.0167336 0.770856 0.0543244 +VERTEX_SE3:QUAT 301 -37.4412 -2.59244 97.9837 0.626337 0.0441139 0.778303 -0.00101642 +VERTEX_SE3:QUAT 302 -36.9983 -7.2253 98.2106 0.625957 0.0722164 0.774824 -0.0510936 +VERTEX_SE3:QUAT 303 -36.0506 -11.792 98.3563 0.62394 0.100885 0.768204 -0.101904 +VERTEX_SE3:QUAT 304 -34.572 -16.2492 98.4149 0.611936 0.131205 0.762421 -0.164421 +VERTEX_SE3:QUAT 305 -32.4765 -20.4763 98.347 0.608595 0.163219 0.747264 -0.211111 +VERTEX_SE3:QUAT 306 -29.9184 -24.4114 98.2009 0.595684 0.197786 0.731331 -0.266826 +VERTEX_SE3:QUAT 307 -26.8268 -27.9896 97.9943 0.584208 0.230072 0.70772 -0.323884 +VERTEX_SE3:QUAT 308 -23.2736 -31.1232 97.6722 0.56847 0.259569 0.683514 -0.377194 +VERTEX_SE3:QUAT 309 -19.3225 -33.7355 97.2578 0.552222 0.287424 0.657097 -0.425044 +VERTEX_SE3:QUAT 310 -15.0592 -35.824 96.7607 0.531064 0.305744 0.63221 -0.474133 +VERTEX_SE3:QUAT 311 -10.5693 -37.3968 96.1281 -0.510555 -0.32436 -0.606257 0.516311 +VERTEX_SE3:QUAT 312 -5.93658 -38.4472 95.4179 -0.493948 -0.333288 -0.576992 0.558583 +VERTEX_SE3:QUAT 313 -1.21728 -39.0078 94.5338 -0.472589 -0.352658 -0.550707 0.590774 +VERTEX_SE3:QUAT 314 3.5415 -39.0923 93.6618 -0.433512 -0.383423 -0.517206 0.630517 +VERTEX_SE3:QUAT 315 8.29256 -38.4825 92.8779 -0.39149 -0.395739 -0.478957 0.678768 +VERTEX_SE3:QUAT 316 12.9145 -37.1624 92.0818 -0.363767 -0.408863 -0.440785 0.711487 +VERTEX_SE3:QUAT 317 17.3512 -35.3032 91.2725 -0.327595 -0.428036 -0.398351 0.742147 +VERTEX_SE3:QUAT 318 21.5192 -32.8426 90.515 -0.296711 -0.448762 -0.35064 0.766568 +VERTEX_SE3:QUAT 319 25.3546 -29.8591 89.7694 -0.253428 -0.470872 -0.303322 0.788701 +VERTEX_SE3:QUAT 320 28.7388 -26.336 89.1821 -0.219693 -0.480528 -0.254899 0.809848 +VERTEX_SE3:QUAT 321 31.668 -22.4102 88.594 -0.185152 -0.482917 -0.208692 0.830035 +VERTEX_SE3:QUAT 322 34.0979 -18.1263 88.0271 -0.153003 -0.492148 -0.153026 0.843186 +VERTEX_SE3:QUAT 323 35.9469 -13.5624 87.4611 -0.123626 -0.495389 -0.105863 0.853287 +VERTEX_SE3:QUAT 324 37.2594 -8.78248 86.8955 -0.084917 -0.498421 -0.0644609 0.860355 +VERTEX_SE3:QUAT 325 38.0424 -3.87565 86.4533 -0.0569053 -0.503709 -0.0205088 0.861753 +VERTEX_SE3:QUAT 326 38.3063 1.10754 86.0295 -0.0165406 -0.50554 0.025573 0.862266 +VERTEX_SE3:QUAT 327 37.974 6.11386 85.7327 0.0316548 -0.500174 0.0763585 0.86197 +VERTEX_SE3:QUAT 328 36.9407 11.0238 85.5874 0.0735092 -0.494638 0.131834 0.855891 +VERTEX_SE3:QUAT 329 35.2406 15.786 85.5262 0.123169 -0.490089 0.180888 0.843754 +VERTEX_SE3:QUAT 330 32.886 20.287 85.6581 0.162521 -0.49282 0.223821 0.824997 +VERTEX_SE3:QUAT 331 30.007 24.4805 85.867 0.203447 -0.484179 0.264083 0.808975 +VERTEX_SE3:QUAT 332 26.6416 28.3199 86.1818 0.24447 -0.46251 0.312111 0.793036 +VERTEX_SE3:QUAT 333 22.8075 31.6655 86.6653 0.275393 -0.456272 0.364985 0.763387 +VERTEX_SE3:QUAT 334 18.5379 34.481 87.0704 0.305662 -0.454687 0.408322 0.730139 +VERTEX_SE3:QUAT 335 13.9525 36.7647 87.4071 0.335195 -0.441295 0.448807 0.701053 +VERTEX_SE3:QUAT 336 9.10423 38.4808 87.7442 0.362927 -0.420764 0.491661 0.670455 +VERTEX_SE3:QUAT 337 4.08181 39.586 88.0572 0.387076 -0.396179 0.536696 0.636531 +VERTEX_SE3:QUAT 338 -1.05374 40.0137 88.3426 0.409517 -0.379929 0.573477 0.599228 +VERTEX_SE3:QUAT 339 -6.24753 39.8412 88.5483 0.430259 -0.361234 0.612836 0.555715 +VERTEX_SE3:QUAT 340 -11.3902 38.9972 88.6539 0.451503 -0.334789 0.643068 0.52012 +VERTEX_SE3:QUAT 341 -16.4142 37.5753 88.7991 0.468377 -0.305876 0.681972 0.471144 +VERTEX_SE3:QUAT 342 -21.1695 35.4346 88.8625 0.482728 -0.283305 0.714897 0.419088 +VERTEX_SE3:QUAT 343 -25.6577 32.6783 88.8044 0.506734 -0.251164 0.736248 0.371586 +VERTEX_SE3:QUAT 344 -29.7605 29.3579 88.785 0.517934 -0.212013 0.762049 0.325694 +VERTEX_SE3:QUAT 345 -33.3948 25.5203 88.8105 0.531378 -0.176864 0.783253 0.269946 +VERTEX_SE3:QUAT 346 -36.4549 21.186 88.7993 0.541579 -0.139669 0.798521 0.222596 +VERTEX_SE3:QUAT 347 -38.9493 16.4884 88.8382 0.539809 -0.111179 0.816647 0.17127 +VERTEX_SE3:QUAT 348 -40.8818 11.5163 88.8045 0.543132 -0.0851793 0.827317 0.115317 +VERTEX_SE3:QUAT 349 -42.1764 6.34485 88.6575 0.544784 -0.0472466 0.835163 0.0589953 +VERTEX_SE3:QUAT 350 -42.7516 1.00728 88.5137 0.539562 -0.00934342 0.841865 -0.00700798 +VERTEX_SE3:QUAT 351 -42.5246 -4.34405 88.3173 0.537545 0.0116156 0.84067 -0.0646925 +VERTEX_SE3:QUAT 352 -41.6373 -9.6643 87.9934 0.530915 0.0507713 0.836924 -0.12292 +VERTEX_SE3:QUAT 353 -40.0043 -14.8075 87.6924 0.530562 0.0824186 0.82453 -0.178497 +VERTEX_SE3:QUAT 354 -37.7281 -19.7153 87.3468 0.522001 0.115514 0.81047 -0.239397 +VERTEX_SE3:QUAT 355 -34.7685 -24.2294 86.9635 0.508662 0.149334 0.79574 -0.292848 +VERTEX_SE3:QUAT 356 -31.207 -28.3453 86.5865 0.497582 0.182701 0.773636 -0.34716 +VERTEX_SE3:QUAT 357 -27.1253 -31.9371 86.1968 0.476692 0.219743 0.751753 -0.399181 +VERTEX_SE3:QUAT 358 -22.5696 -34.9453 85.8624 0.452264 0.254696 0.727242 -0.449117 +VERTEX_SE3:QUAT 359 -17.6259 -37.3068 85.6127 0.431855 0.277915 0.706229 -0.487346 +VERTEX_SE3:QUAT 360 -12.4227 -39.1315 85.4196 -0.403966 -0.304745 -0.681747 0.528359 +VERTEX_SE3:QUAT 361 -7.05931 -40.3066 85.3076 -0.379849 -0.329978 -0.647075 0.57282 +VERTEX_SE3:QUAT 362 -1.56359 -40.7737 85.23 -0.358248 -0.358313 -0.616784 0.602368 +VERTEX_SE3:QUAT 363 3.96629 -40.6193 85.2451 -0.333874 -0.387816 -0.576334 0.637155 +VERTEX_SE3:QUAT 364 9.44802 -39.7597 85.3269 -0.308901 -0.409281 -0.532599 0.673355 +VERTEX_SE3:QUAT 365 14.7877 -38.1892 85.3858 -0.288657 -0.43319 -0.491168 0.698411 +VERTEX_SE3:QUAT 366 19.9204 -35.995 85.4768 -0.25849 -0.441407 -0.45561 0.728534 +VERTEX_SE3:QUAT 367 24.7888 -33.2652 85.573 -0.230542 -0.465686 -0.410364 0.749392 +VERTEX_SE3:QUAT 368 29.2995 -29.9463 85.7195 -0.194014 -0.48018 -0.364756 0.773782 +VERTEX_SE3:QUAT 369 33.3568 -26.0723 85.9585 -0.167027 -0.488013 -0.317389 0.795745 +VERTEX_SE3:QUAT 370 36.9399 -21.7403 86.154 -0.138209 -0.495184 -0.264117 0.816047 +VERTEX_SE3:QUAT 371 39.9461 -16.9689 86.3004 -0.107829 -0.508544 -0.222452 0.824785 +VERTEX_SE3:QUAT 372 42.4244 -11.8847 86.515 -0.0799308 -0.517211 -0.17219 0.834538 +VERTEX_SE3:QUAT 373 44.297 -6.52146 86.7179 -0.051528 -0.527436 -0.114708 0.840237 +VERTEX_SE3:QUAT 374 45.4675 -0.943737 86.8557 -0.0211696 -0.527444 -0.0596509 0.847229 +VERTEX_SE3:QUAT 375 45.9282 4.74459 86.9582 0.00484696 -0.533023 -0.00121398 0.846086 +VERTEX_SE3:QUAT 376 45.6495 10.461 86.9393 0.0388628 -0.530219 0.0478779 0.845615 +VERTEX_SE3:QUAT 377 44.6929 16.0992 86.9532 0.0786673 -0.532117 0.0858648 0.838624 +VERTEX_SE3:QUAT 378 43.1429 21.637 87.1075 0.112986 -0.526444 0.14595 0.829933 +VERTEX_SE3:QUAT 379 40.8284 26.9296 87.2252 0.150023 -0.516316 0.193122 0.82074 +VERTEX_SE3:QUAT 380 37.8737 31.9031 87.4228 0.189419 -0.506298 0.24188 0.805777 +VERTEX_SE3:QUAT 381 34.2983 36.4487 87.7057 0.211823 -0.501474 0.289095 0.787451 +VERTEX_SE3:QUAT 382 30.2218 40.5992 87.8949 0.234224 -0.494085 0.346472 0.762218 +VERTEX_SE3:QUAT 383 25.6429 44.1905 87.9059 0.260502 -0.482071 0.393889 0.737969 +VERTEX_SE3:QUAT 384 20.6461 47.2177 87.8684 0.280278 -0.46902 0.443544 0.710446 +VERTEX_SE3:QUAT 385 15.3087 49.612 87.6758 0.29956 -0.444 0.496925 0.682783 +VERTEX_SE3:QUAT 386 9.69586 51.283 87.4244 0.322022 -0.411429 0.539195 0.660528 +VERTEX_SE3:QUAT 387 3.9118 52.2584 87.274 0.346524 -0.384424 0.585427 0.624031 +VERTEX_SE3:QUAT 388 -1.97506 52.4296 87.0996 0.3723 -0.361605 0.628028 0.579841 +VERTEX_SE3:QUAT 389 -7.84681 51.783 86.9147 0.391078 -0.33841 0.661833 0.542691 +VERTEX_SE3:QUAT 390 -13.5896 50.4294 86.7097 0.415195 -0.317795 0.695437 0.492937 +VERTEX_SE3:QUAT 391 -19.1386 48.3289 86.4412 0.435789 -0.293756 0.721651 0.450572 +VERTEX_SE3:QUAT 392 -24.4184 45.5999 86.1698 0.450913 -0.267555 0.747825 0.407247 +VERTEX_SE3:QUAT 393 -29.3499 42.2559 85.9133 0.468424 -0.231266 0.77424 0.357277 +VERTEX_SE3:QUAT 394 -33.7731 38.2617 85.7036 0.483336 -0.204077 0.795257 0.303819 +VERTEX_SE3:QUAT 395 -37.6555 33.7213 85.4454 0.497394 -0.171377 0.812241 0.251979 +VERTEX_SE3:QUAT 396 -40.9287 28.6972 85.2049 0.510477 -0.14579 0.824262 0.196853 +VERTEX_SE3:QUAT 397 -43.5251 23.2805 84.899 0.518154 -0.113816 0.836163 0.139261 +VERTEX_SE3:QUAT 398 -45.3913 17.5593 84.5524 0.518826 -0.0784982 0.846707 0.088007 +VERTEX_SE3:QUAT 399 -46.5078 11.6075 84.2436 0.518969 -0.0489362 0.852734 0.0334959 +VERTEX_SE3:QUAT 400 -46.9045 5.57837 83.9093 0.517195 -0.0224198 0.855407 -0.0168985 +VERTEX_SE3:QUAT 401 -46.5908 -0.46235 83.4965 0.50612 0.00293366 0.858301 -0.0845785 +VERTEX_SE3:QUAT 402 -45.4242 -6.41785 82.9516 0.503099 0.0338516 0.852549 -0.137498 +VERTEX_SE3:QUAT 403 -43.5283 -12.2078 82.394 0.495682 0.0603842 0.845486 -0.189226 +VERTEX_SE3:QUAT 404 -40.949 -17.7345 81.8215 0.496922 0.0886596 0.829404 -0.239369 +VERTEX_SE3:QUAT 405 -37.7278 -22.9292 81.1828 0.490148 0.112051 0.815568 -0.286442 +VERTEX_SE3:QUAT 406 -33.9643 -27.7305 80.5301 0.469716 0.142466 0.803174 -0.337611 +VERTEX_SE3:QUAT 407 -29.6026 -32.0325 79.9252 0.45193 0.175484 0.785444 -0.384764 +VERTEX_SE3:QUAT 408 -24.7314 -35.7686 79.4307 0.429184 0.20246 0.767197 -0.431531 +VERTEX_SE3:QUAT 409 -19.4186 -38.899 79.0198 0.415836 0.234075 0.737626 -0.4777 +VERTEX_SE3:QUAT 410 -13.749 -41.3228 78.6613 -0.397553 -0.261512 -0.704795 0.526144 +VERTEX_SE3:QUAT 411 -7.7921 -42.9803 78.3008 -0.37381 -0.284771 -0.67389 0.570126 +VERTEX_SE3:QUAT 412 -1.63995 -43.881 77.9909 -0.3414 -0.308411 -0.646481 0.608597 +VERTEX_SE3:QUAT 413 4.58461 -44.0288 77.8345 -0.324804 -0.329494 -0.602249 0.650563 +VERTEX_SE3:QUAT 414 10.7806 -43.3514 77.6632 -0.295357 -0.351178 -0.570425 0.681215 +VERTEX_SE3:QUAT 415 16.8897 -41.9862 77.6096 -0.264725 -0.377952 -0.527026 0.713664 +VERTEX_SE3:QUAT 416 22.7802 -39.7969 77.7055 -0.22671 -0.401225 -0.479292 0.746928 +VERTEX_SE3:QUAT 417 28.2976 -36.7676 77.9686 -0.202239 -0.424478 -0.436066 0.76731 +VERTEX_SE3:QUAT 418 33.4374 -33.1411 78.3184 -0.163955 -0.439378 -0.395973 0.789475 +VERTEX_SE3:QUAT 419 38.1052 -28.9147 78.8432 -0.133354 -0.452837 -0.356396 0.806311 +VERTEX_SE3:QUAT 420 42.2986 -24.1991 79.4711 -0.101551 -0.468021 -0.296781 0.826175 +VERTEX_SE3:QUAT 421 45.7632 -18.9299 80.1324 -0.079083 -0.469339 -0.24188 0.845553 +VERTEX_SE3:QUAT 422 48.5694 -13.2658 80.6758 -0.048283 -0.469887 -0.194132 0.85976 +VERTEX_SE3:QUAT 423 50.7105 -7.29368 81.2708 -0.0141207 -0.479335 -0.140615 0.866179 +VERTEX_SE3:QUAT 424 52.0663 -1.08585 81.914 0.0120995 -0.479624 -0.0922782 0.872525 +VERTEX_SE3:QUAT 425 52.7195 5.25327 82.5434 0.0424325 -0.476527 -0.0359352 0.8774 +VERTEX_SE3:QUAT 426 52.5774 11.6339 83.1833 0.0800127 -0.472928 0.0181641 0.877272 +VERTEX_SE3:QUAT 427 51.5845 17.9445 83.9208 0.110882 -0.469361 0.0672081 0.873435 +VERTEX_SE3:QUAT 428 49.8587 24.1047 84.7153 0.135189 -0.473145 0.118458 0.862453 +VERTEX_SE3:QUAT 429 47.4233 30.0378 85.4259 0.163759 -0.467554 0.16425 0.852993 +VERTEX_SE3:QUAT 430 44.3438 35.6818 86.1828 0.199464 -0.462875 0.213044 0.837003 +VERTEX_SE3:QUAT 431 40.5756 40.9032 87.0044 0.231004 -0.447519 0.272703 0.819754 +VERTEX_SE3:QUAT 432 36.0927 45.5495 87.8185 0.250874 -0.431819 0.327616 0.802037 +VERTEX_SE3:QUAT 433 31.0609 49.6252 88.5083 0.279485 -0.420686 0.379026 0.775404 +VERTEX_SE3:QUAT 434 25.507 53.0048 89.1834 0.307835 -0.409605 0.424239 0.746647 +VERTEX_SE3:QUAT 435 19.5671 55.6815 89.8346 0.340488 -0.393528 0.46628 0.715393 +VERTEX_SE3:QUAT 436 13.3293 57.576 90.5351 0.354427 -0.381386 0.514571 0.68128 +VERTEX_SE3:QUAT 437 6.89246 58.7284 91.0455 0.374749 -0.363272 0.558022 0.645142 +VERTEX_SE3:QUAT 438 0.328131 59.0552 91.4657 0.408353 -0.344238 0.598359 0.597256 +VERTEX_SE3:QUAT 439 -6.21286 58.4103 91.8715 0.421454 -0.327313 0.632848 0.561022 +VERTEX_SE3:QUAT 440 -12.6767 57.0655 92.1616 0.442633 -0.308178 0.669633 0.510582 +VERTEX_SE3:QUAT 441 -18.9359 54.8923 92.3125 0.455866 -0.28218 0.706273 0.462318 +VERTEX_SE3:QUAT 442 -24.855 51.8613 92.3567 0.470164 -0.261519 0.736978 0.409167 +VERTEX_SE3:QUAT 443 -30.3412 48.0914 92.2571 0.480447 -0.238855 0.761633 0.363365 +VERTEX_SE3:QUAT 444 -35.3497 43.7232 92.0563 0.493674 -0.217096 0.781308 0.314186 +VERTEX_SE3:QUAT 445 -39.8368 38.8087 91.7585 0.504271 -0.200396 0.797362 0.264131 +VERTEX_SE3:QUAT 446 -43.7677 33.42 91.2847 0.517272 -0.174349 0.810603 0.212027 +VERTEX_SE3:QUAT 447 -46.9907 27.5821 90.7307 0.52414 -0.142834 0.823956 0.161159 +VERTEX_SE3:QUAT 448 -49.4943 21.3762 90.1599 0.523752 -0.116001 0.836577 0.111208 +VERTEX_SE3:QUAT 449 -51.279 14.8984 89.5217 0.527378 -0.0889426 0.842688 0.061954 +VERTEX_SE3:QUAT 450 -52.3133 8.28353 88.8463 0.523782 -0.0563574 0.849973 0.00465348 +VERTEX_SE3:QUAT 451 -52.4535 1.58098 88.1456 0.519052 -0.023277 0.852742 -0.0536054 +VERTEX_SE3:QUAT 452 -51.6956 -5.08698 87.3974 0.515099 0.00645699 0.850901 -0.10295 +VERTEX_SE3:QUAT 453 -50.1501 -11.6364 86.6563 0.507855 0.0323505 0.845248 -0.163068 +VERTEX_SE3:QUAT 454 -47.751 -17.9448 85.8151 0.501838 0.0631898 0.835267 -0.215627 +VERTEX_SE3:QUAT 455 -44.5952 -23.9038 84.9824 0.487484 0.0802387 0.827224 -0.267622 +VERTEX_SE3:QUAT 456 -40.7745 -29.4783 84.0358 0.475434 0.107298 0.811027 -0.32355 +VERTEX_SE3:QUAT 457 -36.2517 -34.5141 83.0555 0.45786 0.131162 0.795882 -0.373809 +VERTEX_SE3:QUAT 458 -31.1529 -38.9408 82.0709 0.436539 0.155657 0.777629 -0.42485 +VERTEX_SE3:QUAT 459 -25.5116 -42.7235 81.1199 0.413556 0.184345 0.75627 -0.472275 +VERTEX_SE3:QUAT 460 -19.4194 -45.7724 80.2947 -0.383586 -0.205166 -0.733598 0.522113 +VERTEX_SE3:QUAT 461 -12.9613 -48.0204 79.566 -0.353346 -0.227028 -0.703981 0.572727 +VERTEX_SE3:QUAT 462 -6.20876 -49.3623 78.9493 -0.328108 -0.252128 -0.67306 0.612998 +VERTEX_SE3:QUAT 463 0.65068 -49.8686 78.4849 -0.308398 -0.265222 -0.636399 0.655396 +VERTEX_SE3:QUAT 464 7.56262 -49.5304 77.9994 -0.28186 -0.285673 -0.602403 0.689969 +VERTEX_SE3:QUAT 465 14.3921 -48.39 77.6654 -0.25755 -0.303896 -0.571519 0.717413 +VERTEX_SE3:QUAT 466 21.0987 -46.5672 77.4928 -0.226427 -0.327518 -0.523956 0.75295 +VERTEX_SE3:QUAT 467 27.5074 -43.8201 77.5093 -0.192113 -0.346932 -0.480386 0.782279 +VERTEX_SE3:QUAT 468 33.5098 -40.2858 77.7175 -0.175776 -0.358834 -0.428989 0.81013 +VERTEX_SE3:QUAT 469 39.038 -36.0383 77.8532 -0.151715 -0.375028 -0.375831 0.833719 +VERTEX_SE3:QUAT 470 43.9981 -31.0758 78.0337 -0.118052 -0.379157 -0.322479 0.85925 +VERTEX_SE3:QUAT 471 48.2352 -25.5007 78.308 -0.0803998 -0.391957 -0.268038 0.876391 +VERTEX_SE3:QUAT 472 51.6766 -19.3992 78.7864 -0.0444633 -0.398128 -0.219897 0.889473 +VERTEX_SE3:QUAT 473 54.3681 -12.9466 79.4424 0.00153743 -0.405123 -0.166968 0.898885 +VERTEX_SE3:QUAT 474 56.1264 -6.19758 80.392 0.0277975 -0.407487 -0.118008 0.905127 +VERTEX_SE3:QUAT 475 57.1261 0.7303 81.4109 0.0548088 -0.410668 -0.0710104 0.907362 +VERTEX_SE3:QUAT 476 57.3659 7.73992 82.4979 0.0883239 -0.410024 -0.015048 0.907664 +VERTEX_SE3:QUAT 477 56.6873 14.7054 83.7009 0.118788 -0.409314 0.0348738 0.903955 +VERTEX_SE3:QUAT 478 55.2094 21.5257 84.9941 0.138427 -0.417036 0.0907741 0.893688 +VERTEX_SE3:QUAT 479 52.9045 28.1599 86.1618 0.178365 -0.415795 0.140299 0.880691 +VERTEX_SE3:QUAT 480 49.7597 34.4349 87.5143 0.211659 -0.413803 0.196289 0.863388 +VERTEX_SE3:QUAT 481 45.7887 40.2152 88.9024 0.235814 -0.408649 0.24525 0.846906 +VERTEX_SE3:QUAT 482 41.1641 45.5083 90.2584 0.271736 -0.400757 0.295427 0.823576 +VERTEX_SE3:QUAT 483 35.8513 50.123 91.6807 0.302592 -0.398014 0.342232 0.79555 +VERTEX_SE3:QUAT 484 29.988 54.0445 93.0813 0.325489 -0.396523 0.399513 0.759747 +VERTEX_SE3:QUAT 485 23.6028 57.1329 94.2663 0.353148 -0.383456 0.444497 0.728471 +VERTEX_SE3:QUAT 486 16.8455 59.3869 95.4076 0.383942 -0.369799 0.486122 0.692476 +VERTEX_SE3:QUAT 487 9.83994 60.7319 96.5306 0.40205 -0.361505 0.52937 0.653787 +VERTEX_SE3:QUAT 488 2.69012 61.2414 97.4399 0.413025 -0.346371 0.57483 0.615637 +VERTEX_SE3:QUAT 489 -4.51036 60.8871 98.1111 0.431537 -0.327601 0.614972 0.572942 +VERTEX_SE3:QUAT 490 -11.6566 59.6227 98.657 0.452455 -0.312894 0.653924 0.51939 +VERTEX_SE3:QUAT 491 -18.5761 57.3884 98.9477 0.470014 -0.292637 0.685236 0.473183 +VERTEX_SE3:QUAT 492 -25.1779 54.3107 99.0947 0.474947 -0.280125 0.718767 0.423473 +VERTEX_SE3:QUAT 493 -31.3847 50.5077 98.9349 0.48773 -0.262716 0.742493 0.376568 +VERTEX_SE3:QUAT 494 -37.1733 46.017 98.6379 0.494223 -0.242283 0.769101 0.324847 +VERTEX_SE3:QUAT 495 -42.3609 40.8514 98.1172 0.501877 -0.222503 0.790329 0.272013 +VERTEX_SE3:QUAT 496 -46.899 35.1192 97.3928 0.507592 -0.187807 0.812496 0.216629 +VERTEX_SE3:QUAT 497 -50.5866 28.8158 96.6532 0.506477 -0.161959 0.830482 0.165982 +VERTEX_SE3:QUAT 498 -53.5019 22.1132 95.7618 0.505744 -0.13777 0.844681 0.108429 +VERTEX_SE3:QUAT 499 -55.5484 15.1109 94.7301 0.503718 -0.117615 0.854138 0.0536867 +VERTEX_SE3:QUAT 500 -56.7736 7.90658 93.5416 0.501906 -0.100213 0.859065 -0.00735365 +VERTEX_SE3:QUAT 501 -57.0821 0.658147 92.0954 0.491161 -0.0781 0.865325 -0.0622468 +VERTEX_SE3:QUAT 502 -56.4853 -6.56617 90.5343 0.486376 -0.0508539 0.864134 -0.118844 +VERTEX_SE3:QUAT 503 -54.9808 -13.6495 88.9305 0.476424 -0.0207901 0.861342 -0.17515 +VERTEX_SE3:QUAT 504 -52.5406 -20.5071 87.3394 0.462488 0.00339109 0.853408 -0.240392 +VERTEX_SE3:QUAT 505 -49.1495 -26.9295 85.6537 0.45306 0.0299391 0.839834 -0.297521 +VERTEX_SE3:QUAT 506 -44.9226 -32.8384 83.957 0.441279 0.0559021 0.826539 -0.344937 +VERTEX_SE3:QUAT 507 -40.0317 -38.2422 82.3132 0.430834 0.0779987 0.805236 -0.399867 +VERTEX_SE3:QUAT 508 -34.4584 -42.9636 80.6183 0.41239 0.106761 0.785329 -0.449216 +VERTEX_SE3:QUAT 509 -28.2989 -46.957 79.0428 -0.394205 -0.131366 -0.759635 0.5003 +VERTEX_SE3:QUAT 510 -21.642 -50.1097 77.5475 -0.372007 -0.150315 -0.729923 0.553379 +VERTEX_SE3:QUAT 511 -14.5979 -52.3237 76.0646 -0.353725 -0.165903 -0.702294 0.595095 +VERTEX_SE3:QUAT 512 -7.3342 -53.7563 74.6184 -0.329223 -0.185495 -0.665993 0.643162 +VERTEX_SE3:QUAT 513 0.0682 -54.1509 73.2648 -0.301601 -0.208042 -0.626101 0.688297 +VERTEX_SE3:QUAT 514 7.51158 -53.5243 72.0927 -0.276181 -0.216013 -0.590618 0.726796 +VERTEX_SE3:QUAT 515 14.8546 -52.0091 71.0056 -0.24094 -0.232421 -0.554056 0.762201 +VERTEX_SE3:QUAT 516 21.9974 -49.5733 70.1842 -0.205615 -0.254492 -0.508691 0.796361 +VERTEX_SE3:QUAT 517 28.7861 -46.1958 69.6987 -0.176802 -0.271108 -0.466537 0.823155 +VERTEX_SE3:QUAT 518 35.1716 -42.0353 69.4351 -0.14807 -0.292804 -0.412543 0.849794 +VERTEX_SE3:QUAT 519 40.9279 -37.0299 69.3778 -0.121704 -0.304857 -0.362753 0.872159 +VERTEX_SE3:QUAT 520 46.0485 -31.3598 69.4748 -0.0917832 -0.316465 -0.318506 0.888808 +VERTEX_SE3:QUAT 521 50.5059 -25.1514 69.7933 -0.0620753 -0.325334 -0.263271 0.906086 +VERTEX_SE3:QUAT 522 54.1358 -18.4286 70.2517 -0.0314818 -0.331933 -0.212801 0.918447 +VERTEX_SE3:QUAT 523 56.936 -11.3042 70.8979 0.00596185 -0.333219 -0.162228 0.928769 +VERTEX_SE3:QUAT 524 58.8386 -3.91139 71.8366 0.0490017 -0.334385 -0.106532 0.935113 +VERTEX_SE3:QUAT 525 59.7513 3.62412 73.0971 0.0825427 -0.341656 -0.0494168 0.934888 +VERTEX_SE3:QUAT 526 59.6367 11.1995 74.5511 0.117712 -0.351723 0.00627861 0.928653 +VERTEX_SE3:QUAT 527 58.5229 18.6686 76.1808 0.144468 -0.356814 0.05129 0.921511 +VERTEX_SE3:QUAT 528 56.6257 25.9477 77.9243 0.173271 -0.367288 0.104245 0.90786 +VERTEX_SE3:QUAT 529 53.7899 32.9276 79.7113 0.211692 -0.365195 0.148794 0.894248 +VERTEX_SE3:QUAT 530 50.1759 39.4907 81.7549 0.251337 -0.370324 0.203952 0.870685 +VERTEX_SE3:QUAT 531 45.6346 45.4212 83.9118 0.286951 -0.358007 0.251591 0.852169 +VERTEX_SE3:QUAT 532 40.3817 50.6882 86.2266 0.31096 -0.355226 0.304486 0.827289 +VERTEX_SE3:QUAT 533 34.4523 55.2493 88.4765 0.328158 -0.354197 0.348721 0.803275 +VERTEX_SE3:QUAT 534 28.0085 59.1702 90.5413 0.360146 -0.350586 0.389856 0.771619 +VERTEX_SE3:QUAT 535 21.1206 62.2591 92.6162 0.372899 -0.347671 0.432124 0.743868 +VERTEX_SE3:QUAT 536 13.8751 64.6404 94.4738 0.392481 -0.334157 0.479638 0.710102 +VERTEX_SE3:QUAT 537 6.34323 66.0936 96.1713 0.418613 -0.321293 0.516391 0.674443 +VERTEX_SE3:QUAT 538 -1.32329 66.627 97.8502 0.436832 -0.320274 0.556964 0.629598 +VERTEX_SE3:QUAT 539 -9.06322 66.2473 99.2 0.456304 -0.305468 0.596738 0.585132 +VERTEX_SE3:QUAT 540 -16.7543 64.8768 100.361 0.474315 -0.294363 0.632212 0.537293 +VERTEX_SE3:QUAT 541 -24.2563 62.554 101.251 0.492584 -0.285585 0.664605 0.483841 +VERTEX_SE3:QUAT 542 -31.4565 59.2924 101.806 0.501878 -0.279061 0.700295 0.424064 +VERTEX_SE3:QUAT 543 -38.225 55.1426 101.862 0.51172 -0.273057 0.721579 0.378028 +VERTEX_SE3:QUAT 544 -44.5534 50.3784 101.573 0.520133 -0.256666 0.747009 0.324902 +VERTEX_SE3:QUAT 545 -50.2706 44.9016 101.015 0.52162 -0.248089 0.771852 0.265724 +VERTEX_SE3:QUAT 546 -55.3164 38.8131 99.9612 0.522044 -0.242153 0.789852 0.212051 +VERTEX_SE3:QUAT 547 -59.6878 32.3096 98.4979 0.529832 -0.228433 0.801581 0.156726 +VERTEX_SE3:QUAT 548 -63.2945 25.4143 96.7173 0.524546 -0.216609 0.817572 0.0975101 +VERTEX_SE3:QUAT 549 -66.0486 18.2091 94.5024 0.519456 -0.202055 0.829536 0.0347664 +VERTEX_SE3:QUAT 550 -67.8329 10.814 91.9434 0.513549 -0.178013 0.839162 -0.0196308 +VERTEX_SE3:QUAT 551 -68.6784 3.29745 89.2386 0.504137 -0.157739 0.845209 -0.0811538 +VERTEX_SE3:QUAT 552 -68.4679 -4.1932 86.2911 0.489834 -0.141704 0.848707 -0.140282 +VERTEX_SE3:QUAT 553 -67.2884 -11.5006 83.1218 0.468273 -0.116932 0.852599 -0.200306 +VERTEX_SE3:QUAT 554 -65.0568 -18.5293 79.907 0.458734 -0.0955603 0.844286 -0.260023 +VERTEX_SE3:QUAT 555 -61.8586 -25.164 76.5917 0.43771 -0.0789365 0.836065 -0.321208 +VERTEX_SE3:QUAT 556 -57.7416 -31.2214 73.1912 0.415387 -0.060366 0.821417 -0.386114 +VERTEX_SE3:QUAT 557 -52.7263 -36.5495 69.7408 0.398816 -0.0343903 0.803809 -0.440062 +VERTEX_SE3:QUAT 558 -46.94 -41.1677 66.4194 0.370892 -0.00818728 0.79114 -0.486282 +VERTEX_SE3:QUAT 559 -40.5042 -45.0824 63.3773 -0.345881 -0.0174038 -0.773428 0.530917 +VERTEX_SE3:QUAT 560 -33.5416 -48.2473 60.6373 -0.317488 -0.0435854 -0.750956 0.577379 +VERTEX_SE3:QUAT 561 -26.1169 -50.5204 58.2155 -0.296054 -0.0691862 -0.719624 0.624265 +VERTEX_SE3:QUAT 562 -18.3389 -51.8086 56.0573 -0.270273 -0.0846443 -0.68856 0.667588 +VERTEX_SE3:QUAT 563 -10.4215 -52.1536 54.114 -0.243534 -0.104852 -0.652705 0.7097 +VERTEX_SE3:QUAT 564 -2.43452 -51.491 52.4759 -0.2107 -0.130609 -0.628704 0.737073 +VERTEX_SE3:QUAT 565 5.54374 -50.0963 51.36 -0.186195 -0.150328 -0.587994 0.772655 +VERTEX_SE3:QUAT 566 13.3617 -47.7209 50.5377 -0.150173 -0.173859 -0.546234 0.805512 +VERTEX_SE3:QUAT 567 20.861 -44.4007 50.1899 -0.120447 -0.18809 -0.510219 0.830536 +VERTEX_SE3:QUAT 568 28.0004 -40.3276 50.2242 -0.0957148 -0.199506 -0.462212 0.858717 +VERTEX_SE3:QUAT 569 34.6179 -35.4204 50.4891 -0.0537834 -0.222795 -0.427957 0.874256 +VERTEX_SE3:QUAT 570 40.7117 -29.9393 51.3759 -0.0248008 -0.237342 -0.377108 0.894898 +VERTEX_SE3:QUAT 571 46.0819 -23.7502 52.5727 0.0092715 -0.256716 -0.325073 0.910131 +VERTEX_SE3:QUAT 572 50.5834 -16.9838 54.1744 0.0437396 -0.273147 -0.276834 0.920239 +VERTEX_SE3:QUAT 573 54.2358 -9.79882 56.1341 0.0708784 -0.289056 -0.227013 0.927301 +VERTEX_SE3:QUAT 574 56.9878 -2.27908 58.3542 0.111797 -0.303972 -0.174875 0.929796 +VERTEX_SE3:QUAT 575 58.7089 5.42392 60.9972 0.138694 -0.316853 -0.119058 0.930695 +VERTEX_SE3:QUAT 576 59.3925 13.2347 63.794 0.170343 -0.321096 -0.071352 0.928865 +VERTEX_SE3:QUAT 577 59.155 21.0145 66.8094 0.198852 -0.326092 -0.0180707 0.92401 +VERTEX_SE3:QUAT 578 57.9284 28.6595 69.9435 0.227824 -0.329433 0.0278943 0.915856 +VERTEX_SE3:QUAT 579 55.809 36.0436 73.2404 0.252491 -0.336589 0.076885 0.903905 +VERTEX_SE3:QUAT 580 52.8057 43.1163 76.5911 0.287739 -0.343926 0.132047 0.884016 +VERTEX_SE3:QUAT 581 48.7903 49.6331 80.0182 0.320284 -0.349789 0.192048 0.859176 +VERTEX_SE3:QUAT 582 43.7722 55.4473 83.4103 0.348034 -0.355766 0.244001 0.832326 +VERTEX_SE3:QUAT 583 37.9574 60.546 86.6875 0.375675 -0.358866 0.287283 0.804706 +VERTEX_SE3:QUAT 584 31.4944 64.9065 89.8917 0.39803 -0.359704 0.333954 0.775022 +VERTEX_SE3:QUAT 585 24.4477 68.4613 92.8871 0.418279 -0.357723 0.384718 0.740992 +VERTEX_SE3:QUAT 586 16.9031 71.1037 95.5781 0.434103 -0.354185 0.432569 0.706393 +VERTEX_SE3:QUAT 587 8.97075 72.8675 97.9554 0.449842 -0.353579 0.479465 0.665385 +VERTEX_SE3:QUAT 588 0.777982 73.6616 99.9284 0.463395 -0.349318 0.519425 0.627248 +VERTEX_SE3:QUAT 589 -7.54862 73.5499 101.53 0.482125 -0.34115 0.555887 0.584946 +VERTEX_SE3:QUAT 590 -15.8806 72.4902 102.848 0.496511 -0.326545 0.589175 0.547466 +VERTEX_SE3:QUAT 591 -24.0961 70.5345 103.951 0.508347 -0.321127 0.627223 0.495027 +VERTEX_SE3:QUAT 592 -32.0737 67.59 104.526 0.516247 -0.315306 0.662146 0.442306 +VERTEX_SE3:QUAT 593 -39.6906 63.7624 104.572 0.519976 -0.305528 0.6968 0.388262 +VERTEX_SE3:QUAT 594 -46.8051 59.0998 104.11 0.526963 -0.296336 0.726049 0.32764 +VERTEX_SE3:QUAT 595 -53.2811 53.6361 103.097 0.531951 -0.279514 0.752487 0.269562 +VERTEX_SE3:QUAT 596 -59.0278 47.4542 101.679 0.533434 -0.273328 0.770694 0.216266 +VERTEX_SE3:QUAT 597 -64.0604 40.7789 99.7787 0.535802 -0.257854 0.788723 0.156023 +VERTEX_SE3:QUAT 598 -68.2073 33.6154 97.4552 0.52836 -0.245715 0.8064 0.100897 +VERTEX_SE3:QUAT 599 -71.4596 26.1645 94.7195 0.51763 -0.233311 0.822075 0.0426378 +VERTEX_SE3:QUAT 600 -73.7588 18.4711 91.5799 0.504593 -0.213978 0.836273 -0.0157172 +VERTEX_SE3:QUAT 601 -74.954 10.6559 88.1672 0.491852 -0.204707 0.842601 -0.078743 +VERTEX_SE3:QUAT 602 -75.1419 2.91569 84.3588 0.474814 -0.190957 0.8485 -0.134667 +VERTEX_SE3:QUAT 603 -74.3191 -4.66257 80.3182 0.462769 -0.179399 0.84738 -0.188699 +VERTEX_SE3:QUAT 604 -72.5882 -11.9767 76.0473 0.444157 -0.174966 0.8455 -0.239253 +VERTEX_SE3:QUAT 605 -70.041 -18.9257 71.566 0.413666 -0.154559 0.84522 -0.300988 +VERTEX_SE3:QUAT 606 -66.3509 -25.3635 67.0845 0.391518 -0.137529 0.838242 -0.353765 +VERTEX_SE3:QUAT 607 -61.7587 -31.2744 62.6591 0.367389 -0.114887 0.829177 -0.405329 +VERTEX_SE3:QUAT 608 -56.306 -36.5678 58.4158 0.352956 -0.0981372 0.812046 -0.454282 +VERTEX_SE3:QUAT 609 -50.2006 -41.1558 54.2485 -0.328127 0.0816245 -0.792885 0.506955 +VERTEX_SE3:QUAT 610 -43.4004 -44.8722 50.2758 -0.299533 0.0566481 -0.773099 0.556228 +VERTEX_SE3:QUAT 611 -35.9648 -47.7182 46.6614 -0.270591 0.0365161 -0.750949 0.601268 +VERTEX_SE3:QUAT 612 -28.0937 -49.7067 43.4361 -0.240436 0.0183579 -0.72767 0.642144 +VERTEX_SE3:QUAT 613 -19.8705 -50.8046 40.6073 -0.204355 -0.000379522 -0.70305 0.681146 +VERTEX_SE3:QUAT 614 -11.4081 -50.9862 38.3144 -0.175161 -0.0237582 -0.680668 0.710946 +VERTEX_SE3:QUAT 615 -2.81946 -50.4394 36.5601 -0.149568 -0.0492897 -0.651746 0.741908 +VERTEX_SE3:QUAT 616 5.77276 -49.0581 35.3365 -0.10182 -0.0696159 -0.621679 0.773499 +VERTEX_SE3:QUAT 617 14.2687 -46.8166 34.8785 -0.0759295 -0.0884423 -0.583986 0.803351 +VERTEX_SE3:QUAT 618 22.5052 -43.7004 34.8993 -0.0376481 -0.108351 -0.543882 0.831285 +VERTEX_SE3:QUAT 619 30.3469 -39.7323 35.5735 -0.0100594 -0.134248 -0.498802 0.856197 +VERTEX_SE3:QUAT 620 37.6615 -34.9251 36.7808 0.0252179 -0.15518 -0.450344 0.878905 +VERTEX_SE3:QUAT 621 44.2825 -29.3646 38.5694 0.0595459 -0.169882 -0.410885 0.893738 +VERTEX_SE3:QUAT 622 50.2741 -23.2836 40.9006 0.093217 -0.202196 -0.366928 0.903211 +VERTEX_SE3:QUAT 623 55.4275 -16.7303 43.8351 0.125797 -0.21827 -0.31185 0.916124 +VERTEX_SE3:QUAT 624 59.5973 -9.63609 47.1949 0.161525 -0.237878 -0.264278 0.920587 +VERTEX_SE3:QUAT 625 62.7852 -2.30057 51.0212 0.18868 -0.26589 -0.213335 0.920973 +VERTEX_SE3:QUAT 626 64.9369 5.26088 55.1546 0.229283 -0.278862 -0.159958 0.918738 +VERTEX_SE3:QUAT 627 65.9486 12.8637 59.735 0.263362 -0.290196 -0.106476 0.913832 +VERTEX_SE3:QUAT 628 65.8405 20.3301 64.5749 0.292487 -0.303644 -0.0488266 0.905465 +VERTEX_SE3:QUAT 629 64.5522 27.6523 69.5631 0.32314 -0.326166 0.0111602 0.888297 +VERTEX_SE3:QUAT 630 62.0143 34.6371 74.5457 0.349391 -0.344705 0.0734858 0.868161 +VERTEX_SE3:QUAT 631 58.2555 41.1594 79.3766 0.365185 -0.354114 0.130161 0.851059 +VERTEX_SE3:QUAT 632 53.5337 47.2466 83.9638 0.387582 -0.364659 0.192155 0.824549 +VERTEX_SE3:QUAT 633 47.7642 52.6389 88.249 0.405471 -0.359473 0.24254 0.804703 +VERTEX_SE3:QUAT 634 41.2939 57.337 92.3394 0.411695 -0.365013 0.291963 0.782324 +VERTEX_SE3:QUAT 635 34.1674 61.4642 95.971 0.427802 -0.366119 0.346504 0.750251 +VERTEX_SE3:QUAT 636 26.4106 64.6908 99.2263 0.446333 -0.366678 0.40061 0.711228 +VERTEX_SE3:QUAT 637 18.1026 66.8883 102.032 0.455082 -0.372658 0.449504 0.672289 +VERTEX_SE3:QUAT 638 9.45567 68.1736 104.244 0.46091 -0.381348 0.501669 0.624871 +VERTEX_SE3:QUAT 639 0.532749 68.4497 105.676 0.466413 -0.382594 0.545604 0.581718 +VERTEX_SE3:QUAT 640 -8.46323 67.7894 106.482 0.478242 -0.379521 0.584313 0.534628 +VERTEX_SE3:QUAT 641 -17.3665 66.1474 106.779 0.479256 -0.36745 0.630484 0.487631 +VERTEX_SE3:QUAT 642 -26.0361 63.4812 106.49 0.468518 -0.364658 0.671581 0.443277 +VERTEX_SE3:QUAT 643 -34.3888 60.0488 105.499 0.477364 -0.352643 0.704944 0.388355 +VERTEX_SE3:QUAT 644 -42.2267 55.6445 104.029 0.473872 -0.336674 0.742425 0.33302 +VERTEX_SE3:QUAT 645 -49.3432 50.3452 102.045 0.476027 -0.321982 0.770182 0.276668 +VERTEX_SE3:QUAT 646 -55.7015 44.2644 99.64 0.46893 -0.305899 0.801266 0.210958 +VERTEX_SE3:QUAT 647 -61.0337 37.4666 96.712 0.467123 -0.295022 0.81929 0.15337 +VERTEX_SE3:QUAT 648 -65.4492 30.2184 93.3693 0.460082 -0.279541 0.838488 0.0843731 +VERTEX_SE3:QUAT 649 -68.6637 22.5667 89.5715 0.4479 -0.266003 0.853 0.0319114 +VERTEX_SE3:QUAT 650 -70.888 14.6833 85.4745 0.441589 -0.250289 0.860982 -0.0326254 +VERTEX_SE3:QUAT 651 -71.9482 6.69996 81.0861 0.427118 -0.23499 0.868386 -0.0908581 +VERTEX_SE3:QUAT 652 -71.8639 -1.22578 76.471 0.41223 -0.21126 0.873144 -0.151837 +VERTEX_SE3:QUAT 653 -70.5476 -9.05412 71.7947 0.397453 -0.187641 0.873889 -0.207704 +VERTEX_SE3:QUAT 654 -68.1117 -16.619 67.1735 0.382576 -0.168034 0.869815 -0.26234 +VERTEX_SE3:QUAT 655 -64.6525 -23.8257 62.5637 0.369683 -0.139041 0.864284 -0.311471 +VERTEX_SE3:QUAT 656 -60.2297 -30.6307 58.1708 0.346468 -0.117162 0.857398 -0.36208 +VERTEX_SE3:QUAT 657 -54.8592 -36.8897 53.9684 0.326215 -0.104269 0.846117 -0.40841 +VERTEX_SE3:QUAT 658 -48.7434 -42.4692 49.8751 0.300839 -0.0847964 0.82915 -0.463482 +VERTEX_SE3:QUAT 659 -41.8058 -47.2182 46.0097 -0.270748 0.062365 -0.810098 0.516282 +VERTEX_SE3:QUAT 660 -34.108 -51.0382 42.5585 -0.240826 0.0416702 -0.789539 0.562935 +VERTEX_SE3:QUAT 661 -25.8371 -53.9472 39.5176 -0.214723 0.018485 -0.764319 0.607758 +VERTEX_SE3:QUAT 662 -17.1465 -55.8991 36.9521 -0.189113 0.00215334 -0.736039 0.649983 +VERTEX_SE3:QUAT 663 -8.13814 -56.86 34.7789 -0.164718 -0.0151079 -0.698749 0.695981 +VERTEX_SE3:QUAT 664 0.977285 -56.662 32.967 -0.131056 -0.0431189 -0.666316 0.732795 +VERTEX_SE3:QUAT 665 10.1547 -55.4615 31.8584 -0.10313 -0.0603753 -0.628531 0.768549 +VERTEX_SE3:QUAT 666 19.2125 -53.2111 31.259 -0.0762981 -0.0866908 -0.592227 0.797453 +VERTEX_SE3:QUAT 667 28.0025 -50.0792 31.2169 -0.0455703 -0.103203 -0.54896 0.8282 +VERTEX_SE3:QUAT 668 36.3914 -45.9477 31.7333 -0.0161299 -0.124615 -0.509456 0.851273 +VERTEX_SE3:QUAT 669 44.2823 -41.036 32.8124 0.0188357 -0.145871 -0.464881 0.87307 +VERTEX_SE3:QUAT 670 51.5159 -35.3353 34.5435 0.0536333 -0.15414 -0.409196 0.897732 +VERTEX_SE3:QUAT 671 57.8786 -28.8067 36.7784 0.09237 -0.174705 -0.364028 0.910181 +VERTEX_SE3:QUAT 672 63.3795 -21.7707 39.6877 0.127763 -0.190891 -0.31246 0.921741 +VERTEX_SE3:QUAT 673 67.8898 -14.2725 43.1503 0.158687 -0.210444 -0.262256 0.928307 +VERTEX_SE3:QUAT 674 71.3714 -6.43713 47.0488 0.186119 -0.219344 -0.213871 0.933545 +VERTEX_SE3:QUAT 675 73.8713 1.5993 51.2696 0.210135 -0.236572 -0.172113 0.932874 +VERTEX_SE3:QUAT 676 75.4506 9.74661 55.7721 0.233847 -0.251151 -0.129114 0.930359 +VERTEX_SE3:QUAT 677 76.0912 17.8945 60.5048 0.249951 -0.266833 -0.0709119 0.92806 +VERTEX_SE3:QUAT 678 75.5638 26.0877 65.2261 0.273626 -0.278939 -0.0158263 0.920365 +VERTEX_SE3:QUAT 679 73.8846 34.064 70.0307 0.29587 -0.291014 0.0361569 0.909101 +VERTEX_SE3:QUAT 680 71.1477 41.7426 74.8385 0.319365 -0.303168 0.0926816 0.893031 +VERTEX_SE3:QUAT 681 67.2422 48.9703 79.6088 0.343993 -0.30249 0.151787 0.875859 +VERTEX_SE3:QUAT 682 62.275 55.5669 84.3301 0.359277 -0.316857 0.21063 0.852149 +VERTEX_SE3:QUAT 683 56.2788 61.5096 88.7047 0.384569 -0.326074 0.271798 0.8197 +VERTEX_SE3:QUAT 684 49.2793 66.5161 92.8177 0.398697 -0.339571 0.322202 0.788618 +VERTEX_SE3:QUAT 685 41.5325 70.715 96.4711 0.40817 -0.351872 0.374128 0.754726 +VERTEX_SE3:QUAT 686 33.1522 74.0328 99.5651 0.413025 -0.35662 0.424144 0.722728 +VERTEX_SE3:QUAT 687 24.2675 76.495 102.1 0.432664 -0.359914 0.481307 0.672017 +VERTEX_SE3:QUAT 688 14.9858 77.6334 104.032 0.435197 -0.363675 0.52314 0.636136 +VERTEX_SE3:QUAT 689 5.49802 77.9347 105.364 0.439082 -0.370834 0.569968 0.587218 +VERTEX_SE3:QUAT 690 -4.04103 77.1776 105.918 0.431777 -0.364394 0.619654 0.544806 +VERTEX_SE3:QUAT 691 -13.4741 75.4221 105.776 0.435363 -0.361139 0.654214 0.502037 +VERTEX_SE3:QUAT 692 -22.6659 72.7804 105.112 0.438251 -0.349967 0.68905 0.458988 +VERTEX_SE3:QUAT 693 -31.5046 69.183 104.033 0.44076 -0.327269 0.725284 0.415439 +VERTEX_SE3:QUAT 694 -39.8506 64.581 102.677 0.437152 -0.325979 0.755549 0.363018 +VERTEX_SE3:QUAT 695 -47.5743 59.2021 100.66 0.430057 -0.321014 0.78549 0.30823 +VERTEX_SE3:QUAT 696 -54.5696 53.0748 98.0651 0.434251 -0.307719 0.809037 0.249388 +VERTEX_SE3:QUAT 697 -60.6562 46.1978 95.0542 0.428383 -0.295193 0.832271 0.191504 +VERTEX_SE3:QUAT 698 -65.7584 38.7401 91.6346 0.42012 -0.282452 0.851231 0.138297 +VERTEX_SE3:QUAT 699 -69.8679 30.8124 87.8601 0.416674 -0.265834 0.865294 0.0835546 +VERTEX_SE3:QUAT 700 -72.9455 22.5353 83.853 0.408289 -0.24569 0.879014 0.0164758 +VERTEX_SE3:QUAT 701 -74.6493 14.013 79.5963 0.394306 -0.234366 0.88748 -0.0444476 +VERTEX_SE3:QUAT 702 -75.1615 5.44434 75.0291 0.382126 -0.214013 0.893783 -0.0965981 +VERTEX_SE3:QUAT 703 -74.5601 -3.12183 70.4586 0.363277 -0.199554 0.896151 -0.158495 +VERTEX_SE3:QUAT 704 -72.6984 -11.4281 65.7572 0.341856 -0.179144 0.897868 -0.211838 +VERTEX_SE3:QUAT 705 -69.7001 -19.4526 61.14 0.319791 -0.166831 0.895931 -0.259245 +VERTEX_SE3:QUAT 706 -65.7446 -27.1086 56.5782 0.293648 -0.145029 0.892259 -0.310824 +VERTEX_SE3:QUAT 707 -60.7058 -34.2759 52.2702 0.269861 -0.130728 0.882115 -0.363262 +VERTEX_SE3:QUAT 708 -54.7017 -40.7894 48.1322 0.2458 -0.110838 0.868524 -0.415888 +VERTEX_SE3:QUAT 709 -47.7878 -46.5587 44.3182 0.228825 -0.0962365 0.852389 -0.460229 +VERTEX_SE3:QUAT 710 -40.2023 -51.5967 40.7427 -0.210216 0.0742232 -0.829674 0.511801 +VERTEX_SE3:QUAT 711 -31.9043 -55.6989 37.5262 -0.195064 0.0550077 -0.803233 0.560126 +VERTEX_SE3:QUAT 712 -23.0701 -58.8341 34.6392 -0.168231 0.0273779 -0.77722 0.605705 +VERTEX_SE3:QUAT 713 -13.7434 -60.9396 32.3591 -0.145082 0.00400181 -0.752677 0.642194 +VERTEX_SE3:QUAT 714 -4.15765 -62.151 30.6196 -0.106415 -0.0195039 -0.718527 0.687033 +VERTEX_SE3:QUAT 715 5.6408 -62.1768 29.6294 -0.0680929 -0.0471284 -0.678417 0.729995 +VERTEX_SE3:QUAT 716 15.401 -60.968 29.4511 -0.0467369 -0.0687885 -0.641901 0.762264 +VERTEX_SE3:QUAT 717 24.9808 -58.766 29.8005 -0.0173286 -0.090254 -0.601397 0.793647 +VERTEX_SE3:QUAT 718 34.2359 -55.5397 30.7698 0.0115301 -0.1068 -0.561623 0.82039 +VERTEX_SE3:QUAT 719 43.0735 -51.4234 32.3237 0.0326959 -0.131819 -0.515781 0.845887 +VERTEX_SE3:QUAT 720 51.3079 -46.3874 34.3731 0.0628082 -0.147036 -0.478663 0.863318 +VERTEX_SE3:QUAT 721 58.9638 -40.692 36.9887 0.0928717 -0.172057 -0.42317 0.884703 +VERTEX_SE3:QUAT 722 65.6597 -34.1197 40.17 0.117954 -0.201462 -0.370578 0.898984 +VERTEX_SE3:QUAT 723 71.3568 -26.8995 43.831 0.155014 -0.220758 -0.317428 0.909107 +VERTEX_SE3:QUAT 724 75.9154 -19.2088 48.0863 0.17216 -0.242853 -0.262513 0.917862 +VERTEX_SE3:QUAT 725 79.3658 -11.0106 52.512 0.202286 -0.256413 -0.211511 0.921192 +VERTEX_SE3:QUAT 726 81.6816 -2.61408 57.2933 0.232448 -0.266382 -0.159964 0.92164 +VERTEX_SE3:QUAT 727 82.835 5.85852 62.381 0.250261 -0.282519 -0.109833 0.919505 +VERTEX_SE3:QUAT 728 82.8856 14.3852 67.5391 0.272682 -0.298258 -0.0530383 0.913167 +VERTEX_SE3:QUAT 729 81.6943 22.8073 72.7121 0.291737 -0.310985 0.00177763 0.90453 +VERTEX_SE3:QUAT 730 79.3021 31.0259 77.8311 0.306988 -0.319809 0.0563308 0.894599 +VERTEX_SE3:QUAT 731 75.801 38.9286 82.8072 0.321121 -0.33126 0.11173 0.88015 +VERTEX_SE3:QUAT 732 71.2016 46.4334 87.5269 0.342798 -0.346958 0.168658 0.856542 +VERTEX_SE3:QUAT 733 65.4723 53.3141 91.9928 0.358936 -0.364408 0.230451 0.827807 +VERTEX_SE3:QUAT 734 58.6218 59.415 95.9926 0.367387 -0.368108 0.283387 0.805739 +VERTEX_SE3:QUAT 735 50.9527 64.8159 99.5518 0.382803 -0.376758 0.331827 0.775503 +VERTEX_SE3:QUAT 736 42.5816 69.3641 102.673 0.396022 -0.380121 0.383593 0.742652 +VERTEX_SE3:QUAT 737 33.5826 72.9262 105.316 0.404031 -0.382941 0.431725 0.709739 +VERTEX_SE3:QUAT 738 24.1026 75.5535 107.404 0.409157 -0.384919 0.488059 0.668002 +VERTEX_SE3:QUAT 739 14.2426 77.0342 108.744 0.413014 -0.383327 0.541216 0.624151 +VERTEX_SE3:QUAT 740 4.18587 77.3488 109.383 0.420457 -0.387548 0.58249 0.577692 +VERTEX_SE3:QUAT 741 -5.85662 76.6225 109.336 0.420331 -0.388176 0.62762 0.527953 +VERTEX_SE3:QUAT 742 -15.7302 74.8031 108.52 0.41763 -0.38492 0.671481 0.475956 +VERTEX_SE3:QUAT 743 -25.2593 71.8888 106.93 0.417383 -0.373976 0.708125 0.429525 +VERTEX_SE3:QUAT 744 -34.3441 67.978 104.841 0.41402 -0.369114 0.742853 0.37485 +VERTEX_SE3:QUAT 745 -42.7836 63.1332 102.073 0.404713 -0.364883 0.776666 0.316004 +VERTEX_SE3:QUAT 746 -50.3923 57.4154 98.5775 0.395626 -0.356456 0.807242 0.254517 +VERTEX_SE3:QUAT 747 -57.003 50.9126 94.4866 0.387335 -0.336896 0.835551 0.195776 +VERTEX_SE3:QUAT 748 -62.5065 43.6398 90.0281 0.376139 -0.324988 0.856697 0.137742 +VERTEX_SE3:QUAT 749 -66.8879 35.8771 85.1731 0.361747 -0.310989 0.875058 0.0818451 +VERTEX_SE3:QUAT 750 -70.1044 27.7026 80.0288 0.34457 -0.291371 0.89221 0.0183189 +VERTEX_SE3:QUAT 751 -71.9236 19.2313 74.6979 0.329432 -0.277252 0.901822 -0.0363749 +VERTEX_SE3:QUAT 752 -72.567 10.6793 69.2272 0.320174 -0.249386 0.909133 -0.0936652 +VERTEX_SE3:QUAT 753 -71.9015 2.03235 63.8792 0.301228 -0.229567 0.912761 -0.15306 +VERTEX_SE3:QUAT 754 -69.9265 -6.43676 58.6096 0.28227 -0.211419 0.909968 -0.218139 +VERTEX_SE3:QUAT 755 -66.5485 -14.554 53.3919 0.253363 -0.195476 0.906104 -0.276717 +VERTEX_SE3:QUAT 756 -61.9231 -22.1531 48.3453 0.230144 -0.173289 0.895417 -0.339459 +VERTEX_SE3:QUAT 757 -56.0456 -29.0814 43.6338 0.204898 -0.158218 0.884054 -0.389143 +VERTEX_SE3:QUAT 758 -49.2521 -35.3228 39.2356 0.187854 -0.138351 0.865615 -0.443036 +VERTEX_SE3:QUAT 759 -41.54 -40.7459 35.1902 0.155164 -0.112812 0.846673 -0.49633 +VERTEX_SE3:QUAT 760 -32.9726 -45.2209 31.8045 -0.123287 0.0886485 -0.820211 0.55154 +VERTEX_SE3:QUAT 761 -23.6744 -48.5756 29.1002 -0.0896458 0.0670726 -0.795555 0.595447 +VERTEX_SE3:QUAT 762 -13.8695 -50.9388 27.1152 -0.0692506 0.0430337 -0.764747 0.639151 +VERTEX_SE3:QUAT 763 -3.76613 -52.2545 25.7441 -0.0444516 0.0216441 -0.73007 0.681582 +VERTEX_SE3:QUAT 764 6.52149 -52.4416 25.0243 -0.0174229 -0.00133976 -0.693405 0.720336 +VERTEX_SE3:QUAT 765 16.777 -51.5079 25.0131 0.011741 -0.021192 -0.657459 0.753101 +VERTEX_SE3:QUAT 766 26.8816 -49.5787 25.7184 0.0403709 -0.0440939 -0.60798 0.791698 +VERTEX_SE3:QUAT 767 36.588 -46.4129 27.1622 0.0603282 -0.0675589 -0.57405 0.813795 +VERTEX_SE3:QUAT 768 45.9284 -42.4771 29.2063 0.0864875 -0.0968728 -0.530733 0.837531 +VERTEX_SE3:QUAT 769 54.651 -37.6629 31.9832 0.105488 -0.118088 -0.478566 0.863656 +VERTEX_SE3:QUAT 770 62.6074 -31.87 35.1998 0.123018 -0.139418 -0.428341 0.884281 +VERTEX_SE3:QUAT 771 69.6733 -25.2346 38.8583 0.140056 -0.165268 -0.367277 0.904532 +VERTEX_SE3:QUAT 772 75.5959 -17.7491 42.8493 0.167506 -0.183832 -0.313999 0.916271 +VERTEX_SE3:QUAT 773 80.4153 -9.70899 47.3226 0.184656 -0.197622 -0.259431 0.927116 +VERTEX_SE3:QUAT 774 84.1054 -1.20487 52.0075 0.20875 -0.212637 -0.194961 0.934451 +VERTEX_SE3:QUAT 775 86.4011 7.66157 56.9408 0.234556 -0.237185 -0.13736 0.932662 +VERTEX_SE3:QUAT 776 87.3275 16.6363 62.1361 0.259466 -0.255063 -0.0810152 0.927931 +VERTEX_SE3:QUAT 777 86.9279 25.5331 67.5102 0.285197 -0.267523 -0.0253226 0.920029 +VERTEX_SE3:QUAT 778 85.2505 34.2027 73.0298 0.298073 -0.281161 0.0355546 0.911502 +VERTEX_SE3:QUAT 779 82.2619 42.6708 78.3362 0.313371 -0.296951 0.10327 0.896077 +VERTEX_SE3:QUAT 780 77.8548 50.6921 83.3731 0.332184 -0.310816 0.16213 0.875649 +VERTEX_SE3:QUAT 781 72.2377 58.0693 88.1677 0.341863 -0.324422 0.213836 0.85566 +VERTEX_SE3:QUAT 782 65.628 64.8618 92.5615 0.350858 -0.330125 0.259072 0.837137 +VERTEX_SE3:QUAT 783 58.2474 71.0422 96.6414 0.374362 -0.335596 0.317209 0.804119 +VERTEX_SE3:QUAT 784 49.9061 76.1317 100.39 0.380969 -0.345808 0.371533 0.772814 +VERTEX_SE3:QUAT 785 40.7975 80.3034 103.523 0.382981 -0.352524 0.423285 0.741541 +VERTEX_SE3:QUAT 786 31.1388 83.5409 105.997 0.386991 -0.355665 0.481716 0.701206 +VERTEX_SE3:QUAT 787 20.9897 85.5993 107.72 0.398197 -0.356985 0.533079 0.655613 +VERTEX_SE3:QUAT 788 10.5621 86.3577 108.812 0.40507 -0.351613 0.57205 0.62052 +VERTEX_SE3:QUAT 789 0.0655118 86.1029 109.473 0.399717 -0.352795 0.622018 0.573459 +VERTEX_SE3:QUAT 790 -10.3534 84.6658 109.272 0.39902 -0.355803 0.661748 0.525621 +VERTEX_SE3:QUAT 791 -20.5446 82.2018 108.327 0.396545 -0.352723 0.699488 0.478596 +VERTEX_SE3:QUAT 792 -30.3611 78.6905 106.733 0.392884 -0.346365 0.738035 0.425414 +VERTEX_SE3:QUAT 793 -39.6026 74.108 104.494 0.381992 -0.350598 0.771912 0.367853 +VERTEX_SE3:QUAT 794 -48.1047 68.6592 101.403 0.375137 -0.340784 0.800686 0.319437 +VERTEX_SE3:QUAT 795 -55.8154 62.3766 97.8214 0.363491 -0.338321 0.826172 0.266184 +VERTEX_SE3:QUAT 796 -62.6274 55.454 93.6636 0.349606 -0.326133 0.852673 0.210624 +VERTEX_SE3:QUAT 797 -68.3461 47.8365 89.0573 0.344716 -0.311838 0.872372 0.15131 +VERTEX_SE3:QUAT 798 -72.8873 39.6215 84.1464 0.333503 -0.29504 0.89008 0.0973908 +VERTEX_SE3:QUAT 799 -76.2405 30.9678 79.0495 0.317906 -0.287563 0.902488 0.0419301 +VERTEX_SE3:QUAT 800 -78.4007 22.0831 73.6752 0.305408 -0.273099 0.91211 -0.0141132 +VERTEX_SE3:QUAT 801 -79.3018 13.0512 68.1597 0.296158 -0.254901 0.918007 -0.0676737 +VERTEX_SE3:QUAT 802 -78.9981 3.95732 62.62 0.284206 -0.237454 0.92047 -0.124812 +VERTEX_SE3:QUAT 803 -77.4016 -5.00202 57.1253 0.26903 -0.215011 0.920164 -0.186256 +VERTEX_SE3:QUAT 804 -74.4119 -13.719 51.8034 0.24753 -0.202548 0.915752 -0.243107 +VERTEX_SE3:QUAT 805 -70.1754 -21.9523 46.5594 0.229335 -0.192425 0.905776 -0.299914 +VERTEX_SE3:QUAT 806 -64.8154 -29.5901 41.4054 0.210097 -0.1717 0.894021 -0.356518 +VERTEX_SE3:QUAT 807 -58.3224 -36.5219 36.5756 0.191618 -0.157149 0.878817 -0.407758 +VERTEX_SE3:QUAT 808 -50.8894 -42.7117 32.0541 0.167011 -0.141934 0.863078 -0.455036 +VERTEX_SE3:QUAT 809 -42.6291 -48.0551 27.9344 -0.136218 0.119541 -0.837954 0.514769 +VERTEX_SE3:QUAT 810 -33.4515 -52.272 24.431 -0.115584 0.10983 -0.808477 0.566518 +VERTEX_SE3:QUAT 811 -23.6681 -55.3127 21.3253 -0.0893041 0.0879163 -0.783199 0.609011 +VERTEX_SE3:QUAT 812 -13.4484 -57.3601 18.8951 -0.0685929 0.0657205 -0.751268 0.653125 +VERTEX_SE3:QUAT 813 -2.92079 -58.2845 17.0921 -0.0469929 0.0424126 -0.714701 0.696559 +VERTEX_SE3:QUAT 814 7.72875 -57.9877 15.9516 -0.0281885 0.0144845 -0.681686 0.730958 +VERTEX_SE3:QUAT 815 18.3726 -56.6814 15.5262 -0.00523449 -0.00837421 -0.644114 0.764866 +VERTEX_SE3:QUAT 816 28.8323 -54.2822 15.7677 0.0239393 -0.0258272 -0.600419 0.79891 +VERTEX_SE3:QUAT 817 38.9413 -50.7473 16.7127 0.0476157 -0.0487078 -0.555092 0.828996 +VERTEX_SE3:QUAT 818 48.5329 -46.1542 18.3477 0.0615121 -0.0619903 -0.51887 0.850381 +VERTEX_SE3:QUAT 819 57.643 -40.7735 20.3553 0.0915645 -0.084377 -0.468812 0.874478 +VERTEX_SE3:QUAT 820 65.9275 -34.4458 23.1168 0.114414 -0.107926 -0.416669 0.895348 +VERTEX_SE3:QUAT 821 73.2612 -27.2797 26.4502 0.13603 -0.118225 -0.370337 0.911246 +VERTEX_SE3:QUAT 822 79.7031 -19.4778 30.2039 0.157662 -0.136513 -0.321213 0.923758 +VERTEX_SE3:QUAT 823 85.1062 -11.1252 34.4176 0.176774 -0.154768 -0.266566 0.934741 +VERTEX_SE3:QUAT 824 89.3251 -2.28956 38.9519 0.198247 -0.175031 -0.20547 0.942255 +VERTEX_SE3:QUAT 825 92.1629 6.94706 43.7947 0.220278 -0.186915 -0.152318 0.945166 +VERTEX_SE3:QUAT 826 93.7773 16.3636 48.9234 0.236893 -0.203556 -0.0955343 0.945156 +VERTEX_SE3:QUAT 827 94.0762 25.8288 54.1697 0.255826 -0.21486 -0.0398447 0.941701 +VERTEX_SE3:QUAT 828 93.0733 35.1762 59.5267 0.275799 -0.226875 0.0158396 0.933923 +VERTEX_SE3:QUAT 829 90.7789 44.3079 64.9361 0.289713 -0.238787 0.0716642 0.924073 +VERTEX_SE3:QUAT 830 87.2503 53.0892 70.2427 0.311607 -0.245829 0.136215 0.907697 +VERTEX_SE3:QUAT 831 82.3113 61.2459 75.4948 0.325921 -0.260053 0.19606 0.88753 +VERTEX_SE3:QUAT 832 76.1564 68.7026 80.4596 0.324286 -0.271555 0.246705 0.871914 +VERTEX_SE3:QUAT 833 69.0727 75.6587 84.8898 0.332827 -0.286449 0.301791 0.846224 +VERTEX_SE3:QUAT 834 61.0068 81.7849 88.8562 0.337786 -0.282634 0.366809 0.819433 +VERTEX_SE3:QUAT 835 51.9938 86.8354 92.332 0.340327 -0.288871 0.421778 0.789199 +VERTEX_SE3:QUAT 836 42.3132 90.8658 95.2318 0.348429 -0.290777 0.476135 0.753221 +VERTEX_SE3:QUAT 837 32.0553 93.691 97.5995 0.353599 -0.303043 0.523059 0.713822 +VERTEX_SE3:QUAT 838 21.4248 95.4028 99.2837 0.357253 -0.309492 0.570275 0.671842 +VERTEX_SE3:QUAT 839 10.5452 95.9235 100.287 0.365265 -0.312687 0.612853 0.627073 +VERTEX_SE3:QUAT 840 -0.372839 95.2205 100.685 0.37506 -0.303104 0.655263 0.581454 +VERTEX_SE3:QUAT 841 -11.1069 93.1806 100.728 0.373805 -0.308168 0.693413 0.533367 +VERTEX_SE3:QUAT 842 -21.5924 90.0544 100.019 0.366801 -0.316776 0.732124 0.478649 +VERTEX_SE3:QUAT 843 -31.5815 85.8704 98.4257 0.359019 -0.320222 0.767503 0.423677 +VERTEX_SE3:QUAT 844 -40.9248 80.6855 96.0017 0.345802 -0.31404 0.803629 0.368756 +VERTEX_SE3:QUAT 845 -49.4395 74.4877 92.9105 0.341342 -0.306317 0.836823 0.29897 +VERTEX_SE3:QUAT 846 -56.7644 67.2087 89.1852 0.338429 -0.297403 0.858947 0.243367 +VERTEX_SE3:QUAT 847 -63.058 59.212 85.0856 0.330919 -0.28675 0.879966 0.184193 +VERTEX_SE3:QUAT 848 -68.1716 50.5829 80.595 0.326297 -0.273786 0.897105 0.117362 +VERTEX_SE3:QUAT 849 -71.8773 41.4038 75.7975 0.312866 -0.25565 0.912808 0.0594899 +VERTEX_SE3:QUAT 850 -74.2493 31.8611 70.8362 0.298098 -0.238731 0.924176 0.00660284 +VERTEX_SE3:QUAT 851 -75.3351 22.0901 65.8429 0.280037 -0.222616 0.932429 -0.0509729 +VERTEX_SE3:QUAT 852 -75.0362 12.2916 60.8119 0.265947 -0.211109 0.934214 -0.109311 +VERTEX_SE3:QUAT 853 -73.4054 2.64759 55.7233 0.255004 -0.188382 0.934504 -0.161826 +VERTEX_SE3:QUAT 854 -70.5375 -6.82347 50.8504 0.236644 -0.17788 0.925475 -0.236338 +VERTEX_SE3:QUAT 855 -66.0626 -15.6274 45.934 0.220949 -0.162333 0.913148 -0.301646 +VERTEX_SE3:QUAT 856 -60.2205 -23.7238 41.175 0.205382 -0.144062 0.897084 -0.363737 +VERTEX_SE3:QUAT 857 -53.1866 -30.9769 36.7 0.198752 -0.118966 0.87919 -0.416377 +VERTEX_SE3:QUAT 858 -45.1842 -37.3994 32.5786 0.178081 -0.0999612 0.861124 -0.465576 +VERTEX_SE3:QUAT 859 -36.3208 -42.9356 28.8903 -0.154622 0.089842 -0.836736 0.517585 +VERTEX_SE3:QUAT 860 -26.7217 -47.3316 25.5487 -0.134745 0.0720406 -0.808731 0.567986 +VERTEX_SE3:QUAT 861 -16.4923 -50.5737 22.687 -0.113513 0.0606075 -0.779586 0.612933 +VERTEX_SE3:QUAT 862 -5.86234 -52.6456 20.231 -0.0906399 0.0420912 -0.750148 0.653674 +VERTEX_SE3:QUAT 863 5.0416 -53.5917 18.3877 -0.0645262 0.0224839 -0.716833 0.693889 +VERTEX_SE3:QUAT 864 16.0979 -53.3739 17.2031 -0.0326627 0.00444676 -0.681349 0.731216 +VERTEX_SE3:QUAT 865 27.1269 -51.9794 16.7815 -0.00269284 -0.0155255 -0.643249 0.765495 +VERTEX_SE3:QUAT 866 37.9625 -49.4473 17.1261 0.018293 -0.0305326 -0.60244 0.79737 +VERTEX_SE3:QUAT 867 48.4493 -45.818 18.036 0.0265619 -0.0526713 -0.555228 0.829604 +VERTEX_SE3:QUAT 868 58.4082 -40.9984 19.3328 0.0453754 -0.0744868 -0.503844 0.85938 +VERTEX_SE3:QUAT 869 67.652 -35.0264 21.1758 0.0644472 -0.0926331 -0.457391 0.882077 +VERTEX_SE3:QUAT 870 76.1096 -28.153 23.5054 0.0883908 -0.113042 -0.403352 0.903723 +VERTEX_SE3:QUAT 871 83.5325 -20.3547 26.412 0.101155 -0.133682 -0.352604 0.920634 +VERTEX_SE3:QUAT 872 89.9753 -11.7879 29.6148 0.123155 -0.148905 -0.298667 0.93459 +VERTEX_SE3:QUAT 873 95.242 -2.61762 33.2344 0.141399 -0.1619 -0.244987 0.945397 +VERTEX_SE3:QUAT 874 99.3261 7.03565 37.1458 0.161329 -0.171708 -0.187539 0.953582 +VERTEX_SE3:QUAT 875 102.091 17.0807 41.2977 0.172919 -0.188847 -0.124714 0.958584 +VERTEX_SE3:QUAT 876 103.393 27.3876 45.4907 0.184274 -0.198608 -0.0619385 0.960605 +VERTEX_SE3:QUAT 877 103.252 37.7693 49.666 0.206316 -0.212229 -0.00158529 0.955191 +VERTEX_SE3:QUAT 878 101.664 47.9903 53.9873 0.214009 -0.230974 0.0658502 0.946845 +VERTEX_SE3:QUAT 879 98.5352 57.9808 58.0475 0.225454 -0.242875 0.117941 0.936094 +VERTEX_SE3:QUAT 880 94.2261 67.59 61.97 0.234007 -0.255229 0.178 0.921094 +VERTEX_SE3:QUAT 881 88.6344 76.6417 65.6025 0.242666 -0.261747 0.2333 0.904529 +VERTEX_SE3:QUAT 882 81.9369 85.0349 68.9461 0.254176 -0.267005 0.289902 0.88321 +VERTEX_SE3:QUAT 883 74.1569 92.5741 71.9868 0.265305 -0.26963 0.348508 0.857587 +VERTEX_SE3:QUAT 884 65.3782 99.0979 74.6981 0.276348 -0.274046 0.398376 0.830558 +VERTEX_SE3:QUAT 885 55.8545 104.596 77.1005 0.288363 -0.280058 0.44723 0.798999 +VERTEX_SE3:QUAT 886 45.6725 108.971 79.1337 0.297485 -0.292784 0.493347 0.763144 +VERTEX_SE3:QUAT 887 34.9901 112.245 80.623 0.299269 -0.304833 0.53631 0.727933 +VERTEX_SE3:QUAT 888 23.9682 114.491 81.4792 0.29992 -0.302927 0.585765 0.689321 +VERTEX_SE3:QUAT 889 12.7406 115.471 81.7647 0.289034 -0.302799 0.634429 0.649824 +VERTEX_SE3:QUAT 890 1.45213 115.219 81.2982 0.285466 -0.306788 0.677339 0.604651 +VERTEX_SE3:QUAT 891 -9.70001 113.779 80.1392 0.282256 -0.29742 0.722184 0.557067 +VERTEX_SE3:QUAT 892 -20.5152 110.937 78.4652 0.282787 -0.295157 0.759436 0.506134 +VERTEX_SE3:QUAT 893 -30.8535 106.866 76.2721 0.28658 -0.284693 0.792794 0.456398 +VERTEX_SE3:QUAT 894 -40.5604 101.626 73.7595 0.295427 -0.285804 0.821537 0.395115 +VERTEX_SE3:QUAT 895 -49.432 95.2546 70.7564 0.294361 -0.289029 0.846009 0.337761 +VERTEX_SE3:QUAT 896 -57.3899 88.0445 67.1419 0.288851 -0.281035 0.871883 0.278217 +VERTEX_SE3:QUAT 897 -64.2182 79.9424 63.1019 0.275979 -0.268635 0.895208 0.224219 +VERTEX_SE3:QUAT 898 -69.8966 71.1256 58.7841 0.269088 -0.268877 0.910697 0.161024 +VERTEX_SE3:QUAT 899 -74.2564 61.7988 53.9544 0.262861 -0.256951 0.924025 0.105158 +VERTEX_SE3:QUAT 900 -77.3941 52.0729 48.9896 0.252181 -0.238055 0.936334 0.0548983 +VERTEX_SE3:QUAT 901 -79.2904 41.9896 44.0548 0.23689 -0.219712 0.946352 -0.00524464 +VERTEX_SE3:QUAT 902 -79.6915 31.7269 39.1574 0.21612 -0.21909 0.949532 -0.0606763 +VERTEX_SE3:QUAT 903 -78.811 21.6035 34.0286 0.202583 -0.206523 0.950487 -0.113501 +VERTEX_SE3:QUAT 904 -76.6484 11.644 28.9642 0.190703 -0.191964 0.946328 -0.176764 +VERTEX_SE3:QUAT 905 -73.0162 2.03427 24.0145 0.173615 -0.172228 0.941295 -0.232722 +VERTEX_SE3:QUAT 906 -68.094 -7.16552 19.3823 0.156472 -0.153004 0.932232 -0.288183 +VERTEX_SE3:QUAT 907 -61.9518 -15.7929 15.1232 0.139339 -0.13855 0.918178 -0.344003 +VERTEX_SE3:QUAT 908 -54.6629 -23.6427 11.1851 0.129192 -0.128482 0.900142 -0.395659 +VERTEX_SE3:QUAT 909 -46.435 -30.6232 7.47452 0.100972 -0.106855 0.88 -0.451648 +VERTEX_SE3:QUAT 910 -37.1845 -36.6047 4.40389 -0.0851594 0.0964973 -0.851042 0.509082 +VERTEX_SE3:QUAT 911 -27.1284 -41.33 1.67007 -0.0739094 0.0892489 -0.822253 0.557201 +VERTEX_SE3:QUAT 912 -16.5216 -44.8737 -0.795182 -0.0543041 0.0664628 -0.791806 0.604713 +VERTEX_SE3:QUAT 913 -5.45871 -47.2207 -2.57692 -0.0322369 0.0457391 -0.761359 0.645911 +VERTEX_SE3:QUAT 914 5.88096 -48.4241 -3.66771 -0.00961046 0.0299522 -0.725403 0.687606 +VERTEX_SE3:QUAT 915 17.3392 -48.3763 -4.11945 0.00865879 0.0200346 -0.687239 0.726104 +VERTEX_SE3:QUAT 916 28.7365 -47.0856 -4.10953 0.0232847 0.0149223 -0.633102 0.773574 +VERTEX_SE3:QUAT 917 39.8462 -44.2025 -3.70677 0.0406714 -0.00538324 -0.586551 0.808873 +VERTEX_SE3:QUAT 918 50.4991 -40.0584 -2.69503 0.062905 -0.0148973 -0.538203 0.840332 +VERTEX_SE3:QUAT 919 60.5648 -34.7438 -1.08182 0.0778612 -0.0256145 -0.491579 0.866967 +VERTEX_SE3:QUAT 920 69.9448 -28.4128 0.939023 0.0936281 -0.0467103 -0.43226 0.895658 +VERTEX_SE3:QUAT 921 78.3004 -20.9182 3.50781 0.121091 -0.0623709 -0.372786 0.917866 +VERTEX_SE3:QUAT 922 85.51 -12.543 6.74265 0.147759 -0.0787312 -0.313169 0.934823 +VERTEX_SE3:QUAT 923 91.4049 -3.43181 10.605 0.16357 -0.0929069 -0.261001 0.946832 +VERTEX_SE3:QUAT 924 96.128 6.19175 14.8147 0.178963 -0.102649 -0.206535 0.956441 +VERTEX_SE3:QUAT 925 99.5902 16.2115 19.3079 0.196343 -0.113804 -0.145539 0.962973 +VERTEX_SE3:QUAT 926 101.658 26.5196 24.0858 0.212357 -0.125035 -0.0887438 0.965088 +VERTEX_SE3:QUAT 927 102.329 36.9047 29.0677 0.232771 -0.149057 -0.0259636 0.96069 +VERTEX_SE3:QUAT 928 101.414 47.1735 34.2546 0.241874 -0.162759 0.034226 0.955947 +VERTEX_SE3:QUAT 929 99.0746 57.2497 39.3659 0.254585 -0.175784 0.0959421 0.946088 +VERTEX_SE3:QUAT 930 95.2962 66.9285 44.3926 0.269736 -0.192938 0.157678 0.930137 +VERTEX_SE3:QUAT 931 90.0802 76.019 49.3172 0.278952 -0.208115 0.221929 0.910836 +VERTEX_SE3:QUAT 932 83.4778 84.3577 53.8988 0.295623 -0.215735 0.27852 0.887971 +VERTEX_SE3:QUAT 933 75.7564 91.7661 58.3431 0.310751 -0.227265 0.327195 0.862976 +VERTEX_SE3:QUAT 934 67.1046 98.2196 62.5385 0.317332 -0.226231 0.38415 0.836988 +VERTEX_SE3:QUAT 935 57.592 103.589 66.3517 0.321721 -0.22975 0.449126 0.801247 +VERTEX_SE3:QUAT 936 47.1834 107.608 69.5927 0.325888 -0.229108 0.503962 0.766374 +VERTEX_SE3:QUAT 937 36.246 110.316 72.3405 0.32215 -0.236043 0.553617 0.730761 +VERTEX_SE3:QUAT 938 24.9116 111.85 74.4041 0.328425 -0.239657 0.591671 0.696152 +VERTEX_SE3:QUAT 939 13.4147 112.241 76.0393 0.325901 -0.239705 0.635647 0.657482 +VERTEX_SE3:QUAT 940 1.85751 111.426 77.0744 0.334942 -0.251044 0.675883 0.606608 +VERTEX_SE3:QUAT 941 -9.5758 109.267 77.4371 0.332555 -0.252134 0.713322 0.563034 +VERTEX_SE3:QUAT 942 -20.7265 105.95 77.1795 0.327062 -0.251945 0.750215 0.516461 +VERTEX_SE3:QUAT 943 -31.4337 101.465 76.2932 0.32428 -0.249473 0.78586 0.463713 +VERTEX_SE3:QUAT 944 -41.4932 95.8016 74.8324 0.322615 -0.244155 0.821343 0.402125 +VERTEX_SE3:QUAT 945 -50.6643 88.8695 72.805 0.308097 -0.244082 0.85344 0.342259 +VERTEX_SE3:QUAT 946 -58.77 80.9697 70.0639 0.302243 -0.240326 0.87789 0.283199 +VERTEX_SE3:QUAT 947 -65.7237 72.2159 66.7961 0.295387 -0.239304 0.897566 0.223285 +VERTEX_SE3:QUAT 948 -71.4998 62.8181 63.003 0.277813 -0.24682 0.912469 0.171175 +VERTEX_SE3:QUAT 949 -76.1279 53.0789 58.5698 0.267032 -0.240523 0.926584 0.110835 +VERTEX_SE3:QUAT 950 -79.3901 42.9376 53.7992 0.248403 -0.226039 0.940157 0.0575068 +VERTEX_SE3:QUAT 951 -81.2894 32.4717 48.9506 0.22916 -0.221495 0.947853 -0.00108905 +VERTEX_SE3:QUAT 952 -81.7789 21.9593 43.8516 0.214148 -0.214204 0.951469 -0.0544499 +VERTEX_SE3:QUAT 953 -80.9584 11.5063 38.6811 0.191379 -0.207544 0.951493 -0.122315 +VERTEX_SE3:QUAT 954 -78.4959 1.35034 33.4263 0.16736 -0.192669 0.948159 -0.189378 +VERTEX_SE3:QUAT 955 -74.4188 -8.36738 28.3728 0.152219 -0.186148 0.937899 -0.250048 +VERTEX_SE3:QUAT 956 -68.9721 -17.4856 23.3927 0.124849 -0.171778 0.928803 -0.303695 +VERTEX_SE3:QUAT 957 -62.2948 -25.9706 18.8042 0.109563 -0.161129 0.912076 -0.360765 +VERTEX_SE3:QUAT 958 -54.485 -33.5703 14.5135 0.0854271 -0.142405 0.897383 -0.408812 +VERTEX_SE3:QUAT 959 -45.6838 -40.3966 10.8029 0.0694753 -0.125145 0.876771 -0.459113 +VERTEX_SE3:QUAT 960 -36.0289 -46.2639 7.60901 -0.041922 0.109226 -0.854362 0.506337 +VERTEX_SE3:QUAT 961 -25.6514 -51.1178 5.09079 -0.0188938 0.0895184 -0.823266 0.560235 +VERTEX_SE3:QUAT 962 -14.6026 -54.6762 3.29929 -0.000185349 0.0610438 -0.78741 0.613399 +VERTEX_SE3:QUAT 963 -3.07692 -56.8469 2.35054 0.0219575 0.0439682 -0.750847 0.658645 +VERTEX_SE3:QUAT 964 8.64133 -57.6906 2.11755 0.0346159 0.0230152 -0.708204 0.704783 +VERTEX_SE3:QUAT 965 20.3857 -57.0748 2.48491 0.0476442 0.0102155 -0.663678 0.74643 +VERTEX_SE3:QUAT 966 31.9475 -55.0636 3.33252 0.063249 -0.0101261 -0.612569 0.787817 +VERTEX_SE3:QUAT 967 43.0941 -51.5633 4.81645 0.0776886 -0.0198396 -0.562036 0.823217 +VERTEX_SE3:QUAT 968 53.6894 -46.726 6.74826 0.104248 -0.0390481 -0.509274 0.853374 +VERTEX_SE3:QUAT 969 63.4652 -40.7161 9.46605 0.12564 -0.0621885 -0.454401 0.879697 +VERTEX_SE3:QUAT 970 72.2449 -33.6355 12.8775 0.147046 -0.0840391 -0.404275 0.89882 +VERTEX_SE3:QUAT 971 80.0348 -25.7185 16.8862 0.159195 -0.0995553 -0.347334 0.918752 +VERTEX_SE3:QUAT 972 86.6126 -16.9422 21.2156 0.162018 -0.108602 -0.287623 0.937672 +VERTEX_SE3:QUAT 973 91.9346 -7.34974 25.567 0.175167 -0.124278 -0.23702 0.947467 +VERTEX_SE3:QUAT 974 96.087 2.70474 30.1878 0.196294 -0.136305 -0.178291 0.954516 +VERTEX_SE3:QUAT 975 98.7846 13.0691 35.1699 0.210366 -0.145161 -0.131207 0.957841 +VERTEX_SE3:QUAT 976 100.353 23.5921 40.3427 0.2252 -0.153476 -0.07023 0.959582 +VERTEX_SE3:QUAT 977 100.415 34.1833 45.6248 0.241363 -0.164096 -0.0121076 0.956384 +VERTEX_SE3:QUAT 978 99.061 44.627 51.0182 0.248526 -0.169925 0.0577575 0.951853 +VERTEX_SE3:QUAT 979 96.0737 54.8436 56.2276 0.255985 -0.174462 0.11741 0.94353 +VERTEX_SE3:QUAT 980 91.7204 64.6367 61.3014 0.2612 -0.18937 0.175383 0.930137 +VERTEX_SE3:QUAT 981 86.0635 73.9063 66.0527 0.269727 -0.194426 0.239386 0.912217 +VERTEX_SE3:QUAT 982 79.062 82.3526 70.5241 0.275135 -0.204428 0.296405 0.891434 +VERTEX_SE3:QUAT 983 70.9351 89.9395 74.6174 0.275497 -0.203934 0.348046 0.872569 +VERTEX_SE3:QUAT 984 61.9122 96.7153 78.3267 0.287407 -0.20634 0.401945 0.844548 +VERTEX_SE3:QUAT 985 52.0381 102.307 81.7839 0.29276 -0.217617 0.454658 0.812539 +VERTEX_SE3:QUAT 986 41.4146 106.712 84.7167 0.296726 -0.216144 0.507525 0.779522 +VERTEX_SE3:QUAT 987 30.233 109.828 87.2417 0.297744 -0.223061 0.555779 0.74344 +VERTEX_SE3:QUAT 988 18.6513 111.67 89.186 0.301642 -0.231064 0.59812 0.705602 +VERTEX_SE3:QUAT 989 6.86011 112.313 90.5518 0.299332 -0.233153 0.643611 0.664684 +VERTEX_SE3:QUAT 990 -4.99324 111.62 91.2947 0.303504 -0.234729 0.688164 0.615806 +VERTEX_SE3:QUAT 991 -16.72 109.467 91.4733 0.296124 -0.243374 0.731707 0.563636 +VERTEX_SE3:QUAT 992 -28.0728 105.981 90.7863 0.295581 -0.245989 0.767116 0.513472 +VERTEX_SE3:QUAT 993 -38.9296 101.257 89.4891 0.291329 -0.24487 0.795488 0.471556 +VERTEX_SE3:QUAT 994 -49.2373 95.5616 87.7273 0.279598 -0.238452 0.828838 0.421893 +VERTEX_SE3:QUAT 995 -58.7668 88.771 85.4355 0.267964 -0.230957 0.861295 0.364725 +VERTEX_SE3:QUAT 996 -67.274 80.8872 82.6471 0.256791 -0.2306 0.886192 0.309106 +VERTEX_SE3:QUAT 997 -74.6868 72.1587 79.3311 0.244505 -0.227523 0.909135 0.248847 +VERTEX_SE3:QUAT 998 -80.831 62.6505 75.5434 0.236767 -0.215243 0.928373 0.189039 +VERTEX_SE3:QUAT 999 -85.6194 52.4712 71.5676 0.22974 -0.206944 0.941385 0.134861 +VERTEX_SE3:QUAT 1000 -89.123 41.8166 67.4122 0.220753 -0.210165 0.949374 0.0760739 +VERTEX_SE3:QUAT 1001 -91.2606 30.9964 62.8238 0.201939 -0.201196 0.958374 0.0161586 +VERTEX_SE3:QUAT 1002 -91.9116 20.0283 58.1116 0.196684 -0.195416 0.959951 -0.0402705 +VERTEX_SE3:QUAT 1003 -91.1914 9.11674 53.2585 0.189282 -0.195523 0.955855 -0.110831 +VERTEX_SE3:QUAT 1004 -88.8605 -1.4459 48.1461 0.171541 -0.181691 0.955103 -0.159187 +VERTEX_SE3:QUAT 1005 -85.2999 -11.7771 43.2416 0.156454 -0.175747 0.947507 -0.216483 +VERTEX_SE3:QUAT 1006 -80.4222 -21.5729 38.3918 0.145801 -0.164103 0.932716 -0.286098 +VERTEX_SE3:QUAT 1007 -74.0218 -30.5567 33.7026 0.128783 -0.151259 0.918313 -0.3424 +VERTEX_SE3:QUAT 1008 -66.3915 -38.7191 29.3182 0.109738 -0.136645 0.899198 -0.40091 +VERTEX_SE3:QUAT 1009 -57.6341 -45.8804 25.3457 0.0989815 -0.126306 0.875044 -0.45667 +VERTEX_SE3:QUAT 1010 -47.9211 -51.8968 21.6766 -0.084525 0.109823 -0.846099 0.514695 +VERTEX_SE3:QUAT 1011 -37.3629 -56.5983 18.4761 -0.0585621 0.0986322 -0.815973 0.566595 +VERTEX_SE3:QUAT 1012 -26.1616 -59.9943 15.8667 -0.0400452 0.0871366 -0.785813 0.610984 +VERTEX_SE3:QUAT 1013 -14.5442 -62.1462 13.7549 -0.0209948 0.072487 -0.74645 0.661148 +VERTEX_SE3:QUAT 1014 -2.63185 -62.8247 12.2726 -0.00333679 0.0522503 -0.707754 0.704516 +VERTEX_SE3:QUAT 1015 9.34433 -62.1264 11.4677 0.0152653 0.0420517 -0.669322 0.741625 +VERTEX_SE3:QUAT 1016 21.1974 -60.1766 11.2166 0.0310071 0.027513 -0.623212 0.780953 +VERTEX_SE3:QUAT 1017 32.7494 -56.8445 11.5308 0.044689 0.0222692 -0.576871 0.815308 +VERTEX_SE3:QUAT 1018 43.8347 -52.2146 12.2485 0.0588788 0.00373633 -0.530887 0.845387 +VERTEX_SE3:QUAT 1019 54.3003 -46.4123 13.5417 0.0736916 -0.0074445 -0.47847 0.874975 +VERTEX_SE3:QUAT 1020 63.9637 -39.4283 15.3138 0.100412 -0.01942 -0.427216 0.898347 +VERTEX_SE3:QUAT 1021 72.6546 -31.496 17.804 0.122952 -0.0405045 -0.379338 0.916158 +VERTEX_SE3:QUAT 1022 80.3657 -22.7987 20.9742 0.13577 -0.0494031 -0.316185 0.937632 +VERTEX_SE3:QUAT 1023 86.7568 -13.2022 24.4935 0.143712 -0.0646746 -0.258085 0.953182 +VERTEX_SE3:QUAT 1024 91.8157 -2.90628 28.251 0.158612 -0.0820286 -0.197815 0.963838 +VERTEX_SE3:QUAT 1025 95.4147 7.86918 32.3341 0.166214 -0.0874921 -0.141305 0.971983 +VERTEX_SE3:QUAT 1026 97.6953 18.97 36.5056 0.172142 -0.0958786 -0.0798856 0.977135 +VERTEX_SE3:QUAT 1027 98.453 30.2409 40.7132 0.189994 -0.107198 -0.0240524 0.975619 +VERTEX_SE3:QUAT 1028 97.7972 41.4445 45.1842 0.206555 -0.117817 0.0405828 0.970467 +VERTEX_SE3:QUAT 1029 95.5432 52.379 49.8116 0.21492 -0.135613 0.0978304 0.96221 +VERTEX_SE3:QUAT 1030 91.8596 62.9568 54.3321 0.230297 -0.140045 0.158432 0.949868 +VERTEX_SE3:QUAT 1031 86.7588 72.9385 58.8994 0.227394 -0.152039 0.218031 0.936823 +VERTEX_SE3:QUAT 1032 80.3447 82.3359 63.009 0.234838 -0.162339 0.268919 0.91988 +VERTEX_SE3:QUAT 1033 72.8628 90.9879 66.9286 0.232749 -0.169952 0.329849 0.898968 +VERTEX_SE3:QUAT 1034 64.196 98.7029 70.3557 0.224657 -0.171108 0.392268 0.87543 +VERTEX_SE3:QUAT 1035 54.4931 105.372 73.1931 0.228405 -0.172476 0.446485 0.847782 +VERTEX_SE3:QUAT 1036 43.9749 110.849 75.7162 0.238624 -0.175008 0.50021 0.81377 +VERTEX_SE3:QUAT 1037 32.8042 114.93 77.97 0.238894 -0.172681 0.558507 0.775358 +VERTEX_SE3:QUAT 1038 21.0939 117.497 79.7852 0.242852 -0.182804 0.607734 0.733665 +VERTEX_SE3:QUAT 1039 9.09515 118.591 81.048 0.239106 -0.183653 0.653381 0.694401 +VERTEX_SE3:QUAT 1040 -2.99606 118.328 81.8089 0.243327 -0.181888 0.7007 0.645545 +VERTEX_SE3:QUAT 1041 -14.9754 116.478 82.1705 0.244489 -0.189979 0.743621 0.592588 +VERTEX_SE3:QUAT 1042 -26.6443 113.118 81.8737 0.237543 -0.197891 0.784292 0.537865 +VERTEX_SE3:QUAT 1043 -37.7606 108.369 80.8392 0.235807 -0.203302 0.821154 0.478299 +VERTEX_SE3:QUAT 1044 -48.1139 102.252 79.1581 0.234054 -0.198937 0.854184 0.419538 +VERTEX_SE3:QUAT 1045 -57.5221 94.8506 77.0711 0.227329 -0.195692 0.883451 0.359916 +VERTEX_SE3:QUAT 1046 -65.8251 86.3645 74.512 0.222618 -0.193371 0.909155 0.294085 +VERTEX_SE3:QUAT 1047 -72.8053 76.8529 71.5139 0.214896 -0.19292 0.929488 0.229466 +VERTEX_SE3:QUAT 1048 -78.3887 66.6218 68.0596 0.206535 -0.199342 0.944284 0.161039 +VERTEX_SE3:QUAT 1049 -82.4215 55.8815 64.0121 0.196779 -0.197783 0.956241 0.0881121 +VERTEX_SE3:QUAT 1050 -84.7069 44.7698 59.5918 0.189669 -0.195073 0.962003 0.0228705 +VERTEX_SE3:QUAT 1051 -85.4247 33.5565 54.8984 0.174441 -0.179787 0.96751 -0.0342244 +VERTEX_SE3:QUAT 1052 -84.671 22.2888 50.3401 0.167475 -0.182562 0.963457 -0.101857 +VERTEX_SE3:QUAT 1053 -82.3322 11.3821 45.4953 0.151747 -0.180509 0.957502 -0.166069 +VERTEX_SE3:QUAT 1054 -78.4224 0.965912 40.5569 0.134262 -0.174266 0.945888 -0.238538 +VERTEX_SE3:QUAT 1055 -72.8469 -8.70322 35.6795 0.126979 -0.175891 0.928063 -0.302717 +VERTEX_SE3:QUAT 1056 -65.9472 -17.4566 30.7327 0.114422 -0.171992 0.908833 -0.362422 +VERTEX_SE3:QUAT 1057 -57.8639 -25.2175 25.9061 0.0949211 -0.174174 0.887575 -0.41577 +VERTEX_SE3:QUAT 1058 -48.8112 -31.8649 21.2072 0.0781606 -0.163913 0.866714 -0.464575 +VERTEX_SE3:QUAT 1059 -38.8855 -37.5471 16.905 -0.0675936 0.159962 -0.836719 0.519369 +VERTEX_SE3:QUAT 1060 -28.2122 -41.895 12.8857 -0.0457213 0.151305 -0.805525 0.571092 +VERTEX_SE3:QUAT 1061 -16.8831 -44.8913 9.41491 -0.0287233 0.143581 -0.77313 0.617114 +VERTEX_SE3:QUAT 1062 -5.18295 -46.5785 6.43192 -0.0104371 0.135016 -0.741164 0.657524 +VERTEX_SE3:QUAT 1063 6.77532 -47.0586 4.0024 0.00780087 0.11398 -0.702032 0.702922 +VERTEX_SE3:QUAT 1064 18.854 -46.152 2.34824 0.00969775 0.0960511 -0.657207 0.747502 +VERTEX_SE3:QUAT 1065 30.7617 -43.786 1.15318 0.0337426 0.0955753 -0.611535 0.784698 +VERTEX_SE3:QUAT 1066 42.3816 -40.0378 0.574425 0.05893 0.0812125 -0.564209 0.819512 +VERTEX_SE3:QUAT 1067 53.533 -35.0106 0.818215 0.0737748 0.0799905 -0.512451 0.851794 +VERTEX_SE3:QUAT 1068 63.978 -28.7095 1.53706 0.0814649 0.0739321 -0.463596 0.87919 +VERTEX_SE3:QUAT 1069 73.6421 -21.3288 2.65366 0.0963711 0.0576068 -0.403679 0.907985 +VERTEX_SE3:QUAT 1070 82.24 -12.7964 4.39292 0.115904 0.0383388 -0.349245 0.929045 +VERTEX_SE3:QUAT 1071 89.7108 -3.41487 6.87048 0.135186 0.0303118 -0.296382 0.944968 +VERTEX_SE3:QUAT 1072 96.0274 6.62465 9.91431 0.146269 0.0212388 -0.232365 0.961333 +VERTEX_SE3:QUAT 1073 100.895 17.3327 13.3537 0.164818 0.0182823 -0.17895 0.969782 +VERTEX_SE3:QUAT 1074 104.499 28.3508 17.2686 0.182001 0.00404427 -0.11775 0.976214 +VERTEX_SE3:QUAT 1075 106.605 39.5867 21.6667 0.199105 0.0044617 -0.0571038 0.978303 +VERTEX_SE3:QUAT 1076 107.248 50.8524 26.4901 0.211851 -0.00457331 0.0029602 0.977287 +VERTEX_SE3:QUAT 1077 106.382 61.9817 31.5922 0.228755 -0.020617 0.0706542 0.970698 +VERTEX_SE3:QUAT 1078 103.85 72.7053 36.9752 0.241316 -0.0262614 0.133031 0.960926 +VERTEX_SE3:QUAT 1079 99.8304 82.8953 42.5119 0.258198 -0.0374961 0.194927 0.945479 +VERTEX_SE3:QUAT 1080 94.3948 92.3008 48.2235 0.261576 -0.0561034 0.252066 0.929996 +VERTEX_SE3:QUAT 1081 87.6351 100.981 53.6806 0.268766 -0.0586864 0.305358 0.911634 +VERTEX_SE3:QUAT 1082 79.8147 108.774 59.071 0.281855 -0.0693517 0.359947 0.886671 +VERTEX_SE3:QUAT 1083 70.9543 115.437 64.3637 0.292913 -0.0796481 0.420611 0.854953 +VERTEX_SE3:QUAT 1084 61.0668 120.749 69.4218 0.311419 -0.102742 0.471947 0.81837 +VERTEX_SE3:QUAT 1085 50.427 124.622 74.1449 0.309177 -0.120377 0.521284 0.786246 +VERTEX_SE3:QUAT 1086 39.1367 127.292 78.1929 0.31136 -0.132525 0.578157 0.742446 +VERTEX_SE3:QUAT 1087 27.3621 128.368 81.5803 0.321584 -0.135527 0.619546 0.703121 +VERTEX_SE3:QUAT 1088 15.454 128.083 84.6323 0.319077 -0.147986 0.66541 0.658422 +VERTEX_SE3:QUAT 1089 3.49459 126.374 86.9194 0.316503 -0.153477 0.720521 0.597595 +VERTEX_SE3:QUAT 1090 -8.21619 122.833 88.3933 0.321801 -0.160877 0.754559 0.54882 +VERTEX_SE3:QUAT 1091 -19.4932 118.032 89.2652 0.319961 -0.175355 0.786504 0.498284 +VERTEX_SE3:QUAT 1092 -30.2819 112.084 89.3062 0.313032 -0.184801 0.815701 0.449991 +VERTEX_SE3:QUAT 1093 -40.4147 105.14 88.5493 0.297194 -0.192643 0.843581 0.403652 +VERTEX_SE3:QUAT 1094 -49.8 97.3095 87.041 0.288773 -0.194654 0.871014 0.34649 +VERTEX_SE3:QUAT 1095 -58.1471 88.521 84.8758 0.27207 -0.198915 0.896455 0.287712 +VERTEX_SE3:QUAT 1096 -65.2954 78.8908 81.9902 0.25717 -0.200434 0.914976 0.237714 +VERTEX_SE3:QUAT 1097 -71.339 68.7081 78.5695 0.247585 -0.211419 0.929952 0.170859 +VERTEX_SE3:QUAT 1098 -75.9074 58.0342 74.3769 0.232155 -0.215404 0.941977 0.111289 +VERTEX_SE3:QUAT 1099 -79.0675 47.0777 69.6686 0.2095 -0.215265 0.952139 0.0565807 +VERTEX_SE3:QUAT 1100 -80.7964 35.9624 64.6288 0.202652 -0.214948 0.955356 -0.004918 +VERTEX_SE3:QUAT 1101 -81.0494 24.8477 59.2653 0.186247 -0.215311 0.956388 -0.06538 +VERTEX_SE3:QUAT 1102 -79.7796 13.9073 53.6807 0.171948 -0.214514 0.95317 -0.126031 +VERTEX_SE3:QUAT 1103 -77.0472 3.33954 47.9265 0.159497 -0.215023 0.943125 -0.19708 +VERTEX_SE3:QUAT 1104 -72.6402 -6.56829 42.0029 0.147311 -0.217671 0.931157 -0.252716 +VERTEX_SE3:QUAT 1105 -66.9788 -15.7644 35.9813 0.125392 -0.210526 0.919628 -0.306986 +VERTEX_SE3:QUAT 1106 -60.0589 -24.2083 30.1923 0.103346 -0.210494 0.900233 -0.366868 +VERTEX_SE3:QUAT 1107 -51.9037 -31.5846 24.5578 0.0907359 -0.204426 0.87632 -0.426663 +VERTEX_SE3:QUAT 1108 -42.6478 -37.8033 19.2065 0.0688869 -0.200644 0.849357 -0.483311 +VERTEX_SE3:QUAT 1109 -32.457 -42.745 14.2549 -0.0467093 0.18803 -0.822092 0.535376 +VERTEX_SE3:QUAT 1110 -21.4694 -46.4572 9.91925 -0.025725 0.177527 -0.792417 0.583007 +VERTEX_SE3:QUAT 1111 -9.92664 -48.9263 6.21145 -0.00911583 0.164744 -0.761902 0.626324 +VERTEX_SE3:QUAT 1112 2.01022 -50.1822 3.11352 0.0200818 0.143583 -0.720552 0.678074 +VERTEX_SE3:QUAT 1113 14.2115 -49.9204 1.05803 0.0358021 0.143074 -0.676846 0.721199 +VERTEX_SE3:QUAT 1114 26.3683 -48.1891 -0.506592 0.0602603 0.134664 -0.631745 0.761008 +VERTEX_SE3:QUAT 1115 38.3328 -45.0724 -1.25237 0.0753393 0.121189 -0.581527 0.800914 +VERTEX_SE3:QUAT 1116 49.8355 -40.5318 -1.29761 0.0928088 0.107489 -0.530512 0.835697 +VERTEX_SE3:QUAT 1117 60.729 -34.6804 -0.575213 0.107076 0.095101 -0.482141 0.864309 +VERTEX_SE3:QUAT 1118 70.8822 -27.7337 0.76787 0.125922 0.0886588 -0.436487 0.886432 +VERTEX_SE3:QUAT 1119 80.2706 -19.89 2.78001 0.137413 0.0799099 -0.386356 0.908549 +VERTEX_SE3:QUAT 1120 88.6991 -11.1683 5.29934 0.148807 0.0776001 -0.330556 0.928745 +VERTEX_SE3:QUAT 1121 95.9916 -1.59209 8.25638 0.170559 0.0637011 -0.268878 0.94581 +VERTEX_SE3:QUAT 1122 101.897 8.66439 11.9782 0.175587 0.0513268 -0.207532 0.960971 +VERTEX_SE3:QUAT 1123 106.355 19.4934 16.0221 0.191342 0.0400642 -0.162436 0.96716 +VERTEX_SE3:QUAT 1124 109.692 30.5631 20.533 0.209946 0.0397315 -0.0986403 0.971913 +VERTEX_SE3:QUAT 1125 111.519 41.7471 25.5727 0.226088 0.0311409 -0.0478785 0.972431 +VERTEX_SE3:QUAT 1126 112.078 52.8844 31.0342 0.238061 0.0127616 0.0117608 0.971095 +VERTEX_SE3:QUAT 1127 111.102 63.8477 36.7738 0.257281 -0.00223463 0.079301 0.963075 +VERTEX_SE3:QUAT 1128 108.436 74.3021 42.8494 0.263721 -0.0227088 0.136423 0.954633 +VERTEX_SE3:QUAT 1129 104.333 84.32 48.9077 0.266743 -0.0361201 0.19657 0.942817 +VERTEX_SE3:QUAT 1130 98.8112 93.7368 54.8403 0.283233 -0.051802 0.244927 0.9258 +VERTEX_SE3:QUAT 1131 92.1428 102.344 60.8424 0.286209 -0.0560535 0.300964 0.907944 +VERTEX_SE3:QUAT 1132 84.3467 110.079 66.6495 0.29204 -0.0702112 0.362674 0.882185 +VERTEX_SE3:QUAT 1133 75.3458 116.634 72.1372 0.300708 -0.075824 0.416078 0.854813 +VERTEX_SE3:QUAT 1134 65.4679 121.982 77.4257 0.307364 -0.091723 0.473682 0.820207 +VERTEX_SE3:QUAT 1135 54.7205 125.906 82.2404 0.305964 -0.105549 0.528233 0.784994 +VERTEX_SE3:QUAT 1136 43.2952 128.492 86.4398 0.307433 -0.11662 0.577896 0.746941 +VERTEX_SE3:QUAT 1137 31.4368 129.664 90.0427 0.30755 -0.1279 0.629777 0.701738 +VERTEX_SE3:QUAT 1138 19.3827 129.264 92.9491 0.311835 -0.139328 0.671481 0.657617 +VERTEX_SE3:QUAT 1139 7.29816 127.469 95.2439 0.311362 -0.152257 0.710862 0.612002 +VERTEX_SE3:QUAT 1140 -4.64758 124.32 96.7914 0.303293 -0.164209 0.747444 0.567782 +VERTEX_SE3:QUAT 1141 -16.3034 120.006 97.5026 0.297749 -0.172874 0.782823 0.518313 +VERTEX_SE3:QUAT 1142 -27.448 114.458 97.4624 0.295283 -0.18135 0.813076 0.467789 +VERTEX_SE3:QUAT 1143 -37.9338 107.788 96.7023 0.283634 -0.185684 0.849212 0.40486 +VERTEX_SE3:QUAT 1144 -47.3929 99.8575 95.1344 0.271052 -0.194561 0.877082 0.345549 +VERTEX_SE3:QUAT 1145 -55.7704 90.9792 92.7338 0.256716 -0.204026 0.902376 0.279621 +VERTEX_SE3:QUAT 1146 -62.7969 81.2305 89.4686 0.252379 -0.208253 0.918994 0.219966 +VERTEX_SE3:QUAT 1147 -68.5492 70.8488 85.6354 0.240029 -0.220332 0.930355 0.168167 +VERTEX_SE3:QUAT 1148 -73.1305 60.1879 81.1249 0.22412 -0.232858 0.94006 0.10879 +VERTEX_SE3:QUAT 1149 -76.2922 49.3367 75.8959 0.213201 -0.239762 0.946241 0.0410752 +VERTEX_SE3:QUAT 1150 -77.8259 38.3952 70.116 0.191644 -0.256045 0.947361 -0.0148643 +VERTEX_SE3:QUAT 1151 -77.9871 27.7023 63.7226 0.175529 -0.260328 0.946852 -0.069931 +VERTEX_SE3:QUAT 1152 -76.7586 17.2643 57.0474 0.149889 -0.269159 0.943921 -0.118743 +VERTEX_SE3:QUAT 1153 -74.2724 7.22258 50.0991 0.126551 -0.274318 0.936178 -0.179738 +VERTEX_SE3:QUAT 1154 -70.2526 -2.21329 43.0124 0.108936 -0.280457 0.923849 -0.236602 +VERTEX_SE3:QUAT 1155 -64.9119 -10.9036 35.8503 0.0957745 -0.273947 0.911196 -0.292409 +VERTEX_SE3:QUAT 1156 -58.3126 -18.8694 28.9111 0.0743968 -0.269428 0.892155 -0.354871 +VERTEX_SE3:QUAT 1157 -50.3671 -25.8245 22.2907 0.0564668 -0.278458 0.869919 -0.40313 +VERTEX_SE3:QUAT 1158 -41.521 -31.7043 15.7583 0.0318602 -0.262189 0.853715 -0.448789 +VERTEX_SE3:QUAT 1159 -31.7296 -36.8169 9.92223 0.0110595 -0.264933 0.826439 -0.496676 +VERTEX_SE3:QUAT 1160 -21.1986 -40.7367 4.4976 0.0186872 0.25095 -0.798642 0.546668 +VERTEX_SE3:QUAT 1161 -9.88883 -43.4995 -0.0487942 0.0462224 0.242754 -0.760993 0.599853 +VERTEX_SE3:QUAT 1162 1.9787 -44.8235 -3.71821 0.0677625 0.243438 -0.724837 0.640904 +VERTEX_SE3:QUAT 1163 14.0913 -44.8619 -6.76151 0.0910937 0.239111 -0.681961 0.68517 +VERTEX_SE3:QUAT 1164 26.3083 -43.4752 -8.94362 0.104045 0.230987 -0.637635 0.72749 +VERTEX_SE3:QUAT 1165 38.3989 -40.716 -10.4131 0.128434 0.215685 -0.591884 0.765936 +VERTEX_SE3:QUAT 1166 50.2109 -36.7255 -10.7991 0.148474 0.20863 -0.550479 0.794608 +VERTEX_SE3:QUAT 1167 61.6352 -31.6947 -10.366 0.167622 0.192585 -0.502288 0.826148 +VERTEX_SE3:QUAT 1168 72.4448 -25.6018 -8.97783 0.175229 0.173903 -0.45169 0.857338 +VERTEX_SE3:QUAT 1169 82.4437 -18.4063 -6.86896 0.193889 0.160026 -0.39586 0.883229 +VERTEX_SE3:QUAT 1170 91.4203 -10.2416 -3.87346 0.216652 0.152214 -0.334239 0.904531 +VERTEX_SE3:QUAT 1171 99.2013 -1.2834 0.0416105 0.237916 0.146765 -0.27534 0.919807 +VERTEX_SE3:QUAT 1172 105.763 8.25502 4.74594 0.253453 0.137878 -0.214927 0.933037 +VERTEX_SE3:QUAT 1173 110.959 18.258 10.1463 0.268729 0.125517 -0.153306 0.942617 +VERTEX_SE3:QUAT 1174 114.689 28.5498 16.1963 0.281149 0.102728 -0.0980153 0.949102 +VERTEX_SE3:QUAT 1175 116.98 38.9374 22.7519 0.294453 0.0906028 -0.0345831 0.950733 +VERTEX_SE3:QUAT 1176 117.686 49.2487 29.7778 0.308724 0.0812551 0.0254276 0.947333 +VERTEX_SE3:QUAT 1177 116.938 59.2974 37.1913 0.314796 0.054607 0.0857795 0.943697 +VERTEX_SE3:QUAT 1178 114.583 68.9953 44.7053 0.31531 0.0281739 0.149502 0.936715 +VERTEX_SE3:QUAT 1179 110.557 78.2365 52.1123 0.319201 0.0112471 0.208402 0.92442 +VERTEX_SE3:QUAT 1180 105.119 86.7922 59.3964 0.326328 -0.00335378 0.263712 0.907719 +VERTEX_SE3:QUAT 1181 98.4394 94.5569 66.5877 0.325843 -0.0237569 0.3247 0.887599 +VERTEX_SE3:QUAT 1182 90.4191 101.351 73.3879 0.324637 -0.0459971 0.381845 0.864112 +VERTEX_SE3:QUAT 1183 81.2415 107.109 79.6496 0.321228 -0.0568211 0.437594 0.837911 +VERTEX_SE3:QUAT 1184 71.1344 111.742 85.4071 0.317906 -0.0747826 0.497699 0.803517 +VERTEX_SE3:QUAT 1185 60.1517 114.969 90.4755 0.311554 -0.0821831 0.551552 0.769396 +VERTEX_SE3:QUAT 1186 48.594 116.859 94.9102 0.29752 -0.087843 0.601757 0.735971 +VERTEX_SE3:QUAT 1187 36.6512 117.497 98.6317 0.293708 -0.0938717 0.651395 0.693259 +VERTEX_SE3:QUAT 1188 24.5458 116.596 101.738 0.288041 -0.116677 0.697276 0.64593 +VERTEX_SE3:QUAT 1189 12.4182 114.244 103.864 0.280436 -0.130448 0.738935 0.598594 +VERTEX_SE3:QUAT 1190 0.529311 110.535 105.142 0.266675 -0.134949 0.777407 0.553454 +VERTEX_SE3:QUAT 1191 -10.9418 105.577 105.704 0.258625 -0.142415 0.817506 0.494484 +VERTEX_SE3:QUAT 1192 -21.6848 99.1427 105.49 0.251447 -0.158915 0.847833 0.438976 +VERTEX_SE3:QUAT 1193 -31.6377 91.6075 104.372 0.243666 -0.176962 0.874494 0.380225 +VERTEX_SE3:QUAT 1194 -40.5966 83.096 102.332 0.244646 -0.190268 0.895062 0.320641 +VERTEX_SE3:QUAT 1195 -48.4233 73.7269 99.5409 0.229572 -0.194874 0.918259 0.257139 +VERTEX_SE3:QUAT 1196 -54.8755 63.5639 96.0741 0.221098 -0.208093 0.931047 0.202396 +VERTEX_SE3:QUAT 1197 -60.115 52.9765 91.9046 0.20152 -0.212484 0.944328 0.14995 +VERTEX_SE3:QUAT 1198 -64.0586 42.0375 87.2201 0.180671 -0.218587 0.95444 0.0928547 +VERTEX_SE3:QUAT 1199 -66.573 30.8878 82.0628 0.168771 -0.234321 0.956831 0.0329203 +VERTEX_SE3:QUAT 1200 -67.6231 19.8235 76.2729 0.153326 -0.244649 0.956975 -0.0289225 +VERTEX_SE3:QUAT 1201 -67.1534 8.97616 70.0271 0.139614 -0.243867 0.95567 -0.0879315 +VERTEX_SE3:QUAT 1202 -65.1855 -1.64373 63.6332 0.132253 -0.244602 0.949175 -0.147468 +VERTEX_SE3:QUAT 1203 -61.8036 -11.8115 57.1407 0.104131 -0.248134 0.940903 -0.205641 +VERTEX_SE3:QUAT 1204 -56.9387 -21.3622 50.6369 0.0903203 -0.24898 0.926413 -0.267602 +VERTEX_SE3:QUAT 1205 -50.6831 -30.0676 44.1677 0.0732079 -0.249433 0.907525 -0.329881 +VERTEX_SE3:QUAT 1206 -43.0555 -37.7668 37.8597 0.0626197 -0.249056 0.888702 -0.379814 +VERTEX_SE3:QUAT 1207 -34.4786 -44.5115 31.7368 0.0526224 -0.247553 0.865124 -0.433022 +VERTEX_SE3:QUAT 1208 -24.9768 -50.1761 25.8259 0.0330866 -0.240027 0.837736 -0.489378 +VERTEX_SE3:QUAT 1209 -14.512 -54.5783 20.463 -0.0183024 0.241156 -0.805232 0.541396 +VERTEX_SE3:QUAT 1210 -3.38809 -57.5806 15.4802 -0.00383927 0.236719 -0.770812 0.591438 +VERTEX_SE3:QUAT 1211 8.21587 -59.1702 11.0048 0.0110229 0.231334 -0.729824 0.64321 +VERTEX_SE3:QUAT 1212 20.1411 -59.2401 7.11745 0.0183638 0.220208 -0.684032 0.695177 +VERTEX_SE3:QUAT 1213 32.1532 -57.6788 3.84465 0.0347557 0.224375 -0.643938 0.73061 +VERTEX_SE3:QUAT 1214 44.0486 -54.8321 1.07918 0.0504098 0.211232 -0.589997 0.777652 +VERTEX_SE3:QUAT 1215 55.5883 -50.3494 -0.842799 0.0674166 0.207339 -0.535976 0.815595 +VERTEX_SE3:QUAT 1216 66.5989 -44.4478 -2.0094 0.0755249 0.198124 -0.48133 0.850508 +VERTEX_SE3:QUAT 1217 76.8411 -37.2335 -2.55481 0.0937266 0.188465 -0.436453 0.87476 +VERTEX_SE3:QUAT 1218 86.3973 -29.0891 -2.32161 0.107143 0.18181 -0.379652 0.900739 +VERTEX_SE3:QUAT 1219 94.9228 -19.9164 -1.39898 0.114083 0.173495 -0.323039 0.923326 +VERTEX_SE3:QUAT 1220 102.279 -9.8518 0.0519431 0.122395 0.161826 -0.265433 0.942538 +VERTEX_SE3:QUAT 1221 108.389 0.920838 2.06774 0.126994 0.155049 -0.209254 0.957103 +VERTEX_SE3:QUAT 1222 113.165 12.2755 4.4752 0.125239 0.139272 -0.144686 0.971589 +VERTEX_SE3:QUAT 1223 116.361 24.1034 7.17852 0.138816 0.121962 -0.0871823 0.978905 +VERTEX_SE3:QUAT 1224 118.152 36.0829 10.4488 0.154321 0.111289 -0.0307493 0.981251 +VERTEX_SE3:QUAT 1225 118.561 48.0394 14.2544 0.16171 0.0973866 0.0303921 0.981551 +VERTEX_SE3:QUAT 1226 117.429 59.8417 18.3536 0.175295 0.0980533 0.0824506 0.976145 +VERTEX_SE3:QUAT 1227 115.057 71.3052 22.8737 0.180639 0.0852232 0.149888 0.968318 +VERTEX_SE3:QUAT 1228 111.057 82.2176 27.5534 0.185306 0.0764341 0.209524 0.957037 +VERTEX_SE3:QUAT 1229 105.65 92.4781 32.3433 0.184443 0.0706627 0.264044 0.94407 +VERTEX_SE3:QUAT 1230 99.0424 102.015 37.1028 0.189985 0.0588216 0.332917 0.921744 +VERTEX_SE3:QUAT 1231 91.0134 110.42 41.8992 0.20165 0.0506255 0.392103 0.896119 +VERTEX_SE3:QUAT 1232 81.9026 117.537 46.7621 0.211329 0.0395281 0.449489 0.867028 +VERTEX_SE3:QUAT 1233 71.8568 123.281 51.5972 0.202347 0.0229447 0.503503 0.839651 +VERTEX_SE3:QUAT 1234 60.9686 127.801 55.9175 0.201803 0.0170549 0.555556 0.806438 +VERTEX_SE3:QUAT 1235 49.4921 130.895 59.9878 0.211905 0.00960037 0.601113 0.770498 +VERTEX_SE3:QUAT 1236 37.6885 132.55 63.9345 0.213093 -0.00382774 0.65032 0.72915 +VERTEX_SE3:QUAT 1237 25.6307 132.628 67.4267 0.208655 -0.016318 0.696375 0.686483 +VERTEX_SE3:QUAT 1238 13.5033 131.193 70.381 0.205615 -0.0246464 0.735494 0.645107 +VERTEX_SE3:QUAT 1239 1.5141 128.395 72.8857 0.20325 -0.0351863 0.774008 0.598635 +VERTEX_SE3:QUAT 1240 -10.1616 124.198 74.8678 0.198973 -0.0461815 0.809135 0.550978 +VERTEX_SE3:QUAT 1241 -21.3406 118.66 76.2815 0.195923 -0.0581624 0.83809 0.505802 +VERTEX_SE3:QUAT 1242 -31.9394 112.008 77.1344 0.188929 -0.072399 0.872763 0.444239 +VERTEX_SE3:QUAT 1243 -41.6343 104.011 77.2197 0.18479 -0.0936379 0.902133 0.378472 +VERTEX_SE3:QUAT 1244 -50.1454 94.8212 76.4495 0.172245 -0.104396 0.927496 0.314936 +VERTEX_SE3:QUAT 1245 -57.3571 84.6435 74.9734 0.166455 -0.110645 0.945272 0.257899 +VERTEX_SE3:QUAT 1246 -63.3258 73.7539 73.0396 0.15673 -0.123029 0.961039 0.191583 +VERTEX_SE3:QUAT 1247 -67.7693 62.2902 70.4384 0.151649 -0.126151 0.972658 0.122574 +VERTEX_SE3:QUAT 1248 -70.536 50.4194 67.4506 0.141942 -0.136212 0.979034 0.0528337 +VERTEX_SE3:QUAT 1249 -71.6046 38.412 63.931 0.129119 -0.142526 0.981326 -0.00364409 +VERTEX_SE3:QUAT 1250 -71.2454 26.4579 60.0899 0.119215 -0.153259 0.978784 -0.0654383 +VERTEX_SE3:QUAT 1251 -69.3721 14.7629 55.8525 0.109133 -0.169793 0.970066 -0.135025 +VERTEX_SE3:QUAT 1252 -65.8518 3.68621 51.1191 0.102293 -0.18365 0.960133 -0.184267 +VERTEX_SE3:QUAT 1253 -61.1883 -6.80917 46.0115 0.0998861 -0.190953 0.945599 -0.243725 +VERTEX_SE3:QUAT 1254 -55.2491 -16.5012 40.688 0.0892487 -0.196405 0.930293 -0.296671 +VERTEX_SE3:QUAT 1255 -48.1659 -25.3638 35.2898 0.0700734 -0.190905 0.914012 -0.351038 +VERTEX_SE3:QUAT 1256 -39.8957 -33.3293 30.1925 0.0498256 -0.191705 0.891382 -0.407681 +VERTEX_SE3:QUAT 1257 -30.5382 -40.1615 25.3113 0.0363415 -0.189693 0.864912 -0.463274 +VERTEX_SE3:QUAT 1258 -20.2417 -45.7412 20.7434 -0.016077 0.190774 -0.834749 0.516276 +VERTEX_SE3:QUAT 1259 -9.17464 -49.9644 16.5414 -0.00814037 0.191592 -0.801827 0.565951 +VERTEX_SE3:QUAT 1260 2.42464 -52.7951 12.5971 0.0130452 0.200874 -0.761228 0.616451 +VERTEX_SE3:QUAT 1261 14.4017 -54.0121 9.06265 0.0214857 0.200807 -0.720883 0.66298 +VERTEX_SE3:QUAT 1262 26.5526 -53.7094 5.87912 0.0330766 0.194298 -0.669609 0.716085 +VERTEX_SE3:QUAT 1263 38.6876 -51.6498 3.33912 0.0570665 0.185233 -0.633816 0.748806 +VERTEX_SE3:QUAT 1264 50.7311 -48.4852 1.61313 0.0673206 0.184783 -0.582395 0.788758 +VERTEX_SE3:QUAT 1265 62.3301 -43.835 0.428196 0.0796371 0.179003 -0.522735 0.829677 +VERTEX_SE3:QUAT 1266 73.1958 -37.5959 -0.0903261 0.0933012 0.174363 -0.471336 0.859497 +VERTEX_SE3:QUAT 1267 83.3207 -30.2169 0.0414377 0.0995511 0.169412 -0.423405 0.884374 +VERTEX_SE3:QUAT 1268 92.6429 -21.8275 0.617867 0.105311 0.160451 -0.367077 0.910176 +VERTEX_SE3:QUAT 1269 100.874 -12.4057 1.7112 0.113061 0.156678 -0.304675 0.932653 +VERTEX_SE3:QUAT 1270 107.803 -2.05318 3.29199 0.115365 0.149034 -0.242844 0.951581 +VERTEX_SE3:QUAT 1271 113.342 9.05264 5.27019 0.125028 0.128676 -0.180318 0.967107 +VERTEX_SE3:QUAT 1272 117.38 20.6666 7.82293 0.132444 0.114414 -0.115473 0.97777 +VERTEX_SE3:QUAT 1273 119.814 32.6081 10.7939 0.148102 0.103432 -0.0520899 0.982168 +VERTEX_SE3:QUAT 1274 120.676 44.6294 14.3399 0.15189 0.0908443 0.00172046 0.984212 +VERTEX_SE3:QUAT 1275 120.161 56.5943 18.0855 0.145854 0.0843152 0.0638648 0.983636 +VERTEX_SE3:QUAT 1276 118.097 68.4303 21.8058 0.147324 0.0835564 0.121682 0.978012 +VERTEX_SE3:QUAT 1277 114.652 79.8705 25.6227 0.153295 0.0701554 0.181246 0.96888 +VERTEX_SE3:QUAT 1278 109.757 90.736 29.5756 0.159943 0.0541136 0.233964 0.957471 +VERTEX_SE3:QUAT 1279 103.643 100.935 33.5964 0.157843 0.0393725 0.293007 0.942169 +VERTEX_SE3:QUAT 1280 96.2129 110.283 37.4372 0.152244 0.0258911 0.344075 0.926155 +VERTEX_SE3:QUAT 1281 87.7107 118.802 41.0191 0.157019 0.0152205 0.413498 0.896734 +VERTEX_SE3:QUAT 1282 77.9461 125.882 44.4813 0.157162 0.00223327 0.479169 0.863535 +VERTEX_SE3:QUAT 1283 67.1607 131.408 47.6568 0.156492 -0.016206 0.531165 0.832533 +VERTEX_SE3:QUAT 1284 55.6545 135.616 50.4024 0.146424 -0.0230283 0.578131 0.802368 +VERTEX_SE3:QUAT 1285 43.6645 138.568 52.6896 0.149685 -0.0348381 0.630368 0.760931 +VERTEX_SE3:QUAT 1286 31.3473 139.877 54.6489 0.13699 -0.0441728 0.676372 0.72236 +VERTEX_SE3:QUAT 1287 18.866 139.732 56.0354 0.126814 -0.0538169 0.724665 0.67519 +VERTEX_SE3:QUAT 1288 6.46773 137.98 56.8374 0.118744 -0.0551632 0.764228 0.631516 +VERTEX_SE3:QUAT 1289 -5.66958 134.814 57.2977 0.106116 -0.0688262 0.799847 0.586725 +VERTEX_SE3:QUAT 1290 -17.3863 130.354 57.1088 0.0998847 -0.0756875 0.836192 0.533927 +VERTEX_SE3:QUAT 1291 -28.4536 124.447 56.5059 0.0981365 -0.0970357 0.868131 0.476761 +VERTEX_SE3:QUAT 1292 -38.6588 117.247 55.1966 0.0901021 -0.107451 0.89861 0.415735 +VERTEX_SE3:QUAT 1293 -47.7525 108.82 53.3452 0.0768109 -0.112093 0.92459 0.355905 +VERTEX_SE3:QUAT 1294 -55.6313 99.3268 51.0998 0.0635777 -0.117899 0.943175 0.304103 +VERTEX_SE3:QUAT 1295 -62.386 89.0795 48.4786 0.0608108 -0.126289 0.960013 0.242339 +VERTEX_SE3:QUAT 1296 -67.7406 78.1169 45.5209 0.050102 -0.135409 0.973835 0.175497 +VERTEX_SE3:QUAT 1297 -71.4412 66.6266 42.1674 0.0420406 -0.135646 0.98334 0.113465 +VERTEX_SE3:QUAT 1298 -73.6207 54.7868 38.6987 0.0196158 -0.14446 0.988138 0.0482678 +VERTEX_SE3:QUAT 1299 -74.0981 42.8402 34.9266 0.0113885 -0.146013 0.989146 -0.0118354 +VERTEX_SE3:QUAT 1300 -73.0572 30.9337 31.1213 -0.00108388 -0.150332 0.985264 -0.0815753 +VERTEX_SE3:QUAT 1301 -70.2853 19.338 27.2724 -0.0209233 -0.158698 0.977008 -0.140827 +VERTEX_SE3:QUAT 1302 -66.0087 8.21925 23.379 -0.023799 -0.167383 0.964308 -0.203782 +VERTEX_SE3:QUAT 1303 -60.2797 -2.19557 19.3764 -0.0344631 -0.161893 0.951392 -0.259724 +VERTEX_SE3:QUAT 1304 -53.2979 -11.9202 15.6804 -0.0362928 -0.159345 0.93518 -0.314214 +VERTEX_SE3:QUAT 1305 -45.1787 -20.8106 12.1937 -0.0561652 -0.161982 0.911016 -0.375043 +VERTEX_SE3:QUAT 1306 -35.8555 -28.5438 9.02696 -0.0666306 -0.1621 0.885099 -0.431141 +VERTEX_SE3:QUAT 1307 -25.5644 -35.0886 6.18455 -0.0690634 -0.162331 0.855281 -0.487209 +VERTEX_SE3:QUAT 1308 -14.4713 -40.2859 3.59546 0.0757752 0.161459 -0.822652 0.539845 +VERTEX_SE3:QUAT 1309 -2.75673 -44.1165 1.33958 0.0850894 0.166512 -0.782132 0.594393 +VERTEX_SE3:QUAT 1310 9.40003 -46.3267 -0.557562 0.0913412 0.165909 -0.738633 0.646956 +VERTEX_SE3:QUAT 1311 21.8208 -46.9026 -2.0442 0.0963101 0.165256 -0.696172 0.691924 +VERTEX_SE3:QUAT 1312 34.2465 -45.9633 -3.13865 0.100523 0.157874 -0.654995 0.732088 +VERTEX_SE3:QUAT 1313 46.5155 -43.6543 -3.76772 0.112027 0.145295 -0.611032 0.770052 +VERTEX_SE3:QUAT 1314 58.4849 -40.0204 -3.71271 0.11283 0.142487 -0.56631 0.803903 +VERTEX_SE3:QUAT 1315 70.0004 -35.1297 -3.36613 0.118573 0.139272 -0.510189 0.840388 +VERTEX_SE3:QUAT 1316 80.7602 -28.7733 -2.57235 0.123581 0.138125 -0.451704 0.872704 +VERTEX_SE3:QUAT 1317 90.5796 -21.1016 -1.33055 0.123488 0.13496 -0.392344 0.901445 +VERTEX_SE3:QUAT 1318 99.2898 -12.2463 0.208812 0.119962 0.130844 -0.335133 0.925297 +VERTEX_SE3:QUAT 1319 106.823 -2.40993 1.96219 0.123173 0.119862 -0.274123 0.946212 +VERTEX_SE3:QUAT 1320 112.996 8.25478 4.09327 0.132651 0.111347 -0.216063 0.960897 +VERTEX_SE3:QUAT 1321 117.838 19.4896 6.69773 0.134568 0.0999279 -0.157266 0.973228 +VERTEX_SE3:QUAT 1322 121.237 31.1765 9.56498 0.135425 0.092237 -0.0900598 0.982365 +VERTEX_SE3:QUAT 1323 122.964 43.1591 12.6547 0.134339 0.0837026 -0.0355887 0.986752 +VERTEX_SE3:QUAT 1324 123.33 55.2435 15.8413 0.124596 0.0775211 0.0305078 0.988704 +VERTEX_SE3:QUAT 1325 122.018 67.2858 18.8933 0.1254 0.0643572 0.0939191 0.985552 +VERTEX_SE3:QUAT 1326 119.115 79.0532 22.0216 0.129516 0.0566102 0.164136 0.976258 +VERTEX_SE3:QUAT 1327 114.523 90.2329 25.2683 0.1379 0.0462122 0.221059 0.964355 +VERTEX_SE3:QUAT 1328 108.645 100.718 28.6629 0.132022 0.0283149 0.276309 0.951537 +VERTEX_SE3:QUAT 1329 101.495 110.471 31.7823 0.130112 0.0175439 0.329119 0.935117 +VERTEX_SE3:QUAT 1330 93.2466 119.384 34.7287 0.123302 0.00585851 0.38453 0.914822 +VERTEX_SE3:QUAT 1331 83.9183 127.281 37.3204 0.111086 -0.00668748 0.44931 0.886417 +VERTEX_SE3:QUAT 1332 73.4858 133.813 39.4 0.098945 -0.0183135 0.507076 0.856008 +VERTEX_SE3:QUAT 1333 62.2263 138.976 40.9799 0.100831 -0.0253639 0.560425 0.821653 +VERTEX_SE3:QUAT 1334 50.386 142.702 42.3717 0.0869649 -0.0304817 0.612621 0.784986 +VERTEX_SE3:QUAT 1335 38.1307 144.909 43.2772 0.0737 -0.039792 0.659627 0.746911 +VERTEX_SE3:QUAT 1336 25.6855 145.666 43.6534 0.0601636 -0.0498013 0.705968 0.703924 +VERTEX_SE3:QUAT 1337 13.219 144.874 43.504 0.0512988 -0.0516803 0.749247 0.658275 +VERTEX_SE3:QUAT 1338 0.969682 142.549 43.0524 0.0390234 -0.0627267 0.787155 0.612315 +VERTEX_SE3:QUAT 1339 -10.9011 138.809 42.1247 0.0377065 -0.073366 0.821752 0.563843 +VERTEX_SE3:QUAT 1340 -22.2385 133.726 40.8188 0.0216847 -0.0801132 0.854394 0.512955 +VERTEX_SE3:QUAT 1341 -32.8344 127.343 39.0868 0.016805 -0.0920646 0.880866 0.464022 +VERTEX_SE3:QUAT 1342 -42.581 119.878 36.9476 0.00880577 -0.0922907 0.906236 0.412482 +VERTEX_SE3:QUAT 1343 -51.3842 111.326 34.6774 -0.000919612 -0.0990194 0.926843 0.362155 +VERTEX_SE3:QUAT 1344 -59.135 101.902 32.1049 -0.0147579 -0.105681 0.946878 0.303375 +VERTEX_SE3:QUAT 1345 -65.5873 91.6154 29.2576 -0.0269429 -0.102033 0.965432 0.238335 +VERTEX_SE3:QUAT 1346 -70.5308 80.5287 26.4358 -0.0311181 -0.106591 0.977898 0.177159 +VERTEX_SE3:QUAT 1347 -74.0114 68.9287 23.5235 -0.0409066 -0.111853 0.987046 0.107497 +VERTEX_SE3:QUAT 1348 -75.7479 56.9751 20.4975 -0.0508545 -0.114666 0.991098 0.0446228 +VERTEX_SE3:QUAT 1349 -75.9051 44.9027 17.4646 -0.0568392 -0.113534 0.99151 -0.028047 +VERTEX_SE3:QUAT 1350 -74.2708 32.9132 14.5866 -0.0506327 -0.115198 0.988468 -0.0842467 +VERTEX_SE3:QUAT 1351 -71.2916 21.1728 11.7345 -0.0551513 -0.118379 0.979783 -0.151557 +VERTEX_SE3:QUAT 1352 -66.6791 9.96467 8.94906 -0.0530272 -0.121677 0.966809 -0.218317 +VERTEX_SE3:QUAT 1353 -60.5637 -0.513657 6.22177 -0.0565567 -0.121599 0.950804 -0.27926 +VERTEX_SE3:QUAT 1354 -53.1117 -10.1698 3.65538 -0.0618381 -0.120129 0.932653 -0.334521 +VERTEX_SE3:QUAT 1355 -44.5706 -18.9157 1.32206 -0.0730893 -0.123902 0.903433 -0.403875 +VERTEX_SE3:QUAT 1356 -34.7485 -26.2728 -0.76096 -0.0850614 -0.124931 0.874129 -0.46158 +VERTEX_SE3:QUAT 1357 -24.0267 -32.3299 -2.51263 0.0893502 0.126648 -0.841959 0.516799 +VERTEX_SE3:QUAT 1358 -12.5936 -36.9901 -4.01018 0.0899829 0.126637 -0.805515 0.57185 +VERTEX_SE3:QUAT 1359 -0.619233 -40.1257 -5.26483 0.0890974 0.133852 -0.766697 0.621547 +VERTEX_SE3:QUAT 1360 11.6649 -41.718 -6.41406 0.0947834 0.12843 -0.72446 0.670582 +VERTEX_SE3:QUAT 1361 24.0911 -41.7507 -7.10565 0.098906 0.133302 -0.677641 0.716415 +VERTEX_SE3:QUAT 1362 36.4124 -40.1583 -7.56244 0.105385 0.132046 -0.630754 0.757369 +VERTEX_SE3:QUAT 1363 48.4547 -37.1055 -7.61742 0.103888 0.137271 -0.580142 0.796115 +VERTEX_SE3:QUAT 1364 60.0296 -32.5332 -7.49989 0.0991503 0.125243 -0.534335 0.830042 +VERTEX_SE3:QUAT 1365 71.0245 -26.7156 -7.10717 0.1043 0.123458 -0.478285 0.863205 +VERTEX_SE3:QUAT 1366 81.1654 -19.5558 -6.32339 0.10256 0.117829 -0.425333 0.891454 +VERTEX_SE3:QUAT 1367 90.3662 -11.287 -5.31527 0.105385 0.124927 -0.363721 0.917057 +VERTEX_SE3:QUAT 1368 98.391 -1.88832 -4.03035 0.0986099 0.118705 -0.305599 0.939571 +VERTEX_SE3:QUAT 1369 105.132 8.43396 -2.64939 0.0956411 0.118576 -0.244644 0.957571 +VERTEX_SE3:QUAT 1370 110.534 19.5206 -1.12708 0.0959899 0.108381 -0.183975 0.97221 +VERTEX_SE3:QUAT 1371 114.465 31.1424 0.654207 0.091172 0.105297 -0.123156 0.982564 +VERTEX_SE3:QUAT 1372 116.931 43.1685 2.4975 0.0912068 0.104266 -0.0630017 0.988353 +VERTEX_SE3:QUAT 1373 117.911 55.4022 4.4922 0.0820333 0.0931162 -0.0115812 0.992202 +VERTEX_SE3:QUAT 1374 117.572 67.6757 6.39802 0.091173 0.0943086 0.053904 0.989893 +VERTEX_SE3:QUAT 1375 115.665 79.701 8.65372 0.0855958 0.0901858 0.116791 0.985342 +VERTEX_SE3:QUAT 1376 112.228 91.4013 10.8825 0.0807003 0.0932471 0.167614 0.978109 +VERTEX_SE3:QUAT 1377 107.606 102.683 13.0888 0.0695649 0.089347 0.234158 0.965582 +VERTEX_SE3:QUAT 1378 101.435 113.258 15.1354 0.060732 0.0824603 0.293993 0.950305 +VERTEX_SE3:QUAT 1379 93.9843 122.968 17.0349 0.0617641 0.073464 0.357165 0.929097 +VERTEX_SE3:QUAT 1380 85.2724 131.586 18.9276 0.0599128 0.0691963 0.409414 0.907746 +VERTEX_SE3:QUAT 1381 75.6501 139.147 20.777 0.0555852 0.0600683 0.469563 0.879098 +VERTEX_SE3:QUAT 1382 65.0765 145.346 22.4814 0.0548965 0.0473488 0.528499 0.845833 +VERTEX_SE3:QUAT 1383 53.7225 150.041 24.0166 0.0482418 0.0337574 0.585672 0.808406 +VERTEX_SE3:QUAT 1384 41.8157 153.142 25.2226 0.0406279 0.0200679 0.634373 0.771698 +VERTEX_SE3:QUAT 1385 29.5573 154.767 26.0566 0.0285153 0.0199154 0.68057 0.731857 +VERTEX_SE3:QUAT 1386 17.2225 154.893 26.6509 0.0274676 0.0209236 0.724405 0.688509 +VERTEX_SE3:QUAT 1387 4.958 153.511 27.223 0.0266709 0.00718467 0.767028 0.641019 +VERTEX_SE3:QUAT 1388 -7.05799 150.564 27.5021 0.0236037 -0.00691924 0.803684 0.594547 +VERTEX_SE3:QUAT 1389 -18.6365 146.256 27.421 0.0114088 -0.000896292 0.83777 0.545904 +VERTEX_SE3:QUAT 1390 -29.6252 140.573 27.2519 0.00941951 -0.00621958 0.870192 0.492584 +VERTEX_SE3:QUAT 1391 -39.817 133.572 26.9357 -0.00163978 -0.0242238 0.894735 0.445937 +VERTEX_SE3:QUAT 1392 -49.1829 125.556 26.1074 -0.00304938 -0.028976 0.916745 0.398408 +VERTEX_SE3:QUAT 1393 -57.6619 116.62 25.1443 -0.0150751 -0.0394817 0.941541 0.334238 +VERTEX_SE3:QUAT 1394 -64.7938 106.618 23.8257 -0.0161568 -0.0531977 0.957556 0.282835 +VERTEX_SE3:QUAT 1395 -70.7836 95.948 22.1965 -0.0283056 -0.0564587 0.972461 0.224345 +VERTEX_SE3:QUAT 1396 -75.4048 84.6398 20.4518 -0.0335614 -0.0551067 0.985009 0.159984 +VERTEX_SE3:QUAT 1397 -78.4967 72.8115 18.7433 -0.0378351 -0.0726552 0.991762 0.098481 +VERTEX_SE3:QUAT 1398 -80.0518 60.7598 16.6501 -0.0355905 -0.0825853 0.995443 0.0317225 +VERTEX_SE3:QUAT 1399 -79.9639 48.6168 14.373 -0.0425785 -0.0894255 0.994765 -0.0251626 +VERTEX_SE3:QUAT 1400 -78.4823 36.5916 12.0135 -0.0481532 -0.10012 0.990855 -0.0765752 +VERTEX_SE3:QUAT 1401 -75.7312 24.8466 9.48412 -0.055943 -0.101781 0.983537 -0.138441 +VERTEX_SE3:QUAT 1402 -71.4931 13.5238 7.02743 -0.0606394 -0.106695 0.972347 -0.198699 +VERTEX_SE3:QUAT 1403 -65.8681 2.82087 4.62615 -0.0621032 -0.116412 0.958286 -0.253532 +VERTEX_SE3:QUAT 1404 -59.0541 -7.11819 2.12282 -0.0581484 -0.120991 0.941529 -0.309035 +VERTEX_SE3:QUAT 1405 -51.1077 -16.1984 -0.355689 -0.0605011 -0.12455 0.920105 -0.366379 +VERTEX_SE3:QUAT 1406 -42.0733 -24.2391 -2.73696 -0.0659172 -0.138445 0.892776 -0.423603 +VERTEX_SE3:QUAT 1407 -32.076 -31.0109 -5.16645 -0.0763679 -0.141044 0.86659 -0.472543 +VERTEX_SE3:QUAT 1408 -21.3515 -36.6272 -7.34931 0.0832005 0.155792 -0.833217 0.523981 +VERTEX_SE3:QUAT 1409 -10.0001 -40.8311 -9.48391 0.0817267 0.164564 -0.79487 0.578291 +VERTEX_SE3:QUAT 1410 1.82579 -43.4617 -11.5586 0.0757764 0.165404 -0.754921 0.630074 +VERTEX_SE3:QUAT 1411 13.9389 -44.5228 -13.4563 0.0818021 0.171586 -0.714621 0.673189 +VERTEX_SE3:QUAT 1412 26.1104 -44.1616 -15.1038 0.0869406 0.180486 -0.673798 0.711241 +VERTEX_SE3:QUAT 1413 38.1857 -42.4206 -16.5365 0.082091 0.18439 -0.625385 0.753761 +VERTEX_SE3:QUAT 1414 49.9569 -39.1234 -17.8238 0.0863197 0.19064 -0.56884 0.795378 +VERTEX_SE3:QUAT 1415 61.1862 -34.2239 -18.751 0.0736835 0.18312 -0.512281 0.835826 +VERTEX_SE3:QUAT 1416 71.646 -27.8295 -19.5339 0.0720589 0.182171 -0.456402 0.867939 +VERTEX_SE3:QUAT 1417 81.2076 -20.1724 -20.0225 0.0681331 0.187505 -0.402818 0.893274 +VERTEX_SE3:QUAT 1418 89.7923 -11.4151 -20.3558 0.069249 0.18784 -0.343065 0.917729 +VERTEX_SE3:QUAT 1419 97.2102 -1.64153 -20.3567 0.0619054 0.190064 -0.283707 0.937845 +VERTEX_SE3:QUAT 1420 103.359 8.98238 -20.2355 0.0588666 0.178908 -0.236507 0.9532 +VERTEX_SE3:QUAT 1421 108.417 20.1377 -19.9032 0.053734 0.171761 -0.178734 0.967298 +VERTEX_SE3:QUAT 1422 112.119 31.8241 -19.3912 0.0479106 0.16441 -0.118451 0.978082 +VERTEX_SE3:QUAT 1423 114.367 43.8713 -18.7496 0.0447216 0.158691 -0.0526378 0.984909 +VERTEX_SE3:QUAT 1424 115.023 56.0777 -17.8951 0.0409253 0.152082 0.00897745 0.987479 +VERTEX_SE3:QUAT 1425 114.154 68.2602 -16.9321 0.0316988 0.142453 0.0618629 0.987358 +VERTEX_SE3:QUAT 1426 111.971 80.2625 -16.018 0.0277606 0.144138 0.122304 0.981578 +VERTEX_SE3:QUAT 1427 108.359 91.9396 -14.9817 0.0223392 0.153892 0.186518 0.970067 +VERTEX_SE3:QUAT 1428 103.281 103.025 -13.8105 0.0167261 0.140786 0.253418 0.956911 +VERTEX_SE3:QUAT 1429 96.7112 113.314 -12.631 -0.00242057 0.128009 0.306712 0.943152 +VERTEX_SE3:QUAT 1430 88.9839 122.782 -11.8309 -0.00561999 0.132939 0.3683 0.920136 +VERTEX_SE3:QUAT 1431 80.1023 131.126 -10.8685 -0.0135064 0.124621 0.421022 0.898347 +VERTEX_SE3:QUAT 1432 70.3015 138.381 -9.99665 -0.0185777 0.128587 0.479599 0.867816 +VERTEX_SE3:QUAT 1433 59.6564 144.315 -8.99658 -0.0201876 0.118179 0.537314 0.834817 +VERTEX_SE3:QUAT 1434 48.3036 148.726 -7.98748 -0.0260826 0.123172 0.589125 0.798173 +VERTEX_SE3:QUAT 1435 36.5088 151.688 -6.83974 -0.0349477 0.120002 0.645493 0.75347 +VERTEX_SE3:QUAT 1436 24.4137 152.905 -5.73429 -0.0378264 0.109302 0.699002 0.705704 +VERTEX_SE3:QUAT 1437 12.2662 152.364 -4.67877 -0.0422379 0.103874 0.738692 0.66465 +VERTEX_SE3:QUAT 1438 0.25675 150.42 -3.64459 -0.0514847 0.0946376 0.780017 0.616414 +VERTEX_SE3:QUAT 1439 -11.4075 146.947 -2.76276 -0.0518485 0.085033 0.812185 0.574837 +VERTEX_SE3:QUAT 1440 -22.6134 142.252 -1.96847 -0.0537904 0.0772799 0.84315 0.529369 +VERTEX_SE3:QUAT 1441 -33.2649 136.329 -1.25144 -0.0545079 0.0676388 0.877194 0.472213 +VERTEX_SE3:QUAT 1442 -43.0197 129.02 -0.61638 -0.0550799 0.0652307 0.906258 0.414014 +VERTEX_SE3:QUAT 1443 -51.7389 120.519 0.0599277 -0.0515962 0.0559626 0.92917 0.36173 +VERTEX_SE3:QUAT 1444 -59.4288 111.079 0.643039 -0.0488971 0.0471302 0.950253 0.303985 +VERTEX_SE3:QUAT 1445 -65.9104 100.752 1.15868 -0.0592683 0.0244768 0.969166 0.23792 +VERTEX_SE3:QUAT 1446 -70.8655 89.6359 1.1893 -0.0617546 0.00677418 0.980278 0.187605 +VERTEX_SE3:QUAT 1447 -74.613 78.0689 0.842283 -0.0586723 -0.00805804 0.990812 0.12159 +VERTEX_SE3:QUAT 1448 -76.7876 66.1038 0.258715 -0.0487476 -0.0164871 0.996761 0.0618021 +VERTEX_SE3:QUAT 1449 -77.4926 53.9687 -0.447609 -0.0515356 -0.0263786 0.998319 0.00284739 +VERTEX_SE3:QUAT 1450 -76.7504 41.8745 -1.32859 -0.0543055 -0.0416424 0.996117 -0.055395 +VERTEX_SE3:QUAT 1451 -74.6051 29.9536 -2.4813 -0.061747 -0.0614252 0.988775 -0.121398 +VERTEX_SE3:QUAT 1452 -70.8656 18.5035 -3.97845 -0.0567465 -0.082895 0.978773 -0.178638 +VERTEX_SE3:QUAT 1453 -65.8066 7.639 -5.90962 -0.0605231 -0.0971018 0.965875 -0.232367 +VERTEX_SE3:QUAT 1454 -59.5309 -2.53256 -8.02986 -0.065563 -0.115458 0.946437 -0.294325 +VERTEX_SE3:QUAT 1455 -51.9776 -11.749 -10.3791 -0.0727478 -0.136268 0.922128 -0.35471 +VERTEX_SE3:QUAT 1456 -43.2736 -19.8112 -12.932 -0.0822379 -0.151895 0.89155 -0.418692 +VERTEX_SE3:QUAT 1457 -33.4652 -26.4799 -15.478 -0.0907405 -0.172009 0.857936 -0.475525 +VERTEX_SE3:QUAT 1458 -22.8316 -31.6993 -18.0645 0.0959879 0.181939 -0.823901 0.528083 +VERTEX_SE3:QUAT 1459 -11.5899 -35.5112 -20.4964 0.0899694 0.190561 -0.790435 0.575156 +VERTEX_SE3:QUAT 1460 0.0273515 -37.9474 -22.9283 0.0980101 0.210519 -0.750969 0.61816 +VERTEX_SE3:QUAT 1461 11.8676 -38.9307 -25.2731 0.10476 0.220311 -0.709754 0.660862 +VERTEX_SE3:QUAT 1462 23.7936 -38.4843 -27.3431 0.104699 0.231489 -0.664504 0.702769 +VERTEX_SE3:QUAT 1463 35.6047 -36.5382 -29.2426 0.107566 0.233796 -0.614778 0.745532 +VERTEX_SE3:QUAT 1464 47.1151 -33.0837 -30.7135 0.104159 0.236515 -0.559992 0.78716 +VERTEX_SE3:QUAT 1465 58.0822 -28.0809 -31.8686 0.118922 0.236273 -0.504165 0.822101 +VERTEX_SE3:QUAT 1466 68.4098 -21.7632 -32.2917 0.117255 0.239576 -0.452327 0.851032 +VERTEX_SE3:QUAT 1467 77.9207 -14.3088 -32.3913 0.121015 0.241696 -0.392144 0.879296 +VERTEX_SE3:QUAT 1468 86.4151 -5.7257 -32.0131 0.119764 0.238325 -0.332767 0.904502 +VERTEX_SE3:QUAT 1469 93.7638 3.83743 -31.2396 0.116909 0.24171 -0.269787 0.924729 +VERTEX_SE3:QUAT 1470 99.7846 14.2385 -30.1148 0.122375 0.242295 -0.201566 0.94111 +VERTEX_SE3:QUAT 1471 104.345 25.2995 -28.4273 0.116228 0.251335 -0.143261 0.950157 +VERTEX_SE3:QUAT 1472 107.581 36.7705 -26.5548 0.111505 0.247507 -0.0854767 0.958645 +VERTEX_SE3:QUAT 1473 109.439 48.4968 -24.4168 0.119851 0.236321 -0.0196305 0.964055 +VERTEX_SE3:QUAT 1474 109.782 60.2356 -21.6974 0.121895 0.228186 0.0459161 0.964865 +VERTEX_SE3:QUAT 1475 108.589 71.8323 -18.5897 0.124964 0.221214 0.0974438 0.962265 +VERTEX_SE3:QUAT 1476 106.193 83.1545 -15.1722 0.118005 0.210451 0.164832 0.956355 +VERTEX_SE3:QUAT 1477 102.237 93.9873 -11.6549 0.109506 0.190962 0.233231 0.947178 +VERTEX_SE3:QUAT 1478 96.6858 104.106 -8.17887 0.103587 0.181001 0.303158 0.929841 +VERTEX_SE3:QUAT 1479 89.6654 113.237 -4.66877 0.106766 0.168608 0.355278 0.913209 +VERTEX_SE3:QUAT 1480 81.6711 121.465 -1.03136 0.101175 0.151383 0.409729 0.89385 +VERTEX_SE3:QUAT 1481 72.673 128.658 2.44502 0.0966231 0.133214 0.468455 0.868025 +VERTEX_SE3:QUAT 1482 62.7205 134.573 5.73782 0.0828257 0.123791 0.521379 0.840226 +VERTEX_SE3:QUAT 1483 52.0428 139.235 8.71934 0.0574873 0.114204 0.571131 0.810841 +VERTEX_SE3:QUAT 1484 40.7654 142.624 11.1705 0.0442948 0.099156 0.611704 0.783597 +VERTEX_SE3:QUAT 1485 29.1333 144.874 13.1978 0.0391707 0.0895749 0.658394 0.746297 +VERTEX_SE3:QUAT 1486 17.3069 145.698 15.0268 0.0248548 0.0712572 0.708799 0.701362 +VERTEX_SE3:QUAT 1487 5.40355 144.892 16.3536 0.0170574 0.0538713 0.748272 0.660982 +VERTEX_SE3:QUAT 1488 -6.364 142.719 17.2914 0.0107718 0.0359913 0.790428 0.611402 +VERTEX_SE3:QUAT 1489 -17.7669 139.044 17.8021 0.00480547 0.019071 0.829648 0.557941 +VERTEX_SE3:QUAT 1490 -28.5931 133.859 17.9064 -0.00225151 0.0125876 0.86269 0.505572 +VERTEX_SE3:QUAT 1491 -38.6801 127.378 17.7993 -0.0176637 -0.0110061 0.889903 0.455675 +VERTEX_SE3:QUAT 1492 -47.9563 119.816 17.0244 -0.028904 -0.0274434 0.919531 0.390992 +VERTEX_SE3:QUAT 1493 -56.0149 111.012 15.8238 -0.0299222 -0.0444507 0.939261 0.338995 +VERTEX_SE3:QUAT 1494 -63.0228 101.438 14.2573 -0.0413665 -0.0652355 0.956319 0.281934 +VERTEX_SE3:QUAT 1495 -68.7595 91.1458 12.1696 -0.0497607 -0.0865779 0.970046 0.221447 +VERTEX_SE3:QUAT 1496 -73.1053 80.3041 9.58535 -0.0576617 -0.112434 0.978876 0.160735 +VERTEX_SE3:QUAT 1497 -75.9871 69.1312 6.45337 -0.0666518 -0.124383 0.984626 0.102941 +VERTEX_SE3:QUAT 1498 -77.4633 57.7588 3.09616 -0.0834524 -0.135537 0.986536 0.0375808 +VERTEX_SE3:QUAT 1499 -77.3346 46.3214 -0.397307 -0.0896947 -0.148228 0.984514 -0.0267474 +VERTEX_SE3:QUAT 1500 -75.6432 35.0636 -4.02929 -0.100562 -0.160607 0.97839 -0.082736 +VERTEX_SE3:QUAT 1501 -72.5879 24.1459 -7.74597 -0.101735 -0.169135 0.971567 -0.13077 +VERTEX_SE3:QUAT 1502 -68.4286 13.619 -11.5064 -0.112573 -0.180895 0.957154 -0.196114 +VERTEX_SE3:QUAT 1503 -62.7799 3.78004 -15.2453 -0.117773 -0.196287 0.939771 -0.253834 +VERTEX_SE3:QUAT 1504 -55.913 -5.1949 -19.0085 -0.115805 -0.205219 0.919493 -0.314654 +VERTEX_SE3:QUAT 1505 -47.883 -13.1947 -22.7077 -0.122976 -0.223837 0.89254 -0.371682 +VERTEX_SE3:QUAT 1506 -38.8153 -19.9804 -26.4107 -0.132938 -0.237232 0.860436 -0.430928 +VERTEX_SE3:QUAT 1507 -28.8254 -25.4425 -29.9068 -0.137478 -0.245803 0.828787 -0.483522 +VERTEX_SE3:QUAT 1508 -18.1347 -29.6087 -33.1319 0.139999 0.252507 -0.790844 0.539636 +VERTEX_SE3:QUAT 1509 -6.91768 -32.3171 -36.0251 0.143458 0.254799 -0.753592 0.588725 +VERTEX_SE3:QUAT 1510 4.64508 -33.6321 -38.5172 0.140415 0.256645 -0.713046 0.637168 +VERTEX_SE3:QUAT 1511 16.3413 -33.5161 -40.6735 0.14262 0.263852 -0.663938 0.685002 +VERTEX_SE3:QUAT 1512 27.982 -31.799 -42.4315 0.156289 0.262996 -0.617538 0.724606 +VERTEX_SE3:QUAT 1513 39.4165 -28.8071 -43.4865 0.163861 0.271433 -0.561845 0.764071 +VERTEX_SE3:QUAT 1514 50.3956 -24.3334 -44.0075 0.162783 0.27594 -0.51124 0.797492 +VERTEX_SE3:QUAT 1515 60.7715 -18.5937 -44.1455 0.165082 0.27068 -0.457887 0.830554 +VERTEX_SE3:QUAT 1516 70.419 -11.6997 -43.6999 0.166373 0.27572 -0.399043 0.858524 +VERTEX_SE3:QUAT 1517 79.1267 -3.68335 -42.7824 0.172423 0.275474 -0.340043 0.882471 +VERTEX_SE3:QUAT 1518 86.7807 5.24269 -41.2613 0.171398 0.273458 -0.280377 0.904009 +VERTEX_SE3:QUAT 1519 93.2513 14.979 -39.2799 0.169728 0.267255 -0.218505 0.923051 +VERTEX_SE3:QUAT 1520 98.3969 25.3814 -36.8488 0.172697 0.269137 -0.150189 0.935513 +VERTEX_SE3:QUAT 1521 102.092 36.2343 -33.8859 0.163533 0.268568 -0.0897187 0.945029 +VERTEX_SE3:QUAT 1522 104.342 47.4076 -30.7252 0.161899 0.26518 -0.0355869 0.949843 +VERTEX_SE3:QUAT 1523 105.354 58.6632 -27.2647 0.161445 0.256322 0.0232134 0.952731 +VERTEX_SE3:QUAT 1524 105.008 69.8603 -23.4885 0.163264 0.250691 0.0918455 0.94977 +VERTEX_SE3:QUAT 1525 103.121 80.734 -19.2854 0.155578 0.229175 0.148567 0.949317 +VERTEX_SE3:QUAT 1526 99.8599 91.2683 -15.0471 0.144939 0.217142 0.207029 0.942858 +VERTEX_SE3:QUAT 1527 95.2439 101.287 -10.8461 0.142065 0.200646 0.267222 0.931746 +VERTEX_SE3:QUAT 1528 89.3485 110.582 -6.59311 0.136425 0.188119 0.319978 0.918484 +VERTEX_SE3:QUAT 1529 82.3822 119.112 -2.38283 0.133341 0.171029 0.371457 0.902767 +VERTEX_SE3:QUAT 1530 74.4107 126.746 1.73421 0.119711 0.154445 0.424983 0.883858 +VERTEX_SE3:QUAT 1531 65.4583 133.399 5.53808 0.11362 0.136713 0.479297 0.859462 +VERTEX_SE3:QUAT 1532 55.6416 138.886 9.10169 0.0938059 0.111662 0.529036 0.835974 +VERTEX_SE3:QUAT 1533 45.1047 143.222 12.0139 0.080397 0.0948653 0.581277 0.804148 +VERTEX_SE3:QUAT 1534 34.0237 146.221 14.4865 0.0720065 0.0868637 0.627324 0.770541 +VERTEX_SE3:QUAT 1535 22.5951 147.921 16.7136 0.0545359 0.0777922 0.670294 0.735989 +VERTEX_SE3:QUAT 1536 10.9961 148.34 18.5339 0.0374023 0.0556963 0.711793 0.699178 +VERTEX_SE3:QUAT 1537 -0.648075 147.457 19.7077 0.0220177 0.0358306 0.756212 0.652974 +VERTEX_SE3:QUAT 1538 -12.142 145.08 20.3188 0.00425801 0.0238395 0.794712 0.606503 +VERTEX_SE3:QUAT 1539 -23.2456 141.318 20.4459 -0.0072082 0.00207696 0.832303 0.554271 +VERTEX_SE3:QUAT 1540 -33.7817 136.17 20.0383 -0.0252266 -0.00678546 0.866396 0.498674 +VERTEX_SE3:QUAT 1541 -43.5142 129.692 19.2335 -0.0342846 -0.0177531 0.896301 0.441762 +VERTEX_SE3:QUAT 1542 -52.3289 122.008 18.1458 -0.047926 -0.0261341 0.92261 0.381852 +VERTEX_SE3:QUAT 1543 -60.023 113.268 16.8157 -0.0619094 -0.0496311 0.94121 0.328371 +VERTEX_SE3:QUAT 1544 -66.5729 103.751 14.9227 -0.0747284 -0.0662323 0.957278 0.271381 +VERTEX_SE3:QUAT 1545 -71.8659 93.576 12.6681 -0.0820637 -0.0900159 0.968315 0.21801 +VERTEX_SE3:QUAT 1546 -75.9453 82.9651 9.91142 -0.096958 -0.112329 0.976267 0.157749 +VERTEX_SE3:QUAT 1547 -78.5612 72.0168 6.73431 -0.102853 -0.12699 0.981351 0.101222 +VERTEX_SE3:QUAT 1548 -79.8184 60.8918 3.33187 -0.118626 -0.142766 0.981242 0.0520503 +VERTEX_SE3:QUAT 1549 -79.8608 49.7832 -0.313913 -0.139293 -0.152118 0.978437 -0.0108531 +VERTEX_SE3:QUAT 1550 -78.3504 38.7809 -3.92348 -0.154492 -0.167239 0.971214 -0.0700509 +VERTEX_SE3:QUAT 1551 -75.4012 28.0928 -7.59153 -0.155614 -0.18413 0.961971 -0.128421 +VERTEX_SE3:QUAT 1552 -71.1176 17.9244 -11.3616 -0.161116 -0.192326 0.948951 -0.191163 +VERTEX_SE3:QUAT 1553 -65.4816 8.36857 -14.9785 -0.170255 -0.204252 0.930051 -0.253574 +VERTEX_SE3:QUAT 1554 -58.5513 -0.322556 -18.4397 -0.176966 -0.218183 0.907236 -0.313053 +VERTEX_SE3:QUAT 1555 -50.488 -8.02152 -21.773 -0.186179 -0.220714 0.880205 -0.376645 +VERTEX_SE3:QUAT 1556 -41.3266 -14.6158 -24.6404 -0.182799 -0.23251 0.853819 -0.428389 +VERTEX_SE3:QUAT 1557 -31.4174 -20.0499 -27.4145 -0.188478 -0.228766 0.827685 -0.476528 +VERTEX_SE3:QUAT 1558 -20.8853 -24.4705 -29.6985 0.186698 0.239237 -0.791866 0.52996 +VERTEX_SE3:QUAT 1559 -9.84583 -27.489 -31.7621 0.19259 0.244189 -0.750501 0.583121 +VERTEX_SE3:QUAT 1560 1.55818 -29.0519 -33.3373 0.190607 0.253524 -0.711536 0.626985 +VERTEX_SE3:QUAT 1561 13.0759 -29.2571 -34.6763 0.198226 0.251559 -0.671515 0.668201 +VERTEX_SE3:QUAT 1562 24.6063 -28.2541 -35.4306 0.199386 0.254413 -0.624682 0.710839 +VERTEX_SE3:QUAT 1563 35.9351 -25.8602 -35.7297 0.198687 0.251489 -0.573525 0.753887 +VERTEX_SE3:QUAT 1564 46.8641 -22.069 -35.5235 0.197831 0.254054 -0.522277 0.78965 +VERTEX_SE3:QUAT 1565 57.2851 -16.9828 -34.8927 0.188922 0.260108 -0.480319 0.816055 +VERTEX_SE3:QUAT 1566 67.1111 -10.9105 -34.1279 0.184525 0.267968 -0.433514 0.840363 +VERTEX_SE3:QUAT 1567 76.2222 -3.85228 -33.1461 0.179487 0.268987 -0.377402 0.867754 +VERTEX_SE3:QUAT 1568 84.3639 4.26279 -31.7991 0.170163 0.264319 -0.328377 0.890701 +VERTEX_SE3:QUAT 1569 91.5624 13.1582 -30.2386 0.159921 0.256451 -0.267786 0.914849 +VERTEX_SE3:QUAT 1570 97.5068 22.8997 -28.4151 0.147614 0.256871 -0.208399 0.932093 +VERTEX_SE3:QUAT 1571 102.172 33.2857 -26.4501 0.137906 0.249293 -0.147877 0.947084 +VERTEX_SE3:QUAT 1572 105.469 44.1486 -24.2875 0.121854 0.24204 -0.0831275 0.958988 +VERTEX_SE3:QUAT 1573 107.224 55.3539 -22.0937 0.119514 0.239456 -0.0276722 0.963126 +VERTEX_SE3:QUAT 1574 107.727 66.6107 -19.6357 0.123485 0.233167 0.0310624 0.964064 +VERTEX_SE3:QUAT 1575 106.925 77.7499 -16.792 0.0997719 0.225841 0.0844926 0.965351 +VERTEX_SE3:QUAT 1576 104.809 88.7515 -14.2393 0.0933788 0.218781 0.143803 0.960591 +VERTEX_SE3:QUAT 1577 101.36 99.3962 -11.5565 0.093038 0.202726 0.213568 0.951123 +VERTEX_SE3:QUAT 1578 96.405 109.384 -8.66538 0.0751152 0.196642 0.267271 0.940349 +VERTEX_SE3:QUAT 1579 90.2887 118.742 -6.00467 0.0563825 0.186285 0.324273 0.925725 +VERTEX_SE3:QUAT 1580 83.0165 127.316 -3.61741 0.0416701 0.172132 0.380692 0.907583 +VERTEX_SE3:QUAT 1581 74.6868 134.917 -1.45091 0.020903 0.168067 0.432505 0.885582 +VERTEX_SE3:QUAT 1582 65.4877 141.512 0.432247 0.0104607 0.156408 0.485806 0.859895 +VERTEX_SE3:QUAT 1583 55.5276 146.952 2.15294 -0.000586927 0.147731 0.539616 0.828848 +VERTEX_SE3:QUAT 1584 44.9452 151.085 3.72044 -0.0141362 0.131049 0.58938 0.79703 +VERTEX_SE3:QUAT 1585 33.9159 153.872 4.97052 -0.0215956 0.112918 0.635151 0.763784 +VERTEX_SE3:QUAT 1586 22.5867 155.369 5.96748 -0.0370992 0.0968836 0.688251 0.718017 +VERTEX_SE3:QUAT 1587 11.1597 155.221 6.59827 -0.0533113 0.0867055 0.7291 0.676796 +VERTEX_SE3:QUAT 1588 -0.161467 153.712 6.9542 -0.063669 0.0680753 0.76762 0.634091 +VERTEX_SE3:QUAT 1589 -11.2215 150.868 6.93479 -0.0721338 0.048469 0.806257 0.585148 +VERTEX_SE3:QUAT 1590 -21.8387 146.657 6.54432 -0.0882985 0.0363173 0.837411 0.53817 +VERTEX_SE3:QUAT 1591 -31.8699 141.232 5.87252 -0.105869 0.0280592 0.865318 0.48911 +VERTEX_SE3:QUAT 1592 -41.1881 134.701 4.98656 -0.108314 0.0120593 0.895731 0.431033 +VERTEX_SE3:QUAT 1593 -49.5414 127.001 3.87441 -0.122136 -0.0125503 0.917901 0.377336 +VERTEX_SE3:QUAT 1594 -56.8373 118.389 2.28659 -0.132449 -0.0308268 0.934519 0.32891 +VERTEX_SE3:QUAT 1595 -63.1306 109.076 0.380553 -0.148028 -0.052798 0.951507 0.26445 +VERTEX_SE3:QUAT 1596 -68.0093 99.0548 -1.89625 -0.16302 -0.0672612 0.96144 0.211027 +VERTEX_SE3:QUAT 1597 -71.6472 88.5672 -4.35064 -0.173165 -0.080412 0.970257 0.148825 +VERTEX_SE3:QUAT 1598 -73.8697 77.7108 -6.9105 -0.170913 -0.102258 0.976242 0.0853476 +VERTEX_SE3:QUAT 1599 -74.6161 66.7181 -9.70037 -0.178958 -0.118838 0.976392 0.0225907 +VERTEX_SE3:QUAT 1600 -73.8846 55.7583 -12.5728 -0.180972 -0.14205 0.972108 -0.0455736 +VERTEX_SE3:QUAT 1601 -71.5484 45.0868 -15.6734 -0.183233 -0.154623 0.965624 -0.100441 +VERTEX_SE3:QUAT 1602 -67.9881 34.7808 -18.7615 -0.191774 -0.176254 0.951527 -0.163568 +VERTEX_SE3:QUAT 1603 -62.9968 25.1087 -21.9523 -0.193248 -0.187618 0.937338 -0.221025 +VERTEX_SE3:QUAT 1604 -56.8344 16.1194 -25.042 -0.194121 -0.203514 0.91973 -0.273853 +VERTEX_SE3:QUAT 1605 -49.6409 7.92311 -28.1475 -0.184814 -0.214408 0.900902 -0.32901 +VERTEX_SE3:QUAT 1606 -41.5118 0.660663 -31.204 -0.189352 -0.230209 0.87257 -0.387003 +VERTEX_SE3:QUAT 1607 -32.4392 -5.43076 -34.1043 -0.197438 -0.242988 0.845166 -0.433208 +VERTEX_SE3:QUAT 1608 -22.6918 -10.4872 -36.8042 -0.202074 -0.258299 0.813568 -0.480162 +VERTEX_SE3:QUAT 1609 -12.3872 -14.342 -39.315 0.211543 0.271322 -0.774533 0.530785 +VERTEX_SE3:QUAT 1610 -1.59067 -16.8651 -41.4811 0.207774 0.276991 -0.739501 0.577273 +VERTEX_SE3:QUAT 1611 9.47419 -18.1329 -43.328 0.203618 0.283515 -0.699729 0.623328 +VERTEX_SE3:QUAT 1612 20.6506 -18.0706 -44.846 0.202753 0.285365 -0.656018 0.668655 +VERTEX_SE3:QUAT 1613 31.7702 -16.6661 -45.9298 0.205629 0.289489 -0.611415 0.707167 +VERTEX_SE3:QUAT 1614 42.698 -14.0181 -46.5467 0.198526 0.298494 -0.558973 0.747689 +VERTEX_SE3:QUAT 1615 53.194 -9.98113 -46.8694 0.189181 0.296153 -0.503353 0.789392 +VERTEX_SE3:QUAT 1616 63.0505 -4.58039 -46.7728 0.185724 0.301159 -0.451885 0.818908 +VERTEX_SE3:QUAT 1617 72.2154 1.94008 -46.3162 0.179287 0.29921 -0.393662 0.850506 +VERTEX_SE3:QUAT 1618 80.4472 9.57136 -45.4653 0.169971 0.296338 -0.33294 0.878888 +VERTEX_SE3:QUAT 1619 87.5558 18.1534 -44.2616 0.159293 0.298738 -0.268572 0.901804 +VERTEX_SE3:QUAT 1620 93.4255 27.6172 -42.7816 0.152198 0.300006 -0.203523 0.919462 +VERTEX_SE3:QUAT 1621 97.9495 37.722 -40.9653 0.14824 0.300479 -0.156908 0.929041 +VERTEX_SE3:QUAT 1622 101.504 48.1414 -38.9154 0.142681 0.292373 -0.0968644 0.940626 +VERTEX_SE3:QUAT 1623 103.726 58.8566 -36.5435 0.132005 0.288753 -0.0396477 0.94743 +VERTEX_SE3:QUAT 1624 104.657 69.7201 -34.0065 0.11524 0.287553 0.0171619 0.950652 +VERTEX_SE3:QUAT 1625 104.267 80.6096 -31.4831 0.102086 0.28243 0.0832677 0.950199 +VERTEX_SE3:QUAT 1626 102.388 91.3096 -28.8233 0.0911363 0.277563 0.150503 0.944459 +VERTEX_SE3:QUAT 1627 99.0363 101.601 -26.0547 0.0837135 0.262357 0.207988 0.938564 +VERTEX_SE3:QUAT 1628 94.4668 111.362 -23.187 0.0602687 0.251964 0.272298 0.92668 +VERTEX_SE3:QUAT 1629 88.5089 120.417 -20.5381 0.0546934 0.23031 0.329245 0.914092 +VERTEX_SE3:QUAT 1630 81.4805 128.648 -17.8886 0.0378891 0.218975 0.390443 0.893403 +VERTEX_SE3:QUAT 1631 73.3504 135.857 -15.4046 0.0276149 0.209431 0.446482 0.8695 +VERTEX_SE3:QUAT 1632 64.359 141.973 -12.9947 0.0166576 0.189696 0.492797 0.849052 +VERTEX_SE3:QUAT 1633 54.7142 147.091 -10.84 -0.0042544 0.174102 0.533896 0.827421 +VERTEX_SE3:QUAT 1634 44.5373 151.225 -9.09476 -0.0167176 0.158641 0.582335 0.797145 +VERTEX_SE3:QUAT 1635 33.9363 154.117 -7.6075 -0.029751 0.140995 0.624749 0.767414 +VERTEX_SE3:QUAT 1636 23.051 155.835 -6.42846 -0.0410065 0.132335 0.669969 0.729347 +VERTEX_SE3:QUAT 1637 11.9921 156.215 -5.40299 -0.0510185 0.118221 0.711959 0.690315 +VERTEX_SE3:QUAT 1638 0.965794 155.303 -4.6034 -0.067066 0.107422 0.749366 0.649933 +VERTEX_SE3:QUAT 1639 -9.89488 153.136 -4.08451 -0.0803021 0.0924497 0.784003 0.608559 +VERTEX_SE3:QUAT 1640 -20.4515 149.776 -3.86707 -0.0888886 0.0615751 0.815988 0.567865 +VERTEX_SE3:QUAT 1641 -30.5575 145.296 -4.17206 -0.11226 0.0529533 0.847655 0.515824 +VERTEX_SE3:QUAT 1642 -39.9928 139.577 -4.74815 -0.126861 0.0416419 0.872679 0.469685 +VERTEX_SE3:QUAT 1643 -48.7386 132.867 -5.54034 -0.137344 0.0171013 0.899639 0.414118 +VERTEX_SE3:QUAT 1644 -56.5094 125.12 -6.74135 -0.144893 -0.0197895 0.918935 0.366296 +VERTEX_SE3:QUAT 1645 -63.3047 116.626 -8.59374 -0.16656 -0.0339553 0.935777 0.308911 +VERTEX_SE3:QUAT 1646 -68.9329 107.371 -10.6901 -0.171705 -0.0572315 0.948462 0.260118 +VERTEX_SE3:QUAT 1647 -73.485 97.6239 -13.115 -0.192088 -0.0784114 0.956525 0.204975 +VERTEX_SE3:QUAT 1648 -76.771 87.4574 -15.8458 -0.192469 -0.0931644 0.965545 0.148321 +VERTEX_SE3:QUAT 1649 -78.7922 77.002 -18.6435 -0.197639 -0.111815 0.969244 0.0948832 +VERTEX_SE3:QUAT 1650 -79.5946 66.4545 -21.6306 -0.205923 -0.125589 0.970039 0.0291117 +VERTEX_SE3:QUAT 1651 -78.9062 55.8985 -24.603 -0.213393 -0.146467 0.965464 -0.0298325 +VERTEX_SE3:QUAT 1652 -76.8514 45.5624 -27.7114 -0.231178 -0.168455 0.954458 -0.0847943 +VERTEX_SE3:QUAT 1653 -73.5112 35.6041 -30.9016 -0.239286 -0.184572 0.942444 -0.143087 +VERTEX_SE3:QUAT 1654 -68.9089 26.1536 -34.0196 -0.252782 -0.206329 0.9245 -0.197051 +VERTEX_SE3:QUAT 1655 -63.1196 17.3736 -37.1294 -0.256285 -0.2293 0.903357 -0.256294 +VERTEX_SE3:QUAT 1656 -56.1769 9.48942 -40.2141 -0.260104 -0.246362 0.880281 -0.311058 +VERTEX_SE3:QUAT 1657 -48.2587 2.53635 -43.1575 -0.265207 -0.265618 0.852171 -0.364578 +VERTEX_SE3:QUAT 1658 -39.4703 -3.34915 -45.9374 -0.264731 -0.264067 0.823251 -0.427134 +VERTEX_SE3:QUAT 1659 -29.8676 -8.12523 -48.1432 -0.271369 -0.275433 0.789633 -0.476419 +VERTEX_SE3:QUAT 1660 -19.716 -11.7454 -49.9671 0.272686 0.285195 -0.749035 0.532215 +VERTEX_SE3:QUAT 1661 -9.12385 -13.9875 -51.3679 0.269159 0.294408 -0.717286 0.571295 +VERTEX_SE3:QUAT 1662 1.67 -15.1454 -52.5187 0.271871 0.30345 -0.672655 0.617689 +VERTEX_SE3:QUAT 1663 12.5179 -14.9755 -53.1656 0.26759 0.299067 -0.630178 0.664703 +VERTEX_SE3:QUAT 1664 23.3128 -13.5494 -53.2733 0.261041 0.3153 -0.58361 0.701315 +VERTEX_SE3:QUAT 1665 33.8453 -10.8377 -53.1724 0.252359 0.311164 -0.535818 0.74323 +VERTEX_SE3:QUAT 1666 43.9674 -6.87821 -52.6072 0.244983 0.31393 -0.484399 0.778967 +VERTEX_SE3:QUAT 1667 53.5163 -1.76909 -51.6366 0.235606 0.30893 -0.429846 0.815036 +VERTEX_SE3:QUAT 1668 62.2929 4.49924 -50.2576 0.229989 0.308714 -0.374208 0.843664 +VERTEX_SE3:QUAT 1669 70.1839 11.7181 -48.4716 0.21023 0.307688 -0.324766 0.869286 +VERTEX_SE3:QUAT 1670 77.1536 19.8302 -46.6305 0.203881 0.308876 -0.265344 0.890292 +VERTEX_SE3:QUAT 1671 83.0275 28.6735 -44.4255 0.188489 0.296328 -0.20197 0.914259 +VERTEX_SE3:QUAT 1672 87.5745 38.1938 -41.9662 0.174434 0.294053 -0.143051 0.928785 +VERTEX_SE3:QUAT 1673 90.8286 48.1767 -39.3878 0.157518 0.285141 -0.0701648 0.942847 +VERTEX_SE3:QUAT 1674 92.5095 58.5109 -36.6642 0.14809 0.282035 -0.0108167 0.947844 +VERTEX_SE3:QUAT 1675 92.8942 68.9107 -33.7764 0.133691 0.275305 0.0560636 0.950363 +VERTEX_SE3:QUAT 1676 91.7902 79.2344 -30.7921 0.118575 0.262508 0.110321 0.951241 +VERTEX_SE3:QUAT 1677 89.4644 89.3608 -27.8711 0.0947378 0.245832 0.173487 0.948943 +VERTEX_SE3:QUAT 1678 85.6952 99.0951 -25.1799 0.0784684 0.240213 0.226679 0.940615 +VERTEX_SE3:QUAT 1679 80.8244 108.374 -22.5885 0.0625095 0.232325 0.285782 0.927603 +VERTEX_SE3:QUAT 1680 74.7891 116.93 -20.1339 0.0367004 0.219347 0.357181 0.907173 +VERTEX_SE3:QUAT 1681 67.4349 124.458 -17.9563 0.0156756 0.202372 0.409336 0.889519 +VERTEX_SE3:QUAT 1682 59.178 131.094 -16.1148 -0.00724193 0.186974 0.460782 0.867565 +VERTEX_SE3:QUAT 1683 50.1554 136.707 -14.6624 -0.0274465 0.175937 0.511644 0.840544 +VERTEX_SE3:QUAT 1684 40.4664 141.216 -13.494 -0.0351415 0.159767 0.559709 0.812382 +VERTEX_SE3:QUAT 1685 30.3372 144.553 -12.4723 -0.0512775 0.14306 0.607259 0.779834 +VERTEX_SE3:QUAT 1686 19.8435 146.656 -11.7343 -0.0697705 0.121956 0.65689 0.740779 +VERTEX_SE3:QUAT 1687 9.16245 147.345 -11.4137 -0.089357 0.110386 0.700754 0.699124 +VERTEX_SE3:QUAT 1688 -1.52562 146.691 -11.3875 -0.106295 0.0914886 0.741776 0.655819 +VERTEX_SE3:QUAT 1689 -12.0415 144.7 -11.7364 -0.117016 0.075794 0.777448 0.613301 +VERTEX_SE3:QUAT 1690 -22.247 141.508 -12.3069 -0.132721 0.0531417 0.811557 0.566512 +VERTEX_SE3:QUAT 1691 -31.9309 137.117 -13.3002 -0.156542 0.0302939 0.843608 0.512741 +VERTEX_SE3:QUAT 1692 -40.8755 131.508 -14.7702 -0.173817 0.0125611 0.871944 0.45754 +VERTEX_SE3:QUAT 1693 -48.965 124.775 -16.4997 -0.190589 -0.00769658 0.895382 0.402377 +VERTEX_SE3:QUAT 1694 -56.089 117.127 -18.5358 -0.209466 -0.0279144 0.914552 0.344875 +VERTEX_SE3:QUAT 1695 -62.0947 108.638 -20.8629 -0.218781 -0.0501293 0.930901 0.288177 +VERTEX_SE3:QUAT 1696 -66.9324 99.508 -23.4093 -0.241699 -0.0685734 0.938126 0.238325 +VERTEX_SE3:QUAT 1697 -70.6697 89.94 -26.1813 -0.251728 -0.0773852 0.947132 0.183265 +VERTEX_SE3:QUAT 1698 -73.2445 80.0047 -28.8654 -0.265465 -0.097036 0.950612 0.128251 +VERTEX_SE3:QUAT 1699 -74.565 69.8514 -31.6694 -0.280518 -0.107901 0.951527 0.0652948 +VERTEX_SE3:QUAT 1700 -74.5038 59.6054 -34.3238 -0.28684 -0.119061 0.950548 -0.00237742 +VERTEX_SE3:QUAT 1701 -73.0208 49.405 -36.7874 -0.284341 -0.140479 0.94578 -0.0701142 +VERTEX_SE3:QUAT 1702 -70.076 39.5485 -39.2474 -0.290401 -0.155873 0.934784 -0.132473 +VERTEX_SE3:QUAT 1703 -65.8118 30.1547 -41.5542 -0.292453 -0.16678 0.921705 -0.192653 +VERTEX_SE3:QUAT 1704 -60.3887 21.3335 -43.6458 -0.303263 -0.183437 0.900369 -0.252424 +VERTEX_SE3:QUAT 1705 -53.8174 13.2719 -45.5294 -0.300805 -0.195401 0.881896 -0.305932 +VERTEX_SE3:QUAT 1706 -46.367 6.02424 -47.2098 -0.298651 -0.212835 0.856879 -0.362309 +VERTEX_SE3:QUAT 1707 -38.0145 -0.217444 -48.7523 -0.302424 -0.226301 0.826329 -0.41774 +VERTEX_SE3:QUAT 1708 -28.894 -5.40045 -49.9915 -0.292878 -0.230534 0.798342 -0.472997 +VERTEX_SE3:QUAT 1709 -19.2062 -9.41376 -50.9134 0.298532 0.238334 -0.759879 0.525984 +VERTEX_SE3:QUAT 1710 -9.06798 -12.2161 -51.3859 0.286907 0.248302 -0.726886 0.572422 +VERTEX_SE3:QUAT 1711 1.3157 -13.8151 -51.696 0.279296 0.26081 -0.680861 0.62482 +VERTEX_SE3:QUAT 1712 11.8223 -13.945 -51.7209 0.274978 0.275429 -0.634001 0.668258 +VERTEX_SE3:QUAT 1713 22.2432 -12.7232 -51.498 0.269328 0.282587 -0.584413 0.711385 +VERTEX_SE3:QUAT 1714 32.3888 -10.2186 -50.8808 0.251677 0.293502 -0.531778 0.753477 +VERTEX_SE3:QUAT 1715 42.0785 -6.30387 -50.1302 0.231469 0.293241 -0.488984 0.788243 +VERTEX_SE3:QUAT 1716 51.2181 -1.30452 -49.2918 0.220563 0.298578 -0.437615 0.81896 +VERTEX_SE3:QUAT 1717 59.6802 4.72859 -48.2242 0.208166 0.306899 -0.38588 0.844734 +VERTEX_SE3:QUAT 1718 67.3592 11.7072 -47.0199 0.192946 0.308046 -0.337144 0.868455 +VERTEX_SE3:QUAT 1719 74.1756 19.4997 -45.6935 0.176784 0.311543 -0.281966 0.890047 +VERTEX_SE3:QUAT 1720 79.9662 28.0534 -44.2626 0.157001 0.321921 -0.224742 0.906206 +VERTEX_SE3:QUAT 1721 84.6279 37.2484 -42.8211 0.138387 0.318001 -0.155605 0.924939 +VERTEX_SE3:QUAT 1722 87.8617 47.0056 -41.2163 0.124326 0.326726 -0.0989954 0.931661 +VERTEX_SE3:QUAT 1723 89.9214 57.061 -39.5156 0.0999805 0.328634 -0.0406488 0.93827 +VERTEX_SE3:QUAT 1724 90.6696 67.2836 -37.8828 0.0825365 0.320221 0.0166701 0.943593 +VERTEX_SE3:QUAT 1725 90.1626 77.5285 -36.2133 0.0634703 0.310884 0.0772383 0.945176 +VERTEX_SE3:QUAT 1726 88.3316 87.5963 -34.5577 0.0447064 0.303317 0.142764 0.941073 +VERTEX_SE3:QUAT 1727 85.135 97.3283 -32.8816 0.0181091 0.300069 0.188092 0.935014 +VERTEX_SE3:QUAT 1728 80.9442 106.681 -31.4677 0.00302845 0.286257 0.2446 0.926401 +VERTEX_SE3:QUAT 1729 75.6343 115.471 -30.0856 -0.0234819 0.276413 0.297877 0.913408 +VERTEX_SE3:QUAT 1730 69.2913 123.546 -28.9684 -0.0400223 0.27067 0.35182 0.895186 +VERTEX_SE3:QUAT 1731 62.0365 130.811 -27.8905 -0.0627215 0.259606 0.406173 0.873896 +VERTEX_SE3:QUAT 1732 53.91 137.097 -27.0007 -0.0847593 0.252409 0.450735 0.852023 +VERTEX_SE3:QUAT 1733 45.1625 142.482 -26.3311 -0.0952337 0.242386 0.502122 0.824653 +VERTEX_SE3:QUAT 1734 35.8223 146.776 -25.5968 -0.110071 0.22877 0.557129 0.790668 +VERTEX_SE3:QUAT 1735 25.9888 149.753 -24.9447 -0.131939 0.218579 0.593071 0.763598 +VERTEX_SE3:QUAT 1736 15.908 151.774 -24.5229 -0.140419 0.211541 0.638409 0.726614 +VERTEX_SE3:QUAT 1737 5.67747 152.567 -24.0264 -0.153097 0.189733 0.67843 0.693034 +VERTEX_SE3:QUAT 1738 -4.56822 152.209 -23.7461 -0.169412 0.18166 0.717417 0.650855 +VERTEX_SE3:QUAT 1739 -14.7095 150.621 -23.5227 -0.187343 0.165023 0.752436 0.609515 +VERTEX_SE3:QUAT 1740 -24.58 147.858 -23.4838 -0.194221 0.154418 0.795127 0.55336 +VERTEX_SE3:QUAT 1741 -33.9382 143.729 -23.3723 -0.211435 0.136605 0.823976 0.50764 +VERTEX_SE3:QUAT 1742 -42.7483 138.541 -23.4605 -0.224715 0.120355 0.855773 0.45019 +VERTEX_SE3:QUAT 1743 -50.7705 132.202 -23.6048 -0.237103 0.0987836 0.882345 0.394323 +VERTEX_SE3:QUAT 1744 -57.8592 124.865 -23.905 -0.241864 0.0707194 0.905684 0.340936 +VERTEX_SE3:QUAT 1745 -63.9536 116.704 -24.4569 -0.248471 0.0538675 0.924023 0.285557 +VERTEX_SE3:QUAT 1746 -69.0024 107.879 -25.0624 -0.251876 0.0306838 0.940309 0.226794 +VERTEX_SE3:QUAT 1747 -72.8765 98.4898 -25.817 -0.259517 0.00685121 0.952155 0.161261 +VERTEX_SE3:QUAT 1748 -75.3819 88.6733 -26.7005 -0.275808 -0.0155778 0.955943 0.0993023 +VERTEX_SE3:QUAT 1749 -76.5273 78.6333 -27.7193 -0.280256 -0.0362583 0.958277 0.0429682 +VERTEX_SE3:QUAT 1750 -76.4562 68.5264 -28.8231 -0.279202 -0.0667275 0.957852 -0.0106334 +VERTEX_SE3:QUAT 1751 -75.1816 58.5644 -30.1967 -0.28114 -0.0798818 0.954803 -0.0541381 +VERTEX_SE3:QUAT 1752 -72.9915 48.7554 -31.5762 -0.270921 -0.0993881 0.950961 -0.111338 +VERTEX_SE3:QUAT 1753 -69.626 39.2986 -33.0219 -0.274822 -0.12075 0.939343 -0.165911 +VERTEX_SE3:QUAT 1754 -65.1597 30.342 -34.511 -0.273138 -0.140079 0.926215 -0.218858 +VERTEX_SE3:QUAT 1755 -59.7023 21.9864 -36.0559 -0.271733 -0.160967 0.908474 -0.273727 +VERTEX_SE3:QUAT 1756 -53.2333 14.3575 -37.6014 -0.264574 -0.186987 0.886858 -0.329423 +VERTEX_SE3:QUAT 1757 -45.8539 7.69471 -39.2816 -0.261359 -0.210689 0.86093 -0.382232 +VERTEX_SE3:QUAT 1758 -37.7038 2.03426 -40.9883 -0.26323 -0.236082 0.829479 -0.432365 +VERTEX_SE3:QUAT 1759 -28.8948 -2.52226 -42.6981 -0.25394 -0.251427 0.803016 -0.476931 +VERTEX_SE3:QUAT 1760 -19.6257 -6.08308 -44.3567 0.255615 0.269219 -0.769672 0.519411 +VERTEX_SE3:QUAT 1761 -10.0095 -8.56663 -45.8705 0.24855 0.277203 -0.73059 0.572381 +VERTEX_SE3:QUAT 1762 -0.123682 -9.79713 -47.087 0.24646 0.291374 -0.685256 0.620308 +VERTEX_SE3:QUAT 1763 9.8695 -9.68125 -48.0173 0.2334 0.310846 -0.636176 0.666468 +VERTEX_SE3:QUAT 1764 19.7403 -8.17065 -48.843 0.226269 0.32125 -0.589542 0.70572 +VERTEX_SE3:QUAT 1765 29.3681 -5.44891 -49.4186 0.215139 0.331621 -0.538281 0.74431 +VERTEX_SE3:QUAT 1766 38.5526 -1.48992 -49.7688 0.202737 0.339165 -0.489733 0.777192 +VERTEX_SE3:QUAT 1767 47.2066 3.51055 -49.939 0.192824 0.343919 -0.439248 0.807217 +VERTEX_SE3:QUAT 1768 55.1901 9.4912 -49.8399 0.163162 0.348307 -0.380944 0.840799 +VERTEX_SE3:QUAT 1769 62.2246 16.571 -49.757 0.155383 0.35228 -0.32072 0.865386 +VERTEX_SE3:QUAT 1770 68.2956 24.4534 -49.3437 0.139569 0.355991 -0.271711 0.883156 +VERTEX_SE3:QUAT 1771 73.4509 32.951 -48.836 0.127429 0.354613 -0.215066 0.900976 +VERTEX_SE3:QUAT 1772 77.5559 41.9797 -48.1043 0.113907 0.355688 -0.150731 0.915309 +VERTEX_SE3:QUAT 1773 80.4263 51.4264 -47.1469 0.100227 0.350809 -0.0887556 0.926828 +VERTEX_SE3:QUAT 1774 82.0506 61.1462 -45.9757 0.0826433 0.350351 -0.0278053 0.932551 +VERTEX_SE3:QUAT 1775 82.4318 70.9747 -44.6817 0.060965 0.34858 0.0422198 0.934341 +VERTEX_SE3:QUAT 1776 81.367 80.7312 -43.3228 0.0449597 0.345143 0.0976802 0.93237 +VERTEX_SE3:QUAT 1777 79.1994 90.2672 -41.8964 0.0215183 0.334598 0.160851 0.928282 +VERTEX_SE3:QUAT 1778 75.7263 99.4315 -40.527 0.00310693 0.326804 0.21159 0.921097 +VERTEX_SE3:QUAT 1779 71.2653 108.136 -39.2225 -0.0200915 0.319329 0.270303 0.908054 +VERTEX_SE3:QUAT 1780 65.6919 116.197 -38.0078 -0.0408856 0.303418 0.330571 0.892742 +VERTEX_SE3:QUAT 1781 59.0852 123.441 -36.8752 -0.0625766 0.288999 0.38783 0.873013 +VERTEX_SE3:QUAT 1782 51.5949 129.764 -35.8898 -0.0867319 0.268891 0.439954 0.852418 +VERTEX_SE3:QUAT 1783 43.3505 135.093 -35.1951 -0.107589 0.259738 0.488336 0.826129 +VERTEX_SE3:QUAT 1784 34.5249 139.394 -34.6392 -0.138613 0.236699 0.543157 0.793562 +VERTEX_SE3:QUAT 1785 25.1735 142.429 -34.475 -0.148379 0.215375 0.590442 0.763529 +VERTEX_SE3:QUAT 1786 15.5563 144.312 -34.4243 -0.163583 0.19634 0.635748 0.728365 +VERTEX_SE3:QUAT 1787 5.77705 144.997 -34.5572 -0.177324 0.172515 0.678962 0.691235 +VERTEX_SE3:QUAT 1788 -4.00204 144.473 -34.9023 -0.194277 0.153393 0.710864 0.658331 +VERTEX_SE3:QUAT 1789 -13.6353 142.963 -35.5058 -0.218397 0.141611 0.742738 0.616919 +VERTEX_SE3:QUAT 1790 -23.0299 140.381 -36.291 -0.226055 0.132848 0.7807 0.567238 +VERTEX_SE3:QUAT 1791 -32.0193 136.622 -36.9766 -0.242079 0.117628 0.811231 0.519101 +VERTEX_SE3:QUAT 1792 -40.474 131.821 -37.7599 -0.26159 0.0965941 0.839546 0.466264 +VERTEX_SE3:QUAT 1793 -48.199 125.956 -38.7261 -0.279292 0.082176 0.862357 0.414225 +VERTEX_SE3:QUAT 1794 -55.1238 119.207 -39.766 -0.298994 0.0557982 0.878207 0.36911 +VERTEX_SE3:QUAT 1795 -61.2118 111.766 -41.1153 -0.305006 0.0369286 0.89875 0.312819 +VERTEX_SE3:QUAT 1796 -66.331 103.613 -42.4738 -0.308673 0.0117332 0.91678 0.253176 +VERTEX_SE3:QUAT 1797 -70.2864 94.8718 -43.9347 -0.317328 -0.0154691 0.92807 0.194293 +VERTEX_SE3:QUAT 1798 -73.0154 85.7238 -45.5561 -0.322338 -0.0348426 0.936751 0.131839 +VERTEX_SE3:QUAT 1799 -74.5085 76.2744 -47.1258 -0.330043 -0.0599702 0.939182 0.07357 +VERTEX_SE3:QUAT 1800 -74.7928 66.772 -48.7722 -0.334595 -0.0870913 0.93806 0.0224561 +VERTEX_SE3:QUAT 1801 -73.9575 57.3054 -50.592 -0.340141 -0.114734 0.932756 -0.0332594 +VERTEX_SE3:QUAT 1802 -71.9348 48.068 -52.5131 -0.33966 -0.131204 0.926426 -0.0956669 +VERTEX_SE3:QUAT 1803 -68.7394 39.1728 -54.291 -0.341407 -0.158307 0.914407 -0.149128 +VERTEX_SE3:QUAT 1804 -64.4433 30.7569 -56.1577 -0.344747 -0.176291 0.897555 -0.210871 +VERTEX_SE3:QUAT 1805 -59.0515 22.9712 -57.8335 -0.346434 -0.202748 0.879316 -0.256283 +VERTEX_SE3:QUAT 1806 -52.8501 15.8524 -59.5586 -0.341709 -0.221063 0.860661 -0.305987 +VERTEX_SE3:QUAT 1807 -45.8449 9.49281 -61.2043 -0.332464 -0.244996 0.833638 -0.366731 +VERTEX_SE3:QUAT 1808 -38.0005 4.19357 -62.7874 -0.342388 -0.25252 0.799513 -0.424008 +VERTEX_SE3:QUAT 1809 -29.5051 -0.126995 -63.8553 -0.333428 -0.259513 0.766897 -0.483061 +VERTEX_SE3:QUAT 1810 -20.5051 -3.28282 -64.5771 0.319014 0.27392 -0.733746 0.533681 +VERTEX_SE3:QUAT 1811 -11.1677 -5.29365 -65.1447 0.312461 0.288215 -0.694419 0.580588 +VERTEX_SE3:QUAT 1812 -1.66845 -6.14227 -65.4932 0.296059 0.303835 -0.65311 0.627281 +VERTEX_SE3:QUAT 1813 7.85756 -5.72323 -65.7104 0.28724 0.319177 -0.604792 0.670706 +VERTEX_SE3:QUAT 1814 17.2393 -4.05863 -65.6727 0.278347 0.334631 -0.557594 0.706848 +VERTEX_SE3:QUAT 1815 26.32 -1.26927 -65.4497 0.252597 0.354556 -0.50882 0.742689 +VERTEX_SE3:QUAT 1816 34.9375 2.7311 -65.2778 0.244976 0.360747 -0.458277 0.774487 +VERTEX_SE3:QUAT 1817 43.0453 7.68887 -64.7826 0.237336 0.359547 -0.403155 0.807381 +VERTEX_SE3:QUAT 1818 50.4345 13.5787 -63.8806 0.221721 0.356757 -0.342212 0.840509 +VERTEX_SE3:QUAT 1819 56.8909 20.3898 -62.6535 0.202331 0.360476 -0.278157 0.867034 +VERTEX_SE3:QUAT 1820 62.3058 28.0439 -61.2414 0.184238 0.362954 -0.217468 0.887146 +VERTEX_SE3:QUAT 1821 66.624 36.283 -59.6845 0.163146 0.367653 -0.153259 0.902622 +VERTEX_SE3:QUAT 1822 69.7398 45.0386 -58.0019 0.143774 0.357483 -0.0866676 0.918708 +VERTEX_SE3:QUAT 1823 71.5665 54.1231 -56.175 0.12469 0.357365 -0.0234031 0.925308 +VERTEX_SE3:QUAT 1824 72.1419 63.3302 -54.2478 0.0911643 0.355252 0.0194188 0.930112 +VERTEX_SE3:QUAT 1825 71.7321 72.6014 -52.6071 0.0612184 0.352705 0.0753842 0.930682 +VERTEX_SE3:QUAT 1826 70.1457 81.7417 -51.1299 0.0507108 0.348937 0.134532 0.926052 +VERTEX_SE3:QUAT 1827 67.4816 90.598 -49.4685 0.0251593 0.340494 0.188442 0.920826 +VERTEX_SE3:QUAT 1828 63.767 99.0789 -47.9654 0.00346388 0.333304 0.249077 0.909317 +VERTEX_SE3:QUAT 1829 58.9612 106.974 -46.4836 -0.0138334 0.328819 0.304844 0.893732 +VERTEX_SE3:QUAT 1830 53.2234 114.212 -44.9802 -0.0397502 0.312799 0.35725 0.879175 +VERTEX_SE3:QUAT 1831 46.6434 120.698 -43.7014 -0.0676742 0.298012 0.404674 0.861886 +VERTEX_SE3:QUAT 1832 39.2905 126.424 -42.717 -0.085053 0.281262 0.464979 0.835136 +VERTEX_SE3:QUAT 1833 31.2315 131.036 -41.7976 -0.102708 0.266297 0.511212 0.810678 +VERTEX_SE3:QUAT 1834 22.7044 134.722 -41.0023 -0.133711 0.245609 0.563631 0.77725 +VERTEX_SE3:QUAT 1835 13.7399 137.176 -40.5535 -0.152302 0.230206 0.607801 0.744572 +VERTEX_SE3:QUAT 1836 4.55027 138.569 -40.2779 -0.180082 0.208408 0.652148 0.706286 +VERTEX_SE3:QUAT 1837 -4.72063 138.732 -40.3343 -0.19402 0.180998 0.696819 0.666362 +VERTEX_SE3:QUAT 1838 -13.9271 137.678 -40.6181 -0.217161 0.155063 0.7371 0.620871 +VERTEX_SE3:QUAT 1839 -22.8802 135.378 -41.23 -0.241775 0.1284 0.764716 0.583325 +VERTEX_SE3:QUAT 1840 -31.5087 132.125 -42.2307 -0.261985 0.105716 0.795117 0.536634 +VERTEX_SE3:QUAT 1841 -39.6236 127.84 -43.4756 -0.279253 0.0818064 0.820887 0.491396 +VERTEX_SE3:QUAT 1842 -47.1318 122.653 -44.968 -0.290816 0.0645308 0.853501 0.427549 +VERTEX_SE3:QUAT 1843 -53.7655 116.385 -46.4169 -0.301901 0.0396038 0.875059 0.376244 +VERTEX_SE3:QUAT 1844 -59.5803 109.416 -48.0356 -0.308543 0.011032 0.894357 0.323734 +VERTEX_SE3:QUAT 1845 -64.4162 101.811 -49.8688 -0.329472 -0.0201446 0.906329 0.263837 +VERTEX_SE3:QUAT 1846 -68.0877 93.6562 -51.9622 -0.338255 -0.0398403 0.914099 0.220044 +VERTEX_SE3:QUAT 1847 -70.9169 85.2042 -54.1326 -0.342852 -0.0618536 0.922154 0.168105 +VERTEX_SE3:QUAT 1848 -72.7241 76.5023 -56.3699 -0.35949 -0.0907938 0.923427 0.0990297 +VERTEX_SE3:QUAT 1849 -73.1419 67.6403 -58.6465 -0.365006 -0.11788 0.922583 0.0414261 +VERTEX_SE3:QUAT 1850 -72.3779 58.8271 -61.0061 -0.369538 -0.137059 0.918682 -0.0260649 +VERTEX_SE3:QUAT 1851 -70.3606 50.1866 -63.184 -0.376996 -0.162477 0.907857 -0.0852684 +VERTEX_SE3:QUAT 1852 -67.2008 41.8948 -65.3059 -0.381311 -0.178717 0.897364 -0.131912 +VERTEX_SE3:QUAT 1853 -63.1801 33.958 -67.3508 -0.386688 -0.20593 0.878953 -0.188434 +VERTEX_SE3:QUAT 1854 -58.1497 26.6196 -69.3411 -0.393725 -0.228414 0.857244 -0.240709 +VERTEX_SE3:QUAT 1855 -52.2675 19.9452 -71.1747 -0.391744 -0.24165 0.836524 -0.29727 +VERTEX_SE3:QUAT 1856 -45.5613 14.004 -72.7027 -0.390847 -0.26344 0.806957 -0.35589 +VERTEX_SE3:QUAT 1857 -38.0811 9.02674 -73.9701 -0.386206 -0.278327 0.7793 -0.407517 +VERTEX_SE3:QUAT 1858 -30.0472 4.94807 -74.9952 -0.381462 -0.296539 0.743115 -0.46296 +VERTEX_SE3:QUAT 1859 -21.5215 1.98019 -75.7336 0.373588 0.311808 -0.714845 0.5022 +VERTEX_SE3:QUAT 1860 -12.7333 -0.107475 -76.2852 0.366505 0.325357 -0.672853 0.554153 +VERTEX_SE3:QUAT 1861 -3.75588 -1.03508 -76.509 0.362898 0.337919 -0.632628 0.594893 +VERTEX_SE3:QUAT 1862 5.27611 -0.966651 -76.3858 0.355073 0.353607 -0.588854 0.634143 +VERTEX_SE3:QUAT 1863 14.2169 0.179024 -75.9812 0.352117 0.365488 -0.536665 0.674109 +VERTEX_SE3:QUAT 1864 22.8873 2.40849 -75.1256 0.341987 0.368309 -0.489785 0.712393 +VERTEX_SE3:QUAT 1865 31.2032 5.60902 -73.9049 0.328904 0.374566 -0.442498 0.745465 +VERTEX_SE3:QUAT 1866 39.0347 9.68997 -72.3931 0.316466 0.379444 -0.391192 0.776428 +VERTEX_SE3:QUAT 1867 46.2912 14.6418 -70.5869 0.295771 0.375779 -0.337625 0.810752 +VERTEX_SE3:QUAT 1868 52.7498 20.4841 -68.5292 0.284528 0.373882 -0.28261 0.836294 +VERTEX_SE3:QUAT 1869 58.4179 26.9871 -66.146 0.268038 0.365748 -0.232577 0.860402 +VERTEX_SE3:QUAT 1870 63.2302 34.0765 -63.5574 0.25352 0.365032 -0.17755 0.878041 +VERTEX_SE3:QUAT 1871 67.1024 41.6157 -60.7548 0.225283 0.357731 -0.123074 0.897847 +VERTEX_SE3:QUAT 1872 69.893 49.6153 -57.9952 0.204941 0.354808 -0.0697529 0.90953 +VERTEX_SE3:QUAT 1873 71.7115 57.8529 -55.2155 0.184926 0.350767 -0.0214417 0.917772 +VERTEX_SE3:QUAT 1874 72.5751 66.2527 -52.4387 0.153114 0.3486 0.0398082 0.923823 +VERTEX_SE3:QUAT 1875 72.2192 74.7192 -49.8069 0.127977 0.336841 0.103579 0.927055 +VERTEX_SE3:QUAT 1876 70.6545 83.035 -47.2433 0.0946443 0.319201 0.160486 0.929192 +VERTEX_SE3:QUAT 1877 67.9412 91.1407 -44.9566 0.0639621 0.3021 0.211855 0.927233 +VERTEX_SE3:QUAT 1878 64.2302 98.9168 -43.0078 0.0379889 0.282922 0.259527 0.922582 +VERTEX_SE3:QUAT 1879 59.6302 106.274 -41.3561 0.00902469 0.274823 0.315501 0.908213 +VERTEX_SE3:QUAT 1880 54.1135 113.017 -39.9497 -0.0204523 0.256786 0.371454 0.892 +VERTEX_SE3:QUAT 1881 47.7471 119 -38.8605 -0.0444164 0.244183 0.417315 0.874214 +VERTEX_SE3:QUAT 1882 40.7541 124.255 -38.0344 -0.0783036 0.230473 0.467898 0.849601 +VERTEX_SE3:QUAT 1883 33.1347 128.599 -37.5812 -0.101108 0.209913 0.511883 0.826855 +VERTEX_SE3:QUAT 1884 25.0783 132.06 -37.4593 -0.13117 0.1897 0.551286 0.801805 +VERTEX_SE3:QUAT 1885 16.7046 134.647 -37.7573 -0.159152 0.176367 0.586726 0.774156 +VERTEX_SE3:QUAT 1886 8.1422 136.344 -38.3995 -0.193151 0.150175 0.628699 0.738158 +VERTEX_SE3:QUAT 1887 -0.518707 136.962 -39.5326 -0.223926 0.138054 0.659757 0.703931 +VERTEX_SE3:QUAT 1888 -9.1373 136.613 -40.943 -0.250507 0.116193 0.696844 0.661932 +VERTEX_SE3:QUAT 1889 -17.5626 135.197 -42.6556 -0.272494 0.0856701 0.733442 0.616823 +VERTEX_SE3:QUAT 1890 -25.6555 132.693 -44.7196 -0.303069 0.0657567 0.757757 0.574133 +VERTEX_SE3:QUAT 1891 -33.2898 129.265 -47.0934 -0.319362 0.0453962 0.788148 0.524185 +VERTEX_SE3:QUAT 1892 -40.3781 124.898 -49.5616 -0.335754 0.0239629 0.814291 0.472891 +VERTEX_SE3:QUAT 1893 -46.7724 119.648 -52.1525 -0.362077 -0.000363584 0.83017 0.423932 +VERTEX_SE3:QUAT 1894 -52.3912 113.69 -54.9787 -0.378926 -0.018965 0.845672 0.375357 +VERTEX_SE3:QUAT 1895 -57.2268 107.143 -57.8184 -0.391972 -0.0466205 0.865168 0.309303 +VERTEX_SE3:QUAT 1896 -60.9813 99.926 -60.7063 -0.404668 -0.0711947 0.87461 0.257357 +VERTEX_SE3:QUAT 1897 -63.7599 92.3058 -63.6514 -0.423257 -0.103535 0.877019 0.202414 +VERTEX_SE3:QUAT 1898 -65.4377 84.4431 -66.7474 -0.436592 -0.131481 0.878371 0.1434 +VERTEX_SE3:QUAT 1899 -66.0043 76.4227 -69.8388 -0.455971 -0.152958 0.873374 0.0768924 +VERTEX_SE3:QUAT 1900 -65.326 68.3702 -72.7152 -0.459457 -0.168388 0.871994 0.0130591 +VERTEX_SE3:QUAT 1901 -63.5875 60.3876 -75.3121 -0.465861 -0.19524 0.861634 -0.0494107 +VERTEX_SE3:QUAT 1902 -60.6898 52.7037 -77.7607 -0.467482 -0.218634 0.850167 -0.104287 +VERTEX_SE3:QUAT 1903 -56.8502 45.4073 -80.0294 -0.468098 -0.247297 0.832035 -0.16567 +VERTEX_SE3:QUAT 1904 -51.9939 38.7161 -82.1389 -0.476868 -0.263934 0.808193 -0.223069 +VERTEX_SE3:QUAT 1905 -46.288 32.6025 -83.8347 -0.475052 -0.286818 0.784081 -0.277989 +VERTEX_SE3:QUAT 1906 -39.8125 27.2302 -85.2994 -0.474841 -0.299617 0.761747 -0.32326 +VERTEX_SE3:QUAT 1907 -32.815 22.4948 -86.4241 -0.476593 -0.311809 0.729391 -0.378977 +VERTEX_SE3:QUAT 1908 -25.2661 18.6089 -87.0645 -0.472272 -0.322216 0.700079 -0.427815 +VERTEX_SE3:QUAT 1909 -17.3589 15.5603 -87.2888 -0.465841 -0.325465 0.6669 -0.481985 +VERTEX_SE3:QUAT 1910 -9.16477 13.3923 -87.0102 0.449775 0.328485 -0.632193 0.53864 +VERTEX_SE3:QUAT 1911 -0.800056 12.2606 -86.2726 0.440395 0.337979 -0.596492 0.579672 +VERTEX_SE3:QUAT 1912 7.57899 12.0264 -85.2421 0.425783 0.340416 -0.555432 0.62795 +VERTEX_SE3:QUAT 1913 15.8535 12.8171 -83.8176 0.404913 0.354399 -0.513912 0.668088 +VERTEX_SE3:QUAT 1914 23.9329 14.6233 -82.2285 0.392611 0.359288 -0.470139 0.704087 +VERTEX_SE3:QUAT 1915 31.6951 17.309 -80.3316 0.370233 0.366612 -0.419293 0.743449 +VERTEX_SE3:QUAT 1916 38.9247 21.0052 -78.217 0.348301 0.366248 -0.368686 0.78014 +VERTEX_SE3:QUAT 1917 45.5541 25.6053 -75.8976 0.331499 0.358592 -0.31818 0.812577 +VERTEX_SE3:QUAT 1918 51.4708 30.9297 -73.2944 0.306834 0.364278 -0.26958 0.836947 +VERTEX_SE3:QUAT 1919 56.6804 36.9346 -70.6434 0.288522 0.366392 -0.214589 0.858174 +VERTEX_SE3:QUAT 1920 61.0239 43.499 -67.859 0.265105 0.364141 -0.148308 0.880412 +VERTEX_SE3:QUAT 1921 64.2869 50.6132 -64.9304 0.235292 0.363395 -0.0965723 0.896245 +VERTEX_SE3:QUAT 1922 66.5975 58.1072 -62.0806 0.210439 0.359512 -0.042449 0.908111 +VERTEX_SE3:QUAT 1923 67.9162 65.853 -59.2793 0.178771 0.355275 0.016047 0.917367 +VERTEX_SE3:QUAT 1924 68.1314 73.7278 -56.59 0.147657 0.347005 0.0688202 0.923606 +VERTEX_SE3:QUAT 1925 67.3094 81.5991 -54.0673 0.123633 0.33871 0.124184 0.924429 +VERTEX_SE3:QUAT 1926 65.5169 89.3244 -51.6572 0.0913593 0.329943 0.175803 0.922976 +VERTEX_SE3:QUAT 1927 62.741 96.8175 -49.5064 0.0566361 0.314302 0.228309 0.919718 +VERTEX_SE3:QUAT 1928 59.0227 103.98 -47.6801 0.0225176 0.302271 0.278777 0.911267 +VERTEX_SE3:QUAT 1929 54.4515 110.674 -46.2005 -0.0141362 0.291823 0.337773 0.894734 +VERTEX_SE3:QUAT 1930 48.94 116.695 -45.0309 -0.046009 0.278408 0.389031 0.876942 +VERTEX_SE3:QUAT 1931 42.7057 121.999 -44.1723 -0.0766398 0.26225 0.433107 0.858935 +VERTEX_SE3:QUAT 1932 35.907 126.61 -43.6417 -0.112268 0.246126 0.477374 0.836022 +VERTEX_SE3:QUAT 1933 28.6368 130.384 -43.5114 -0.147479 0.237983 0.521658 0.805908 +VERTEX_SE3:QUAT 1934 20.9559 133.247 -43.6818 -0.173534 0.229979 0.563071 0.774562 +VERTEX_SE3:QUAT 1935 12.9984 135.202 -43.9958 -0.19996 0.214245 0.599506 0.744787 +VERTEX_SE3:QUAT 1936 4.91739 136.285 -44.5792 -0.230795 0.196923 0.642734 0.703454 +VERTEX_SE3:QUAT 1937 -3.21344 136.264 -45.3986 -0.253133 0.185933 0.677817 0.664768 +VERTEX_SE3:QUAT 1938 -11.2567 135.3 -46.3068 -0.269117 0.167725 0.713369 0.62494 +VERTEX_SE3:QUAT 1939 -19.1184 133.403 -47.3073 -0.285475 0.146901 0.744962 0.58477 +VERTEX_SE3:QUAT 1940 -26.6652 130.667 -48.4677 -0.30574 0.128765 0.770811 0.543868 +VERTEX_SE3:QUAT 1941 -33.8335 127.111 -49.7485 -0.337565 0.109126 0.797736 0.487605 +VERTEX_SE3:QUAT 1942 -40.3918 122.571 -51.1569 -0.363023 0.0852157 0.816841 0.44014 +VERTEX_SE3:QUAT 1943 -46.2909 117.316 -52.7503 -0.373273 0.0572352 0.833987 0.402315 +VERTEX_SE3:QUAT 1944 -51.612 111.511 -54.5593 -0.386072 0.0385744 0.85505 0.34402 +VERTEX_SE3:QUAT 1945 -56.0964 105.044 -56.2982 -0.394754 0.00493094 0.873117 0.286027 +VERTEX_SE3:QUAT 1946 -59.5936 98.0592 -58.1788 -0.412908 -0.0255945 0.882296 0.224514 +VERTEX_SE3:QUAT 1947 -62.0558 90.6487 -60.1383 -0.420442 -0.0497783 0.889479 0.17198 +VERTEX_SE3:QUAT 1948 -63.5949 83.0268 -62.0972 -0.432459 -0.0775547 0.890651 0.117065 +VERTEX_SE3:QUAT 1949 -64.1268 75.2807 -64.0716 -0.43717 -0.0951949 0.892296 0.0602379 +VERTEX_SE3:QUAT 1950 -63.7192 67.5357 -65.919 -0.448967 -0.115768 0.885985 0.00756032 +VERTEX_SE3:QUAT 1951 -62.4208 59.8437 -67.656 -0.451191 -0.145248 0.878723 -0.0563639 +VERTEX_SE3:QUAT 1952 -60.0073 52.4212 -69.2855 -0.449622 -0.174681 0.86749 -0.121607 +VERTEX_SE3:QUAT 1953 -56.5277 45.4174 -70.8355 -0.451539 -0.192086 0.854302 -0.171417 +VERTEX_SE3:QUAT 1954 -52.2929 38.8381 -72.2122 -0.443675 -0.213626 0.839544 -0.229527 +VERTEX_SE3:QUAT 1955 -47.2632 32.8195 -73.4201 -0.434746 -0.237993 0.81843 -0.290737 +VERTEX_SE3:QUAT 1956 -41.4267 27.5422 -74.489 -0.432955 -0.266669 0.790338 -0.341766 +VERTEX_SE3:QUAT 1957 -34.9698 23.0723 -75.4416 -0.426171 -0.28514 0.765516 -0.388664 +VERTEX_SE3:QUAT 1958 -28.0525 19.3513 -76.2566 -0.417493 -0.314094 0.731841 -0.437555 +VERTEX_SE3:QUAT 1959 -20.7025 16.5945 -76.9592 -0.41346 -0.339678 0.691377 -0.485456 +VERTEX_SE3:QUAT 1960 -13.0407 14.8217 -77.4212 0.398255 0.350503 -0.658629 0.533618 +VERTEX_SE3:QUAT 1961 -5.22402 13.936 -77.6643 0.387788 0.363409 -0.616246 0.581201 +VERTEX_SE3:QUAT 1962 2.63272 14.0436 -77.5762 0.374545 0.374793 -0.573895 0.624412 +VERTEX_SE3:QUAT 1963 10.3908 15.102 -77.2448 0.356727 0.391916 -0.525378 0.665677 +VERTEX_SE3:QUAT 1964 17.914 17.1916 -76.7026 0.339998 0.401942 -0.474233 0.705653 +VERTEX_SE3:QUAT 1965 25.0618 20.221 -75.8734 0.319416 0.410182 -0.429522 0.7384 +VERTEX_SE3:QUAT 1966 31.765 24.0679 -74.918 0.291614 0.409408 -0.379724 0.776631 +VERTEX_SE3:QUAT 1967 37.8883 28.7785 -73.7959 0.264877 0.415019 -0.326142 0.806988 +VERTEX_SE3:QUAT 1968 43.2886 34.2336 -72.5938 0.233267 0.434239 -0.272462 0.82631 +VERTEX_SE3:QUAT 1969 47.8964 40.3793 -71.4527 0.209654 0.439689 -0.216107 0.846178 +VERTEX_SE3:QUAT 1970 51.6639 47.0402 -70.2005 0.17961 0.436905 -0.166043 0.865612 +VERTEX_SE3:QUAT 1971 54.5918 54.1075 -68.9572 0.15176 0.441842 -0.115995 0.876521 +VERTEX_SE3:QUAT 1972 56.6286 61.4583 -67.7389 0.124259 0.43738 -0.0583628 0.888736 +VERTEX_SE3:QUAT 1973 57.6898 68.9953 -66.4899 0.0928907 0.435069 0.00412105 0.895583 +VERTEX_SE3:QUAT 1974 57.6756 76.5959 -65.2526 0.0688156 0.428576 0.0640903 0.898598 +VERTEX_SE3:QUAT 1975 56.6582 84.1109 -63.9799 0.031702 0.425594 0.125068 0.895669 +VERTEX_SE3:QUAT 1976 54.5777 91.4019 -62.828 0.00180159 0.418115 0.179425 0.890496 +VERTEX_SE3:QUAT 1977 51.6024 98.3866 -61.7632 -0.0304226 0.40939 0.235072 0.881031 +VERTEX_SE3:QUAT 1978 47.7403 104.924 -60.8299 -0.0543268 0.404031 0.28229 0.868401 +VERTEX_SE3:QUAT 1979 43.1677 110.998 -59.9336 -0.0904054 0.39219 0.338382 0.850595 +VERTEX_SE3:QUAT 1980 37.7945 116.372 -59.2215 -0.120531 0.375802 0.390125 0.831894 +VERTEX_SE3:QUAT 1981 31.8084 121.034 -58.6788 -0.143976 0.370358 0.452683 0.798238 +VERTEX_SE3:QUAT 1982 25.1813 124.737 -58.0279 -0.158799 0.348251 0.498221 0.777997 +VERTEX_SE3:QUAT 1983 18.2016 127.669 -57.4287 -0.186329 0.334675 0.539378 0.749897 +VERTEX_SE3:QUAT 1984 10.9403 129.778 -56.9648 -0.216915 0.316321 0.5788 0.719639 +VERTEX_SE3:QUAT 1985 3.48285 131.011 -56.7033 -0.236722 0.295114 0.619512 0.687805 +VERTEX_SE3:QUAT 1986 -4.03748 131.366 -56.5755 -0.260739 0.275262 0.655162 0.653459 +VERTEX_SE3:QUAT 1987 -11.5667 130.869 -56.5765 -0.288586 0.258688 0.687934 0.613633 +VERTEX_SE3:QUAT 1988 -18.9538 129.455 -56.7012 -0.311467 0.241243 0.725935 0.563745 +VERTEX_SE3:QUAT 1989 -26.0892 127.066 -56.8447 -0.339355 0.213195 0.757124 0.515897 +VERTEX_SE3:QUAT 1990 -32.8044 123.728 -57.1964 -0.358101 0.180252 0.785033 0.472224 +VERTEX_SE3:QUAT 1991 -39.0244 119.6 -57.7427 -0.376784 0.15067 0.814254 0.415118 +VERTEX_SE3:QUAT 1992 -44.5577 114.609 -58.3695 -0.388496 0.122278 0.835483 0.368899 +VERTEX_SE3:QUAT 1993 -49.4583 109.026 -59.1084 -0.402204 0.0934735 0.853024 0.319132 +VERTEX_SE3:QUAT 1994 -53.6214 102.897 -59.9562 -0.417685 0.0674962 0.865168 0.269199 +VERTEX_SE3:QUAT 1995 -57.021 96.3235 -60.8737 -0.427053 0.0255871 0.878201 0.213857 +VERTEX_SE3:QUAT 1996 -59.4479 89.3995 -62.0019 -0.442574 -0.00881525 0.884622 0.146612 +VERTEX_SE3:QUAT 1997 -60.7562 82.1896 -63.1666 -0.453178 -0.0430207 0.886042 0.0877931 +VERTEX_SE3:QUAT 1998 -61.0677 74.9116 -64.3848 -0.454403 -0.0721509 0.887254 0.0330477 +VERTEX_SE3:QUAT 1999 -60.438 67.6679 -65.6061 -0.460358 -0.105185 0.881195 -0.0224125 +VERTEX_SE3:QUAT 2000 -58.8735 60.5728 -66.872 -0.464605 -0.125339 0.873616 -0.0723038 +VERTEX_SE3:QUAT 2001 -56.542 53.6743 -68.0071 -0.464876 -0.146424 0.863237 -0.131426 +VERTEX_SE3:QUAT 2002 -53.3471 47.1295 -69.0026 -0.463538 -0.176044 0.85005 -0.177639 +VERTEX_SE3:QUAT 2003 -49.4421 41.0069 -70.0249 -0.459316 -0.1956 0.834113 -0.234574 +VERTEX_SE3:QUAT 2004 -44.8163 35.4003 -70.8362 -0.453396 -0.216271 0.81786 -0.280648 +VERTEX_SE3:QUAT 2005 -39.6182 30.3301 -71.5898 -0.444759 -0.241016 0.793595 -0.338095 +VERTEX_SE3:QUAT 2006 -33.76 25.9866 -72.2164 -0.430038 -0.264148 0.768967 -0.392407 +VERTEX_SE3:QUAT 2007 -27.4057 22.4345 -72.7163 -0.410726 -0.29762 0.746147 -0.431267 +VERTEX_SE3:QUAT 2008 -20.7352 19.6771 -73.3797 -0.399593 -0.324752 0.713092 -0.475775 +VERTEX_SE3:QUAT 2009 -13.755 17.7806 -73.9613 0.386428 0.346492 -0.674296 0.525302 +VERTEX_SE3:QUAT 2010 -6.59231 16.8118 -74.4155 0.371138 0.363157 -0.634397 0.572637 +VERTEX_SE3:QUAT 2011 0.64253 16.7981 -74.6885 0.346158 0.377711 -0.596522 0.617796 +VERTEX_SE3:QUAT 2012 7.825 17.6862 -74.853 0.330284 0.397086 -0.552292 0.654377 +VERTEX_SE3:QUAT 2013 14.8166 19.4748 -74.8978 0.309635 0.41108 -0.510921 0.688549 +VERTEX_SE3:QUAT 2014 21.5335 22.0385 -74.8467 0.290242 0.420336 -0.467956 0.721176 +VERTEX_SE3:QUAT 2015 27.907 25.3722 -74.6802 0.269181 0.431658 -0.418832 0.752192 +VERTEX_SE3:QUAT 2016 33.79 29.4658 -74.3743 0.2487 0.444606 -0.364949 0.779286 +VERTEX_SE3:QUAT 2017 39.0775 34.2638 -73.9421 0.216995 0.448824 -0.320177 0.805579 +VERTEX_SE3:QUAT 2018 43.7568 39.6451 -73.5105 0.191991 0.460892 -0.261696 0.825974 +VERTEX_SE3:QUAT 2019 47.651 45.609 -73.0097 0.169069 0.459568 -0.21086 0.846021 +VERTEX_SE3:QUAT 2020 50.8112 51.9679 -72.3938 0.14587 0.45642 -0.157805 0.863424 +VERTEX_SE3:QUAT 2021 53.2082 58.6305 -71.691 0.119287 0.465102 -0.112558 0.869932 +VERTEX_SE3:QUAT 2022 54.8433 65.5018 -71.0115 0.082919 0.467357 -0.0582063 0.878245 +VERTEX_SE3:QUAT 2023 55.5831 72.5206 -70.4381 0.0535134 0.468947 0.00740306 0.881572 +VERTEX_SE3:QUAT 2024 55.3066 79.5397 -69.7889 0.0183724 0.464905 0.060318 0.883113 +VERTEX_SE3:QUAT 2025 54.1324 86.4798 -69.2424 -0.00725128 0.458695 0.113247 0.881318 +VERTEX_SE3:QUAT 2026 52.1405 93.2204 -68.6945 -0.0312251 0.451782 0.164695 0.876238 +VERTEX_SE3:QUAT 2027 49.3902 99.6766 -68.1281 -0.0587619 0.447336 0.214679 0.866228 +VERTEX_SE3:QUAT 2028 45.9274 105.75 -67.5844 -0.0944772 0.439043 0.263697 0.853686 +VERTEX_SE3:QUAT 2029 41.7546 111.358 -67.1938 -0.12924 0.43004 0.30779 0.838825 +VERTEX_SE3:QUAT 2030 36.9642 116.424 -66.961 -0.162653 0.413856 0.361114 0.819673 +VERTEX_SE3:QUAT 2031 31.5382 120.807 -66.8416 -0.193095 0.399614 0.412158 0.795707 +VERTEX_SE3:QUAT 2032 25.602 124.448 -66.8012 -0.22219 0.389101 0.459093 0.767115 +VERTEX_SE3:QUAT 2033 19.2819 127.304 -66.7839 -0.262285 0.362141 0.504776 0.738419 +VERTEX_SE3:QUAT 2034 12.6368 129.256 -67.0214 -0.29488 0.339895 0.549383 0.704056 +VERTEX_SE3:QUAT 2035 5.79489 130.258 -67.4136 -0.312751 0.320651 0.584587 0.676482 +VERTEX_SE3:QUAT 2036 -1.08499 130.57 -67.8407 -0.329766 0.297168 0.621501 0.645509 +VERTEX_SE3:QUAT 2037 -7.94397 130.119 -68.3471 -0.363659 0.280387 0.652893 0.602383 +VERTEX_SE3:QUAT 2038 -14.6718 128.788 -68.9398 -0.390767 0.255213 0.680337 0.565074 +VERTEX_SE3:QUAT 2039 -21.1934 126.688 -69.6603 -0.412438 0.231839 0.710783 0.520512 +VERTEX_SE3:QUAT 2040 -27.36 123.81 -70.4272 -0.434777 0.210457 0.735288 0.475425 +VERTEX_SE3:QUAT 2041 -33.1367 120.184 -71.2004 -0.458532 0.179425 0.760637 0.423068 +VERTEX_SE3:QUAT 2042 -38.3032 115.818 -72.0304 -0.483672 0.154198 0.779191 0.367621 +VERTEX_SE3:QUAT 2043 -42.8413 110.804 -72.8411 -0.501742 0.123194 0.796801 0.313348 +VERTEX_SE3:QUAT 2044 -46.6547 105.215 -73.6658 -0.51944 0.109489 0.808861 0.252859 +VERTEX_SE3:QUAT 2045 -49.7306 99.2019 -74.2624 -0.532132 0.0813518 0.821477 0.188131 +VERTEX_SE3:QUAT 2046 -51.9216 92.8026 -74.6944 -0.536372 0.0566722 0.831725 0.131633 +VERTEX_SE3:QUAT 2047 -53.2946 86.1813 -75.0211 -0.535765 0.031884 0.839851 0.0811803 +VERTEX_SE3:QUAT 2048 -53.9095 79.4591 -75.2353 -0.537821 0.00215479 0.842567 0.0287077 +VERTEX_SE3:QUAT 2049 -53.7276 72.7385 -75.4119 -0.542128 -0.0280141 0.839432 -0.0258215 +VERTEX_SE3:QUAT 2050 -52.7093 66.1028 -75.5527 -0.552081 -0.0534657 0.828464 -0.0774301 +VERTEX_SE3:QUAT 2051 -50.9428 59.6416 -75.5491 -0.547255 -0.0668051 0.822662 -0.138841 +VERTEX_SE3:QUAT 2052 -48.4473 53.4346 -75.2472 -0.536113 -0.0965965 0.815612 -0.195011 +VERTEX_SE3:QUAT 2053 -45.1523 47.6152 -74.9012 -0.52782 -0.120589 0.800481 -0.25709 +VERTEX_SE3:QUAT 2054 -41.133 42.3325 -74.3758 -0.52165 -0.143992 0.78357 -0.305232 +VERTEX_SE3:QUAT 2055 -36.541 37.5347 -73.744 -0.509005 -0.167805 0.763404 -0.360513 +VERTEX_SE3:QUAT 2056 -31.396 33.3881 -73.0064 -0.494577 -0.194684 0.741765 -0.408995 +VERTEX_SE3:QUAT 2057 -25.7926 29.9295 -72.2531 -0.476476 -0.219396 0.713409 -0.464633 +VERTEX_SE3:QUAT 2058 -19.7978 27.2655 -71.4256 0.46304 0.22801 -0.682809 0.517085 +VERTEX_SE3:QUAT 2059 -13.5505 25.3631 -70.3451 0.439121 0.246792 -0.657562 0.560249 +VERTEX_SE3:QUAT 2060 -7.14905 24.2143 -69.313 0.414822 0.267456 -0.630508 0.59904 +VERTEX_SE3:QUAT 2061 -0.680415 23.8232 -68.3189 0.393946 0.288914 -0.58637 0.646147 +VERTEX_SE3:QUAT 2062 5.77707 24.3695 -67.2591 0.372434 0.304096 -0.549046 0.683643 +VERTEX_SE3:QUAT 2063 12.1049 25.6732 -66.1913 0.338673 0.32408 -0.509419 0.721641 +VERTEX_SE3:QUAT 2064 18.1906 27.8201 -65.2512 0.316812 0.339882 -0.471556 0.749497 +VERTEX_SE3:QUAT 2065 24.0047 30.6026 -64.3331 0.282545 0.365338 -0.425957 0.777982 +VERTEX_SE3:QUAT 2066 29.4146 34.1537 -63.5806 0.247709 0.372519 -0.392116 0.803813 +VERTEX_SE3:QUAT 2067 34.4068 38.2414 -62.994 0.215748 0.382846 -0.343985 0.829793 +VERTEX_SE3:QUAT 2068 38.8326 42.9665 -62.5087 0.180614 0.403875 -0.299877 0.845185 +VERTEX_SE3:QUAT 2069 42.6726 48.1673 -62.2182 0.152334 0.416297 -0.261531 0.857375 +VERTEX_SE3:QUAT 2070 45.9665 53.7099 -62.0621 0.121548 0.422901 -0.21181 0.87265 +VERTEX_SE3:QUAT 2071 48.5636 59.6211 -61.9729 0.0894249 0.429039 -0.156662 0.885091 +VERTEX_SE3:QUAT 2072 50.3628 65.7899 -61.9411 0.0530239 0.433956 -0.102879 0.893469 +VERTEX_SE3:QUAT 2073 51.3632 72.1332 -62.0263 0.0268391 0.440607 -0.03932 0.896437 +VERTEX_SE3:QUAT 2074 51.4775 78.5428 -62.0779 -0.017842 0.447133 0.00948447 0.894239 +VERTEX_SE3:QUAT 2075 50.755 84.8824 -62.3464 -0.0507532 0.452519 0.0627342 0.888096 +VERTEX_SE3:QUAT 2076 49.2649 91.0764 -62.6575 -0.0863166 0.44708 0.111291 0.883336 +VERTEX_SE3:QUAT 2077 47.0512 97.0196 -63.0869 -0.116141 0.443031 0.155148 0.875308 +VERTEX_SE3:QUAT 2078 44.2246 102.671 -63.6271 -0.147784 0.432741 0.214575 0.863048 +VERTEX_SE3:QUAT 2079 40.6488 107.887 -64.1839 -0.183737 0.427336 0.266613 0.844122 +VERTEX_SE3:QUAT 2080 36.4316 112.559 -64.8068 -0.210151 0.425027 0.313106 0.822893 +VERTEX_SE3:QUAT 2081 31.7082 116.693 -65.3999 -0.232111 0.420293 0.360364 0.79976 +VERTEX_SE3:QUAT 2082 26.5523 120.283 -65.9058 -0.271533 0.407977 0.407974 0.770312 +VERTEX_SE3:QUAT 2083 20.9822 123.094 -66.5064 -0.300892 0.391724 0.45306 0.742127 +VERTEX_SE3:QUAT 2084 15.0996 125.189 -67.1669 -0.332932 0.38141 0.496294 0.705249 +VERTEX_SE3:QUAT 2085 9.01329 126.474 -67.7878 -0.357596 0.368946 0.534638 0.670945 +VERTEX_SE3:QUAT 2086 2.81648 127.058 -68.3732 -0.379101 0.357405 0.57169 0.633811 +VERTEX_SE3:QUAT 2087 -3.40077 126.919 -68.8602 -0.399148 0.338717 0.603128 0.601821 +VERTEX_SE3:QUAT 2088 -9.54712 126.138 -69.3422 -0.423558 0.315221 0.636321 0.562432 +VERTEX_SE3:QUAT 2089 -15.5374 124.609 -69.8474 -0.445983 0.298259 0.667958 0.515725 +VERTEX_SE3:QUAT 2090 -21.2819 122.343 -70.2433 -0.463499 0.284169 0.702349 0.459481 +VERTEX_SE3:QUAT 2091 -26.6677 119.324 -70.4323 -0.479106 0.263215 0.728063 0.413641 +VERTEX_SE3:QUAT 2092 -31.6641 115.708 -70.5282 -0.493758 0.236076 0.753112 0.365095 +VERTEX_SE3:QUAT 2093 -36.1455 111.507 -70.5697 -0.509646 0.205064 0.773369 0.316403 +VERTEX_SE3:QUAT 2094 -40.0579 106.778 -70.6054 -0.52009 0.171212 0.795613 0.259215 +VERTEX_SE3:QUAT 2095 -43.2424 101.573 -70.6042 -0.52945 0.144092 0.811174 0.202277 +VERTEX_SE3:QUAT 2096 -45.7518 95.9963 -70.4879 -0.53557 0.118768 0.82153 0.155396 +VERTEX_SE3:QUAT 2097 -47.6123 90.2005 -70.3331 -0.536896 0.0950899 0.83154 0.106032 +VERTEX_SE3:QUAT 2098 -48.8269 84.2329 -70.0797 -0.54054 0.0543198 0.838061 0.0501848 +VERTEX_SE3:QUAT 2099 -49.1957 78.1884 -69.8913 -0.54139 0.022958 0.840435 -0.0061944 +VERTEX_SE3:QUAT 2100 -48.7821 72.1563 -69.6516 -0.538558 -0.00805264 0.840627 -0.056884 +VERTEX_SE3:QUAT 2101 -47.6705 66.2135 -69.3881 -0.539077 -0.0455785 0.834181 -0.107051 +VERTEX_SE3:QUAT 2102 -45.8229 60.5022 -69.1923 -0.534692 -0.0782452 0.825901 -0.160838 +VERTEX_SE3:QUAT 2103 -43.267 55.0901 -68.9654 -0.528039 -0.111675 0.814031 -0.214607 +VERTEX_SE3:QUAT 2104 -40.0438 50.0335 -68.7238 -0.520781 -0.137203 0.79929 -0.266643 +VERTEX_SE3:QUAT 2105 -36.2593 45.4263 -68.4092 -0.512485 -0.163102 0.78093 -0.317656 +VERTEX_SE3:QUAT 2106 -31.9566 41.3075 -68.0295 -0.498923 -0.193165 0.761108 -0.366713 +VERTEX_SE3:QUAT 2107 -27.1788 37.7798 -67.6316 -0.478253 -0.220351 0.735935 -0.425581 +VERTEX_SE3:QUAT 2108 -21.9254 34.9984 -67.1894 -0.464226 -0.245344 0.707598 -0.472869 +VERTEX_SE3:QUAT 2109 -16.4314 32.9013 -66.6978 0.447033 0.2651 -0.680336 0.516745 +VERTEX_SE3:QUAT 2110 -10.7201 31.447 -66.1643 0.426084 0.292466 -0.646422 0.561298 +VERTEX_SE3:QUAT 2111 -4.90014 30.7408 -65.6644 0.408084 0.319187 -0.611534 0.598007 +VERTEX_SE3:QUAT 2112 0.958908 30.7427 -65.1494 0.37654 0.337586 -0.570867 0.646811 +VERTEX_SE3:QUAT 2113 6.72052 31.5926 -64.607 0.350591 0.366812 -0.523908 0.684145 +VERTEX_SE3:QUAT 2114 12.3072 33.2448 -64.1187 0.328951 0.383955 -0.478227 0.718101 +VERTEX_SE3:QUAT 2115 17.6229 35.6009 -63.5693 0.291637 0.407147 -0.437009 0.747129 +VERTEX_SE3:QUAT 2116 22.5663 38.6248 -63.1757 0.252856 0.421466 -0.394867 0.776216 +VERTEX_SE3:QUAT 2117 27.0736 42.2563 -62.927 0.220305 0.440458 -0.347906 0.797762 +VERTEX_SE3:QUAT 2118 31.1044 46.4175 -62.7455 0.194023 0.454355 -0.292509 0.818752 +VERTEX_SE3:QUAT 2119 34.5308 51.0727 -62.5226 0.156907 0.461442 -0.251445 0.836198 +VERTEX_SE3:QUAT 2120 37.4041 56.0727 -62.4307 0.129639 0.465604 -0.198298 0.852693 +VERTEX_SE3:QUAT 2121 39.6209 61.3756 -62.3186 0.0953942 0.466523 -0.14841 0.866736 +VERTEX_SE3:QUAT 2122 41.1714 66.8929 -62.2885 0.0653649 0.47166 -0.103461 0.873247 +VERTEX_SE3:QUAT 2123 42.1103 72.5385 -62.3022 0.0263045 0.47509 -0.0550196 0.877821 +VERTEX_SE3:QUAT 2124 42.3383 78.2269 -62.4439 -0.011142 0.474211 -0.00410841 0.880331 +VERTEX_SE3:QUAT 2125 41.8468 83.9122 -62.6957 -0.0457063 0.47618 0.0594583 0.876144 +VERTEX_SE3:QUAT 2126 40.5412 89.4395 -62.9228 -0.0776044 0.477156 0.114643 0.867846 +VERTEX_SE3:QUAT 2127 38.5369 94.7221 -63.1851 -0.110909 0.472122 0.167654 0.858307 +VERTEX_SE3:QUAT 2128 35.892 99.7173 -63.4554 -0.144952 0.468401 0.221143 0.843021 +VERTEX_SE3:QUAT 2129 32.6509 104.321 -63.7358 -0.178076 0.465291 0.273357 0.822842 +VERTEX_SE3:QUAT 2130 28.8505 108.456 -64.0314 -0.205416 0.456034 0.330155 0.800522 +VERTEX_SE3:QUAT 2131 24.5123 112.034 -64.258 -0.228524 0.444422 0.379499 0.778618 +VERTEX_SE3:QUAT 2132 19.8069 115.059 -64.4475 -0.252567 0.428552 0.423931 0.756859 +VERTEX_SE3:QUAT 2133 14.8214 117.529 -64.6441 -0.281193 0.409245 0.468766 0.730553 +VERTEX_SE3:QUAT 2134 9.55981 119.342 -64.8749 -0.309946 0.396602 0.508948 0.698293 +VERTEX_SE3:QUAT 2135 4.15564 120.506 -65.124 -0.339737 0.378936 0.54459 0.666639 +VERTEX_SE3:QUAT 2136 -1.34285 121.026 -65.4338 -0.363472 0.360552 0.576563 0.636762 +VERTEX_SE3:QUAT 2137 -6.85738 120.956 -65.7787 -0.380834 0.341595 0.609 0.606133 +VERTEX_SE3:QUAT 2138 -12.338 120.322 -66.107 -0.403204 0.310094 0.646292 0.568836 +VERTEX_SE3:QUAT 2139 -17.6683 118.987 -66.5184 -0.426224 0.275797 0.684364 0.523369 +VERTEX_SE3:QUAT 2140 -22.7284 116.925 -66.9669 -0.442229 0.245911 0.71275 0.485746 +VERTEX_SE3:QUAT 2141 -27.5073 114.304 -67.4855 -0.468646 0.212123 0.734764 0.44215 +VERTEX_SE3:QUAT 2142 -31.867 111.103 -68.1223 -0.482998 0.182395 0.754731 0.404755 +VERTEX_SE3:QUAT 2143 -35.8486 107.476 -68.8199 -0.49547 0.143919 0.775776 0.363274 +VERTEX_SE3:QUAT 2144 -39.3418 103.388 -69.6373 -0.51246 0.11767 0.787969 0.32038 +VERTEX_SE3:QUAT 2145 -42.3742 98.9753 -70.4623 -0.524353 0.0891248 0.805376 0.261687 +VERTEX_SE3:QUAT 2146 -44.7464 94.2029 -71.2285 -0.538719 0.059165 0.81505 0.20488 +VERTEX_SE3:QUAT 2147 -46.4689 89.1476 -71.9582 -0.554645 0.0333071 0.817415 0.151959 +VERTEX_SE3:QUAT 2148 -47.5553 83.9233 -72.5988 -0.560998 0.00165887 0.822534 0.0933585 +VERTEX_SE3:QUAT 2149 -47.956 78.6061 -73.1456 -0.57522 -0.0302747 0.815864 0.0507007 +VERTEX_SE3:QUAT 2150 -47.767 73.3041 -73.7239 -0.585036 -0.0624775 0.808563 -0.00741644 +VERTEX_SE3:QUAT 2151 -46.8697 68.0762 -74.2019 -0.583297 -0.0957856 0.804002 -0.0645857 +VERTEX_SE3:QUAT 2152 -45.2937 63.0223 -74.6243 -0.575991 -0.127871 0.799356 -0.113637 +VERTEX_SE3:QUAT 2153 -43.1191 58.1936 -74.9899 -0.5645 -0.156777 0.792298 -0.170365 +VERTEX_SE3:QUAT 2154 -40.3453 53.6865 -75.3055 -0.561021 -0.181886 0.776452 -0.222026 +VERTEX_SE3:QUAT 2155 -37.1023 49.5329 -75.4902 -0.550531 -0.21241 0.759774 -0.273024 +VERTEX_SE3:QUAT 2156 -33.3669 45.8355 -75.5926 -0.543016 -0.237951 0.740154 -0.317309 +VERTEX_SE3:QUAT 2157 -29.2512 42.5696 -75.6338 -0.528352 -0.265813 0.715377 -0.372052 +VERTEX_SE3:QUAT 2158 -24.7471 39.9075 -75.5542 -0.518131 -0.287586 0.684036 -0.425357 +VERTEX_SE3:QUAT 2159 -19.9761 37.8602 -75.3007 -0.503651 -0.308614 0.655953 -0.469914 +VERTEX_SE3:QUAT 2160 -15.013 36.3576 -74.9406 0.486461 0.337149 -0.625827 0.507964 +VERTEX_SE3:QUAT 2161 -9.92323 35.4484 -74.5504 0.460105 0.358539 -0.595008 0.552918 +VERTEX_SE3:QUAT 2162 -4.79004 35.2138 -74.1298 0.431087 0.380489 -0.556303 0.599933 +VERTEX_SE3:QUAT 2163 0.332053 35.7029 -73.672 0.405751 0.402913 -0.520288 0.634293 +VERTEX_SE3:QUAT 2164 5.32743 36.8026 -73.1973 0.38116 0.428555 -0.485745 0.659629 +VERTEX_SE3:QUAT 2165 10.1799 38.4407 -72.7828 0.360585 0.444514 -0.436466 0.694178 +VERTEX_SE3:QUAT 2166 14.7513 40.689 -72.2319 0.325253 0.467574 -0.389563 0.723758 +VERTEX_SE3:QUAT 2167 18.9457 43.5696 -71.7201 0.294748 0.472561 -0.346759 0.754697 +VERTEX_SE3:QUAT 2168 22.7603 46.8933 -71.1686 0.266257 0.49202 -0.296102 0.774175 +VERTEX_SE3:QUAT 2169 26.0915 50.65 -70.6027 0.240683 0.504575 -0.252265 0.789834 +VERTEX_SE3:QUAT 2170 28.9944 54.7421 -69.9985 0.211424 0.515605 -0.206829 0.80416 +VERTEX_SE3:QUAT 2171 31.4055 59.1332 -69.3965 0.171534 0.526805 -0.160846 0.816811 +VERTEX_SE3:QUAT 2172 33.2444 63.8038 -68.892 0.141097 0.529624 -0.109109 0.829268 +VERTEX_SE3:QUAT 2173 34.4892 68.6484 -68.3378 0.10425 0.525823 -0.0542246 0.842438 +VERTEX_SE3:QUAT 2174 35.0601 73.5689 -67.8188 0.0648697 0.530256 -0.00354148 0.845345 +VERTEX_SE3:QUAT 2175 35.0059 78.5255 -67.3517 0.0362861 0.525257 0.0381991 0.849311 +VERTEX_SE3:QUAT 2176 34.4539 83.4488 -66.9245 0.00417857 0.526947 0.0945288 0.844614 +VERTEX_SE3:QUAT 2177 33.2764 88.2568 -66.4651 -0.0247891 0.51592 0.136992 0.845249 +VERTEX_SE3:QUAT 2178 31.5918 92.9184 -66.0666 -0.0638434 0.506057 0.182895 0.840464 +VERTEX_SE3:QUAT 2179 29.362 97.3125 -65.7782 -0.101271 0.492636 0.228086 0.833685 +VERTEX_SE3:QUAT 2180 26.6496 101.391 -65.6099 -0.147634 0.4872 0.275973 0.815279 +VERTEX_SE3:QUAT 2181 23.4078 105.051 -65.5514 -0.178839 0.469394 0.318968 0.803707 +VERTEX_SE3:QUAT 2182 19.8013 108.335 -65.5947 -0.216287 0.458879 0.370105 0.778249 +VERTEX_SE3:QUAT 2183 15.7948 111.085 -65.6852 -0.246951 0.442806 0.414572 0.755691 +VERTEX_SE3:QUAT 2184 11.5064 113.326 -65.8071 -0.280387 0.427206 0.451673 0.731348 +VERTEX_SE3:QUAT 2185 7.00749 115.056 -66.0017 -0.30708 0.405356 0.499299 0.701491 +VERTEX_SE3:QUAT 2186 2.33037 116.16 -66.2224 -0.331207 0.380394 0.540589 0.673324 +VERTEX_SE3:QUAT 2187 -2.44951 116.702 -66.4798 -0.368607 0.356316 0.576456 0.636291 +VERTEX_SE3:QUAT 2188 -7.22488 116.608 -66.8681 -0.395005 0.339595 0.609596 0.597528 +VERTEX_SE3:QUAT 2189 -11.945 115.948 -67.2149 -0.426047 0.30841 0.644293 0.555206 +VERTEX_SE3:QUAT 2190 -16.5094 114.635 -67.64 -0.439907 0.274756 0.680342 0.517808 +VERTEX_SE3:QUAT 2191 -20.8567 112.786 -68.1124 -0.464761 0.247006 0.709099 0.469217 +VERTEX_SE3:QUAT 2192 -24.8795 110.369 -68.5953 -0.493243 0.212831 0.729168 0.423944 +VERTEX_SE3:QUAT 2193 -28.5292 107.445 -69.1694 -0.510962 0.180957 0.7523 0.374456 +VERTEX_SE3:QUAT 2194 -31.7778 104.07 -69.7531 -0.524183 0.151087 0.768402 0.334611 +VERTEX_SE3:QUAT 2195 -34.622 100.396 -70.378 -0.534435 0.116291 0.79006 0.276877 +VERTEX_SE3:QUAT 2196 -36.8984 96.3557 -70.9787 -0.550873 0.0747795 0.799328 0.228083 +VERTEX_SE3:QUAT 2197 -38.6254 92.0745 -71.6311 -0.565083 0.0422002 0.803476 0.182557 +VERTEX_SE3:QUAT 2198 -39.8325 87.6506 -72.3168 -0.575791 0.00828062 0.807059 0.130579 +VERTEX_SE3:QUAT 2199 -40.4339 83.1009 -72.9747 -0.584774 -0.0250398 0.806665 0.0818767 +VERTEX_SE3:QUAT 2200 -40.498 78.5324 -73.6218 -0.591192 -0.0574984 0.804118 0.0241091 +VERTEX_SE3:QUAT 2201 -39.9622 73.9962 -74.1955 -0.587291 -0.0917105 0.803583 -0.0305566 +VERTEX_SE3:QUAT 2202 -38.8443 69.5781 -74.7176 -0.587565 -0.124405 0.795841 -0.0769914 +VERTEX_SE3:QUAT 2203 -37.2273 65.3277 -75.216 -0.593648 -0.151063 0.78049 -0.124888 +VERTEX_SE3:QUAT 2204 -35.1565 61.2875 -75.6101 -0.593508 -0.179676 0.765731 -0.170647 +VERTEX_SE3:QUAT 2205 -32.641 57.5163 -75.9196 -0.587934 -0.207073 0.74889 -0.224984 +VERTEX_SE3:QUAT 2206 -29.6978 54.0546 -76.1018 -0.584548 -0.233044 0.727063 -0.274542 +VERTEX_SE3:QUAT 2207 -26.3813 51.0068 -76.1516 -0.57457 -0.267144 0.702369 -0.324315 +VERTEX_SE3:QUAT 2208 -22.7123 48.4156 -76.1341 -0.561993 -0.304672 0.673088 -0.371875 +VERTEX_SE3:QUAT 2209 -18.7248 46.3367 -76.0716 -0.551243 -0.32981 0.639826 -0.421877 +VERTEX_SE3:QUAT 2210 -14.5408 44.805 -75.8463 -0.528433 -0.362506 0.610072 -0.466005 +VERTEX_SE3:QUAT 2211 -10.2024 43.8318 -75.5975 0.508616 0.388558 -0.570755 0.514365 +VERTEX_SE3:QUAT 2212 -5.78369 43.4854 -75.2088 0.491633 0.406766 -0.538862 0.549969 +VERTEX_SE3:QUAT 2213 -1.38644 43.6157 -74.7133 0.469718 0.417749 -0.503408 0.592816 +VERTEX_SE3:QUAT 2214 2.94325 44.2461 -74.1039 0.444915 0.435243 -0.46215 0.631689 +VERTEX_SE3:QUAT 2215 7.12833 45.4035 -73.4025 0.407611 0.452181 -0.425977 0.669275 +VERTEX_SE3:QUAT 2216 11.1082 47.1183 -72.7062 0.379792 0.457225 -0.384599 0.706249 +VERTEX_SE3:QUAT 2217 14.8275 49.2965 -71.9038 0.348478 0.464329 -0.346077 0.737016 +VERTEX_SE3:QUAT 2218 18.2439 51.8694 -71.1101 0.310438 0.467389 -0.310775 0.767199 +VERTEX_SE3:QUAT 2219 21.3393 54.8339 -70.3794 0.269217 0.477923 -0.271447 0.790841 +VERTEX_SE3:QUAT 2220 24.0247 58.1524 -69.7435 0.235547 0.479938 -0.226717 0.814111 +VERTEX_SE3:QUAT 2221 26.2777 61.7792 -69.1045 0.192901 0.493272 -0.177642 0.829407 +VERTEX_SE3:QUAT 2222 28.0245 65.6486 -68.5743 0.156262 0.497912 -0.130395 0.843009 +VERTEX_SE3:QUAT 2223 29.2925 69.7422 -68.0985 0.114336 0.494625 -0.0890491 0.856939 +VERTEX_SE3:QUAT 2224 30.0597 73.9373 -67.7389 0.0734966 0.500566 -0.040469 0.861623 +VERTEX_SE3:QUAT 2225 30.3055 78.1564 -67.4735 0.0312263 0.500627 0.00905123 0.865052 +VERTEX_SE3:QUAT 2226 29.9981 82.3778 -67.3117 -0.00309106 0.498136 0.0530264 0.86547 +VERTEX_SE3:QUAT 2227 29.2425 86.5366 -67.2212 -0.0400131 0.49198 0.0930139 0.864698 +VERTEX_SE3:QUAT 2228 28.055 90.5707 -67.2366 -0.0772817 0.484191 0.145005 0.859395 +VERTEX_SE3:QUAT 2229 26.349 94.3964 -67.3216 -0.117844 0.471978 0.195249 0.851603 +VERTEX_SE3:QUAT 2230 24.1786 97.9671 -67.4962 -0.157899 0.460054 0.240865 0.839882 +VERTEX_SE3:QUAT 2231 21.5982 101.221 -67.8035 -0.198536 0.449066 0.280202 0.82487 +VERTEX_SE3:QUAT 2232 18.6873 104.147 -68.2182 -0.238896 0.439809 0.316491 0.80581 +VERTEX_SE3:QUAT 2233 15.4769 106.688 -68.7593 -0.282386 0.423063 0.357229 0.783367 +VERTEX_SE3:QUAT 2234 12.0091 108.782 -69.4337 -0.320779 0.408659 0.390646 0.75993 +VERTEX_SE3:QUAT 2235 8.34746 110.464 -70.212 -0.347021 0.393592 0.435257 0.731583 +VERTEX_SE3:QUAT 2236 4.53927 111.669 -70.9696 -0.379033 0.368613 0.467096 0.708717 +VERTEX_SE3:QUAT 2237 0.645388 112.434 -71.8399 -0.407571 0.34958 0.503468 0.676904 +VERTEX_SE3:QUAT 2238 -3.29016 112.716 -72.7243 -0.446709 0.316664 0.541836 0.637643 +VERTEX_SE3:QUAT 2239 -7.18379 112.424 -73.7098 -0.471666 0.295279 0.568914 0.60554 +VERTEX_SE3:QUAT 2240 -11.0046 111.704 -74.7289 -0.504301 0.279827 0.598578 0.555951 +VERTEX_SE3:QUAT 2241 -14.7081 110.444 -75.6748 -0.5307 0.254416 0.627251 0.510085 +VERTEX_SE3:QUAT 2242 -18.1957 108.714 -76.6092 -0.555463 0.224846 0.654586 0.460894 +VERTEX_SE3:QUAT 2243 -21.3759 106.526 -77.5081 -0.583659 0.199943 0.672622 0.408588 +VERTEX_SE3:QUAT 2244 -24.2404 103.904 -78.3398 -0.602721 0.16824 0.690698 0.362434 +VERTEX_SE3:QUAT 2245 -26.7544 100.956 -79.15 -0.617009 0.144253 0.707872 0.312102 +VERTEX_SE3:QUAT 2246 -28.8815 97.7554 -79.8505 -0.635551 0.105069 0.719537 0.259428 +VERTEX_SE3:QUAT 2247 -30.5755 94.2762 -80.5291 -0.647569 0.0597919 0.731523 0.204824 +VERTEX_SE3:QUAT 2248 -31.6894 90.5916 -81.2104 -0.659185 0.0323852 0.737205 0.144762 +VERTEX_SE3:QUAT 2249 -32.3383 86.7824 -81.7327 -0.67412 0.00401995 0.734169 0.0808888 +VERTEX_SE3:QUAT 2250 -32.4552 82.945 -82.0841 -0.678156 -0.0289393 0.733926 0.0248889 +VERTEX_SE3:QUAT 2251 -32.0754 79.1088 -82.3322 -0.684121 -0.0542228 0.726477 -0.0356266 +VERTEX_SE3:QUAT 2252 -31.2334 75.3563 -82.4003 -0.682926 -0.0869775 0.720765 -0.0809063 +VERTEX_SE3:QUAT 2253 -29.9832 71.715 -82.3888 -0.672964 -0.113438 0.716997 -0.142009 +VERTEX_SE3:QUAT 2254 -28.2932 68.2817 -82.2442 -0.662661 -0.143311 0.707913 -0.197995 +VERTEX_SE3:QUAT 2255 -26.1927 65.1321 -81.9767 -0.647106 -0.186119 0.693197 -0.257082 +VERTEX_SE3:QUAT 2256 -23.6566 62.3433 -81.6538 -0.6383 -0.209196 0.676723 -0.301423 +VERTEX_SE3:QUAT 2257 -20.8722 59.8494 -81.2268 -0.623997 -0.247133 0.656314 -0.344681 +VERTEX_SE3:QUAT 2258 -17.8099 57.7206 -80.7936 -0.605949 -0.27734 0.631698 -0.396063 +VERTEX_SE3:QUAT 2259 -14.486 56.0416 -80.2828 -0.581385 -0.303035 0.609199 -0.446136 +VERTEX_SE3:QUAT 2260 -11.0449 54.7998 -79.7023 -0.553097 -0.330051 0.585917 -0.491784 +VERTEX_SE3:QUAT 2261 -7.46679 54.0171 -79.1127 0.535089 0.34869 -0.554108 0.533909 +VERTEX_SE3:QUAT 2262 -3.86045 53.6814 -78.4322 0.506943 0.369514 -0.515703 0.58354 +VERTEX_SE3:QUAT 2263 -0.260097 53.8632 -77.6693 0.465463 0.389723 -0.489983 0.625601 +VERTEX_SE3:QUAT 2264 3.28617 54.5206 -76.9669 0.428186 0.406305 -0.455489 0.666411 +VERTEX_SE3:QUAT 2265 6.70358 55.6506 -76.2744 0.394049 0.427175 -0.410783 0.702498 +VERTEX_SE3:QUAT 2266 9.88719 57.2508 -75.5986 0.365702 0.439255 -0.37017 0.732319 +VERTEX_SE3:QUAT 2267 12.8518 59.2216 -74.8941 0.324247 0.451614 -0.331048 0.762441 +VERTEX_SE3:QUAT 2268 15.5343 61.5627 -74.2621 0.287647 0.467318 -0.29811 0.781027 +VERTEX_SE3:QUAT 2269 17.9494 64.1629 -73.7401 0.256313 0.476576 -0.252365 0.802179 +VERTEX_SE3:QUAT 2270 20.0105 67.0477 -73.2245 0.210281 0.494159 -0.213732 0.816031 +VERTEX_SE3:QUAT 2271 21.7175 70.1544 -72.8427 0.172853 0.495031 -0.163629 0.835639 +VERTEX_SE3:QUAT 2272 22.9979 73.4381 -72.4773 0.130908 0.498045 -0.122692 0.848388 +VERTEX_SE3:QUAT 2273 23.887 76.853 -72.226 0.0817405 0.510857 -0.0820708 0.851826 +VERTEX_SE3:QUAT 2274 24.3429 80.3485 -72.1281 0.0372733 0.518944 -0.0252043 0.853623 +VERTEX_SE3:QUAT 2275 24.295 83.8584 -72.1009 -0.0023991 0.522706 0.028017 0.852049 +VERTEX_SE3:QUAT 2276 23.7932 87.301 -72.1058 -0.040886 0.520998 0.0733359 0.849418 +VERTEX_SE3:QUAT 2277 22.8945 90.6536 -72.1925 -0.0908113 0.517443 0.11797 0.842668 +VERTEX_SE3:QUAT 2278 21.5875 93.8389 -72.3948 -0.136618 0.514389 0.170042 0.829352 +VERTEX_SE3:QUAT 2279 19.8538 96.7894 -72.6569 -0.182703 0.506148 0.204654 0.81765 +VERTEX_SE3:QUAT 2280 17.8023 99.4928 -73.0552 -0.219604 0.490569 0.249154 0.805629 +VERTEX_SE3:QUAT 2281 15.4587 101.931 -73.5097 -0.257251 0.486527 0.297014 0.780318 +VERTEX_SE3:QUAT 2282 12.8239 104.016 -73.9604 -0.293438 0.466296 0.34436 0.760183 +VERTEX_SE3:QUAT 2283 9.95208 105.734 -74.4658 -0.329289 0.452402 0.39237 0.730032 +VERTEX_SE3:QUAT 2284 6.90332 107.035 -74.978 -0.366297 0.436139 0.431313 0.699699 +VERTEX_SE3:QUAT 2285 3.70723 107.94 -75.4922 -0.40319 0.412439 0.471516 0.667087 +VERTEX_SE3:QUAT 2286 0.433684 108.38 -76.0542 -0.428068 0.391234 0.513497 0.632467 +VERTEX_SE3:QUAT 2287 -2.84573 108.409 -76.5591 -0.457516 0.364752 0.551904 0.594169 +VERTEX_SE3:QUAT 2288 -6.08747 107.996 -77.0788 -0.488849 0.33926 0.582276 0.553971 +VERTEX_SE3:QUAT 2289 -9.22542 107.175 -77.6171 -0.515433 0.31313 0.613371 0.509956 +VERTEX_SE3:QUAT 2290 -12.2355 105.942 -78.1013 -0.539886 0.281998 0.637068 0.472382 +VERTEX_SE3:QUAT 2291 -15.0402 104.36 -78.6485 -0.568081 0.247498 0.660318 0.424274 +VERTEX_SE3:QUAT 2292 -17.5729 102.412 -79.1705 -0.583818 0.208838 0.689632 0.374101 +VERTEX_SE3:QUAT 2293 -19.7917 100.145 -79.6747 -0.611072 0.169705 0.705865 0.315509 +VERTEX_SE3:QUAT 2294 -21.626 97.5727 -80.1568 -0.620742 0.13362 0.721281 0.276729 +VERTEX_SE3:QUAT 2295 -23.1514 94.8212 -80.6377 -0.637134 0.098456 0.726243 0.238617 +VERTEX_SE3:QUAT 2296 -24.3725 91.9272 -81.1348 -0.654121 0.0625139 0.731131 0.183479 +VERTEX_SE3:QUAT 2297 -25.1657 88.8997 -81.6132 -0.671004 0.0317732 0.729862 0.126675 +VERTEX_SE3:QUAT 2298 -25.5602 85.7833 -81.9736 -0.680606 -0.00560617 0.728164 0.0807589 +VERTEX_SE3:QUAT 2299 -25.5967 82.6911 -82.2995 -0.691058 -0.03533 0.721323 0.029738 +VERTEX_SE3:QUAT 2300 -25.2493 79.6026 -82.547 -0.698184 -0.0649881 0.712391 -0.0285259 +VERTEX_SE3:QUAT 2301 -24.5325 76.5873 -82.6437 -0.699403 -0.0987875 0.70385 -0.0753087 +VERTEX_SE3:QUAT 2302 -23.4846 73.695 -82.6971 0.69635 0.134464 -0.692547 0.131893 +VERTEX_SE3:QUAT 2303 -22.0894 70.9734 -82.6472 0.689963 0.170247 -0.679581 0.182037 +VERTEX_SE3:QUAT 2304 -20.3554 68.4765 -82.5333 0.690398 0.195417 -0.655096 0.236667 +VERTEX_SE3:QUAT 2305 -18.3631 66.2029 -82.2509 0.680608 0.219024 -0.636083 0.290172 +VERTEX_SE3:QUAT 2306 -16.1342 64.1869 -81.8564 0.665487 0.256727 -0.611996 0.341583 +VERTEX_SE3:QUAT 2307 -13.6775 62.5346 -81.3809 0.645486 0.279342 -0.600982 0.379654 +VERTEX_SE3:QUAT 2308 -11.0756 61.142 -80.8794 0.629276 0.30954 -0.574056 0.422679 +VERTEX_SE3:QUAT 2309 -8.33065 60.0886 -80.3411 0.607542 0.332074 -0.553933 0.462362 +VERTEX_SE3:QUAT 2310 -5.53539 59.3435 -79.7354 0.591829 0.356138 -0.51805 0.504508 +VERTEX_SE3:QUAT 2311 -2.69173 58.9491 -79.0252 0.568487 0.374792 -0.482193 0.55122 +VERTEX_SE3:QUAT 2312 0.146304 58.9358 -78.2345 0.543975 0.398546 -0.447737 0.587183 +VERTEX_SE3:QUAT 2313 2.90553 59.2531 -77.4137 0.512187 0.423996 -0.412448 0.622718 +VERTEX_SE3:QUAT 2314 5.58377 59.9525 -76.5728 0.482208 0.438335 -0.376352 0.658557 +VERTEX_SE3:QUAT 2315 8.16668 60.9783 -75.6842 0.450968 0.457716 -0.332339 0.690417 +VERTEX_SE3:QUAT 2316 10.5299 62.3168 -74.8103 0.421327 0.470161 -0.290718 0.718969 +VERTEX_SE3:QUAT 2317 12.6969 63.9191 -73.8966 0.382098 0.47783 -0.258601 0.747533 +VERTEX_SE3:QUAT 2318 14.6533 65.7748 -73.0256 0.340507 0.487147 -0.227512 0.77135 +VERTEX_SE3:QUAT 2319 16.4008 67.8787 -72.2201 0.293618 0.492308 -0.192667 0.79643 +VERTEX_SE3:QUAT 2320 17.8624 70.1712 -71.5068 0.251694 0.49828 -0.155694 0.81494 +VERTEX_SE3:QUAT 2321 19.0379 72.6347 -70.8643 0.207947 0.501479 -0.112079 0.832295 +VERTEX_SE3:QUAT 2322 19.8948 75.2363 -70.3071 0.160473 0.505498 -0.0693765 0.84493 +VERTEX_SE3:QUAT 2323 20.4135 77.9024 -69.8494 0.122388 0.507724 -0.0329882 0.852144 +VERTEX_SE3:QUAT 2324 20.6408 80.6064 -69.4647 0.0772062 0.508226 -0.00285275 0.857751 +VERTEX_SE3:QUAT 2325 20.6008 83.3239 -69.2068 0.0285863 0.500924 0.0469929 0.863742 +VERTEX_SE3:QUAT 2326 20.1963 86.0133 -69.0511 -0.0328146 0.498155 0.0829441 0.862487 +VERTEX_SE3:QUAT 2327 19.4647 88.6017 -69.1158 -0.0731979 0.495609 0.122819 0.856697 +VERTEX_SE3:QUAT 2328 18.442 91.0872 -69.2515 -0.119472 0.477925 0.160868 0.85524 +VERTEX_SE3:QUAT 2329 17.1607 93.4333 -69.5087 -0.165513 0.469054 0.205674 0.842788 +VERTEX_SE3:QUAT 2330 15.6158 95.5739 -69.8487 -0.206886 0.460598 0.247263 0.826987 +VERTEX_SE3:QUAT 2331 13.8392 97.4884 -70.2508 -0.248096 0.449382 0.279434 0.811432 +VERTEX_SE3:QUAT 2332 11.9024 99.166 -70.7436 -0.292747 0.437411 0.316008 0.789373 +VERTEX_SE3:QUAT 2333 9.77736 100.579 -71.3254 -0.324857 0.424776 0.354192 0.76719 +VERTEX_SE3:QUAT 2334 7.52488 101.717 -71.9382 -0.363678 0.404781 0.390185 0.742729 +VERTEX_SE3:QUAT 2335 5.18838 102.551 -72.6102 -0.403726 0.382161 0.429635 0.711598 +VERTEX_SE3:QUAT 2336 2.77348 103.056 -73.3124 -0.44393 0.364484 0.467131 0.67221 +VERTEX_SE3:QUAT 2337 0.32947 103.215 -74.0326 -0.489501 0.341383 0.495481 0.631146 +VERTEX_SE3:QUAT 2338 -2.08485 103.012 -74.7948 -0.523425 0.319521 0.526069 0.589223 +VERTEX_SE3:QUAT 2339 -4.44338 102.499 -75.5325 -0.557388 0.292127 0.54991 0.549162 +VERTEX_SE3:QUAT 2340 -6.68437 101.641 -76.2927 -0.587349 0.267853 0.570085 0.508212 +VERTEX_SE3:QUAT 2341 -8.8035 100.564 -77.039 0.613971 -0.240635 -0.589802 -0.46612 +VERTEX_SE3:QUAT 2342 -10.743 99.2078 -77.7603 0.638863 -0.216435 -0.611149 -0.414134 +VERTEX_SE3:QUAT 2343 -12.5012 97.6191 -78.3965 0.660045 -0.191449 -0.627127 -0.366606 +VERTEX_SE3:QUAT 2344 -14.0561 95.8257 -78.9713 0.68234 -0.16157 -0.638493 -0.317229 +VERTEX_SE3:QUAT 2345 -15.3649 93.8528 -79.4981 0.696911 -0.131897 -0.651721 -0.268659 +VERTEX_SE3:QUAT 2346 -16.4268 91.7356 -79.9643 0.71647 -0.0889731 -0.658116 -0.21363 +VERTEX_SE3:QUAT 2347 -17.1425 89.4888 -80.3937 0.721084 -0.0521729 -0.670944 -0.164771 +VERTEX_SE3:QUAT 2348 -17.5933 87.1855 -80.76 0.728638 -0.0220671 -0.675087 -0.113393 +VERTEX_SE3:QUAT 2349 -17.778 84.8455 -81.0516 0.733285 0.00613044 -0.676459 -0.0682537 +VERTEX_SE3:QUAT 2350 -17.7146 82.5039 -81.2715 0.737762 0.0338826 -0.674038 -0.0152254 +VERTEX_SE3:QUAT 2351 -17.3982 80.188 -81.3762 0.741776 0.0622805 -0.666292 0.0441065 +VERTEX_SE3:QUAT 2352 -16.7837 77.9556 -81.3542 0.737416 0.0956918 -0.661283 0.0988209 +VERTEX_SE3:QUAT 2353 -15.8977 75.8411 -81.2699 0.727054 0.1316 -0.655347 0.156826 +VERTEX_SE3:QUAT 2354 -14.7614 73.8579 -81.0883 0.715161 0.17252 -0.642805 0.213502 +VERTEX_SE3:QUAT 2355 -13.3658 72.1026 -80.8541 0.7065 0.208443 -0.619316 0.271768 +VERTEX_SE3:QUAT 2356 -11.7524 70.5408 -80.54 0.687373 0.238049 -0.606766 0.320447 +VERTEX_SE3:QUAT 2357 -9.98841 69.2185 -80.1689 0.671527 0.26302 -0.584636 0.371582 +VERTEX_SE3:QUAT 2358 -8.09872 68.1365 -79.7152 0.646279 0.303924 -0.560555 0.419203 +VERTEX_SE3:QUAT 2359 -6.08879 67.3473 -79.2221 0.626971 0.324117 -0.531592 0.468259 +VERTEX_SE3:QUAT 2360 -4.03612 66.8359 -78.662 0.604768 0.348533 -0.505234 0.507463 +VERTEX_SE3:QUAT 2361 -1.96019 66.5644 -78.0942 0.583109 0.377863 -0.475023 0.53996 +VERTEX_SE3:QUAT 2362 0.123395 66.5253 -77.4869 0.55624 0.394772 -0.44743 0.578411 +VERTEX_SE3:QUAT 2363 2.15927 66.7461 -76.8716 0.521297 0.410401 -0.409622 0.626123 +VERTEX_SE3:QUAT 2364 4.12764 67.2587 -76.2137 0.482939 0.432574 -0.370515 0.665108 +VERTEX_SE3:QUAT 2365 5.97479 68.0356 -75.5435 0.440932 0.449537 -0.344834 0.696121 +VERTEX_SE3:QUAT 2366 7.70285 69.054 -74.9229 0.400599 0.467461 -0.312201 0.723555 +VERTEX_SE3:QUAT 2367 9.29764 70.2722 -74.3682 0.356849 0.484263 -0.276447 0.749483 +VERTEX_SE3:QUAT 2368 10.7289 71.6989 -73.8505 0.320741 0.494386 -0.239549 0.771572 +VERTEX_SE3:QUAT 2369 11.9861 73.2554 -73.383 0.283126 0.505791 -0.194757 0.791255 +VERTEX_SE3:QUAT 2370 13.0146 74.9601 -72.9443 0.238314 0.514376 -0.148308 0.810326 +VERTEX_SE3:QUAT 2371 13.8158 76.7634 -72.5488 0.200486 0.516933 -0.120495 0.823448 +VERTEX_SE3:QUAT 2372 14.4206 78.643 -72.2219 0.164567 0.514175 -0.0750837 0.838394 +VERTEX_SE3:QUAT 2373 14.813 80.5836 -71.9247 0.11924 0.518256 -0.0276726 0.84642 +VERTEX_SE3:QUAT 2374 14.9429 82.5401 -71.6704 0.0700564 0.517468 0.007514 0.852797 +VERTEX_SE3:QUAT 2375 14.8207 84.4805 -71.5128 0.0252463 0.515647 0.0490089 0.855026 +VERTEX_SE3:QUAT 2376 14.4842 86.4106 -71.4464 -0.0228438 0.513641 0.0900513 0.852961 +VERTEX_SE3:QUAT 2377 13.9284 88.2565 -71.4421 -0.0764204 0.512604 0.117826 0.847062 +VERTEX_SE3:QUAT 2378 13.185 90.021 -71.5717 -0.120888 0.506197 0.154444 0.83982 +VERTEX_SE3:QUAT 2379 12.2859 91.6839 -71.7605 -0.167005 0.49661 0.2003 0.827869 +VERTEX_SE3:QUAT 2380 11.1689 93.1739 -71.9907 -0.21766 0.489297 0.241215 0.809338 +VERTEX_SE3:QUAT 2381 9.87288 94.503 -72.2834 -0.268467 0.476696 0.279218 0.789128 +VERTEX_SE3:QUAT 2382 8.42904 95.6318 -72.6452 -0.310749 0.457837 0.320199 0.768956 +VERTEX_SE3:QUAT 2383 6.89127 96.5327 -73.0642 -0.351589 0.43949 0.350008 0.748818 +VERTEX_SE3:QUAT 2384 5.26822 97.2376 -73.5244 -0.392107 0.421901 0.38798 0.71953 +VERTEX_SE3:QUAT 2385 3.60731 97.7134 -74.02 -0.435028 0.398469 0.423073 0.687737 +VERTEX_SE3:QUAT 2386 1.90867 97.9648 -74.5537 -0.475606 0.378612 0.454072 0.651361 +VERTEX_SE3:QUAT 2387 0.210223 97.9486 -75.0886 -0.521026 0.354585 0.480895 0.609542 +VERTEX_SE3:QUAT 2388 -1.44946 97.723 -75.6187 -0.557947 0.330396 0.504929 0.56972 +VERTEX_SE3:QUAT 2389 -3.05571 97.2714 -76.1636 -0.595633 0.300359 0.527988 0.525581 +VERTEX_SE3:QUAT 2390 -4.55784 96.5868 -76.7091 0.622878 -0.267969 -0.553807 -0.483232 +VERTEX_SE3:QUAT 2391 -5.92443 95.713 -77.235 0.649657 -0.235488 -0.578237 -0.433743 +VERTEX_SE3:QUAT 2392 -7.15447 94.6639 -77.7159 0.68 -0.208077 -0.590818 -0.381101 +VERTEX_SE3:QUAT 2393 -8.24349 93.4601 -78.1617 0.700936 -0.172049 -0.60769 -0.331364 +VERTEX_SE3:QUAT 2394 -9.13597 92.1192 -78.5341 0.719915 -0.151573 -0.61741 -0.278484 +VERTEX_SE3:QUAT 2395 -9.89049 90.6844 -78.8391 0.734253 -0.119412 -0.631724 -0.218032 +VERTEX_SE3:QUAT 2396 -10.4144 89.1549 -79.0626 0.739966 -0.0794837 -0.648921 -0.158225 +VERTEX_SE3:QUAT 2397 -10.7121 87.5905 -79.2301 0.749501 -0.0490627 -0.651786 -0.104961 +VERTEX_SE3:QUAT 2398 -10.8368 85.9986 -79.3536 0.754999 -0.0138909 -0.653427 -0.0530733 +VERTEX_SE3:QUAT 2399 -10.7588 84.4222 -79.4055 0.75683 0.0237094 -0.653172 0.00365879 +VERTEX_SE3:QUAT 2400 -10.4682 82.8733 -79.4069 0.750224 0.0645702 -0.655521 0.0573343 +VERTEX_SE3:QUAT 2401 -9.98317 81.3833 -79.3496 0.746146 0.101345 -0.648903 0.10918 +VERTEX_SE3:QUAT 2402 -9.33947 79.9948 -79.2609 0.735778 0.142198 -0.640781 0.166766 +VERTEX_SE3:QUAT 2403 -8.48653 78.7289 -79.1353 0.726381 0.17007 -0.629224 0.218001 +VERTEX_SE3:QUAT 2404 -7.53114 77.5861 -78.9417 0.715517 0.208547 -0.612757 0.262818 +VERTEX_SE3:QUAT 2405 -6.46397 76.5606 -78.7163 0.707584 0.237298 -0.589212 0.309586 +VERTEX_SE3:QUAT 2406 -5.30235 75.6903 -78.4377 0.691571 0.275672 -0.560441 0.362822 +VERTEX_SE3:QUAT 2407 -4.0326 75.026 -78.1325 0.674089 0.300721 -0.537151 0.408215 +VERTEX_SE3:QUAT 2408 -2.72996 74.5026 -77.7776 0.649175 0.327102 -0.517259 0.451686 +VERTEX_SE3:QUAT 2409 -1.39208 74.1698 -77.3815 0.613861 0.357527 -0.493813 0.501495 +VERTEX_SE3:QUAT 2410 -0.0281709 74.0213 -77.0104 0.593432 0.389564 -0.458623 0.534549 +VERTEX_SE3:QUAT 2411 1.31067 74.0693 -76.6069 0.563274 0.410789 -0.432401 0.571843 +VERTEX_SE3:QUAT 2412 2.6026 74.2778 -76.2069 0.537314 0.436588 -0.387849 0.608488 +VERTEX_SE3:QUAT 2413 3.84353 74.6645 -75.7804 0.503433 0.460065 -0.352842 0.640623 +VERTEX_SE3:QUAT 2414 5.00024 75.1994 -75.3469 0.469114 0.473583 -0.319937 0.67327 +VERTEX_SE3:QUAT 2415 6.09334 75.8736 -74.9216 0.427524 0.489986 -0.289435 0.702399 +VERTEX_SE3:QUAT 2416 7.09113 76.6494 -74.5315 0.387624 0.502509 -0.255759 0.72926 +VERTEX_SE3:QUAT 2417 7.96269 77.5507 -74.188 0.349145 0.512854 -0.226467 0.750861 +VERTEX_SE3:QUAT 2418 8.72028 78.5392 -73.8485 0.303325 0.523433 -0.186136 0.774187 +VERTEX_SE3:QUAT 2419 9.32411 79.6199 -73.5339 0.260043 0.539716 -0.13736 0.788807 +VERTEX_SE3:QUAT 2420 9.77089 80.7653 -73.2592 0.222953 0.543548 -0.0985525 0.803203 +VERTEX_SE3:QUAT 2421 10.0827 81.944 -73.0074 0.176914 0.546626 -0.0484735 0.817038 +VERTEX_SE3:QUAT 2422 10.2229 83.1586 -72.7976 0.118055 0.54866 -0.0140103 0.82755 +VERTEX_SE3:QUAT 2423 10.1996 84.3641 -72.6692 0.0712869 0.548521 0.0229394 0.832776 +VERTEX_SE3:QUAT 2424 10.0788 85.56 -72.567 0.021298 0.54889 0.0605345 0.833428 +VERTEX_SE3:QUAT 2425 9.81967 86.702 -72.5242 -0.0202927 0.548126 0.103892 0.82967 +VERTEX_SE3:QUAT 2426 9.42223 87.7813 -72.5039 -0.073571 0.53927 0.138446 0.82741 +VERTEX_SE3:QUAT 2427 8.87801 88.8027 -72.5448 -0.115326 0.532095 0.170117 0.821361 +VERTEX_SE3:QUAT 2428 8.2644 89.776 -72.6134 -0.165183 0.52661 0.203492 0.808695 +VERTEX_SE3:QUAT 2429 7.56232 90.6334 -72.7527 -0.208374 0.516328 0.246319 0.793292 +VERTEX_SE3:QUAT 2430 6.75376 91.3833 -72.9161 -0.249144 0.510881 0.280646 0.773412 +VERTEX_SE3:QUAT 2431 5.88571 92.0031 -73.0817 -0.288705 0.494386 0.310395 0.758872 +VERTEX_SE3:QUAT 2432 4.98444 92.5487 -73.2971 -0.332726 0.47426 0.34787 0.737127 +VERTEX_SE3:QUAT 2433 4.0185 92.9509 -73.5187 -0.371689 0.451169 0.388886 0.712082 +VERTEX_SE3:QUAT 2434 3.06 93.2172 -73.7495 -0.419866 0.430228 0.414911 0.682982 +VERTEX_SE3:QUAT 2435 2.08262 93.3462 -74.021 -0.454114 0.404546 0.447602 0.655573 +VERTEX_SE3:QUAT 2436 1.10903 93.348 -74.2981 -0.498503 0.376987 0.472901 0.62108 +VERTEX_SE3:QUAT 2437 0.178998 93.2114 -74.5855 -0.526244 0.350709 0.505705 0.586799 +VERTEX_SE3:QUAT 2438 -0.721253 92.9656 -74.8712 -0.560726 0.318219 0.529296 0.551515 +VERTEX_SE3:QUAT 2439 -1.55529 92.602 -75.1694 -0.585188 0.293857 0.554736 0.513294 +VERTEX_SE3:QUAT 2440 -2.33736 92.1386 -75.4378 0.611627 -0.267253 -0.574195 -0.474119 +VERTEX_SE3:QUAT 2441 -3.03732 91.6089 -75.7046 0.635424 -0.233736 -0.593129 -0.435663 +VERTEX_SE3:QUAT 2442 -3.6681 91.0054 -75.945 0.663102 -0.201784 -0.605245 -0.391481 +VERTEX_SE3:QUAT 2443 -4.17643 90.3268 -76.1758 0.686376 -0.166396 -0.620115 -0.341552 +VERTEX_SE3:QUAT 2444 -4.59203 89.5663 -76.4087 0.70887 -0.136113 -0.622788 -0.301847 +VERTEX_SE3:QUAT 2445 -4.92675 88.7732 -76.5957 0.726002 -0.10027 -0.632735 -0.250028 +VERTEX_SE3:QUAT 2446 -5.14587 87.964 -76.7552 0.741759 -0.065953 -0.637804 -0.196595 +VERTEX_SE3:QUAT 2447 -5.26838 87.1351 -76.9067 0.753393 -0.0285971 -0.639126 -0.151985 +VERTEX_SE3:QUAT 2448 -5.28585 86.333 -77.0472 0.760652 0.00384518 -0.641923 -0.0965828 +VERTEX_SE3:QUAT 2449 -5.2008 85.5356 -77.1247 0.763397 0.0382588 -0.642646 -0.0526022 +VERTEX_SE3:QUAT 2450 -5.04515 84.7642 -77.1881 0.764068 0.0729179 -0.641001 0.000431157 +VERTEX_SE3:QUAT 2451 -4.80371 84.017 -77.2381 0.762555 0.112369 -0.6347 0.0551313 +VERTEX_SE3:QUAT 2452 -4.47629 83.3568 -77.2553 0.762033 0.152032 -0.620995 0.10275 +VERTEX_SE3:QUAT 2453 -4.06156 82.7457 -77.2347 0.751879 0.192667 -0.612442 0.149906 +VERTEX_SE3:QUAT 2454 -3.57021 82.1907 -77.2184 0.741936 0.218872 -0.602079 0.197804 +VERTEX_SE3:QUAT 2455 -3.04844 81.7131 -77.1659 0.732477 0.244448 -0.587144 0.24287 +VERTEX_SE3:QUAT 2456 -2.49953 81.2997 -77.0803 0.715855 0.278191 -0.568965 0.294007 +VERTEX_SE3:QUAT 2457 -1.9205 80.9773 -76.9843 0.700063 0.307892 -0.551024 0.333896 +VERTEX_SE3:QUAT 2458 -1.31891 80.7435 -76.8766 0.6788 0.342933 -0.525991 0.380738 +VERTEX_SE3:QUAT 2459 -0.702894 80.5869 -76.7385 0.65133 0.371235 -0.503381 0.429606 +VERTEX_SE3:QUAT 2460 -0.0654573 80.5149 -76.6002 0.624966 0.399097 -0.477516 0.471294 +VERTEX_SE3:QUAT 2461 0.552218 80.527 -76.4519 0.591736 0.425011 -0.453331 0.513523 +VERTEX_SE3:QUAT 2462 1.13324 80.5955 -76.3058 0.561884 0.450792 -0.422313 0.550204 +VERTEX_SE3:QUAT 2463 1.69084 80.7668 -76.1597 0.52298 0.475725 -0.38865 0.590871 +VERTEX_SE3:QUAT 2464 2.20306 81.0097 -76.0396 0.48316 0.505505 -0.356009 0.619902 +VERTEX_SE3:QUAT 2465 2.63649 81.3013 -75.9327 0.443266 0.522775 -0.315148 0.656433 +VERTEX_SE3:QUAT 2466 3.02299 81.6629 -75.8063 0.403837 0.535462 -0.277036 0.688075 +VERTEX_SE3:QUAT 2467 3.35977 82.0503 -75.6877 0.365579 0.546811 -0.246204 0.711853 +VERTEX_SE3:QUAT 2468 3.63709 82.4631 -75.5871 0.326811 0.555157 -0.209396 0.735628 +VERTEX_SE3:QUAT 2469 3.85785 82.9212 -75.4971 0.279947 0.567603 -0.17541 0.754114 +VERTEX_SE3:QUAT 2470 3.99894 83.3694 -75.4279 0.248362 0.580311 -0.132121 0.764264 +VERTEX_SE3:QUAT 2471 4.08332 83.8219 -75.3454 0.209973 0.589134 -0.0945565 0.774527 +VERTEX_SE3:QUAT 2472 4.13013 84.2742 -75.3078 0.170573 0.597563 -0.0536188 0.781632 +VERTEX_SE3:QUAT 2473 4.11613 84.7015 -75.2696 0.124803 0.601142 -0.0244543 0.788958 +VERTEX_SE3:QUAT 2474 4.03921 85.12 -75.2357 0.0649375 0.601462 0.0280227 0.795764 +VERTEX_SE3:QUAT 2475 3.90965 85.5033 -75.2053 0.0204231 0.59504 0.0702885 0.800356 +VERTEX_SE3:QUAT 2476 3.73257 85.8449 -75.2224 -0.0329718 0.589776 0.106527 0.79983 +VERTEX_SE3:QUAT 2477 3.52195 86.1569 -75.2349 -0.0822552 0.581527 0.143411 0.796551 +VERTEX_SE3:QUAT 2478 3.28543 86.4244 -75.289 -0.134445 0.570113 0.179344 0.790399 +VERTEX_SE3:QUAT 2479 3.02811 86.6474 -75.3392 -0.175288 0.558549 0.214465 0.781858 +VERTEX_SE3:QUAT 2480 2.76476 86.8274 -75.3965 -0.221836 0.544783 0.256832 0.766836 +VERTEX_SE3:QUAT 2481 2.47653 86.9497 -75.4397 -0.272431 0.524765 0.294296 0.750862 +VERTEX_SE3:QUAT 2482 2.19609 87.0095 -75.5159 -0.316064 0.50925 0.327378 0.730474 +VERTEX_SE3:QUAT 2483 1.92237 87.0442 -75.5848 -0.359905 0.483945 0.366551 0.708453 +VERTEX_SE3:QUAT 2484 1.63343 87.0333 -75.6468 -0.400126 0.460141 0.394988 0.687135 +VERTEX_SE3:QUAT 2485 1.39569 86.9716 -75.7185 -0.440085 0.435773 0.425051 0.66012 +VERTEX_SE3:QUAT 2486 1.15474 86.9122 -75.7931 -0.486957 0.416181 0.456613 0.617391 +VERTEX_SE3:QUAT 2487 0.965465 86.8094 -75.8648 -0.527129 0.381425 0.480184 0.58828 +VERTEX_SE3:QUAT 2488 0.791007 86.6828 -75.9313 -0.563817 0.360864 0.500714 0.548793 +VERTEX_SE3:QUAT 2489 0.655638 86.5262 -75.9852 -0.601472 0.326118 0.52552 0.505674 +VERTEX_SE3:QUAT 2490 0.576149 86.3565 -76.0466 0.63796 -0.288433 -0.537893 -0.469557 +VERTEX_SE3:QUAT 2491 0.525207 86.1889 -76.0895 0.671329 -0.251447 -0.553459 -0.423999 +VERTEX_SE3:QUAT 2492 0.490133 86.016 -76.1142 0.698791 -0.218159 -0.570395 -0.372489 +VERTEX_SE3:QUAT 2493 0.494886 85.839 -76.1233 0.719035 -0.180423 -0.588293 -0.323029 +VERTEX_SE3:QUAT 2494 0.529373 85.6849 -76.1334 0.738553 -0.135966 -0.600372 -0.274967 +VERTEX_SE3:QUAT 2495 0.602277 85.5597 -76.1359 0.753092 -0.0924668 -0.610405 -0.227396 +VERTEX_SE3:QUAT 2496 0.693766 85.4427 -76.1338 0.762427 -0.0510961 -0.61895 -0.181645 +VERTEX_SE3:QUAT 2497 0.796386 85.3713 -76.1324 0.769185 -0.00858573 -0.622899 -0.142402 +VERTEX_SE3:QUAT 2498 0.911804 85.3343 -76.0976 0.776067 0.0278687 -0.621979 -0.10043 +VERTEX_SE3:QUAT 2499 1.0318 85.323 -76.0615 0.779315 0.0718127 -0.620437 -0.0506864 +EDGE_SE3:QUAT 0 1 -0.0187953 0.0328449 -0.125146 0.0634648 -0.000250128 0.00237634 0.997981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1 2 -0.00836587 0.0518559 -0.141405 0.0636098 -0.000538 0.00162238 0.997973 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2 3 0.0116518 0.0646362 -0.123843 0.0628369 0.0060981 -0.00213561 0.998003 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 3 4 -0.00635662 0.0817346 -0.128989 0.0661221 -0.0051306 0.00750755 0.99777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 4 5 -0.00900338 0.0946003 -0.109164 0.0498363 -0.00340117 -0.00255259 0.998748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 5 6 -0.00495715 0.104779 -0.106982 0.0596275 0.00563598 0.00254199 0.998202 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 6 7 -0.00385872 0.132603 -0.128231 0.0734198 0.000112718 -0.000902908 0.997301 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 7 8 -0.000783881 0.156605 -0.122999 0.0574284 -0.0114936 0.00730844 0.998257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 8 9 -0.00262376 0.131903 -0.124046 0.0674511 0.00698356 0.00882454 0.997659 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 9 10 0.00417907 0.167845 -0.123652 0.0678472 0.00148376 0.0030903 0.99769 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 10 11 -0.0171032 0.182701 -0.103582 0.0621382 0.00331651 0.0100614 0.998011 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 11 12 -0.00609717 0.208135 -0.11761 0.0651438 -0.00266045 0.00414405 0.997864 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 12 13 0.00593493 0.241575 -0.113007 0.0635362 -0.000379909 0.00876266 0.997941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 13 14 -0.020841 0.23336 -0.114513 0.068208 0.00616155 0.00741804 0.997625 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 14 15 -0.011533 0.241387 -0.132828 0.0634664 -0.00616933 -0.00789249 0.997934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 15 16 -0.0152151 0.282277 -0.109438 0.053963 0.00680389 -0.00635827 0.9985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 16 17 0.00708851 0.292726 -0.0942899 0.0591002 0.00811689 0.00128459 0.998218 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 17 18 -0.0108792 0.314375 -0.109276 0.0644037 0.00559066 0.0013855 0.997907 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 18 19 0.00188011 0.325052 -0.103879 0.064749 -0.0100272 0.00317167 0.997846 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 19 20 0.0021224 0.335098 -0.100469 0.0776136 0.00308224 -0.0146465 0.996871 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 20 21 0.00990028 0.345171 -0.0974169 0.0521433 0.00993501 0.00386624 0.998583 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 21 22 -0.0115204 0.37996 -0.119745 0.0648033 0.000176006 0.00890499 0.997858 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 22 23 -0.00434813 0.382637 -0.108034 0.0674113 -0.00141103 0.00235716 0.997721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 23 24 -0.00717238 0.400366 -0.106731 0.0599006 0.00228962 0.00648429 0.998181 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 24 25 0.0126834 0.410917 -0.100955 0.0637841 -0.00201352 -0.0106023 0.997905 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 25 26 -0.00703817 0.440537 -0.0926884 0.0608521 -0.00139079 0.00881361 0.998107 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 26 27 -0.00193239 0.451687 -0.0862336 0.0694 0.0008056 0.00112579 0.997588 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 27 28 0.00676253 0.468364 -0.117452 0.0641826 -0.00738154 0.00014596 0.997911 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 28 29 -0.018906 0.473747 -0.110511 0.0613845 0.00241196 0.0021441 0.998109 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 29 30 0.00263 0.470975 -0.106131 0.0624905 -0.00714482 0.00256959 0.998017 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 30 31 -0.000550329 0.48646 -0.0827454 0.0607646 0.0085928 -0.000271748 0.998115 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 31 32 -0.00523 0.503726 -0.107797 0.0582171 -0.00767468 -0.00092796 0.998274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 32 33 0.00862613 0.528053 -0.0771877 0.0507284 0.000247923 -0.00235088 0.99871 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 33 34 -0.0170512 0.549939 -0.0834767 0.0686302 0.00328081 -0.00188496 0.997635 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 34 35 0.0136157 0.570067 -0.0801957 0.0680682 -0.00165271 -0.00283788 0.997675 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 35 36 0.00713014 0.581769 -0.0994257 0.0533091 -0.0013827 0.00263587 0.998574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 36 37 -0.00465065 0.602159 -0.108905 0.0605581 0.00172115 0.0079744 0.998131 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 37 38 -0.000552461 0.618549 -0.0846461 0.0661319 -0.00014674 -0.00269266 0.997807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 38 39 0.0131254 0.658891 -0.0833402 0.0625181 -0.000190476 0.00242979 0.998041 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 39 40 0.00771349 0.613411 -0.082382 0.0608668 0.000821699 0.00245642 0.998143 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 40 41 0.0119753 0.640236 -0.0654981 0.0605473 -0.00226893 0.00245005 0.99816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 41 42 0.0158246 0.680017 -0.0725808 0.0639624 -0.00327179 0.00891179 0.997907 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 42 43 0.00772409 0.696688 -0.0821624 0.058394 0.00691708 0.00973421 0.998222 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 43 44 -0.00316828 0.722551 -0.0919768 0.0622459 0.000393195 0.000637889 0.998061 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 44 45 0.00684723 0.73335 -0.0841821 0.0601531 0.00303422 0.00121552 0.998184 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 45 46 -0.000306453 0.741073 -0.0827784 0.0579342 0.0099118 0.00254426 0.998268 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 46 47 -0.0053681 0.749838 -0.0743335 0.0587039 0.0051776 0.0020814 0.99826 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 47 48 0.00227321 0.780077 -0.0835752 0.0562025 -0.00358683 -0.00333105 0.998407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 48 49 -0.00627079 0.789016 -0.0830163 0.0606904 -0.00529399 -0.00251406 0.998139 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 49 50 -0.00889147 0.778162 -0.0616908 0.0674974 -0.00656846 0.00572909 0.997681 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 50 51 0.00794442 0.81461 -0.0774327 0.0629154 -0.000614764 0.000308158 0.998019 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 51 52 0.00218028 0.847696 -0.0793824 0.0606934 -0.00276019 0.0017089 0.998151 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 52 53 -0.0117992 0.863075 -0.0721191 0.0620832 0.000700445 0.00304757 0.998066 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 53 54 -0.011245 0.86347 -0.0722455 0.0693926 -0.00377854 0.00413461 0.997574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 54 55 -0.0187014 0.88408 -0.0864725 0.0714968 -0.00269094 0.00116347 0.997437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 55 56 -0.00988933 0.893811 -0.0615184 0.0636124 -0.000644669 0.0163301 0.997841 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 56 57 -0.0159592 0.909966 -0.0648518 0.0770793 -0.0105754 -0.000118216 0.996969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 57 58 -0.0126106 0.927799 -0.0851537 0.0756024 0.00076403 0.00848611 0.997102 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 58 59 0.00173025 0.943556 -0.0818017 0.0567154 -0.00520048 0.00457083 0.998366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 59 60 0.0015656 0.961091 -0.0615833 0.0563644 0.00582765 0.000437832 0.998393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 60 61 -0.0142543 0.971622 -0.0490397 0.0660406 -8.79189e-05 0.00670696 0.997794 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 61 62 -0.0213041 0.984754 -0.0627284 0.0495299 -0.00510868 0.00477109 0.998748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 62 63 -0.0174365 0.9979 -0.0793304 0.0666482 0.00825712 0.00341206 0.997737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 63 64 0.00247898 1.01673 -0.0653718 0.0661145 -0.00160944 0.00605505 0.997792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 64 65 0.00538364 1.01456 -0.0618612 0.0629258 -0.00594214 0.00239049 0.997998 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 65 66 -0.0185571 1.04418 -0.0494786 0.0596391 0.00506998 0.00537852 0.998193 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 66 67 -0.0182675 1.08144 -0.0539525 0.0643164 -0.000975605 0.00769301 0.997899 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 67 68 -0.00152958 1.07593 -0.0731181 0.0611857 0.00533379 0.00599331 0.998094 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 68 69 0.0144895 1.11168 -0.0618957 0.0574852 0.00142017 0.0140052 0.998247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 69 70 0.00184496 1.10588 -0.0404124 0.0589049 -0.000938849 0.00104613 0.998263 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 70 71 -0.00997383 1.11375 -0.0586505 0.0602719 0.00270081 0.00940436 0.998134 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 71 72 -0.0135345 1.14788 -0.0448586 0.0684249 0.00429166 0.0167949 0.997506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 72 73 -0.0147801 1.1595 -0.0499407 0.0611921 0.0180169 0.000744292 0.997963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 73 74 -0.000414108 1.18931 -0.0545993 0.0593102 -0.00250703 0.0135084 0.998145 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 74 75 -0.0229826 1.20197 -0.0530722 0.064349 0.00407313 0.00550192 0.997904 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 75 76 -0.00742519 1.19959 -0.0484604 0.0594232 0.00168782 0.00684577 0.998208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 76 77 -0.00123304 1.22613 -0.0505733 0.067195 0.00124912 0.00269302 0.997735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 77 78 0.00125051 1.24093 -0.0327412 0.0612794 0.00459758 0.0041843 0.998101 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 78 79 -0.00682134 1.25418 -0.0466082 0.0684298 -0.00559404 0.00297302 0.997636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 79 80 -0.0127014 1.27204 -0.0361114 0.0621592 0.00945067 -0.00709213 0.997996 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 80 81 -0.00634233 1.28488 -0.050822 0.0692849 -0.00172452 0.0030877 0.997591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 81 82 -0.0205006 1.30359 -0.0298072 0.0648124 0.0122218 0.00201406 0.997821 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 82 83 -0.0204815 1.32301 -0.0500793 0.0714174 0.0015726 0.00270809 0.997442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 83 84 -0.00660915 1.3477 -0.0239152 0.066535 0.00644874 0.00428576 0.997754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 84 85 -0.00720868 1.34336 -0.0278526 0.0718451 -0.000721391 -0.00201255 0.997414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 85 86 -0.0188479 1.37918 -0.0299727 0.0569019 5.13881e-05 0.0114265 0.998314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 86 87 -0.01525 1.38227 -0.0399834 0.0586621 -0.0122142 0.00682792 0.99818 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 87 88 -0.0164766 1.39313 -0.0388216 0.0670275 0.000241576 0.0119258 0.99768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 88 89 -0.00942145 1.40943 -0.0327227 0.0610237 -0.00647573 -0.00135241 0.998114 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 89 90 -0.0103127 1.42509 -0.0267624 0.0559339 0.00500284 0.00676193 0.998399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 90 91 -0.0173358 1.43642 -0.017062 0.0646787 0.000696065 0.00215251 0.997904 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 91 92 -0.01446 1.45803 -0.0318722 0.0661256 -0.00162477 -0.00587499 0.997793 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 92 93 -0.00101131 1.46917 -0.0245212 0.0634576 -0.00648638 0.00206028 0.997961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 93 94 -0.0170642 1.48881 -0.0348897 0.0703879 0.00170059 0.012873 0.997435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 94 95 -0.000972915 1.49547 -0.0406067 0.0634497 0.00480816 0.0167538 0.997833 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 95 96 -0.00740126 1.51033 -0.0252042 0.0586275 -0.00169175 0.0178855 0.998118 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 96 97 -0.0257307 1.53562 -0.0420163 0.0604412 0.00161406 0.00616005 0.998151 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 97 98 -0.0026265 1.54325 -0.0317039 0.0558196 -0.00476048 0.00548746 0.998414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 98 99 -0.00630493 1.58039 -0.0416564 0.0655908 0.00324635 0.0044014 0.997832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 99 100 -0.00873199 1.59083 -0.0322802 0.056647 -0.00233146 0.0103639 0.998338 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 100 101 -0.000695606 1.60259 -0.0286191 0.0522594 -0.00217497 0.00880991 0.998592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 101 102 -0.0156103 1.6104 -0.0134 0.060915 -0.000349821 -0.00519403 0.998129 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 102 103 -0.0105469 1.62939 -0.0307806 0.0586984 0.00688447 0.00990152 0.998203 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 103 104 -0.017392 1.64453 -0.0171199 0.0598116 -0.000144278 0.00864074 0.998172 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 104 105 -0.0124756 1.66342 -0.0218449 0.065734 0.00779013 0.0106785 0.99775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 105 106 -0.0213622 1.67782 -0.0290552 0.0639875 -0.00022531 0.0065406 0.997929 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 106 107 -0.000927223 1.70915 -0.028739 0.060464 0.00295835 0.0098446 0.998117 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 107 108 -0.0102229 1.71161 -0.0264571 0.0622031 0.00438823 0.00412077 0.998045 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 108 109 -0.0151775 1.74453 -0.0250617 0.0625415 0.00140839 0.0162044 0.99791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 109 110 -0.0125054 1.73665 -0.0318697 0.0673129 -3.00548e-05 0.0123406 0.997656 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 110 111 -0.0263933 1.76009 -0.0171706 0.0576213 0.00117928 0.0150655 0.998224 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 111 112 -0.0135146 1.79734 -0.0210142 0.0567844 -0.0126746 0.0141586 0.998206 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 112 113 -0.0165816 1.8177 -0.0368697 0.0641468 -0.00414596 0.00638418 0.997911 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 113 114 -0.00781423 1.79722 -0.0250409 0.0624899 -0.00382988 0.0123087 0.997962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 114 115 -0.0387081 1.8462 -0.0116888 0.0591059 -0.00278835 -0.0005073 0.998248 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 115 116 -0.0219419 1.84374 -0.0196495 0.05716 0.00352931 0.00454417 0.998348 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 116 117 -0.0254894 1.8399 -0.02192 0.0591961 -0.00133878 0.0067188 0.998223 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 117 118 -0.00290256 1.86773 -0.00326624 0.061684 -0.00150357 0.00772363 0.998065 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 118 119 -0.0252742 1.87048 0.00127907 0.0607855 -0.00195817 0.0124523 0.998071 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 119 120 -0.0188834 1.88917 -0.00138895 0.0639172 0.00648893 0.0230962 0.997667 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 120 121 -0.0254142 1.92082 -0.0078593 0.0555356 0.00172114 0.0139213 0.998358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 121 122 -0.019668 1.93332 -0.0151675 0.0679646 0.0115222 0.00788368 0.99759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 122 123 -0.0286719 1.91922 -0.01593 0.0533749 0.00886426 0.0116816 0.998467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 123 124 -0.0187913 1.96102 -0.0201763 0.0575771 -0.0141239 0.00959437 0.998195 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 124 125 -0.0121042 1.98434 0.0119976 0.0708808 -0.0027165 0.00421595 0.997472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 125 126 -0.00764617 1.98766 -0.0142685 0.0619319 0.00133435 0.00591 0.998062 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 126 127 -0.0232564 2.01432 -0.00533964 0.0657859 0.00288055 0.0155607 0.997708 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 127 128 -0.0276058 2.02506 0.0076866 0.0559511 -0.00782668 0.0174697 0.99825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 128 129 -0.0319407 2.03901 -0.0124687 0.0629224 -0.00171054 0.00778964 0.997987 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 129 130 -0.021886 2.04925 0.0126302 0.0603642 -0.00472262 0.00810387 0.998132 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 130 131 -0.0129436 2.06366 0.0116443 0.0573609 3.10576e-05 0.00995236 0.998304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 131 132 -0.00917753 2.0847 -0.00927247 0.0661265 0.00503053 0.014874 0.997688 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 132 133 -0.0122092 2.104 0.00173753 0.0613599 -0.00246049 0.00736767 0.998085 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 133 134 -0.0271498 2.12097 -0.00694551 0.0607222 0.00530136 0.0118282 0.998071 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 134 135 -0.0280149 2.12888 0.0159555 0.0607166 -0.00270712 0.0165123 0.998015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 135 136 -0.00474216 2.14768 0.0118289 0.0612407 -0.000690405 0.0103623 0.998069 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 136 137 -0.0296035 2.15256 0.0110629 0.0608247 0.00485065 0.010155 0.998085 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 137 138 -0.0346426 2.19486 0.0298836 0.0598279 0.00572333 0.00998648 0.998142 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 138 139 -0.0251914 2.18636 0.00661932 0.0499617 0.0043705 0.00963872 0.998695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 139 140 -0.0430841 2.20037 0.0192738 0.0603955 0.00241201 0.00727106 0.998145 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 140 141 -0.0149018 2.22013 0.0167205 0.0559479 -0.00296576 0.00150545 0.998428 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 141 142 -0.030009 2.24735 0.00948862 0.0671974 -0.00250522 0.00508162 0.997724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 142 143 -0.0235198 2.26733 0.0224859 0.0663081 0.00745778 0.0150918 0.997657 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 143 144 -0.0309592 2.29251 0.00796062 0.0649733 0.00861947 0.0126456 0.99777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 144 145 -0.0197624 2.2842 0.0493081 0.0602233 -0.00874576 0.0112129 0.998084 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 145 146 -0.0244951 2.29005 0.00874656 0.0561384 0.000490343 0.0135111 0.998331 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 146 147 -0.039189 2.31116 0.0124469 0.0629613 0.0040595 0.0182257 0.997841 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 147 148 -0.00804677 2.34853 0.0251429 0.0553399 0.00523316 0.00712341 0.998428 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 148 149 -0.0145762 2.35223 0.0262839 0.0586577 0.00563789 0.0168525 0.99812 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 149 150 -0.0136134 2.36267 0.00460367 0.0626968 0.000505648 0.00365549 0.998026 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 150 151 -0.019098 2.37331 0.0236003 0.0614258 0.00835442 0.0111266 0.998015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 151 152 -0.0355231 2.3964 0.022189 0.0569643 -0.00369941 0.0148478 0.998259 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 152 153 -0.0291836 2.41974 0.023943 0.0683365 0.00409087 -5.89021e-05 0.997654 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 153 154 -0.0460629 2.41898 0.0304079 0.0611092 0.00105583 0.0122465 0.998055 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 154 155 -0.0108483 2.43891 0.0326786 0.057054 0.00442287 0.00974709 0.998314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 155 156 -0.0249698 2.45224 0.0349168 0.0647442 0.00214089 0.0101271 0.997848 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 156 157 -0.0370191 2.48391 0.0140686 0.0675221 -0.00074258 0.0136406 0.997624 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 157 158 -0.0378038 2.48187 0.0288689 0.0630607 -0.00255718 0.0155996 0.997884 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 158 159 -0.0311683 2.50255 0.0443685 0.0607229 -0.00331451 0.0143485 0.998046 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 159 160 -0.0208979 2.49098 0.0250114 0.0652011 -0.00785586 0.0102685 0.997788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 160 161 -0.0363667 2.54743 0.0253471 0.0593436 -0.00587954 0.0146284 0.998113 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 161 162 -0.0304919 2.54302 0.0333916 0.0563913 -0.00444457 0.0159446 0.998272 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 162 163 -0.038919 2.56956 0.0545953 0.0578126 -0.00408498 0.0112675 0.998256 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 163 164 -0.0272679 2.56988 0.0212529 0.0621663 -0.00149979 0.00233971 0.998062 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 164 165 -0.0262645 2.61338 0.0354114 0.0630047 -0.00456527 0.019094 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 165 166 -0.0311102 2.60321 0.0232901 0.0651808 0.00606724 0.0220739 0.997611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 166 167 -0.0336376 2.63459 0.0471344 0.0609928 0.00814409 0.0157545 0.997981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 167 168 -0.0199658 2.63635 0.0391788 0.0580042 -0.000409164 0.0125327 0.998238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 168 169 -0.0324138 2.67578 0.0338945 0.0526855 -0.00114554 0.00157937 0.998609 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 169 170 -0.0392687 2.65549 0.040594 0.0626365 -0.00407334 0.0129408 0.997944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 170 171 -0.0156534 2.67694 0.0390625 0.0598296 -0.00232982 -0.000343711 0.998206 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 171 172 -0.0357709 2.71252 0.0309678 0.0672504 0.00223115 0.0179376 0.997572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 172 173 -0.0283261 2.71111 0.0161029 0.0620816 0.00124778 0.0170802 0.997924 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 173 174 -0.0362368 2.73551 0.036577 0.0640798 0.00829588 0.0180407 0.997747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 174 175 -0.0305278 2.75863 0.0429364 0.056984 0.00125388 0.02101 0.998153 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 175 176 -0.0283265 2.77468 0.0373599 0.0562429 -0.00589948 0.0230257 0.998134 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 176 177 -0.0385611 2.77735 0.029899 0.0639995 0.0063954 0.0184118 0.99776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 177 178 -0.0197412 2.7798 0.0464227 0.0529127 0.0106564 0.0217281 0.998306 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 178 179 -0.0464055 2.7981 0.055438 0.058675 0.00788439 0.0145388 0.99814 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 179 180 -0.0362632 2.82493 0.0475372 0.0618515 -0.00647158 0.0235897 0.997786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 180 181 -0.0437699 2.84614 0.0479842 0.0508722 -0.000898136 0.00918008 0.998663 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 181 182 -0.0389649 2.84685 0.0425179 0.0565673 0.00675189 0.0120972 0.998303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 182 183 -0.02026 2.87963 0.0441774 0.0600664 -0.00355338 0.0138158 0.998092 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 183 184 -0.0438043 2.86192 0.0473955 0.0537783 -0.000155668 0.00980692 0.998505 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 184 185 -0.0514056 2.90496 0.0373115 0.0560291 0.000836244 0.00760696 0.9984 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 185 186 -0.041808 2.90858 0.062844 0.0552071 -0.00346015 0.0105219 0.998413 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 186 187 -0.0418417 2.94948 0.0564998 0.062436 0.00279832 0.017445 0.997893 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 187 188 -0.0344686 2.95944 0.0487889 0.0601857 0.00199003 0.0141784 0.998085 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 188 189 -0.0490759 2.96639 0.0649734 0.0510714 0.00461975 0.0154269 0.998565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 189 190 -0.0416692 2.99716 0.0668757 0.0670784 -0.00292681 0.0188352 0.997566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 190 191 -0.0337007 2.98735 0.0540933 0.0589368 0.0046253 0.0215581 0.998018 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 191 192 -0.0432142 3.0306 0.0624408 0.0597117 0.000135641 0.0184945 0.998044 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 192 193 -0.0421504 3.02155 0.0609065 0.0622396 0.00212465 0.0142409 0.997957 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 193 194 -0.0438691 3.03743 0.0461025 0.0555839 0.00976342 0.0156879 0.998283 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 194 195 -0.0271934 3.04288 0.0500092 0.0633038 0.00216409 0.00680382 0.997969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 195 196 -0.0667165 3.06729 0.0711957 0.0638005 -0.000661088 0.016561 0.997825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 196 197 -0.0577032 3.09299 0.0673198 0.0625065 -0.00134842 0.00959916 0.997997 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 197 198 -0.0653835 3.09453 0.0695039 0.0565598 -0.00812523 0.0144726 0.998261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 198 199 -0.0503335 3.10563 0.0588626 0.0594209 0.00805394 0.0148232 0.99809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 199 200 -0.0467111 3.13738 0.0690611 0.0699327 0.0125702 0.0133514 0.997383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 200 201 -0.0513241 3.1275 0.0607952 0.055978 0.00229995 0.0196677 0.998236 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 201 202 -0.0452559 3.1646 0.0790794 0.070305 -0.00469194 0.0217602 0.997277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 202 203 -0.0427523 3.17521 0.0642695 0.0698533 -0.00164599 0.0128359 0.997473 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 203 204 -0.05403 3.16712 0.0661441 0.0613374 -0.000342888 0.0111344 0.998055 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 204 205 -0.0496657 3.20137 0.082201 0.0597139 0.00108092 0.0062955 0.998195 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 205 206 -0.0669759 3.22628 0.0731844 0.0530669 -0.00783246 0.0170239 0.998415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 206 207 -0.0428347 3.23391 0.0698048 0.0564434 -0.00618551 0.00815355 0.998353 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 207 208 -0.0487654 3.25493 0.0683138 0.0588701 -0.00704597 0.0192352 0.998055 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 208 209 -0.0490933 3.27628 0.0873813 0.0642653 0.00977371 0.0144428 0.99778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 209 210 -0.051642 3.28825 0.075202 0.0602503 0.00482362 0.0209241 0.997952 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 210 211 -0.0529017 3.30311 0.0727212 0.0574538 0.00956614 0.00919024 0.99826 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 211 212 -0.0594912 3.31125 0.0682847 0.0598911 0.0034023 0.0164841 0.998063 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 212 213 -0.0668588 3.32652 0.0812212 0.0617426 -0.000256949 0.01681 0.997951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 213 214 -0.0456739 3.34764 0.0906861 0.0618556 0.00212713 0.0193056 0.997896 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 214 215 -0.0470583 3.3604 0.0850003 0.0590756 0.00296636 0.0196264 0.998056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 215 216 -0.0492209 3.36629 0.0833543 0.0650873 0.00394001 0.0231525 0.997603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 216 217 -0.0474554 3.39138 0.0822568 0.0621686 -0.00664286 0.023288 0.997772 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 217 218 -0.0492645 3.42079 0.0803608 0.0661349 0.00307 0.0206141 0.997593 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 218 219 -0.0529678 3.43119 0.0805275 0.0587855 -0.00176514 0.0215731 0.998036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 219 220 -0.0427368 3.44348 0.0849911 0.0575168 0.0108808 0.0201785 0.998081 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 220 221 -0.0504531 3.44225 0.0851028 0.0667018 -0.0132258 0.0263786 0.997337 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 221 222 -0.0561582 3.47882 0.0730586 0.0674286 0.00356037 0.0133688 0.997628 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 222 223 -0.0729816 3.47072 0.0594233 0.056417 -0.0054895 0.0189109 0.998213 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 223 224 -0.0640351 3.50875 0.0878898 0.056836 0.00633275 0.0206642 0.99815 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 224 225 -0.0666663 3.5157 0.0766855 0.0735106 -0.00312911 0.0135349 0.997198 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 225 226 -0.0726401 3.52247 0.0867724 0.0554355 0.00393135 0.0123827 0.998378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 226 227 -0.0572472 3.54265 0.079732 0.0565688 0.00292683 0.0234798 0.998118 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 227 228 -0.0592187 3.56425 0.0974864 0.0558033 0.000523093 0.0216104 0.998208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 228 229 -0.0602537 3.56619 0.0819697 0.0651503 0.000753754 0.00776856 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 229 230 -0.0781297 3.5688 0.0685362 0.0614941 -0.00565185 0.0141613 0.997991 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 230 231 -0.0694468 3.59261 0.0967705 0.0577182 -0.0076707 0.0258703 0.997968 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 231 232 -0.0667011 3.60799 0.0872429 0.0525877 -0.00428766 0.0253481 0.998285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 232 233 -0.0653017 3.62674 0.0889869 0.058315 -0.000161113 0.0197831 0.998102 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 233 234 -0.0726826 3.64288 0.0856328 0.06547 0.00694085 0.0156134 0.997708 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 234 235 -0.0672755 3.66185 0.0903686 0.0526538 -0.00508233 0.0269382 0.998236 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 235 236 -0.0570807 3.67487 0.110154 0.0566584 0.00266629 0.0155079 0.99827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 236 237 -0.0586765 3.69019 0.0917053 0.0512488 -0.0035329 0.010395 0.998626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 237 238 -0.0658347 3.71427 0.0897133 0.0632252 0.00570789 0.0277647 0.997597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 238 239 -0.0666808 3.72668 0.11124 0.0639527 0.0077223 0.0150578 0.997809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 239 240 -0.0721995 3.76404 0.098032 0.0607665 -0.00485276 0.0268025 0.99778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 240 241 -0.0713903 3.74004 0.102537 0.0622777 0.000863987 0.019384 0.99787 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 241 242 -0.0730708 3.77652 0.0934256 0.0640528 0.00388599 0.0230626 0.997672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 242 243 -0.0705522 3.79495 0.122488 0.0578281 -0.00116965 0.0213776 0.998097 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 243 244 -0.0673643 3.79328 0.101093 0.059145 0.00751599 0.0146474 0.998114 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 244 245 -0.0698316 3.79606 0.119607 0.0559108 0.0039766 0.0281642 0.998031 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 245 246 -0.0848233 3.83091 0.0940069 0.0618623 -0.00605954 0.0180398 0.997903 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 246 247 -0.0823613 3.83399 0.0756282 0.0507893 -0.0074597 0.0296167 0.998242 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 247 248 -0.0806081 3.85945 0.105802 0.0670127 0.00203334 0.024113 0.997459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 248 249 -0.0774736 3.89053 0.0987075 0.0545584 0.00706679 0.0194754 0.998296 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 249 250 -0.0798298 3.87727 0.1144 0.0556941 -0.00195407 0.0273231 0.998072 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 250 251 -0.0677945 3.90284 0.108685 0.0580409 -0.00479527 0.0192323 0.998117 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 251 252 -0.0737238 3.90982 0.120766 0.0545169 -0.000345662 0.0250443 0.998199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 252 253 -0.0751351 3.94048 0.114445 0.0617429 -0.00417822 0.0170672 0.997937 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 253 254 -0.0758666 3.95855 0.107059 0.0568549 -0.00501489 0.0233021 0.998098 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 254 255 -0.0714012 3.9507 0.0953208 0.0620315 -0.00267004 0.019617 0.997878 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 255 256 -0.0997141 3.99327 0.10461 0.0608428 -0.000613447 0.0214734 0.997916 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 256 257 -0.0884709 3.99452 0.107582 0.0501394 -0.00220662 0.0174692 0.998587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 257 258 -0.0739265 4.00312 0.102172 0.0579054 0.00603747 0.0196943 0.99811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 258 259 -0.0775465 4.01923 0.103277 0.0561138 0.00666112 0.0250432 0.998088 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 259 260 -0.0741596 4.0338 0.11412 0.0586458 0.00427801 0.0198683 0.998072 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 260 261 -0.0939851 4.04318 0.114559 0.0566414 0.00655047 0.0143189 0.99827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 261 262 -0.0732469 4.06653 0.124952 0.0608559 -0.00187529 0.0196949 0.99795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 262 263 -0.0849066 4.09056 0.126448 0.0552019 -0.00861048 0.0187989 0.998261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 263 264 -0.09981 4.10531 0.130603 0.0579232 -0.00693276 0.010328 0.998244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 264 265 -0.0926447 4.11072 0.112313 0.0534773 -0.000493902 0.0206313 0.998356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 265 266 -0.0815393 4.12093 0.129453 0.0570477 0.00366082 0.0201996 0.99816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 266 267 -0.0865353 4.13938 0.12984 0.0631132 0.00917931 0.0231067 0.997697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 267 268 -0.0779611 4.15842 0.116391 0.0593543 -0.000293594 0.0250703 0.997922 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 268 269 -0.0731881 4.16895 0.116059 0.0605528 -3.67722e-05 0.0210682 0.997943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 269 270 -0.0948238 4.19823 0.1174 0.0534884 -0.00113564 0.0252092 0.99825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 270 271 -0.0853412 4.19974 0.120807 0.059911 -0.00110496 0.0254849 0.997878 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 271 272 -0.0912392 4.21531 0.142543 0.0657142 -0.00348731 0.0142529 0.997731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 272 273 -0.079795 4.22873 0.133336 0.051609 0.00931569 0.0287148 0.998211 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 273 274 -0.0821379 4.24372 0.119548 0.0571464 0.00869913 0.0195203 0.998137 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 274 275 -0.0885965 4.25643 0.136578 0.072259 -0.00313444 0.0287705 0.996966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 275 276 -0.0875238 4.27274 0.116371 0.0643882 -0.00459052 0.0293437 0.997483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 276 277 -0.102739 4.26654 0.135525 0.0609863 -0.000303111 0.0137001 0.998045 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 277 278 -0.0928428 4.30166 0.12768 0.0612249 0.00171332 0.0165957 0.997985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 278 279 -0.0946941 4.31673 0.132681 0.0559954 -0.0109084 0.0235008 0.998095 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 279 280 -0.0918037 4.32661 0.111641 0.0602257 2.61134e-05 0.017349 0.998034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 280 281 -0.0802993 4.33741 0.122942 0.0531299 -0.001952 0.0296622 0.998145 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 281 282 -0.0974653 4.34533 0.141674 0.054286 -0.00379265 0.0212026 0.998293 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 282 283 -0.0898839 4.38929 0.125512 0.0505444 -0.00153066 0.0254175 0.998397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 283 284 -0.0872769 4.38168 0.128412 0.0553033 -0.00538057 0.0170194 0.99831 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 284 285 -0.101832 4.41727 0.147955 0.0599899 0.00261691 0.0183059 0.998028 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 285 286 -0.0888536 4.4296 0.136743 0.0674493 -0.000957321 0.025518 0.997396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 286 287 -0.103283 4.44415 0.151468 0.062718 -0.0108905 0.0264636 0.997621 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 287 288 -0.0907134 4.45392 0.131141 0.0648572 0.000639092 0.0228784 0.997632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 288 289 -0.117919 4.4638 0.118523 0.0649031 -0.00227857 0.0254462 0.997564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 289 290 -0.0865096 4.48248 0.144171 0.0588208 0.00395197 0.0286902 0.997848 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 290 291 -0.0842412 4.48531 0.138627 0.0605314 0.00639692 0.0235584 0.997868 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 291 292 -0.092252 4.51514 0.141267 0.0553684 0.00207873 0.028463 0.998058 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 292 293 -0.102991 4.52839 0.14758 0.0643502 0.00719407 0.0195159 0.997711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 293 294 -0.11331 4.55328 0.128398 0.066015 -0.0064985 0.0227221 0.997539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 294 295 -0.114076 4.54267 0.150162 0.0603162 0.000841537 0.0303548 0.997717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 295 296 -0.0960375 4.56033 0.16136 0.0675307 0.00190223 0.0286698 0.997303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 296 297 -0.0985662 4.57862 0.153536 0.0591165 0.00506813 0.015359 0.99812 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 297 298 -0.129297 4.60871 0.156646 0.0520141 5.47618e-05 0.024238 0.998352 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 298 299 -0.115059 4.61586 0.143102 0.0603571 0.00345959 0.0318917 0.997661 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 299 300 -0.111174 4.61235 0.15942 0.0513975 -0.00483148 0.0325054 0.998137 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 300 301 -0.114187 4.64283 0.161025 0.0556519 0.013406 0.0255563 0.998033 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 301 302 -0.122837 4.65528 0.155742 0.0533913 0.000297114 0.0213604 0.998345 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 302 303 -0.108942 4.66294 0.139131 0.0545995 -0.000375849 0.0216165 0.998274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 303 304 -0.102636 4.6932 0.141119 0.0641057 0.00882995 0.0284863 0.997497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 304 305 -0.09808 4.7149 0.15386 0.0555167 -0.00586512 0.0180608 0.998277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 305 306 -0.118168 4.69194 0.149256 0.0650651 0.00174717 0.0218523 0.99764 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 306 307 -0.105851 4.72975 0.150978 0.0653326 -0.00300146 0.0265265 0.997506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 307 308 -0.102555 4.74553 0.13417 0.0626854 -0.000291588 0.024715 0.997727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 308 309 -0.10025 4.75095 0.158848 0.0592264 -0.00199743 0.0226186 0.997986 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 309 310 -0.101239 4.76913 0.171173 0.0552922 0.00648136 0.0266362 0.998094 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 310 311 -0.114689 4.79537 0.155587 0.0518279 0.00325303 0.0228137 0.99839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 311 312 -0.11547 4.79913 0.158835 0.0450614 0.00422801 0.0307927 0.998501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 312 313 -0.127761 4.82994 0.151615 0.0477675 -0.00074973 0.0165695 0.998721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 313 314 -0.101762 4.8354 0.148564 0.0706254 0.00152822 0.0133586 0.997412 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 314 315 -0.113237 4.85011 0.149739 0.0684485 0.0158874 0.027621 0.997146 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 315 316 -0.121884 4.8684 0.149553 0.0530187 0.00237384 0.025472 0.998266 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 316 317 -0.114115 4.8745 0.149514 0.06269 -0.000596977 0.0219414 0.997792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 317 318 -0.125843 4.89487 0.157958 0.0595986 -0.00825594 0.0251283 0.997872 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 318 319 -0.129984 4.91232 0.141334 0.0687333 -0.00587941 0.0180492 0.997454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 319 320 -0.110603 4.91618 0.169993 0.057696 0.000302281 0.0262729 0.997988 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 320 321 -0.119646 4.92973 0.147253 0.0552214 0.00641946 0.025444 0.998129 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 321 322 -0.131429 4.95336 0.156283 0.0579279 -0.00490945 0.0317147 0.997805 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 322 323 -0.120006 4.95287 0.151695 0.0500226 -0.00048188 0.0263589 0.9984 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 323 324 -0.132204 4.98455 0.163912 0.0547351 -0.000106465 0.0165254 0.998364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 324 325 -0.125501 4.98463 0.153134 0.0464662 -0.00577913 0.0234939 0.998627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 325 326 -0.129561 5.00398 0.157235 0.0580629 -0.00311397 0.0192854 0.998122 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 326 327 -0.116054 5.02227 0.158427 0.0673637 0.00240475 0.0195222 0.997535 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 327 328 -0.139394 5.01477 0.17063 0.0644398 0.000291299 0.0271728 0.997552 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 328 329 -0.133738 5.05274 0.155699 0.0682589 -0.0050508 0.0186872 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 329 330 -0.123836 5.07694 0.173373 0.0560612 -0.0133275 0.0206682 0.998124 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 330 331 -0.130109 5.08617 0.178349 0.0581434 -0.00338322 0.0152283 0.998186 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 331 332 -0.153663 5.11015 0.170262 0.0654065 0.00874974 0.0187919 0.997643 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 332 333 -0.118671 5.10673 0.183156 0.0581728 -0.0054919 0.0353572 0.997665 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 333 334 -0.129279 5.12603 0.169464 0.0526156 -0.0130724 0.0309707 0.998049 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 334 335 -0.125923 5.12932 0.167207 0.0543294 -0.0031313 0.0239139 0.998232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 335 336 -0.124634 5.14926 0.18486 0.0578236 0.00280832 0.0246563 0.998018 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 336 337 -0.136457 5.14763 0.165899 0.0595394 0.00668023 0.0277889 0.997817 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 337 338 -0.141345 5.15635 0.174131 0.0520165 -0.00224199 0.0282522 0.998244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 338 339 -0.152764 5.19593 0.16246 0.0559235 -0.00110534 0.0330025 0.997889 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 339 340 -0.152111 5.2076 0.168989 0.0542481 0.00182634 0.0195621 0.998334 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 340 341 -0.129072 5.2191 0.165734 0.0625072 0.00535551 0.0330264 0.997484 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 341 342 -0.145681 5.20971 0.194313 0.056606 0.000345991 0.0360512 0.997745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 342 343 -0.1317 5.26261 0.178031 0.0620184 -0.00684326 0.0205904 0.997839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 343 344 -0.126949 5.27368 0.175899 0.0627212 0.00784989 0.0207238 0.997785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 344 345 -0.12503 5.28093 0.177397 0.0645338 0.000366328 0.028333 0.997513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 345 346 -0.142614 5.30052 0.185041 0.0597474 0.00178919 0.0196401 0.998019 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 346 347 -0.139265 5.31367 0.192657 0.0526854 0.0104027 0.0298373 0.998111 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 347 348 -0.132119 5.32992 0.178823 0.0531916 0.00127863 0.0331173 0.998034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 348 349 -0.14687 5.32794 0.180543 0.0628311 0.00247104 0.0267572 0.997662 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 349 350 -0.153138 5.36499 0.186219 0.0676214 0.0071301 0.0351165 0.997067 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 350 351 -0.156092 5.35483 0.167946 0.048772 0.000367326 0.0372811 0.998114 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 351 352 -0.148089 5.39809 0.190102 0.0646895 0.00170313 0.0280678 0.997509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 352 353 -0.153336 5.39903 0.192715 0.0566658 -0.00735209 0.0312171 0.997878 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 353 354 -0.146806 5.41584 0.181544 0.0622858 -0.00128965 0.0344589 0.997462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 354 355 -0.145703 5.40568 0.20295 0.0602067 0.00120013 0.0276512 0.997802 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 355 356 -0.152818 5.45001 0.202034 0.0607235 -0.00408798 0.031065 0.997663 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 356 357 -0.149862 5.44535 0.197807 0.0657918 0.00191786 0.0255937 0.997503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 357 358 -0.156541 5.46444 0.177035 0.0652173 0.0037004 0.0252941 0.997544 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 358 359 -0.14972 5.47965 0.171654 0.0486932 0.00464694 0.0215404 0.998571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 359 360 -0.142938 5.51222 0.188837 0.057056 0.00744592 0.0215577 0.99811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 360 361 -0.158915 5.4864 0.182425 0.0584714 0.0026534 0.0310879 0.997801 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 361 362 -0.141611 5.51122 0.182984 0.051927 -0.00400986 0.0185809 0.99847 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 362 363 -0.159283 5.52618 0.198963 0.0598355 -0.0047655 0.0265185 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 363 364 -0.145616 5.54416 0.189437 0.0573302 0.000154359 0.0318775 0.997846 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 364 365 -0.156063 5.56111 0.179832 0.0510623 -0.00786078 0.025572 0.998337 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 365 366 -0.145962 5.5769 0.209785 0.0492034 0.0118633 0.0241889 0.998425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 366 367 -0.154604 5.57697 0.187474 0.0567859 -0.00744389 0.0238546 0.998074 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 367 368 -0.163537 5.59658 0.187878 0.0601837 0.00497175 0.0238351 0.99789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 368 369 -0.146864 5.60968 0.190289 0.0507449 0.00513819 0.0301843 0.998242 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 369 370 -0.154889 5.62011 0.181908 0.0545955 0.00445096 0.0335731 0.997934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 370 371 -0.162147 5.63609 0.183333 0.0501597 -0.00430997 0.0194184 0.998543 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 371 372 -0.166622 5.65436 0.193131 0.0515506 -0.00140247 0.0285029 0.998263 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 372 373 -0.157438 5.67879 0.197539 0.0556499 -0.00528945 0.0334449 0.997876 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 373 374 -0.159851 5.69529 0.194717 0.0549084 0.00432635 0.0310505 0.997999 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 374 375 -0.154976 5.70238 0.196763 0.0531728 -0.00501462 0.0356009 0.997938 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 375 376 -0.178675 5.71678 0.203704 0.0549463 0.00240011 0.0233906 0.998212 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 376 377 -0.177648 5.71248 0.203499 0.0539815 -0.00574064 0.0114256 0.99846 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 377 378 -0.175691 5.74678 0.190704 0.0619235 0.00191265 0.0324271 0.997552 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 378 379 -0.173611 5.77204 0.189661 0.0580886 0.00348987 0.0198492 0.998108 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 379 380 -0.173961 5.78231 0.199713 0.0616877 0.000203164 0.0210638 0.997873 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 380 381 -0.167252 5.78408 0.206318 0.0465957 -0.00186712 0.0302207 0.998455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 381 382 -0.164231 5.81456 0.209278 0.0538939 -0.00115738 0.0396774 0.997757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 382 383 -0.168311 5.81343 0.198156 0.0533001 -0.000822043 0.028746 0.998164 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 383 384 -0.158686 5.83681 0.201354 0.0508416 0.00150879 0.0345521 0.998108 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 384 385 -0.185873 5.84646 0.20264 0.0575862 0.01121 0.0341377 0.997694 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 385 386 -0.165696 5.85583 0.204002 0.0569566 0.0138582 0.02019 0.998076 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 386 387 -0.160321 5.86137 0.219187 0.0615191 0.00449774 0.0314401 0.9976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 387 388 -0.186777 5.88544 0.203862 0.0611341 -0.00307586 0.034637 0.997524 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 388 389 -0.165121 5.90429 0.203977 0.0515104 0.00080813 0.0275077 0.998293 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 389 390 -0.191979 5.89644 0.222109 0.0575615 -0.00846862 0.0349422 0.997694 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 390 391 -0.185799 5.93304 0.200628 0.0527895 -0.00505151 0.0258573 0.998258 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 391 392 -0.187932 5.94371 0.184152 0.052292 -0.000430015 0.0271987 0.998261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 392 393 -0.168482 5.9582 0.199552 0.063868 0.000225168 0.0270779 0.997591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 393 394 -0.178155 5.95754 0.194726 0.05628 -0.00434975 0.032714 0.997869 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 394 395 -0.177156 5.97392 0.188016 0.0587985 -0.00361544 0.0277112 0.997879 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 395 396 -0.177157 5.99554 0.188599 0.0535589 -0.00764715 0.032836 0.997995 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 396 397 -0.184555 6.00779 0.221052 0.0590009 -0.00235449 0.0323726 0.99773 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 397 398 -0.177172 6.02177 0.205197 0.0573822 0.00398542 0.0259485 0.998007 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 398 399 -0.179693 6.05637 0.230383 0.0537978 0.00132924 0.0313365 0.998059 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 399 400 -0.153056 6.04584 0.21036 0.0488359 0.00132201 0.0293882 0.998373 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 400 401 -0.195896 6.05604 0.212458 0.0569433 0.00902426 0.0449806 0.997323 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 401 402 -0.178966 6.08693 0.207282 0.0535929 -0.00277723 0.0302502 0.998101 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 402 403 -0.187757 6.11182 0.199497 0.0499035 0.000872638 0.0314722 0.998258 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 403 404 -0.182484 6.11928 0.214879 0.049498 -0.0113431 0.0314979 0.998213 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 404 405 -0.209949 6.13861 0.205464 0.0456408 -0.00268249 0.0301298 0.9985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 405 406 -0.185366 6.12863 0.218906 0.0571272 0.00761017 0.0280846 0.997943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 406 407 -0.20003 6.14926 0.209114 0.0571984 0.0015277 0.0258148 0.998028 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 407 408 -0.191436 6.15234 0.209144 0.054277 0.00744701 0.0275714 0.998117 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 408 409 -0.190499 6.17355 0.212427 0.0558177 -0.00674624 0.0319106 0.997908 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 409 410 -0.185092 6.1699 0.215018 0.056801 -0.00193304 0.0357272 0.997744 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 410 411 -0.192476 6.18754 0.197343 0.0544523 0.00371097 0.0318038 0.998003 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 411 412 -0.189751 6.21938 0.199212 0.0565949 0.00907344 0.0234853 0.99808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 412 413 -0.205141 6.22167 0.20042 0.051699 -0.00426001 0.0417339 0.997781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 413 414 -0.170218 6.22886 0.22485 0.0526579 0.00339029 0.0224179 0.998355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 414 415 -0.194834 6.25379 0.200922 0.0609647 -0.00218885 0.0294086 0.997704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 415 416 -0.194915 6.27801 0.22041 0.066242 0.00336199 0.031068 0.997314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 416 417 -0.196896 6.29236 0.234419 0.0513873 -0.00726205 0.0269657 0.998288 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 417 418 -0.18174 6.29363 0.221566 0.0573743 0.00656249 0.0211647 0.998107 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 418 419 -0.199569 6.31151 0.22655 0.049638 0.00239991 0.0222601 0.998516 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 419 420 -0.214117 6.33411 0.220495 0.0606992 0.000136424 0.0387212 0.997405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 420 421 -0.195366 6.33336 0.235505 0.0466158 0.00907345 0.0404592 0.998052 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 421 422 -0.20274 6.33736 0.220707 0.0497095 0.00987857 0.0293116 0.998285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 422 423 -0.196443 6.36517 0.225146 0.0566622 -0.00105876 0.0307489 0.997919 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 423 424 -0.212336 6.37948 0.215582 0.0460111 0.0057959 0.0301883 0.998468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 424 425 -0.227446 6.3959 0.218785 0.053145 0.00852058 0.0350246 0.997936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 425 426 -0.204451 6.40751 0.209672 0.0586286 0.00674306 0.0294015 0.997824 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 426 427 -0.210478 6.42332 0.224767 0.0506472 0.00467803 0.0282101 0.998307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 427 428 -0.20456 6.43909 0.232309 0.0462481 -0.00441093 0.0345123 0.998324 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 428 429 -0.220589 6.44487 0.227495 0.0482479 0.00315237 0.0263403 0.998483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 429 430 -0.205311 6.46648 0.232369 0.056657 -0.00135865 0.0267875 0.998033 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 430 431 -0.207022 6.4839 0.230542 0.0607263 0.0100491 0.0359475 0.997456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 431 432 -0.203967 6.50016 0.231644 0.0492371 0.0122081 0.0373277 0.998015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 432 433 -0.225075 6.50474 0.210638 0.0554756 0.000952052 0.0348104 0.997853 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 433 434 -0.217079 6.52845 0.234841 0.0532403 -0.0016144 0.0309341 0.998101 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 434 435 -0.219458 6.53991 0.230301 0.0580419 -0.00170909 0.0263254 0.997966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 435 436 -0.220326 6.54877 0.234457 0.0462523 0.00520493 0.0408332 0.998081 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 436 437 -0.207726 6.55203 0.221968 0.0525459 0.00350124 0.0340274 0.998032 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 437 438 -0.224709 6.57794 0.232172 0.064899 -0.00875102 0.0334043 0.997294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 438 439 -0.221465 6.57684 0.24772 0.0446212 0.00388013 0.0308584 0.99852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 439 440 -0.223883 6.60028 0.243814 0.0572895 -0.00367428 0.0375612 0.997644 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 440 441 -0.213195 6.62098 0.201603 0.056821 0.00575657 0.0354416 0.997739 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 441 442 -0.230874 6.64192 0.237502 0.054096 -0.00154696 0.0382814 0.9978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 442 443 -0.213126 6.64987 0.233872 0.0488928 0.00130861 0.0304975 0.998337 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 443 444 -0.223339 6.6409 0.233195 0.049706 -0.00446083 0.0309929 0.998273 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 444 445 -0.215681 6.65442 0.217848 0.0445735 -0.00597455 0.033607 0.998423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 445 446 -0.228647 6.67946 0.217762 0.0531309 -0.00725112 0.0293031 0.998131 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 446 447 -0.250819 6.68237 0.242319 0.0556435 -0.000847103 0.0265657 0.998097 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 447 448 -0.240244 6.708 0.228092 0.0500297 0.00412513 0.0291826 0.998313 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 448 449 -0.232459 6.74169 0.223035 0.0495459 -0.00253761 0.0272918 0.998396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 449 450 -0.226931 6.72156 0.226838 0.0581033 0.00379453 0.031873 0.997794 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 450 451 -0.218287 6.73278 0.238289 0.0587665 0.00234136 0.032471 0.997741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 451 452 -0.234922 6.74473 0.222234 0.0511368 -0.000326378 0.0268352 0.998331 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 452 453 -0.239381 6.76158 0.238413 0.053782 0.000973919 0.0383524 0.997815 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 453 454 -0.233243 6.7932 0.23899 0.0540633 -0.00331125 0.0301961 0.998075 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 454 455 -0.225059 6.78649 0.234268 0.0439367 0.00756217 0.0357012 0.998368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 455 456 -0.229557 6.81611 0.238375 0.0541725 -0.000681583 0.0364418 0.997866 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 456 457 -0.226083 6.83155 0.233548 0.0505606 0.00472357 0.0324298 0.998183 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 457 458 -0.247985 6.81502 0.238689 0.0532287 0.00615043 0.0334348 0.998004 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 458 459 -0.240842 6.85054 0.222541 0.0561009 0.00374127 0.0298524 0.997972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 459 460 -0.237456 6.8546 0.222156 0.0546904 0.0126437 0.0342628 0.997835 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 460 461 -0.234601 6.8694 0.220924 0.0573181 0.00979358 0.0380029 0.997584 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 461 462 -0.237 6.90416 0.232174 0.0533733 0.00160884 0.0314611 0.998078 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 462 463 -0.241995 6.88572 0.228497 0.0440496 0.00390037 0.0417437 0.998149 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 463 464 -0.245391 6.92885 0.236247 0.0500866 0.00217004 0.0309382 0.998263 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 464 465 -0.251312 6.92348 0.236531 0.0443087 0.00120646 0.0257597 0.998685 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 465 466 -0.248846 6.94353 0.238968 0.0594356 -0.000609486 0.0388907 0.997474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 466 467 -0.23295 6.96424 0.250597 0.0569192 0.00310105 0.0325382 0.997844 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 467 468 -0.246718 6.96049 0.232901 0.0416798 -0.00167404 0.0456323 0.998087 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 468 469 -0.247288 6.96466 0.229406 0.049661 -0.00367612 0.0417036 0.997888 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 469 470 -0.248039 7.01024 0.239615 0.0534992 0.0106892 0.0408252 0.997676 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 470 471 -0.253428 6.99898 0.243949 0.0591454 0.0012162 0.0365193 0.99758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 471 472 -0.243127 7.01272 0.251109 0.0530696 0.0054806 0.031115 0.998091 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 472 473 -0.240308 7.01425 0.232022 0.0639457 0.0052872 0.0305233 0.997472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 473 474 -0.260066 7.02933 0.250806 0.0438248 0.00486359 0.0344167 0.998434 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 474 475 -0.252086 7.0644 0.252601 0.0439128 0.00252533 0.031884 0.998523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 475 476 -0.260705 7.08844 0.244933 0.05333 0.00615606 0.0370006 0.997872 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 476 477 -0.252727 7.09198 0.255784 0.048437 0.00399115 0.0327028 0.998283 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 477 478 -0.244583 7.08892 0.245364 0.0415844 -0.00522762 0.0437681 0.998162 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 478 479 -0.255057 7.11121 0.233129 0.0582578 -0.0010801 0.0286123 0.997891 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 479 480 -0.255434 7.13943 0.241117 0.055967 -0.000124598 0.0375386 0.997727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 480 481 -0.251184 7.1404 0.24419 0.0456156 0.00325134 0.0344216 0.998361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 481 482 -0.249653 7.14984 0.243189 0.0583644 0.00017186 0.031676 0.997793 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 482 483 -0.271239 7.16995 0.251236 0.0525962 -0.00536893 0.0337162 0.998032 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 483 484 -0.264318 7.18248 0.242765 0.0523579 -0.00356732 0.0482585 0.997455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 484 485 -0.239189 7.18324 0.24191 0.0542513 0.00111734 0.0314514 0.998031 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 485 486 -0.254766 7.20539 0.246532 0.0571757 -0.00284211 0.0296908 0.997918 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 486 487 -0.26056 7.21203 0.258938 0.0474197 -0.000761348 0.0388752 0.998118 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 487 488 -0.25237 7.21662 0.250962 0.0469583 0.00857039 0.0398641 0.998064 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 488 489 -0.258668 7.23129 0.254297 0.0537246 0.0027048 0.0350914 0.997935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 489 490 -0.245868 7.26933 0.249729 0.0568993 -0.00517193 0.0420505 0.997481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 490 491 -0.265429 7.26844 0.23365 0.0530707 -0.00125198 0.0318194 0.998083 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 491 492 -0.285222 7.27605 0.235964 0.0440843 0.00375398 0.0426055 0.998112 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 492 493 -0.269615 7.27224 0.233433 0.0468503 -0.0036861 0.0319113 0.998385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 493 494 -0.241368 7.32442 0.239646 0.0498327 0.00226247 0.0367505 0.998079 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 494 495 -0.263303 7.33032 0.251475 0.0489538 -0.00177066 0.0359003 0.998154 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 495 496 -0.266353 7.33803 0.242611 0.061704 0.00372302 0.0311165 0.997602 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 496 497 -0.246086 7.33137 0.261987 0.049846 0.00612358 0.0321366 0.998221 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 497 498 -0.287005 7.35359 0.24695 0.0514157 0.00249329 0.0380205 0.99795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 498 499 -0.267772 7.35885 0.245628 0.0457938 0.00113791 0.0373511 0.998252 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 499 500 -0.248305 7.39553 0.245791 0.046093 -0.00221558 0.0438489 0.997972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 500 501 -0.271294 7.38889 0.239524 0.0472537 0.00670905 0.0370891 0.998172 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 501 502 -0.283483 7.40515 0.259016 0.05158 -0.00256086 0.0360407 0.998015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 502 503 -0.273719 7.40753 0.249776 0.0544058 0.000806345 0.0348711 0.99791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 503 504 -0.271971 7.44137 0.254269 0.054187 0.00263113 0.0463548 0.997451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 504 505 -0.266918 7.44716 0.241522 0.0513905 -0.00441977 0.0397076 0.997879 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 505 506 -0.272096 7.45123 0.254032 0.0471902 -0.00243411 0.0316618 0.998381 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 506 507 -0.270003 7.46278 0.241378 0.0472964 -0.00531859 0.0424145 0.997966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 507 508 -0.280637 7.48883 0.254468 0.05335 -0.00137668 0.0338677 0.998 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 508 509 -0.284188 7.49849 0.245927 0.0513012 -0.00191461 0.0395712 0.997897 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 509 510 -0.27783 7.50636 0.260093 0.0503267 0.00264322 0.0447997 0.997724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 510 511 -0.291321 7.52148 0.250831 0.0411676 0.000710355 0.0371919 0.99846 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 511 512 -0.276086 7.53486 0.232933 0.051365 0.000682169 0.0443652 0.997694 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 512 513 -0.300304 7.5254 0.248194 0.0550405 -0.000866397 0.0431698 0.99755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 513 514 -0.276378 7.55208 0.24532 0.0414804 0.00773742 0.0408341 0.998275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 514 515 -0.281188 7.5663 0.265022 0.0529803 0.00643856 0.0353403 0.997949 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 515 516 -0.309079 7.58049 0.261002 0.0579275 -0.000241614 0.0399757 0.99752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 516 517 -0.285385 7.58791 0.267453 0.0476349 -0.000423297 0.0364503 0.998199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 517 518 -0.290683 7.61591 0.258511 0.0531206 -0.00677908 0.0452485 0.997539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 518 519 -0.301133 7.61792 0.262573 0.0452687 -0.000189668 0.0420328 0.99809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 519 520 -0.285709 7.63081 0.26302 0.045822 0.000420047 0.0340954 0.998368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 520 521 -0.296426 7.63907 0.266964 0.0482952 0.00197804 0.044381 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 521 522 -0.292341 7.64437 0.244308 0.0466444 0.00296381 0.0386214 0.99816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 522 523 -0.303758 7.67211 0.251223 0.0517756 0.00862089 0.0361762 0.997966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 523 524 -0.298001 7.68078 0.266153 0.0586844 0.00834565 0.0384234 0.997502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 524 525 -0.285303 7.68555 0.23856 0.0512486 -0.000502392 0.0425256 0.99778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 525 526 -0.297502 7.70451 0.255592 0.0529201 -0.00520672 0.0405761 0.99776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 526 527 -0.302474 7.7159 0.241284 0.0414875 -0.00210949 0.0330332 0.998591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 527 528 -0.294129 7.71229 0.24178 0.0468725 -0.0083499 0.0407349 0.998035 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 528 529 -0.320031 7.73214 0.255817 0.0538193 0.000615008 0.0273894 0.998175 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 529 530 -0.294688 7.75646 0.250028 0.0598209 -0.00741501 0.0394379 0.997402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 530 531 -0.303632 7.7642 0.264334 0.0558168 0.00857763 0.0289708 0.997984 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 531 532 -0.318403 7.77969 0.262209 0.0472352 0.00260048 0.041942 0.997999 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 532 533 -0.294869 7.80124 0.27575 0.0377216 0.000840122 0.0374779 0.998585 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 533 534 -0.327058 7.80935 0.258281 0.0519123 -0.00596849 0.0315667 0.998135 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 534 535 -0.317306 7.81809 0.257836 0.0357897 0.00277079 0.0379131 0.998636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 535 536 -0.315055 7.83885 0.267915 0.0495173 0.00756945 0.0380871 0.998018 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 536 537 -0.330977 7.84514 0.258248 0.0510032 -0.000890042 0.0294207 0.998265 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 537 538 -0.313478 7.85529 0.273741 0.0446225 -0.00614505 0.0442417 0.998005 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 538 539 -0.308955 7.85564 0.257275 0.0526682 0.00160998 0.0371036 0.997921 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 539 540 -0.306346 7.88797 0.25315 0.049831 -0.00267626 0.0387361 0.998003 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 540 541 -0.318988 7.89296 0.257502 0.0502538 -0.00720328 0.0416553 0.997841 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 541 542 -0.327748 7.91289 0.263669 0.0484701 -0.00251127 0.0511287 0.997512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 542 543 -0.325289 7.92885 0.251652 0.0374227 -0.00651159 0.0355048 0.998647 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 543 544 -0.336002 7.91521 0.2588 0.0491374 -0.00136748 0.0372627 0.998096 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 544 545 -0.305794 7.92594 0.279557 0.0440459 -0.000591557 0.0474354 0.997903 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 545 546 -0.321696 7.96643 0.271265 0.0371578 -0.00267637 0.0430093 0.99838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 546 547 -0.295694 7.96122 0.2775 0.0442101 -0.0105161 0.0371373 0.998276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 547 548 -0.298855 7.97256 0.269936 0.043677 0.0010353 0.0449153 0.998035 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 548 549 -0.318621 8.01493 0.254943 0.0469065 -0.00173425 0.0459323 0.997841 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 549 550 -0.298454 8.01634 0.264483 0.0499406 -0.000254331 0.0341638 0.998168 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 550 551 -0.291512 8.02368 0.252791 0.0498687 -0.000347069 0.0427732 0.997839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 551 552 -0.318182 8.04175 0.266553 0.0450743 0.00322512 0.0438642 0.998015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 552 553 -0.321757 8.04136 0.259914 0.0540023 0.00822378 0.0413179 0.997652 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 553 554 -0.31981 8.03431 0.252327 0.047124 -0.00702284 0.0436869 0.997909 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 554 555 -0.328196 8.06613 0.264579 0.0467839 0.00380996 0.0481783 0.997735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 555 556 -0.334343 8.06376 0.263205 0.0499504 0.00116297 0.0526048 0.997365 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 556 557 -0.335947 8.07937 0.241032 0.0490815 -0.00698878 0.0413232 0.997915 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 557 558 -0.339729 8.10283 0.262328 0.0513481 0.00427249 0.0332372 0.998118 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 558 559 -0.346569 8.11231 0.262009 0.0488185 0.000408382 0.0346388 0.998207 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 559 560 -0.326992 8.11323 0.266184 0.0517849 0.00109553 0.0383154 0.997922 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 560 561 -0.346097 8.12221 0.260161 0.0478518 -0.00658993 0.0442381 0.997853 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 561 562 -0.353652 8.16165 0.278646 0.0421935 0.0027037 0.0442079 0.998127 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 562 563 -0.345039 8.14837 0.255756 0.0461817 -0.00120491 0.0452076 0.997909 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 563 564 -0.338572 8.16891 0.262431 0.0492963 0.000176071 0.025185 0.998467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 564 565 -0.327395 8.16502 0.261199 0.043274 -0.00305812 0.0450216 0.998044 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 565 566 -0.337799 8.20069 0.270954 0.0540636 0.000163126 0.0417898 0.997663 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 566 567 -0.331999 8.19817 0.252672 0.0417382 0.00371611 0.0353734 0.998495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 567 568 -0.335432 8.2082 0.274495 0.0387896 0.00265574 0.0482234 0.99808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 568 569 -0.330587 8.23167 0.268731 0.055093 -0.000795847 0.0260032 0.998142 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 569 570 -0.327141 8.23341 0.260866 0.0440028 0.00154922 0.0460489 0.997968 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 570 571 -0.335878 8.27011 0.262421 0.0505251 -0.0021635 0.0437434 0.997762 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 571 572 -0.340333 8.27172 0.274763 0.0490017 -0.000707551 0.0384932 0.998056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 572 573 -0.347223 8.284 0.243421 0.0426781 -0.00301935 0.0410855 0.998239 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 573 574 -0.346892 8.29821 0.261244 0.0562245 -0.00012581 0.0381435 0.997689 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 574 575 -0.340129 8.31249 0.265873 0.0441273 -0.00075964 0.0453201 0.997997 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 575 576 -0.333312 8.31327 0.274715 0.0453305 0.00585583 0.0347419 0.998351 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 576 577 -0.342988 8.33607 0.26062 0.0447725 0.00491112 0.0408417 0.99815 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 577 578 -0.345595 8.3421 0.248404 0.0434409 0.00391727 0.0335418 0.998485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 578 579 -0.355779 8.34784 0.273835 0.0412542 -1.73317e-05 0.0387057 0.998399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 579 580 -0.337478 8.37114 0.280699 0.0548854 -0.00210875 0.0413794 0.997633 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 580 581 -0.349502 8.37487 0.278229 0.055779 -0.000759075 0.0468162 0.997345 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 581 582 -0.347761 8.38398 0.283846 0.0494672 -0.00321663 0.0420006 0.997887 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 582 583 -0.344729 8.38788 0.270663 0.0472605 -0.0040878 0.0340088 0.998295 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 583 584 -0.348896 8.41744 0.276705 0.045649 -0.000215533 0.0383768 0.99822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 584 585 -0.362739 8.42937 0.279522 0.0481597 0.00273745 0.0426353 0.997926 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 585 586 -0.371926 8.42234 0.266828 0.0446756 0.00417306 0.0416276 0.998125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 586 587 -0.355729 8.45541 0.252935 0.045792 -0.00054777 0.0450283 0.997935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 587 588 -0.343926 8.45342 0.257363 0.0423458 0.000828421 0.0381648 0.998373 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 588 589 -0.365488 8.46778 0.268751 0.0483307 -0.00248612 0.034516 0.998232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 589 590 -0.351264 8.49076 0.257442 0.0459595 0.00380946 0.0283569 0.998533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 590 591 -0.34775 8.50537 0.270482 0.0481327 -0.00224033 0.045171 0.997817 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 591 592 -0.37303 8.51033 0.276319 0.0455771 -0.00125021 0.0448597 0.997952 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 592 593 -0.374703 8.51203 0.275742 0.0469507 0.00270526 0.044889 0.997884 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 593 594 -0.362954 8.50657 0.274619 0.0495754 -0.00461294 0.046683 0.997668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 594 595 -0.376014 8.52084 0.267314 0.0522881 -0.00138837 0.0404875 0.99781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 595 596 -0.359651 8.54764 0.24471 0.0384944 -0.00466057 0.0413065 0.998394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 596 597 -0.367771 8.5607 0.274687 0.0495011 -0.00532729 0.0414265 0.9979 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 597 598 -0.370428 8.58528 0.259762 0.0425086 0.00302076 0.0416524 0.998223 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 598 599 -0.374447 8.56564 0.258926 0.043553 0.00387155 0.0446444 0.998046 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 599 600 -0.35676 8.61018 0.264452 0.048856 0.00527604 0.041612 0.997925 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 600 601 -0.37817 8.59788 0.293977 0.0411093 0.000215423 0.0506556 0.99787 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 601 602 -0.353445 8.61715 0.262236 0.0416419 0.00472713 0.0433812 0.998179 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 602 603 -0.363815 8.61565 0.267869 0.0368705 -0.00218563 0.0428092 0.9984 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 603 604 -0.373184 8.63306 0.254375 0.0303259 0.00499559 0.0444816 0.998537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 604 605 -0.349755 8.64091 0.266597 0.0519205 0.00997151 0.0485346 0.997421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 605 606 -0.376656 8.6563 0.26905 0.0418135 0.00255068 0.0430864 0.998193 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 606 607 -0.366878 8.68306 0.285217 0.0464574 0.00157564 0.0408841 0.998082 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 607 608 -0.374149 8.69147 0.276129 0.0357552 -0.00673931 0.043039 0.998411 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 608 609 -0.378738 8.68811 0.255449 0.0413992 0.000728832 0.0480856 0.997985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 609 610 -0.392123 8.69506 0.28145 0.0488519 -0.000504708 0.043237 0.99787 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 610 611 -0.402279 8.73017 0.270567 0.0438987 0.00199121 0.0427502 0.998119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 611 612 -0.361382 8.72421 0.262118 0.0419773 0.00393471 0.0408802 0.998274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 612 613 -0.378313 8.75313 0.261745 0.0457294 0.00758727 0.0403478 0.99811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 613 614 -0.389253 8.75645 0.275184 0.0424203 3.83126e-05 0.0314076 0.998606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 614 615 -0.381699 8.77064 0.267058 0.0416838 -0.00506199 0.0365566 0.998449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 615 616 -0.39252 8.77493 0.279219 0.0548792 0.0130996 0.0375025 0.997702 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 616 617 -0.384815 8.78622 0.263613 0.0373941 -0.000226171 0.0439945 0.998332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 617 618 -0.387488 8.79326 0.282256 0.0480476 0.00578788 0.043634 0.997875 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 618 619 -0.388356 8.8013 0.281112 0.0428417 -0.00552138 0.0470584 0.997958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 619 620 -0.392351 8.82251 0.28199 0.0473787 0.00223614 0.0478697 0.997727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 620 621 -0.381489 8.81669 0.274451 0.0425415 0.00583408 0.0364045 0.998414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 621 622 -0.37274 8.8375 0.269256 0.0502739 -0.0108184 0.0393828 0.9979 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 622 623 -0.375236 8.82589 0.277562 0.0452572 0.00518195 0.0493963 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 623 624 -0.40163 8.87525 0.269183 0.0486681 0.000136272 0.0396417 0.998028 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 624 625 -0.402123 8.85326 0.266005 0.0444581 -0.0102901 0.0450641 0.997941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 625 626 -0.386693 8.86991 0.257591 0.0547751 0.0061913 0.040334 0.997665 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 626 627 -0.393279 8.92076 0.269023 0.0491622 0.00593352 0.0414461 0.997913 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 627 628 -0.386084 8.88554 0.28428 0.0469798 0.00356628 0.0468812 0.997789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 628 629 -0.3923 8.93936 0.298857 0.0520907 -0.00656352 0.0507575 0.99733 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 629 630 -0.407878 8.9339 0.273488 0.0499479 -0.00318933 0.0530167 0.997339 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 630 631 -0.424415 8.9304 0.27288 0.0385314 0.00457722 0.0483031 0.998079 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 631 632 -0.402338 8.95311 0.265516 0.0493226 0.00136254 0.052131 0.997421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 632 633 -0.409278 8.97162 0.266061 0.0418125 0.0131301 0.0368249 0.99836 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 633 634 -0.401596 8.96836 0.273951 0.0305051 0.00602685 0.0452078 0.998494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 634 635 -0.420467 8.98714 0.251378 0.0453899 0.00517926 0.0466087 0.997868 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 635 636 -0.394358 8.99737 0.26288 0.0502127 0.00201921 0.047569 0.997603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 636 637 -0.407757 9.02727 0.254829 0.0391357 -0.00021323 0.0498356 0.99799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 637 638 -0.3967 9.00495 0.25939 0.0410307 -0.00239264 0.0581671 0.99746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 638 639 -0.415901 9.02771 0.268383 0.0394576 0.000254594 0.0475779 0.998088 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 639 640 -0.420111 9.04213 0.279412 0.0453302 -0.00462842 0.0422513 0.998067 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 640 641 -0.402713 9.04497 0.280457 0.047594 0.0101056 0.0459881 0.997756 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 641 642 -0.414103 9.06141 0.271002 0.0328829 0.01153 0.0506121 0.99811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 642 643 -0.411645 9.07164 0.258502 0.0498883 -0.00501184 0.0428188 0.997824 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 643 644 -0.419836 9.09672 0.259845 0.0495333 0.00704182 0.0471723 0.997633 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 644 645 -0.428434 9.07791 0.266929 0.0476736 -0.00252569 0.0433929 0.997917 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 645 646 -0.415771 9.10712 0.271885 0.0517123 0.00355426 0.0538379 0.997203 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 646 647 -0.413577 9.10899 0.266201 0.0408519 -0.00542167 0.0453981 0.998119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 647 648 -0.404026 9.1091 0.260295 0.049498 -0.00324452 0.0543181 0.997291 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 648 649 -0.415835 9.11405 0.256105 0.0385164 0.00336884 0.0423903 0.998353 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 649 650 -0.423519 9.14494 0.267598 0.0442319 -0.00770783 0.0499449 0.997742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 650 651 -0.407653 9.1587 0.260123 0.0412129 0.000654446 0.0467614 0.998055 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 651 652 -0.436963 9.15768 0.264131 0.0491224 -0.00152468 0.0458837 0.997737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 652 653 -0.43535 9.19893 0.27047 0.0460541 -0.00217854 0.0420526 0.998051 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 653 654 -0.431468 9.17892 0.278222 0.0411747 -0.00294287 0.0435908 0.998196 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 654 655 -0.41654 9.21458 0.267154 0.046468 -0.00676337 0.0352605 0.998274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 655 656 -0.419012 9.21552 0.255457 0.0438925 0.00366711 0.0410246 0.998187 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 656 657 -0.418873 9.24319 0.255321 0.0331177 0.0033596 0.0417137 0.998575 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 657 658 -0.449283 9.22058 0.261681 0.0430361 0.0022412 0.0498207 0.997828 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 658 659 -0.433386 9.24005 0.239705 0.0468148 0.00434521 0.0484128 0.99772 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 659 660 -0.43293 9.24651 0.272141 0.0435617 0.00507923 0.0446706 0.998039 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 660 661 -0.439034 9.26595 0.258328 0.0427434 -0.000384046 0.0450909 0.998068 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 661 662 -0.4247 9.25568 0.266419 0.0365916 0.00279613 0.0464272 0.998247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 662 663 -0.431024 9.30218 0.282095 0.0371792 -0.000415392 0.0548821 0.9978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 663 664 -0.436754 9.28242 0.243408 0.0495547 -0.000760044 0.0431745 0.997838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 664 665 -0.42829 9.30838 0.256053 0.0382777 0.0025523 0.0480459 0.998108 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 665 666 -0.444304 9.33765 0.278935 0.0423343 -0.00535917 0.041735 0.998217 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 666 667 -0.434417 9.31815 0.240759 0.0403799 0.00439438 0.0487892 0.997983 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 667 668 -0.449681 9.35068 0.268853 0.0412652 -0.00099083 0.0413692 0.998291 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 668 669 -0.444107 9.34302 0.259118 0.0465004 0.00171616 0.0443497 0.997932 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 669 670 -0.449072 9.35648 0.272727 0.0418834 0.0136033 0.0551616 0.997506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 670 671 -0.454495 9.37131 0.270594 0.0494846 0.00173075 0.0407747 0.997941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 671 672 -0.452803 9.37806 0.274525 0.0460479 0.00493474 0.0464567 0.997846 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 672 673 -0.441881 9.39588 0.278276 0.0433577 -0.000692857 0.0449213 0.998049 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 673 674 -0.445358 9.40458 0.263204 0.0371504 0.00771256 0.0419298 0.9984 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 674 675 -0.442054 9.40135 0.260767 0.0353892 -0.0033219 0.0367782 0.998691 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 675 676 -0.455665 9.42714 0.25881 0.0353303 -0.001078 0.037133 0.998685 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 676 677 -0.450276 9.43003 0.263097 0.0321625 0.000521976 0.0534752 0.998051 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 677 678 -0.447265 9.45704 0.247876 0.0394524 0.00215902 0.0472857 0.9981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 678 679 -0.441777 9.4476 0.267193 0.0382457 0.000320572 0.0447646 0.998265 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 679 680 -0.436855 9.45059 0.249005 0.0421239 0.000148839 0.0487263 0.997923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 680 681 -0.458217 9.48492 0.274975 0.0454594 0.0119932 0.0466917 0.997802 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 681 682 -0.45343 9.49737 0.272513 0.0371613 -0.00183419 0.0554556 0.997768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 682 683 -0.455421 9.49362 0.265425 0.0506511 -0.00148647 0.0542568 0.99724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 683 684 -0.443192 9.52432 0.256364 0.0363011 -0.00565439 0.0503481 0.998056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 684 685 -0.459615 9.52454 0.248892 0.0346525 -0.00355962 0.0535566 0.997957 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 685 686 -0.450161 9.51494 0.270797 0.0325472 0.00375611 0.0499499 0.998214 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 686 687 -0.448867 9.54724 0.277575 0.0541271 -0.00518483 0.0571787 0.996882 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 687 688 -0.455484 9.53385 0.275992 0.0304725 0.00143867 0.0460979 0.998471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 688 689 -0.457501 9.57097 0.263232 0.0370452 -0.00399685 0.057083 0.997674 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 689 690 -0.459486 9.56999 0.278347 0.0364286 0.0140331 0.0532316 0.997819 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 690 691 -0.449095 9.58194 0.264984 0.0350304 -0.00111127 0.0426179 0.998477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 691 692 -0.449229 9.57276 0.26119 0.0400817 0.00333856 0.0397458 0.9984 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 692 693 -0.451459 9.58876 0.283158 0.0485578 0.00932824 0.035813 0.998135 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 693 694 -0.458604 9.61207 0.264959 0.0324469 -0.000663427 0.0512054 0.998161 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 694 695 -0.491345 9.60956 0.265142 0.0348859 0.0023921 0.052406 0.998013 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 695 696 -0.463176 9.63968 0.272515 0.0446008 -0.00795924 0.0464134 0.997894 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 696 697 -0.480942 9.64902 0.265916 0.0409559 0.000149392 0.0489917 0.997959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 697 698 -0.460842 9.64698 0.258167 0.0374114 0.00173224 0.0448948 0.998289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 698 699 -0.47796 9.67882 0.275358 0.0406403 -0.00432238 0.0425345 0.998259 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 699 700 -0.464782 9.68287 0.252294 0.0483267 -0.00317584 0.0530251 0.997418 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 700 701 -0.492084 9.66136 0.262913 0.0366775 0.000965921 0.0525042 0.997946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 701 702 -0.49068 9.70772 0.249726 0.040645 0.000167714 0.0408314 0.998339 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 702 703 -0.467257 9.713 0.263285 0.0389034 0.00310833 0.0536024 0.997799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 703 704 -0.476652 9.7093 0.258108 0.0414065 0.00594007 0.0443914 0.998138 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 704 705 -0.476976 9.71658 0.245748 0.0315887 0.00804837 0.0427193 0.998555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 705 706 -0.460799 9.73627 0.25323 0.0421931 0.00799095 0.0445525 0.998084 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 706 707 -0.479352 9.74799 0.257392 0.0340807 0.00619554 0.0491914 0.998189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 707 708 -0.488135 9.76172 0.260122 0.038711 0.00345222 0.0491371 0.998036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 708 709 -0.481441 9.76389 0.261245 0.0288516 -0.000210022 0.0435136 0.998636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 709 710 -0.481137 9.76759 0.261578 0.0369432 -0.00443036 0.0511676 0.997997 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 710 711 -0.483222 9.78442 0.250686 0.0318934 -0.00640876 0.0507121 0.998183 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 711 712 -0.457005 9.79453 0.254809 0.0446834 -0.00150376 0.0472672 0.997881 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 712 713 -0.474108 9.81453 0.261251 0.0376565 -0.00129502 0.039927 0.998492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 713 714 -0.474097 9.80254 0.258103 0.0488921 0.00887407 0.0524245 0.997388 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 714 715 -0.479078 9.83317 0.26432 0.0515319 0.00512632 0.0547396 0.997157 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 715 716 -0.485664 9.82119 0.251753 0.0342025 -0.00228916 0.0460663 0.99835 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 716 717 -0.488508 9.82007 0.266197 0.0404487 0.00278058 0.0479942 0.998024 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 717 718 -0.501005 9.83298 0.258895 0.0369075 0.00594815 0.0447575 0.998298 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 718 719 -0.490273 9.85636 0.270822 0.0360176 -0.00538658 0.0499562 0.998087 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 719 720 -0.482858 9.85204 0.265989 0.0376431 0.00617073 0.0369162 0.99859 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 720 721 -0.488804 9.87844 0.261869 0.0447472 -0.000580604 0.0552957 0.997467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 721 722 -0.511357 9.89074 0.250318 0.0423562 -0.00805892 0.0509868 0.997768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 722 723 -0.477912 9.88451 0.247157 0.0499803 0.00469513 0.0463428 0.997663 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 723 724 -0.480156 9.8859 0.267918 0.0333672 -0.00419839 0.0523417 0.998063 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 724 725 -0.495458 9.91955 0.245569 0.0430237 0.00505078 0.0427058 0.998148 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 725 726 -0.489324 9.92083 0.250534 0.0430208 0.00773826 0.0418621 0.998167 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 726 727 -0.496994 9.93416 0.255552 0.0328484 -0.000938762 0.044867 0.998452 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 727 728 -0.490267 9.94999 0.264482 0.0399769 0.000414093 0.0491311 0.997992 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 728 729 -0.490281 9.94052 0.23884 0.0367795 0.00176001 0.0473852 0.998198 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 729 730 -0.509139 9.95735 0.254307 0.0336416 0.00481775 0.0471943 0.998307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 730 731 -0.498498 9.95716 0.277158 0.0341511 0.00134627 0.0493696 0.998196 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 731 732 -0.504919 9.97139 0.264672 0.0437643 -0.00577818 0.0506029 0.997743 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 732 733 -0.501923 9.9902 0.238072 0.0421698 -0.00645579 0.0581574 0.997395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 733 734 -0.496877 9.99176 0.256286 0.0333544 0.00594799 0.0471548 0.998313 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 734 735 -0.50092 10.0167 0.261907 0.0389091 -0.00467209 0.045102 0.998213 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 735 736 -0.505713 10.0092 0.247601 0.0412144 0.000445141 0.0473525 0.998028 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 736 737 -0.497697 10.017 0.262912 0.0361964 0.00138345 0.0464424 0.998264 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 737 738 -0.504932 10.0404 0.264514 0.0412196 0.00316151 0.0568381 0.997527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 738 739 -0.517255 10.0435 0.261151 0.0417567 0.00405067 0.0547749 0.997617 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 739 740 -0.505563 10.066 0.256721 0.0373704 -0.00742444 0.0497956 0.998032 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 740 741 -0.507658 10.0531 0.241926 0.0379651 -0.000590557 0.0553563 0.997744 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 741 742 -0.496806 10.0575 0.249687 0.039499 0.00166608 0.0554712 0.997677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 742 743 -0.512183 10.0748 0.247981 0.0407274 0.00280616 0.0441427 0.998191 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 743 744 -0.49616 10.0937 0.245427 0.0378057 -0.00148219 0.0528614 0.997885 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 744 745 -0.511497 10.1015 0.240016 0.0364984 0.000777946 0.0580727 0.997645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 745 746 -0.525245 10.1225 0.254819 0.0397156 -0.000340503 0.0573221 0.997565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 746 747 -0.508465 10.1192 0.258255 0.0470095 0.00193257 0.0498405 0.997648 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 747 748 -0.525015 10.1351 0.252606 0.0373605 0.000324793 0.0517889 0.997959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 748 749 -0.522408 10.1339 0.239735 0.0370024 0.00299882 0.0498279 0.998068 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 749 750 -0.51883 10.1635 0.257672 0.0440757 0.00308524 0.055238 0.997495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 750 751 -0.524534 10.1564 0.252331 0.0339664 0.0011402 0.04852 0.998244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 751 752 -0.514901 10.1568 0.234157 0.0463669 -0.00613928 0.0447869 0.997901 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 752 753 -0.527404 10.1725 0.234444 0.0397146 0.0017171 0.0520373 0.997854 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 753 754 -0.513793 10.1526 0.235359 0.038428 -0.00125443 0.0587148 0.997534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 754 755 -0.525996 10.2071 0.250687 0.0365313 0.00935119 0.0557583 0.997732 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 755 756 -0.530968 10.2113 0.237484 0.0403365 -7.33877e-05 0.0587247 0.997459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 756 757 -0.523392 10.2179 0.251974 0.0315302 0.00626463 0.0492522 0.998269 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 757 758 -0.518318 10.2043 0.239723 0.0323212 -0.00496786 0.0534454 0.998035 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 758 759 -0.518621 10.2432 0.244742 0.043981 0.00605097 0.054249 0.99754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 759 760 -0.526509 10.2251 0.239525 0.0418612 0.00466178 0.0597257 0.997326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 760 761 -0.532578 10.2314 0.241852 0.0394787 0.00876084 0.0499335 0.997934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 761 762 -0.55176 10.2614 0.246378 0.03312 -0.00378154 0.0523265 0.998073 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 762 763 -0.527501 10.2641 0.243203 0.033654 0.00106642 0.0541985 0.997962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 763 764 -0.527524 10.298 0.249534 0.0361313 0.00159889 0.0528464 0.997948 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 764 765 -0.539462 10.281 0.241982 0.0353925 0.00533967 0.0482282 0.998195 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 765 766 -0.539719 10.2942 0.245583 0.0372137 0.00297443 0.0623005 0.997359 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 766 767 -0.536033 10.2943 0.246698 0.0306704 -0.00409937 0.0403645 0.998706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 767 768 -0.527026 10.3232 0.255327 0.0396105 -0.00462193 0.0488781 0.998008 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 768 769 -0.519898 10.3262 0.264681 0.0299669 -0.000641823 0.057551 0.997893 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 769 770 -0.511484 10.339 0.228252 0.0291029 -0.00229915 0.0534271 0.998145 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 770 771 -0.539364 10.343 0.267587 0.0321621 -0.00522499 0.0634774 0.997451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 771 772 -0.536247 10.329 0.248534 0.0388084 0.00269242 0.0505657 0.997963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 772 773 -0.541876 10.3694 0.249499 0.0282584 0.00388348 0.0525624 0.99821 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 773 774 -0.538449 10.3698 0.254005 0.0376194 0.00568488 0.0596848 0.997492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 774 775 -0.545303 10.386 0.234138 0.0415222 -0.00626391 0.0531133 0.997705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 775 776 -0.547131 10.3944 0.227637 0.0401624 -0.00115877 0.0501861 0.997931 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 776 777 -0.539606 10.3848 0.240858 0.0411415 0.0029571 0.0477087 0.998009 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 777 778 -0.524645 10.3973 0.249374 0.0309095 0.00286009 0.0562377 0.997935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 778 779 -0.546798 10.4139 0.222241 0.0370194 0.000910491 0.0626765 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 779 780 -0.537603 10.4305 0.222589 0.0393063 -0.00198869 0.053611 0.997786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 780 781 -0.538907 10.4222 0.22747 0.0289801 -0.00251966 0.0500285 0.998324 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 781 782 -0.553157 10.4294 0.228834 0.0274858 0.0026521 0.0416996 0.998749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 782 783 -0.535307 10.439 0.236024 0.049035 -0.00117122 0.0513823 0.997474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 783 784 -0.552498 10.4488 0.226757 0.032024 -0.000477038 0.0552195 0.99796 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 784 785 -0.55746 10.4795 0.235852 0.0288703 0.00296395 0.0534761 0.998147 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 785 786 -0.543821 10.4658 0.246256 0.0376898 0.00413186 0.0601916 0.997466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 786 787 -0.544924 10.4816 0.227044 0.0431341 -0.00266174 0.0545041 0.997578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 787 788 -0.554563 10.4946 0.236625 0.0352549 0.0028485 0.0396647 0.998587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 788 789 -0.544964 10.5039 0.227002 0.0326353 0.00602122 0.0602884 0.997629 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 789 790 -0.564209 10.5017 0.237658 0.0308673 -0.00228734 0.053988 0.998062 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 790 791 -0.55182 10.5105 0.219111 0.0329294 0.00158443 0.0506069 0.998174 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 791 792 -0.559328 10.5293 0.237683 0.0373807 0.00213135 0.0544187 0.997816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 792 793 -0.544842 10.5389 0.228368 0.0265908 -0.000389996 0.0623297 0.997701 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 793 794 -0.535428 10.5447 0.230303 0.033637 0.00291853 0.0466119 0.998342 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 794 795 -0.571684 10.5531 0.239516 0.0269139 0.00152456 0.0538252 0.998186 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 795 796 -0.541538 10.5481 0.237697 0.0355347 0.00555094 0.0532231 0.997935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 796 797 -0.564823 10.5629 0.234218 0.0383198 -0.00527602 0.0513216 0.997933 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 797 798 -0.565595 10.5759 0.235178 0.0370663 0.00161364 0.0474235 0.998186 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 798 799 -0.572534 10.57 0.233435 0.0272933 0.00238555 0.0526809 0.998235 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 799 800 -0.545475 10.5888 0.26181 0.0331133 -0.00117156 0.0499775 0.998201 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 800 801 -0.558461 10.6035 0.248886 0.0346975 -0.00464592 0.0457382 0.99834 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 801 802 -0.565828 10.6353 0.218958 0.0343745 -0.00404377 0.0501665 0.998141 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 802 803 -0.57018 10.613 0.223375 0.0399423 -0.00350971 0.0538203 0.997745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 803 804 -0.561703 10.6242 0.235868 0.0298187 0.004052 0.0544043 0.998065 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 804 805 -0.586112 10.6227 0.230116 0.0257345 0.000225631 0.0556254 0.99812 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 805 806 -0.554478 10.6428 0.227049 0.0352607 -0.00237871 0.0537453 0.997929 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 806 807 -0.573371 10.6379 0.205185 0.0277523 -0.000659299 0.0513453 0.998295 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 807 808 -0.549828 10.6606 0.232287 0.0299911 0.0049754 0.0489182 0.99834 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 808 809 -0.5839 10.6474 0.221423 0.0397484 0.0037138 0.063617 0.997176 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 809 810 -0.566486 10.6734 0.204778 0.0222852 0.00208898 0.0596818 0.997966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 810 811 -0.573536 10.6874 0.239977 0.0347399 0.00124413 0.0490282 0.998192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 811 812 -0.570307 10.6846 0.22931 0.0311294 -0.00402643 0.0538354 0.998056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 812 813 -0.562454 10.7037 0.226771 0.032194 -0.00435829 0.0563334 0.997883 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 813 814 -0.574234 10.697 0.214588 0.0332749 -0.00902439 0.047067 0.998297 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 814 815 -0.563214 10.7147 0.237947 0.0327725 -0.00261164 0.0502666 0.998195 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 815 816 -0.579895 10.7161 0.223116 0.0340999 0.00549845 0.0550131 0.997888 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 816 817 -0.576878 10.7333 0.209278 0.0331037 -0.00220168 0.054213 0.997978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 817 818 -0.567694 10.7424 0.223979 0.019639 -0.000531005 0.0418539 0.998931 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 818 819 -0.57112 10.7519 0.218223 0.0387926 0.00112904 0.0545859 0.997755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 819 820 -0.590686 10.7655 0.229306 0.0335103 -0.0033459 0.0556104 0.997884 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 820 821 -0.580942 10.7638 0.228213 0.0268261 0.00680271 0.0469528 0.998514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 821 822 -0.591348 10.7731 0.221833 0.0305909 -0.000492183 0.0493274 0.998314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 822 823 -0.593701 10.7845 0.236761 0.0292474 -0.000609268 0.0542784 0.998097 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 823 824 -0.584748 10.772 0.224462 0.0336004 -0.00125336 0.0593696 0.99767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 824 825 -0.590382 10.7901 0.21176 0.0319266 0.00437608 0.049181 0.99827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 825 826 -0.592082 10.8253 0.208969 0.028855 -0.000691375 0.0542286 0.998111 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 826 827 -0.572268 10.8085 0.223751 0.0311285 0.00361357 0.0511293 0.9982 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 827 828 -0.577605 10.8021 0.243781 0.0332413 0.00205549 0.0509105 0.998148 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 828 829 -0.590026 10.8407 0.211967 0.0281883 0.00181661 0.0524203 0.998226 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 829 830 -0.579673 10.8323 0.219048 0.039885 0.00671406 0.0576357 0.997518 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 830 831 -0.601673 10.8673 0.221805 0.0320511 -0.00117021 0.0579811 0.997802 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 831 832 -0.591865 10.8507 0.218841 0.0145539 0.00255761 0.0521848 0.998528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 832 833 -0.602486 10.8531 0.200295 0.0270616 -0.00420611 0.0568785 0.998005 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 833 834 -0.592371 10.8592 0.216727 0.0328895 0.0156973 0.0604152 0.997508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 834 835 -0.604553 10.8815 0.225598 0.0255431 0.00397994 0.0575219 0.998009 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 835 836 -0.575322 10.8619 0.231742 0.0335366 0.00318425 0.0563815 0.997841 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 836 837 -0.595505 10.8817 0.216981 0.0254261 -0.00680734 0.0568744 0.998034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 837 838 -0.598187 10.8799 0.213766 0.0283871 -0.0025402 0.0568343 0.997977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 838 839 -0.609137 10.9191 0.212563 0.0327326 -0.00536054 0.0527982 0.998054 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 839 840 -0.626904 10.9281 0.199062 0.0419388 0.00123298 0.0479888 0.997966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 840 841 -0.598755 10.9074 0.230187 0.0255506 -0.00238896 0.0559719 0.998103 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 841 842 -0.603473 10.9458 0.21765 0.0226791 -0.00212681 0.0639654 0.997692 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 842 843 -0.574611 10.929 0.229415 0.0251228 -0.000388929 0.060909 0.997827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 843 844 -0.59298 10.939 0.210107 0.0304313 0.00814644 0.0594715 0.997733 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 844 845 -0.598547 10.9575 0.206452 0.0391187 -0.00400532 0.0670522 0.996974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 845 846 -0.621996 10.9582 0.216227 0.0323445 -0.00437697 0.0509936 0.998165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 846 847 -0.604054 10.9522 0.219582 0.0336005 -0.00144218 0.0545711 0.997943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 847 848 -0.602606 10.9714 0.20015 0.0375867 -0.00703714 0.0590005 0.997525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 848 849 -0.595242 10.9818 0.22399 0.0378764 0.00345653 0.0515203 0.997947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 849 850 -0.603705 10.9958 0.184848 0.0340182 0.00452342 0.0474341 0.998285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 850 851 -0.602829 11.0078 0.218451 0.0339067 0.00551247 0.0527725 0.998016 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 851 852 -0.610514 10.9998 0.207645 0.0281822 6.49957e-05 0.0542196 0.998131 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 852 853 -0.60225 11.0069 0.213673 0.0364558 -0.00327073 0.0452942 0.998303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 853 854 -0.59555 11.0125 0.201412 0.0300851 -0.000881046 0.0718733 0.99696 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 854 855 -0.62138 11.0127 0.195541 0.0313591 -0.003683 0.0624674 0.997547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 855 856 -0.621791 11.0408 0.207117 0.0324913 -0.00492544 0.0600338 0.997655 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 856 857 -0.596633 11.0322 0.208403 0.033158 -0.0144395 0.0495323 0.998118 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 857 858 -0.621562 11.0386 0.190868 0.0329452 0.000817089 0.0494593 0.998232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 858 859 -0.610392 11.0635 0.197869 0.0264595 0.00594756 0.0566834 0.998024 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 859 860 -0.621085 11.0547 0.205918 0.0304605 -0.0014401 0.0557014 0.997982 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 860 861 -0.605864 11.0872 0.21999 0.0252625 0.00351194 0.0528926 0.998274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 861 862 -0.612575 11.0862 0.203973 0.0312954 0.00067179 0.049089 0.998304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 862 863 -0.620654 11.0794 0.223981 0.034021 0.00205998 0.0512659 0.998103 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 863 864 -0.607378 11.1032 0.206787 0.0366501 0.00719612 0.050932 0.998003 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 864 865 -0.617556 11.1058 0.200016 0.0364728 0.00441897 0.0506967 0.998038 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 865 866 -0.620488 11.114 0.18543 0.0264372 0.00239628 0.0513762 0.998327 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 866 867 -0.611384 11.1158 0.193497 0.0207825 -0.0108234 0.0572169 0.998087 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 867 868 -0.614894 11.121 0.19317 0.0296359 -0.00471936 0.0587487 0.997822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 868 869 -0.612423 11.1399 0.191384 0.0279631 -0.00218681 0.0507596 0.998317 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 869 870 -0.611246 11.1262 0.190529 0.0340658 -0.00156311 0.056665 0.997811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 870 871 -0.636575 11.1316 0.206188 0.024102 -0.00710721 0.0530645 0.998275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 871 872 -0.62328 11.1684 0.189391 0.0314208 0.001065 0.0531753 0.99809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 872 873 -0.620995 11.1583 0.200583 0.0275942 0.0015241 0.0522804 0.99825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 873 874 -0.607443 11.1694 0.201715 0.0293873 0.0050575 0.0544767 0.99807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 874 875 -0.633277 11.1963 0.174377 0.0242474 -0.0031747 0.0616221 0.9978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 875 876 -0.632121 11.1836 0.184448 0.0236076 0.00329554 0.059971 0.997915 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 876 877 -0.625757 11.1713 0.199123 0.0350012 -0.00167306 0.0557727 0.997828 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 877 878 -0.621768 11.1912 0.187402 0.023412 -0.00575113 0.0666352 0.997486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 878 879 -0.619667 11.2102 0.182864 0.0243857 -0.00335706 0.0499336 0.998449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 879 880 -0.619162 11.2194 0.184687 0.0245181 -0.0026756 0.0586978 0.997971 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 880 881 -0.611431 11.2241 0.200167 0.0248057 0.00116817 0.0532002 0.998275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 881 882 -0.612748 11.2281 0.195071 0.0291729 0.000713705 0.0544345 0.998091 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 882 883 -0.643261 11.2323 0.184955 0.0312296 0.00250926 0.0568857 0.997889 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 883 884 -0.648324 11.2483 0.17708 0.0285479 -0.00169227 0.0503803 0.998321 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 884 885 -0.642299 11.2361 0.188929 0.0296933 -0.00492814 0.0515173 0.998218 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 885 886 -0.65715 11.2463 0.194511 0.024852 -0.0109903 0.0539978 0.998171 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 886 887 -0.653358 11.2514 0.176265 0.0184706 -0.00760433 0.0532203 0.998383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 887 888 -0.634248 11.2616 0.183973 0.0281274 0.00406816 0.0559389 0.99803 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 888 889 -0.629331 11.255 0.172704 0.0191583 0.00909558 0.0599406 0.997977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 889 890 -0.649852 11.2806 0.1913 0.0212005 -0.00160398 0.0587765 0.998045 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 890 891 -0.62506 11.2857 0.167899 0.0317458 0.00604216 0.0576555 0.997813 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 891 892 -0.66706 11.2858 0.177997 0.0273854 -0.00375684 0.0567392 0.998006 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 892 893 -0.659422 11.3048 0.178866 0.0337773 -0.00283071 0.050576 0.998145 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 893 894 -0.663169 11.2932 0.15548 0.0289028 -0.0167313 0.0595024 0.997669 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 894 895 -0.643173 11.3077 0.188122 0.0208666 -0.00956021 0.0580455 0.99805 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 895 896 -0.636606 11.3112 0.165703 0.0299078 -0.00223252 0.0583529 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 896 897 -0.65015 11.3199 0.173491 0.0293827 0.00623504 0.053605 0.99811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 897 898 -0.643369 11.3216 0.17313 0.0198398 -0.00658753 0.0619644 0.997859 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 898 899 -0.668749 11.3509 0.184685 0.028475 -0.00384299 0.051488 0.99826 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 899 900 -0.62167 11.3433 0.178293 0.0327105 0.00217706 0.0455129 0.998426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 900 901 -0.64174 11.3655 0.180546 0.033888 0.00353347 0.0558781 0.997856 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 901 902 -0.658271 11.3578 0.186566 0.0145276 0.00822602 0.056857 0.998243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 902 903 -0.635208 11.3636 0.173892 0.0243796 0.000724915 0.0503503 0.998434 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 903 904 -0.660083 11.36 0.169553 0.0271433 -0.00426833 0.0601076 0.997814 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 904 905 -0.67309 11.3823 0.176214 0.0314029 0.000979796 0.0533607 0.998081 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 905 906 -0.654155 11.3959 0.16471 0.0301529 0.000537805 0.0539289 0.998089 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 906 907 -0.639521 11.3958 0.165532 0.0249961 0.00106678 0.0564468 0.998092 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 907 908 -0.651189 11.3931 0.170457 0.0174335 -0.00381688 0.0536373 0.998401 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 908 909 -0.658964 11.3896 0.186991 0.0352778 0.00704931 0.059199 0.997598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 909 910 -0.653441 11.4157 0.178243 0.0189619 0.000176126 0.0642645 0.997753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 910 911 -0.653387 11.4224 0.168776 0.0132156 -0.00121074 0.0560754 0.998338 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 911 912 -0.665192 11.431 0.173341 0.0304542 -0.00306666 0.0560976 0.997956 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 912 913 -0.652235 11.4286 0.17802 0.0299671 0.000549469 0.051374 0.99823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 913 914 -0.656292 11.4352 0.176405 0.0263337 0.00396373 0.0554952 0.998104 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 914 915 -0.656547 11.447 0.179443 0.0189832 0.0049133 0.0546203 0.998315 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 915 916 -0.665766 11.4498 0.154086 0.0126376 0.00585709 0.0722701 0.997288 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 916 917 -0.644331 11.4654 0.172751 0.0247888 -0.00414306 0.0590905 0.997936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 917 918 -0.65137 11.4556 0.160805 0.0225454 0.00748118 0.0578267 0.998044 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 918 919 -0.656193 11.476 0.189488 0.0173554 0.00237314 0.0539659 0.998389 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 919 920 -0.652178 11.476 0.163762 0.0233251 -0.00518513 0.0667702 0.997482 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 920 921 -0.665025 11.4938 0.182749 0.0320656 0.0044504 0.0630517 0.997485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 921 922 -0.629942 11.4962 0.166181 0.0322417 0.00320162 0.0613591 0.99759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 922 923 -0.670103 11.4981 0.164831 0.0215527 0.000353539 0.0533784 0.998342 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 923 924 -0.669603 11.4964 0.16334 0.0206055 0.00459557 0.0542417 0.998305 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 924 925 -0.682828 11.4924 0.169678 0.024019 0.00450689 0.0599003 0.997905 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 925 926 -0.649395 11.5288 0.157896 0.0231037 0.00290712 0.0553832 0.998194 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 926 927 -0.676495 11.5167 0.163379 0.0306173 -0.00858988 0.0627468 0.997523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 927 928 -0.674426 11.5199 0.154046 0.0191761 0.000376398 0.0595331 0.998042 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 928 929 -0.669191 11.5177 0.159939 0.0241349 0.000436854 0.0604162 0.997881 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 929 930 -0.666977 11.522 0.147663 0.0276011 -0.0047698 0.0616418 0.997705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 930 931 -0.661625 11.5599 0.155284 0.0237821 -0.00196291 0.0651211 0.997592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 931 932 -0.672933 11.5604 0.149662 0.0316498 0.000387411 0.0552761 0.997969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 932 933 -0.650526 11.5675 0.16076 0.0281113 -0.00545488 0.0503278 0.998322 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 933 934 -0.673944 11.5594 0.165085 0.0270368 0.0105321 0.0558368 0.998018 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 934 935 -0.675449 11.5493 0.152324 0.028363 0.00790114 0.0682383 0.997235 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 935 936 -0.682524 11.5977 0.150837 0.0274463 0.00827317 0.0584356 0.99788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 936 937 -0.678525 11.577 0.145976 0.0166217 0.00459159 0.0591189 0.998102 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 937 938 -0.668109 11.6022 0.149781 0.022717 -0.00202477 0.0466512 0.998651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 938 939 -0.684562 11.5977 0.172574 0.0214535 0.00663562 0.0541142 0.998282 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 939 940 -0.688616 11.6107 0.148538 0.0249614 -0.0122844 0.0603206 0.997791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 940 941 -0.679261 11.6203 0.15163 0.0218092 0.00255313 0.0531262 0.998346 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 941 942 -0.6886 11.615 0.142652 0.0218315 0.00455136 0.055315 0.99822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 942 943 -0.697349 11.6204 0.158523 0.0266506 0.00173234 0.0578747 0.997967 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 943 944 -0.676151 11.6155 0.152449 0.0322309 -8.41656e-05 0.0635441 0.997458 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 944 945 -0.663523 11.6538 0.155827 0.0213721 0.00769246 0.0655986 0.997588 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 945 946 -0.658536 11.6261 0.154759 0.0253656 -0.000600854 0.0590441 0.997933 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 946 947 -0.692153 11.6257 0.155385 0.0217932 -0.002144 0.0595089 0.997988 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 947 948 -0.662776 11.6452 0.134484 0.00828849 0.00602724 0.0565256 0.998349 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 948 949 -0.686415 11.6375 0.149047 0.0241475 -5.59991e-05 0.0583859 0.998002 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 949 950 -0.67857 11.6519 0.141943 0.0288612 0.00966412 0.0515303 0.998208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 950 951 -0.694771 11.6681 0.154674 0.01946 0.00701988 0.0587529 0.998058 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 951 952 -0.685673 11.6731 0.132796 0.0199566 0.00323046 0.0522284 0.998431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 952 953 -0.68469 11.6697 0.148819 0.0221145 0.00676995 0.0680216 0.997416 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 953 954 -0.684681 11.6761 0.140241 0.029234 0.00647806 0.0663557 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 954 955 -0.67482 11.6672 0.13076 0.0172266 -0.000285262 0.0612935 0.997971 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 955 956 -0.678026 11.7101 0.147846 0.026795 0.0107057 0.0554974 0.998042 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 956 957 -0.67216 11.7118 0.13471 0.0187849 -0.000928081 0.0593827 0.998058 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 957 958 -0.678425 11.691 0.136826 0.0286811 0.0059076 0.0509615 0.998271 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 958 959 -0.693078 11.7187 0.136184 0.023372 -0.00166515 0.0543626 0.998246 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 959 960 -0.687976 11.7197 0.135899 0.0270846 0.00938217 0.0540353 0.998128 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 960 961 -0.677774 11.7096 0.141804 0.0273602 0.00250529 0.0634824 0.997605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 961 962 -0.686823 11.7241 0.139593 0.0317181 -0.00598709 0.0649923 0.997364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 962 963 -0.684644 11.7459 0.133018 0.0248043 0.00419266 0.0594034 0.997917 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 963 964 -0.68586 11.73 0.140561 0.0211819 -0.00538843 0.0637461 0.997727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 964 965 -0.69263 11.7452 0.121142 0.0157806 0.000788519 0.0616183 0.997975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 965 966 -0.683021 11.7455 0.118408 0.0226541 -0.00281481 0.066746 0.997509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 966 967 -0.695312 11.756 0.124758 0.0155987 0.00474749 0.061964 0.997945 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 967 968 -0.7035 11.7848 0.124755 0.031364 0.00381193 0.0613486 0.997616 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 968 969 -0.705089 11.771 0.130631 0.0294388 -0.00210471 0.0618104 0.997651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 969 970 -0.701551 11.7618 0.149304 0.0294739 -0.00200831 0.0541986 0.998093 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 970 971 -0.686782 11.7874 0.120889 0.019047 0.00101337 0.0604986 0.997986 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 971 972 -0.70592 11.7695 0.133143 0.00866908 0.004058 0.06259 0.997993 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 972 973 -0.715089 11.7791 0.125099 0.0207468 -0.00165419 0.0513788 0.998462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 973 974 -0.691509 11.798 0.126758 0.0289314 0.00477516 0.0567951 0.997955 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 974 975 -0.708718 11.7896 0.142155 0.0207765 0.00375135 0.0453555 0.998748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 975 976 -0.686377 11.8095 0.134353 0.0237846 0.00706224 0.0582308 0.997995 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 976 977 -0.71234 11.8133 0.128072 0.0258961 0.00354311 0.0554595 0.998119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 977 978 -0.688679 11.8111 0.127453 0.0194793 0.0106311 0.0669945 0.997507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 978 979 -0.699672 11.8296 0.11141 0.0190431 0.00866141 0.0571216 0.998148 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 979 980 -0.697801 11.836 0.139647 0.0167127 -0.00217456 0.0591778 0.998105 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 980 981 -0.68685 11.8329 0.11682 0.0238454 0.00712623 0.0623806 0.997742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 981 982 -0.703145 11.8256 0.119473 0.0192303 0.000920176 0.058635 0.998094 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 982 983 -0.704339 11.8259 0.126915 0.0162165 0.0106844 0.0514158 0.998489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 983 984 -0.700748 11.8567 0.0990624 0.0282661 0.00289051 0.0550174 0.998081 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 984 985 -0.705719 11.8412 0.10934 0.0200646 -0.00312999 0.0595215 0.99802 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 985 986 -0.714235 11.8464 0.114046 0.025063 0.00768495 0.0566734 0.998049 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 986 987 -0.699609 11.8578 0.119846 0.0184196 0.00061065 0.05776 0.99816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 987 988 -0.708049 11.8654 0.141666 0.0191606 -0.00394903 0.0540215 0.998348 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 988 989 -0.70428 11.866 0.110217 0.0199743 0.00417499 0.0577352 0.998123 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 989 990 -0.723919 11.8741 0.119097 0.0267774 -0.00179303 0.0605719 0.997803 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 990 991 -0.71941 11.9018 0.118101 0.0155601 0.000724791 0.0670716 0.997627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 991 992 -0.710994 11.8741 0.115408 0.0212534 -0.00279965 0.0575695 0.998111 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 992 993 -0.715508 11.8886 0.122259 0.0180446 0.00191169 0.0474379 0.998709 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 993 994 -0.709893 11.8856 0.135031 0.0222071 0.00991312 0.0562353 0.998121 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 994 995 -0.719677 11.9015 0.113967 0.0250281 0.00824743 0.0617557 0.997743 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 995 996 -0.712076 11.9074 0.0934629 0.016886 0.0035798 0.0594696 0.998081 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 996 997 -0.711526 11.9002 0.110006 0.0196944 0.0038347 0.0625357 0.997841 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 997 998 -0.708503 11.9159 0.112042 0.0282385 0.00118627 0.0579181 0.997921 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 998 999 -0.697471 11.9104 0.102389 0.0220051 -0.000487909 0.0523049 0.998389 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 999 1000 -0.715251 11.9387 0.130849 0.0109146 -0.00230449 0.0590188 0.998195 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1000 1001 -0.724446 11.9231 0.11769 0.0222017 0.00793886 0.0595408 0.997947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1001 1002 -0.70537 11.934 0.107196 0.017167 -0.00590529 0.0539958 0.998376 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1002 1003 -0.736011 11.9408 0.0972489 0.0132727 -0.0074848 0.0693675 0.997475 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1003 1004 -0.71515 11.9423 0.0943373 0.0241938 0.00582861 0.0471548 0.998578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1004 1005 -0.708509 11.9563 0.101994 0.0165277 0.0017496 0.0576543 0.998198 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1005 1006 -0.693275 11.949 0.103427 0.021631 -0.00697562 0.0692134 0.997343 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1006 1007 -0.69099 11.9655 0.105136 0.0226936 0.000859214 0.0575546 0.998084 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1007 1008 -0.719965 11.9809 0.104495 0.0245854 0.00117365 0.0612737 0.997817 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1008 1009 -0.702086 11.9689 0.0890604 0.0164273 -0.00474266 0.0601585 0.998042 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1009 1010 -0.724892 11.9777 0.108864 0.0231131 -0.00507147 0.0641873 0.997657 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1010 1011 -0.72725 11.9701 0.0908709 0.0239096 0.00796143 0.061323 0.9978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1011 1012 -0.710878 11.9706 0.102996 0.0194964 0.00245152 0.0544619 0.998322 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1012 1013 -0.733253 11.9795 0.084589 0.0217302 7.19678e-05 0.0645439 0.997678 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1013 1014 -0.72033 12.0013 0.104395 0.0248858 -0.00415466 0.0588102 0.99795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1014 1015 -0.728525 12.0011 0.0894183 0.0184393 0.00391344 0.0542784 0.998348 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1015 1016 -0.721411 11.993 0.0930621 0.0188662 -0.00119591 0.0614034 0.997934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1016 1017 -0.702361 12.0062 0.0874064 0.0116127 0.00492333 0.0581398 0.998229 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1017 1018 -0.71252 12.0133 0.0888066 0.0198919 -0.00553923 0.0559865 0.998218 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1018 1019 -0.72869 12.0137 0.0953856 0.0165204 0.00138752 0.0607343 0.998016 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1019 1020 -0.719453 12.0321 0.094456 0.0277687 0.00625757 0.0567119 0.997985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1020 1021 -0.734407 12.0044 0.0898076 0.028398 -0.00415823 0.0522999 0.998219 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1021 1022 -0.725731 12.0259 0.0802521 0.0150363 0.00534435 0.066579 0.997654 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1022 1023 -0.712816 12.0336 0.0880311 0.0130348 -0.0031513 0.0610745 0.998043 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1023 1024 -0.729836 12.0489 0.0947693 0.0210473 -0.00334554 0.0617282 0.997865 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1024 1025 -0.731027 12.0496 0.0828854 0.0117512 0.00586913 0.0563211 0.998326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1025 1026 -0.703981 12.0553 0.0698279 0.011465 0.0033457 0.0613017 0.998048 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1026 1027 -0.724854 12.0322 0.0989684 0.023962 -0.00016867 0.0546724 0.998217 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1027 1028 -0.727823 12.0583 0.0930269 0.0243203 0.00176617 0.0631777 0.997704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1028 1029 -0.719143 12.0636 0.0933586 0.0158463 -0.00675732 0.0585822 0.998134 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1029 1030 -0.732907 12.0561 0.0874846 0.025233 0.00558192 0.0583861 0.99796 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1030 1031 -0.735861 12.0816 0.0785097 0.00669315 0.000965075 0.0618471 0.998063 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1031 1032 -0.740292 12.0744 0.058857 0.0163171 -0.00227641 0.0525775 0.998481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1032 1033 -0.71885 12.0697 0.0768612 0.0108333 0.00447247 0.0637993 0.997894 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1033 1034 -0.741805 12.0756 0.0818103 0.00843125 0.0121579 0.0655211 0.997741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1034 1035 -0.730944 12.0886 0.0630746 0.0182333 0.00478164 0.057974 0.99814 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1035 1036 -0.731513 12.102 0.0757673 0.0245669 -0.000304953 0.0595485 0.997923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1036 1037 -0.734716 12.082 0.0746439 0.0207521 0.0089477 0.0660522 0.99756 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1037 1038 -0.7245 12.1031 0.0645668 0.0158761 -0.00549886 0.0631893 0.99786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1038 1039 -0.743815 12.0914 0.0733068 0.0146155 0.00556076 0.0582425 0.99818 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1039 1040 -0.735855 12.0954 0.0792369 0.0244563 0.000809833 0.0635832 0.997677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1040 1041 -0.724766 12.1048 0.075505 0.0157738 -0.00522577 0.0665719 0.997643 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1041 1042 -0.745708 12.1237 0.067761 0.0111061 2.42727e-05 0.0680484 0.99762 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1042 1043 -0.735799 12.1097 0.0752999 0.0162661 -0.00458126 0.0681723 0.99753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1043 1044 -0.731775 12.1201 0.0710838 0.0233177 -0.000628868 0.0633772 0.997717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1044 1045 -0.732581 12.1285 0.0841097 0.0197271 0.00209401 0.0637849 0.997766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1045 1046 -0.736325 12.1226 0.0588987 0.0203504 -0.00204183 0.0678038 0.997489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1046 1047 -0.740929 12.1502 0.0814741 0.0164563 -0.000815889 0.0661218 0.997676 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1047 1048 -0.722009 12.1349 0.0638849 0.00967163 -0.00372289 0.0699898 0.997494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1048 1049 -0.741156 12.1428 0.063229 0.0173466 -0.00260502 0.0724122 0.997221 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1049 1050 -0.752196 12.1516 0.0758073 0.0159418 -0.00473172 0.0637676 0.997826 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1050 1051 -0.752793 12.1536 0.0518411 0.0262612 0.00490597 0.0551225 0.998122 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1051 1052 -0.735652 12.1558 0.0628278 0.00862256 -0.00603254 0.06731 0.997677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1052 1053 -0.734762 12.139 0.0563785 0.0132463 0.00222489 0.0650001 0.997795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1053 1054 -0.769932 12.148 0.0570721 0.0177826 0.000860664 0.0735268 0.997134 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1054 1055 -0.757512 12.1569 0.0426231 0.00571053 -0.00630097 0.0664453 0.997754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1055 1056 -0.742408 12.1714 0.0646291 0.0116188 -0.00246924 0.0629447 0.997946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1056 1057 -0.732306 12.179 0.0567514 0.00753238 0.00690567 0.0597927 0.998159 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1057 1058 -0.744993 12.1516 0.0379349 0.0170746 0.000129501 0.0539368 0.998398 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1058 1059 -0.726068 12.1979 0.0398813 0.00770023 -0.00400309 0.062849 0.997985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1059 1060 -0.731459 12.1835 0.0624819 0.0171089 0.00342299 0.0623921 0.997899 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1060 1061 -0.749471 12.1986 0.0688904 0.0131321 0.000836535 0.0577912 0.998242 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1061 1062 -0.749362 12.1686 0.0527375 0.0144778 0.00213148 0.0533483 0.998469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1062 1063 -0.752548 12.1887 0.0573135 0.0227732 -0.006852 0.0616204 0.997816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1063 1064 -0.751018 12.2019 0.0371619 0.00846322 -0.0160026 0.0631609 0.997839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1064 1065 -0.731816 12.1771 0.0523264 0.0135387 0.012317 0.0608997 0.997976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1065 1066 -0.74593 12.2003 0.0598888 0.0228499 0.00240209 0.0613185 0.997854 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1066 1067 -0.744874 12.2119 0.0354209 0.00674909 0.00780247 0.0619082 0.998029 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1067 1068 -0.753348 12.1963 0.0268876 0.00372606 0.000193089 0.0567149 0.998383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1068 1069 -0.75278 12.1879 0.0527477 0.0138981 -0.00469028 0.0684602 0.997546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1069 1070 -0.738677 12.2149 0.0358241 0.0203487 -0.00557728 0.060908 0.99792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1070 1071 -0.755265 12.2225 0.0594495 0.0168448 0.0047933 0.0563433 0.998258 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1071 1072 -0.764349 12.2217 0.0372558 0.00900914 0.00286915 0.0669065 0.997714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1072 1073 -0.753927 12.2319 0.039937 0.0161482 0.00910134 0.0541393 0.998361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1073 1074 -0.75707 12.2122 0.0205097 0.0170335 -0.000763465 0.0631625 0.997858 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1074 1075 -0.742588 12.2258 0.0296761 0.0160221 0.0134508 0.0594431 0.998012 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1075 1076 -0.751054 12.2487 0.0371819 0.0129202 0.00385246 0.0605585 0.998074 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1076 1077 -0.771423 12.2493 0.0418931 0.0181779 -0.00141835 0.0694975 0.997415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1077 1078 -0.745536 12.2405 0.0408749 0.0153151 0.00770096 0.0622714 0.997912 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1078 1079 -0.76048 12.2501 0.0319402 0.0200808 0.0014895 0.0638009 0.997759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1079 1080 -0.742625 12.2507 0.0426496 0.00570729 -0.00407872 0.0617193 0.998069 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1080 1081 -0.754337 12.2573 0.0214441 0.0138286 0.00869512 0.0544621 0.998382 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1081 1082 -0.753294 12.2634 0.0291691 0.0185883 -0.000512991 0.0594858 0.998056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1082 1083 -0.762061 12.2608 0.0299896 0.0192457 0.00178898 0.0673414 0.997543 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1083 1084 -0.755542 12.288 0.019568 0.0209124 -0.0154042 0.0645676 0.997575 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1084 1085 -0.749495 12.2453 0.0196613 0.00491541 -0.00131049 0.0612587 0.998109 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1085 1086 -0.76595 12.2638 0.0211821 0.0157722 0.00162201 0.0710417 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1086 1087 -0.768127 12.2753 0.0271711 0.0235843 -0.000464852 0.0530452 0.998313 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1087 1088 -0.754569 12.273 0.00962124 0.0111084 0.00148447 0.0642863 0.997869 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1088 1089 -0.764454 12.2717 0.0282816 0.0222156 0.00668117 0.0788951 0.996613 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1089 1090 -0.762864 12.2993 0.0389771 0.0184958 -0.00495318 0.0570134 0.99819 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1090 1091 -0.753812 12.2643 0.0224566 0.00946755 -0.00440674 0.0606196 0.998106 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1091 1092 -0.743951 12.2968 0.0222203 0.0096891 0.00161596 0.0567679 0.998339 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1092 1093 -0.763732 12.2839 0.00404055 0.00613488 0.0095536 0.0557264 0.998382 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1093 1094 -0.757854 12.292 0.0473633 0.0171776 0.00343316 0.0615137 0.997953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1094 1095 -0.747288 12.2899 0.0257748 0.0124269 0.00897769 0.0644931 0.9978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1095 1096 -0.75651 12.3122 0.0433406 0.0116384 0.00801438 0.0535272 0.998466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1096 1097 -0.754426 12.3022 0.0182787 0.00786519 -0.00338967 0.0694765 0.997547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1097 1098 -0.766474 12.3204 0.0227099 0.0109481 0.00405037 0.0617014 0.998026 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1098 1099 -0.745167 12.3144 0.0179897 0.0125001 0.0119314 0.0575123 0.998195 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1099 1100 -0.762398 12.3027 0.0420076 0.0134907 -0.00602696 0.0601449 0.99808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1100 1101 -0.760488 12.3202 0.0167804 0.0122083 0.00288741 0.0613575 0.998037 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1101 1102 -0.757463 12.3255 0.0480788 0.0123006 -3.46687e-05 0.0611464 0.998053 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1102 1103 -0.740538 12.3169 0.0225058 0.0111453 -0.00503636 0.0717462 0.997348 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1103 1104 -0.757752 12.3329 0.0205341 0.00620476 -0.00185669 0.0578731 0.998303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1104 1105 -0.764305 12.3408 0.0295506 0.0176781 0.00509298 0.0571661 0.998195 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1105 1106 -0.771391 12.333 0.0160814 0.0102221 0.00522583 0.0656606 0.997776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1106 1107 -0.770666 12.3317 -0.00170115 0.0112353 -0.00593243 0.0646294 0.997828 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1107 1108 -0.770244 12.3445 0.0171467 0.012264 0.00350642 0.0652694 0.997786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1108 1109 -0.758399 12.3375 0.0183289 0.0195491 0.000415208 0.0609797 0.997947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1109 1110 -0.76809 12.3578 0.00787759 0.0165138 0.00128584 0.0584999 0.99815 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1110 1111 -0.760529 12.3492 0.0113791 0.0155096 -0.00276595 0.0547356 0.998377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1111 1112 -0.771014 12.3721 0.000843768 0.0280692 8.98149e-05 0.0699438 0.997156 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1112 1113 -0.766113 12.3523 -0.00763998 0.00388491 0.00566788 0.0629769 0.997991 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1113 1114 -0.753207 12.3558 -0.00165031 0.0154536 0.00640801 0.063272 0.997856 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1114 1115 -0.756099 12.3631 0.0118292 0.0108207 -0.00307644 0.0662692 0.997738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1115 1116 -0.748972 12.3439 -0.00632515 0.0131554 -0.00118511 0.0642352 0.997847 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1116 1117 -0.762575 12.3631 0.0026364 0.0106402 -0.00137023 0.0582856 0.998242 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1117 1118 -0.758545 12.3521 -0.0140609 0.0126842 0.00630293 0.052608 0.998515 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1118 1119 -0.768544 12.3743 0.00222674 0.00677527 0.00161217 0.0562125 0.998395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1119 1120 -0.7603 12.3643 0.00461806 0.00401007 0.00835719 0.0597273 0.998172 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1120 1121 -0.764735 12.3711 -0.0140017 0.0174714 0.00213568 0.0666802 0.997619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1121 1122 -0.780338 12.3817 -0.0153886 0.00158871 -0.000854677 0.0645285 0.997914 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1122 1123 -0.766923 12.3657 0.00297089 0.0140763 4.73603e-05 0.0474065 0.998776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1123 1124 -0.787759 12.3856 -0.0238475 0.0145822 0.0147167 0.0632821 0.997781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1124 1125 -0.770476 12.3783 -0.00690586 0.0144102 0.00387951 0.0518321 0.998544 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1125 1126 -0.773965 12.3928 -0.0161413 0.0109675 -0.00377393 0.0624593 0.99798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1126 1127 -0.768556 12.3895 -0.00818623 0.0195359 0.00139218 0.0694975 0.99739 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1127 1128 -0.773645 12.3578 -0.0105833 0.00687743 -0.0055512 0.0609353 0.998103 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1128 1129 -0.757983 12.3822 -0.0141519 0.00553791 0.00237837 0.0624984 0.998027 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1129 1130 -0.745444 12.4018 -0.000318917 0.0187501 -0.00574223 0.0525245 0.998427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1130 1131 -0.773353 12.4087 -0.0108536 0.00967441 0.0102815 0.0573022 0.998257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1131 1132 -0.764003 12.3997 -0.0116368 0.0118642 0.0016089 0.067507 0.997647 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1132 1133 -0.776478 12.3892 -0.00532756 0.0173548 0.00557892 0.0580699 0.998146 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1133 1134 -0.775082 12.3911 -0.00675443 0.0138481 -0.00166165 0.067916 0.997594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1134 1135 -0.789515 12.388 -0.00789782 0.00813001 0.00286008 0.0658007 0.997796 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1135 1136 -0.763389 12.421 -0.0111065 0.0121894 0.001712 0.062319 0.99798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1136 1137 -0.779804 12.4244 -0.0200053 0.013516 0.00218514 0.0683284 0.997569 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1137 1138 -0.772265 12.3819 -0.00718411 0.0147134 -0.00353474 0.0600184 0.998083 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1138 1139 -0.766102 12.4072 -0.0145221 0.0107188 -0.00226018 0.0606249 0.998101 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1139 1140 -0.786418 12.4254 -0.00466209 0.00590361 0.00307905 0.0587718 0.998249 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1140 1141 -0.780332 12.4243 -0.0245644 0.0111887 0.00183115 0.0606019 0.998098 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1141 1142 -0.77677 12.4253 -0.0143261 0.0123596 -0.00219008 0.0581819 0.998227 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1142 1143 -0.785185 12.4257 -0.0239652 0.0161624 0.00670241 0.0714623 0.99729 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1143 1144 -0.772599 12.4188 -0.0197102 0.00936538 0.003983 0.0665055 0.997734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1144 1145 -0.763528 12.4172 -0.0297048 0.00953518 0.00333163 0.0719193 0.997359 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1145 1146 -0.782115 12.4281 -0.0275313 0.0136782 -0.00517261 0.0604482 0.998064 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1146 1147 -0.772421 12.4485 -0.0272697 0.00162156 0.000771827 0.0557222 0.998445 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1147 1148 -0.762722 12.426 -0.0281338 0.00206145 0.0019417 0.0633851 0.997985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1148 1149 -0.785931 12.4285 -0.0287965 0.00893823 -0.00486896 0.0684183 0.997605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1149 1150 -0.788773 12.4441 -0.022307 -0.00409856 0.00655546 0.0616183 0.99807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1150 1151 -0.772982 12.4355 -0.0187141 0.00660508 0.00113332 0.0571225 0.998345 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1151 1152 -0.780379 12.4262 -0.0164282 0.00123574 0.011674 0.0546482 0.998437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1152 1153 -0.765038 12.4382 -0.0218673 0.00495969 0.00506338 0.0655487 0.997824 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1153 1154 -0.781054 12.4421 -0.0270444 0.00123348 0.000435227 0.06106 0.998133 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1154 1155 -0.776945 12.4394 -0.0263749 0.011659 -0.006411 0.0575323 0.998255 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1155 1156 -0.786319 12.4313 -0.0305926 0.0111351 -0.000777003 0.0679062 0.997629 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1156 1157 -0.786355 12.4384 -0.0354336 -0.00409465 0.00454435 0.0564486 0.998387 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1157 1158 -0.780784 12.4454 -0.0417213 0.0221389 0.00121784 0.0521852 0.998391 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1158 1159 -0.768318 12.469 -0.0423913 0.00136667 0.00556509 0.0586638 0.998261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1159 1160 -0.763322 12.4544 -0.0243667 0.019519 0.00408663 0.0628484 0.997824 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1160 1161 -0.772487 12.4745 -0.0412268 0.0111568 0.00486693 0.0701199 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1161 1162 -0.770544 12.4684 -0.0373382 0.00172604 0.00850818 0.0581247 0.998272 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1162 1163 -0.767618 12.4654 -0.0479927 0.00465192 0.00626773 0.0655382 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1163 1164 -0.792896 12.4623 -0.0365476 -4.01036e-05 -0.00281562 0.0630687 0.998005 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1164 1165 -0.769489 12.4644 -0.0521821 0.0129323 0.000299037 0.065023 0.9978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1165 1166 -0.773964 12.4498 -0.0344675 0.00691192 0.00559195 0.0539123 0.998506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1166 1167 -0.797816 12.4649 -0.0459437 0.00931054 -0.00163425 0.062032 0.998029 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1167 1168 -0.785428 12.4611 -0.0395887 0.000696004 -0.00913844 0.0620649 0.99803 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1168 1169 -0.782938 12.4734 -0.0418327 0.00801929 0.0018116 0.0652368 0.997836 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1169 1170 -0.805774 12.4724 -0.0543865 0.0092066 0.010649 0.0680151 0.997585 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1170 1171 -0.789009 12.4698 -0.0407372 0.00878041 0.0126144 0.0627991 0.997908 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1171 1172 -0.767267 12.4732 -0.0645307 0.00472422 0.00853566 0.0636058 0.997927 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1172 1173 -0.77234 12.4748 -0.0518574 0.00598539 0.00604636 0.0647927 0.997862 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1173 1174 -0.77335 12.4833 -0.0492931 0.00651837 -0.0055323 0.0607951 0.998114 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1174 1175 -0.773232 12.4711 -0.0514208 0.00684103 0.00746195 0.0651393 0.997825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1175 1176 -0.788991 12.4723 -0.0384503 0.00945475 0.00958477 0.060982 0.998048 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1176 1177 -0.774184 12.4857 -0.060776 0.00129283 -0.00647152 0.0659861 0.997799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1177 1178 -0.770858 12.4682 -0.0609744 -0.00306418 -0.0045479 0.0690831 0.997596 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1178 1179 -0.779969 12.4845 -0.0506708 0.00333119 0.0024807 0.0624569 0.998039 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1179 1180 -0.788709 12.4582 -0.0477141 0.008255 0.00286003 0.059351 0.998199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1180 1181 -0.768581 12.4911 -0.0632395 0.000949094 0.00144249 0.0673262 0.99773 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1181 1182 -0.783379 12.4945 -0.0451658 0.000718561 -0.00128668 0.0656226 0.997843 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1182 1183 -0.784531 12.4889 -0.0630523 0.00399164 0.00884142 0.0618488 0.998038 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1183 1184 -0.775773 12.4963 -0.071412 0.0038201 0.0037568 0.0713721 0.997435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1184 1185 -0.778161 12.4946 -0.0572605 0.00608789 0.0117833 0.0630818 0.99792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1185 1186 -0.777385 12.4984 -0.0740532 0.000619977 0.0162806 0.0599798 0.998067 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1186 1187 -0.763762 12.5018 -0.0738027 0.0106347 0.00887323 0.0643629 0.99783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1187 1188 -0.790627 12.505 -0.063274 -0.000576314 -0.00308575 0.0698671 0.997551 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1188 1189 -0.790883 12.51 -0.0701814 0.00398087 0.00288452 0.0647689 0.997888 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1189 1190 -0.7815 12.4947 -0.0773043 0.00611482 0.0123741 0.0594421 0.998136 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1190 1191 -0.780653 12.4848 -0.0773691 0.0108773 0.00486209 0.0711137 0.997397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1191 1192 -0.795912 12.4987 -0.0619135 0.00163616 -0.00235299 0.065664 0.997838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1192 1193 -0.781248 12.5089 -0.0816067 0.00029352 -0.0039583 0.067289 0.997726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1193 1194 -0.765496 12.5012 -0.0710074 0.00689507 -0.0114483 0.0629954 0.997924 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1194 1195 -0.787785 12.498 -0.0664038 0.010993 0.005608 0.068271 0.99759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1195 1196 -0.780308 12.5028 -0.074639 0.000741427 -0.00335009 0.0582424 0.998297 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1196 1197 -0.785825 12.5024 -0.0665022 0.00630907 0.00936162 0.0565633 0.998335 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1197 1198 -0.79656 12.5107 -0.079633 0.00476509 0.00867904 0.0610924 0.998083 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1198 1199 -0.776716 12.5152 -0.066429 -0.00477062 -0.00277151 0.0628697 0.998006 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1199 1200 -0.793291 12.5064 -0.0629236 8.02584e-05 -2.84012e-05 0.0645401 0.997915 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1200 1201 -0.777012 12.5014 -0.0769646 0.00987281 -0.00153696 0.0597427 0.998164 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1201 1202 -0.784729 12.5265 -0.0853117 0.00667324 -0.00832656 0.0593658 0.998179 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1202 1203 -0.773937 12.5048 -0.0706934 0.00646531 0.0118906 0.0637818 0.997872 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1203 1204 -0.769186 12.5134 -0.061565 0.00489985 -0.00371532 0.0647941 0.99788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1204 1205 -0.770348 12.4967 -0.0860174 0.00508203 -0.00123786 0.0670523 0.997736 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1205 1206 -0.794675 12.5145 -0.0729153 0.00279532 -0.00434839 0.0541386 0.99852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1206 1207 -0.794593 12.4863 -0.0731457 0.00259243 -0.00641428 0.0586365 0.998255 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1207 1208 -0.765034 12.5187 -0.0832656 0.0111567 -0.00175066 0.0650546 0.997818 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1208 1209 -0.787378 12.531 -0.0667636 0.000208041 -0.000623295 0.0630707 0.998009 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1209 1210 -0.796926 12.5278 -0.060818 0.00401828 -0.00345375 0.0623366 0.998041 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1210 1211 -0.806621 12.512 -0.0829674 0.00343729 -0.00414198 0.067646 0.997695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1211 1212 -0.770255 12.5191 -0.0887023 0.00167539 -0.0133153 0.0692009 0.997512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1212 1213 -0.781834 12.5228 -0.0874867 -0.000934895 0.00704296 0.0556434 0.998425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1213 1214 -0.771007 12.5161 -0.0799074 0.00616284 -0.00820309 0.0736712 0.99723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1214 1215 -0.796208 12.5024 -0.104773 0.00219814 0.00171562 0.0681845 0.997669 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1215 1216 -0.777844 12.5223 -0.0881628 -0.00213142 -0.00672532 0.0655837 0.997822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1216 1217 -0.775041 12.5155 -0.092054 0.00940665 -0.000868685 0.054177 0.998487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1217 1218 -0.790577 12.5329 -0.093737 0.00150085 0.000461484 0.0641785 0.997937 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1218 1219 -0.789198 12.5316 -0.097574 -0.00330481 -0.00289634 0.0617214 0.998084 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1219 1220 -0.799426 12.5244 -0.108108 -0.00074184 -0.00485002 0.0621684 0.998054 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1220 1221 -0.780166 12.5232 -0.0942062 -0.00474073 -0.000647777 0.0583908 0.998282 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1221 1222 -0.81524 12.5242 -0.11925 -0.0102286 -0.00951358 0.0665602 0.997685 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1222 1223 -0.804001 12.5207 -0.092344 0.00677107 -0.00867146 0.0609878 0.998078 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1223 1224 -0.788857 12.5212 -0.07934 0.00889959 -0.00154777 0.0588196 0.998228 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1224 1225 -0.780455 12.5296 -0.0874852 0.000827099 -0.0040129 0.062972 0.998007 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1225 1226 -0.775771 12.5207 -0.0972589 0.00915961 0.00918639 0.0524776 0.998538 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1226 1227 -0.78922 12.5234 -0.104926 -0.00108182 -0.000375768 0.0692469 0.997599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1227 1228 -0.77757 12.5045 -0.109187 0.000156513 0.0025239 0.0614227 0.998109 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1228 1229 -0.792001 12.5224 -0.116479 -0.00379938 0.00575152 0.0558988 0.998413 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1229 1230 -0.788531 12.5158 -0.102621 0.00135717 0.0016384 0.0734914 0.997294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1230 1231 -0.761028 12.5509 -0.0837961 0.00940957 0.00131385 0.0653283 0.997819 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1231 1232 -0.788155 12.5168 -0.114431 0.00728347 -0.000695222 0.0655593 0.997822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1232 1233 -0.794577 12.516 -0.109865 -0.0115907 0.00215566 0.0622871 0.997989 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1233 1234 -0.778449 12.5312 -0.107716 0.00210408 0.00662328 0.0616082 0.998076 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1234 1235 -0.791776 12.5384 -0.100888 0.0104808 -0.0018171 0.0583826 0.998238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1235 1236 -0.784452 12.5304 -0.111379 0.00113295 -0.000236411 0.065625 0.997844 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1236 1237 -0.79685 12.5277 -0.124544 -0.00209063 0.00342983 0.064007 0.997941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1237 1238 -0.796757 12.5386 -0.113237 0.00138515 0.00388669 0.0574548 0.99834 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1238 1239 -0.792665 12.5379 -0.111477 0.00122686 0.00171375 0.0612511 0.99812 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1239 1240 -0.779806 12.5398 -0.118222 -0.000148338 0.00219102 0.0603005 0.998178 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1240 1241 -0.802044 12.5291 -0.106961 -0.00104883 -0.000458244 0.0550316 0.998484 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1241 1242 -0.796256 12.5169 -0.10835 -0.00139081 0.00187333 0.0723295 0.997378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1242 1243 -0.772404 12.5433 -0.142196 -0.00582369 -0.00503553 0.0747579 0.997172 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1243 1244 -0.777032 12.5245 -0.100592 -0.000336806 0.00598284 0.0700806 0.997523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1244 1245 -0.795294 12.5351 -0.111298 0.00405978 0.000509743 0.0601807 0.998179 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1245 1246 -0.783338 12.5429 -0.104079 -0.00143068 0.00128528 0.0698901 0.997553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1246 1247 -0.786442 12.5417 -0.124456 0.00827148 -0.00238365 0.0696611 0.997534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1247 1248 -0.793855 12.524 -0.131463 0.000404895 0.000377431 0.0713647 0.99745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1248 1249 -0.787161 12.5325 -0.146181 0.00146904 0.00485331 0.0580578 0.9983 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1249 1250 -0.791119 12.5355 -0.132948 -0.0028792 0.000622037 0.0634468 0.997981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1250 1251 -0.782445 12.5544 -0.116967 -0.0085646 -0.000753974 0.072197 0.997353 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1251 1252 -0.780993 12.5246 -0.118508 -0.00883063 -0.000938751 0.051783 0.998619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1252 1253 -0.798756 12.5434 -0.118831 -0.00315536 -0.00874919 0.0609546 0.998097 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1253 1254 -0.788151 12.5265 -0.126086 -0.000197042 -0.000251485 0.0563721 0.99841 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1254 1255 -0.788168 12.5388 -0.124823 0.0124598 0.00407587 0.0586825 0.998191 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1255 1256 -0.79583 12.5371 -0.119881 0.00602576 0.00638835 0.063638 0.997934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1256 1257 -0.774958 12.5478 -0.146945 0.00498582 -0.000776978 0.0628309 0.998011 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1257 1258 -0.785475 12.5453 -0.127088 0.00465803 0.0068773 0.0636987 0.997935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1258 1259 -0.780805 12.5436 -0.141909 -0.00206789 -0.00295825 0.0599902 0.998192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1259 1260 -0.785404 12.5489 -0.143656 -0.00281985 0.0122342 0.0676043 0.997633 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1260 1261 -0.788786 12.5213 -0.127938 -0.00345675 -0.00243665 0.0619864 0.998068 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1261 1262 -0.798488 12.5383 -0.161184 0.000939538 -0.00552139 0.0747425 0.997187 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1262 1263 -0.792674 12.5421 -0.136924 0.015212 0.00439869 0.0525026 0.998495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1263 1264 -0.792536 12.5456 -0.140097 -0.00384131 0.0016963 0.0657515 0.997827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1264 1265 -0.779771 12.5277 -0.116443 -0.000697791 -0.000931092 0.0735539 0.997291 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1265 1266 -0.805521 12.5135 -0.148026 0.00218688 0.00204885 0.0610473 0.99813 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1266 1267 -0.779036 12.5043 -0.13067 -0.00297339 -0.00117495 0.0544743 0.99851 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1267 1268 -0.776445 12.5298 -0.141333 -0.00322305 -0.00424986 0.0626072 0.998024 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1268 1269 -0.79191 12.5329 -0.135442 -0.00394119 0.00237574 0.0666883 0.997763 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1269 1270 -0.785035 12.5318 -0.161193 -0.00734972 -0.00240203 0.0646585 0.997877 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1270 1271 -0.783869 12.5415 -0.14406 0.00302939 -0.0121268 0.0670582 0.997671 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1271 1272 -0.785043 12.533 -0.136072 6.69537e-05 -0.00571961 0.067372 0.997712 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1272 1273 -0.784968 12.5185 -0.149286 0.00874315 -0.00103922 0.0657281 0.997799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1273 1274 -0.798555 12.5366 -0.15046 -0.00149171 -0.00440745 0.0552133 0.998464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1274 1275 -0.803354 12.5213 -0.155011 -0.0115102 0.00307582 0.0616076 0.998029 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1275 1276 -0.787571 12.5521 -0.140389 -0.00265687 0.00806678 0.0574653 0.998311 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1276 1277 -0.776664 12.5173 -0.152559 0.000577795 -0.00429476 0.0618382 0.998077 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1277 1278 -0.793467 12.5297 -0.160577 0.0015841 -0.00786567 0.0560705 0.998395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1278 1279 -0.778258 12.5275 -0.16522 -0.00620755 -0.00335116 0.0623566 0.998029 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1279 1280 -0.783705 12.5183 -0.165773 -0.00870803 -0.00237011 0.0547141 0.998461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1280 1281 -0.778007 12.5322 -0.137934 0.00343232 -0.000194394 0.0761678 0.997089 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1281 1282 -0.781501 12.5231 -0.149361 -0.00102857 -0.000888302 0.074659 0.997208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1282 1283 -0.789497 12.5022 -0.135513 -0.00465838 -0.00736073 0.0626515 0.997997 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1283 1284 -0.776248 12.5306 -0.161736 -0.00652346 0.00652854 0.0563539 0.998368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1284 1285 -0.7723 12.5329 -0.172265 0.00305921 -0.00466639 0.067524 0.997702 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1285 1286 -0.78287 12.5151 -0.160262 -0.00816804 0.00644157 0.0611587 0.998074 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1286 1287 -0.807265 12.532 -0.149999 -0.00527912 0.0044488 0.0685603 0.997623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1287 1288 -0.789789 12.5211 -0.169436 0.00124324 0.00760586 0.0589671 0.99823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1288 1289 -0.784197 12.526 -0.171086 -0.0111328 0.00278089 0.0590433 0.998189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1289 1290 -0.782848 12.5127 -0.179016 -0.00103979 0.00118095 0.0647117 0.997903 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1290 1291 -0.798133 12.533 -0.160506 -0.0106572 -0.0110729 0.0671195 0.997627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1291 1292 -0.797408 12.5311 -0.167335 -0.00392559 -0.000921148 0.0693112 0.997587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1292 1293 -0.796064 12.5091 -0.179997 -0.00151516 0.00592551 0.0664118 0.997774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1293 1294 -0.792595 12.5133 -0.166121 -0.00401535 0.00579001 0.0564387 0.998381 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1294 1295 -0.776239 12.5248 -0.177642 -0.00284288 -0.00615327 0.0642346 0.997912 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1295 1296 -0.772791 12.5289 -0.15755 -0.00554006 0.000469603 0.069426 0.997572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1296 1297 -0.804124 12.5018 -0.166564 0.00274944 -0.00011449 0.0631802 0.997998 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1297 1298 -0.784939 12.5026 -0.170337 -0.00781969 0.0124091 0.0680681 0.997573 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1298 1299 -0.795859 12.5104 -0.190337 -0.000607482 -0.000607982 0.0606578 0.998158 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1299 1300 -0.794544 12.5165 -0.178999 -0.00389688 0.00216092 0.0708993 0.997474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1300 1301 -0.772258 12.5032 -0.175771 -0.00792993 0.011331 0.0620254 0.997979 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1301 1302 -0.78421 12.5073 -0.16411 -0.0114125 -0.00569252 0.0635711 0.997896 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1302 1303 -0.77965 12.5168 -0.182863 0.00397307 0.000108657 0.0584925 0.99828 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1303 1304 -0.77276 12.5036 -0.194395 -0.00160222 -0.00718415 0.0564359 0.998379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1304 1305 -0.786727 12.5085 -0.186184 -0.00228068 0.0105973 0.0675501 0.997657 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1305 1306 -0.789086 12.4937 -0.193756 -0.00353135 0.00194709 0.0625147 0.998036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1306 1307 -0.787657 12.4966 -0.189104 -0.00772453 -0.00484917 0.0628602 0.997981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1307 1308 -0.790572 12.4944 -0.190847 -0.004916 -0.000975358 0.0620655 0.998059 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1308 1309 -0.768902 12.5045 -0.199718 -0.0098048 0.00465355 0.0678702 0.997635 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1309 1310 -0.770218 12.4758 -0.17689 -0.00752783 -0.000519681 0.068058 0.997653 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1310 1311 -0.763369 12.4981 -0.180384 -0.00745486 -0.000334875 0.0615703 0.998075 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1311 1312 -0.775329 12.4837 -0.180333 -0.00261907 -0.00484645 0.0578595 0.99831 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1312 1313 -0.782664 12.4744 -0.181942 0.00590403 -0.00324764 0.0601314 0.998168 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1313 1314 -0.794969 12.4824 -0.181163 -0.0079556 -0.00158046 0.0555534 0.998423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1314 1315 -0.757799 12.4915 -0.186316 -0.00567529 0.00180143 0.0669591 0.997738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1315 1316 -0.781557 12.496 -0.21254 -0.00718407 0.00402543 0.0664711 0.997754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1316 1317 -0.786895 12.4966 -0.18458 -0.0104025 0.000561749 0.0651639 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1317 1318 -0.781051 12.4902 -0.197609 -0.0122302 -0.00124835 0.0609629 0.998064 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1318 1319 -0.774226 12.4876 -0.185092 -0.00383999 -0.00450359 0.0651993 0.997855 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1319 1320 -0.776617 12.4798 -0.198118 0.00253426 -6.72857e-05 0.0611473 0.998126 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1320 1321 -0.769643 12.4828 -0.197801 -0.00387297 -0.00413185 0.0608907 0.998128 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1321 1322 -0.779872 12.4781 -0.205185 -0.00590171 0.000780502 0.0679646 0.99767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1322 1323 -0.786879 12.4681 -0.19276 -0.00591642 -0.00150955 0.0549612 0.99847 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1323 1324 -0.773441 12.4775 -0.191812 -0.0151884 0.00226964 0.0653053 0.997747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1324 1325 -0.778975 12.4662 -0.20043 -0.00413048 -0.00489455 0.0644936 0.997898 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1325 1326 -0.783025 12.4914 -0.199096 -2.38494e-05 0.00138158 0.0713113 0.997453 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1326 1327 -0.788757 12.4877 -0.20519 0.00479669 -0.00348077 0.0593469 0.99822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1327 1328 -0.77061 12.4651 -0.205784 -0.01041 -0.00774875 0.0583108 0.998214 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1328 1329 -0.785617 12.4627 -0.199122 -0.00412122 -0.00228422 0.0561554 0.998411 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1329 1330 -0.773366 12.4712 -0.198277 -0.00854493 -0.00112035 0.0598967 0.998167 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1330 1331 -0.784237 12.4669 -0.217659 -0.0128776 0.00137422 0.0716594 0.997345 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1331 1332 -0.793846 12.456 -0.215245 -0.0122211 0.00136299 0.0662404 0.997728 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1332 1333 -0.789834 12.4608 -0.199495 0.00241557 -0.00234208 0.0637504 0.99796 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1333 1334 -0.759573 12.4657 -0.206312 -0.00924012 0.00789885 0.0643043 0.997856 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1334 1335 -0.78347 12.4588 -0.21284 -0.0113724 0.00374525 0.0614386 0.998039 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1335 1336 -0.77462 12.4479 -0.222526 -0.0117007 0.00315766 0.0642446 0.997861 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1336 1337 -0.784377 12.4661 -0.20965 -0.00266498 0.00526612 0.063246 0.997981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1337 1338 -0.777749 12.4501 -0.217902 -0.0120403 0.00149509 0.0605903 0.998089 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1338 1339 -0.782043 12.4547 -0.186921 -0.00511936 -0.00716843 0.0598372 0.998169 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1339 1340 -0.774057 12.4668 -0.223814 -0.0102647 0.00685895 0.0616528 0.998021 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1340 1341 -0.769462 12.4651 -0.214085 -0.00953237 -0.00530748 0.0560366 0.998369 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1341 1342 -0.782151 12.4356 -0.230183 -0.000709253 0.00262267 0.0579122 0.998318 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1342 1343 -0.782389 12.4551 -0.208872 -0.00776426 0.00157479 0.055065 0.998451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1343 1344 -0.790516 12.4428 -0.229433 -0.00925627 0.00457448 0.0631 0.997954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1344 1345 -0.78326 12.4456 -0.221857 0.000758933 0.00549733 0.0685548 0.997632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1345 1346 -0.778694 12.4363 -0.219453 -0.00577236 -0.00363353 0.0623364 0.998032 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1346 1347 -0.773554 12.4303 -0.206824 -0.00807245 0.000930047 0.0706217 0.99747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1347 1348 -0.783917 12.4257 -0.223869 -0.00596468 0.00231818 0.0634934 0.997962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1348 1349 -0.778092 12.4221 -0.230803 -0.00279347 -0.00237185 0.072785 0.997341 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1349 1350 -0.766386 12.4124 -0.221502 -0.00536352 -0.0123148 0.0550087 0.998396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1350 1351 -0.762355 12.4183 -0.228275 -0.00717187 -0.00257985 0.067625 0.997682 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1351 1352 -0.789265 12.4087 -0.236048 -0.00877153 -0.00876878 0.0669437 0.99768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1352 1353 -0.785426 12.4082 -0.225409 -0.00433274 -0.00317144 0.0628482 0.998009 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1353 1354 -0.796739 12.4367 -0.231591 -0.0024603 -0.00108182 0.0583364 0.998293 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1354 1355 -0.780116 12.4187 -0.225261 -0.00755357 0.00523087 0.0755763 0.997098 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1355 1356 -0.793755 12.4201 -0.229511 -0.00394304 0.00622379 0.0653756 0.997834 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1356 1357 -0.776339 12.412 -0.230935 -0.00823737 0.000379292 0.0635074 0.997947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1357 1358 -0.772035 12.4108 -0.224951 -0.00919834 -0.00318857 0.0652658 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1358 1359 -0.768076 12.4156 -0.233237 -0.0157053 0.000611662 0.0614684 0.997985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1359 1360 -0.770057 12.4143 -0.220955 -0.00233169 -0.00181042 0.0650916 0.997875 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1360 1361 -0.782169 12.419 -0.212262 -0.0111223 0.0048051 0.0646675 0.997833 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1361 1362 -0.788129 12.4048 -0.24324 -0.00480766 0.00266832 0.0623308 0.99804 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1362 1363 -0.773074 12.397 -0.239966 -0.0151958 0.00323026 0.0620228 0.997954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1363 1364 -0.785753 12.4187 -0.239374 -0.00660639 -0.0122222 0.0567496 0.998292 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1364 1365 -0.767644 12.4193 -0.242545 -0.00507982 0.00267365 0.0650654 0.997864 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1365 1366 -0.780674 12.4116 -0.242284 -0.0082939 -0.00365546 0.0595924 0.998182 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1366 1367 -0.754012 12.386 -0.251685 -0.0103858 0.010831 0.0654187 0.997745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1367 1368 -0.764302 12.3994 -0.230971 -0.0135837 -0.00485726 0.0612994 0.998015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1368 1369 -0.785163 12.3783 -0.249017 -0.0117603 0.00284495 0.0624326 0.997976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1369 1370 -0.756346 12.4007 -0.248308 -0.00576604 -0.00560975 0.0626926 0.998 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1370 1371 -0.781902 12.3702 -0.236544 -0.011702 0.000830627 0.0608075 0.998081 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1371 1372 -0.765284 12.3881 -0.239764 -0.00670068 0.00386616 0.0599162 0.998173 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1372 1373 -0.774059 12.4072 -0.257488 -0.0140767 -0.00730916 0.0511245 0.998566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1373 1374 -0.783763 12.3981 -0.239379 0.00314637 0.00687593 0.065701 0.997811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1374 1375 -0.770665 12.3563 -0.245039 -0.011259 0.00238231 0.0623464 0.997988 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1375 1376 -0.765607 12.3706 -0.246901 -0.00843054 0.0085907 0.0502192 0.998666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1376 1377 -0.756118 12.364 -0.257401 -0.0167395 0.00459009 0.066464 0.997638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1377 1378 -0.768083 12.3876 -0.249821 -0.0144248 0.000945912 0.0610422 0.998031 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1378 1379 -0.768659 12.3595 -0.224049 -0.00558523 -0.00326732 0.0668997 0.997739 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1379 1380 -0.771891 12.3733 -0.252706 -0.00576395 0.00149179 0.0562974 0.998396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1380 1381 -0.763435 12.3502 -0.25646 -0.0101113 -0.000928085 0.0665763 0.99773 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1381 1382 -0.766861 12.3482 -0.243212 -0.00826915 -0.0055841 0.0680965 0.997629 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1382 1383 -0.772095 12.3555 -0.250244 -0.0134643 -0.00306843 0.0685699 0.997551 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1383 1384 -0.762898 12.3368 -0.24424 -0.0140458 -0.00301877 0.0612722 0.998018 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1384 1385 -0.770672 12.3675 -0.241518 -0.00875249 0.0102426 0.0606873 0.998066 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1385 1386 -0.767608 12.3233 -0.247362 0.000282413 0.00356413 0.0615328 0.998099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1386 1387 -0.756058 12.3295 -0.260272 -0.0100884 -0.00671781 0.0641092 0.997869 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1387 1388 -0.76606 12.3488 -0.255396 -0.0118082 -0.00537669 0.0594963 0.998144 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1388 1389 -0.738886 12.3293 -0.256228 -0.00102586 0.0138497 0.0593018 0.998143 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1389 1390 -0.76523 12.3454 -0.289022 -0.00490828 -0.000917345 0.0624312 0.998037 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1390 1391 -0.76424 12.3421 -0.279976 -0.0205227 0.000696189 0.0529206 0.998388 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1391 1392 -0.771847 12.3287 -0.261736 -0.00442537 -0.00204539 0.0523666 0.998616 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1392 1393 -0.759122 12.3302 -0.265268 -0.0138994 0.00490394 0.0690232 0.997506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1393 1394 -0.769073 12.3274 -0.280382 -0.0134184 -0.0058368 0.0535864 0.998456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1394 1395 -0.768287 12.3177 -0.263968 -0.00671076 0.00735848 0.0608168 0.998099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1395 1396 -0.769797 12.3132 -0.261158 -0.000977713 0.00142547 0.0657384 0.997835 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1396 1397 -0.762246 12.3179 -0.278325 -0.0196611 -0.00221371 0.0613082 0.997923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1397 1398 -0.772722 12.3031 -0.279149 -0.0118856 -0.00819376 0.0660323 0.997713 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1398 1399 -0.776394 12.3275 -0.277792 -0.00911128 0.00206546 0.056938 0.998334 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1399 1400 -0.753449 12.3179 -0.266841 -0.0130368 0.00138352 0.051285 0.998598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1400 1401 -0.75691 12.299 -0.270379 -0.0047616 0.00200417 0.0625606 0.998028 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1401 1402 -0.755005 12.3104 -0.29501 -0.00869269 -0.000207784 0.061018 0.998099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1402 1403 -0.757276 12.3008 -0.275118 -0.0139826 -0.00164375 0.0556773 0.99835 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1403 1404 -0.753862 12.2811 -0.29447 -0.0107878 -0.0080496 0.0566916 0.998301 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1404 1405 -0.761878 12.2917 -0.269948 -0.00855091 -0.0023771 0.0606893 0.998117 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1405 1406 -0.760429 12.3 -0.271907 -0.0176666 0.00460034 0.0624994 0.997878 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1406 1407 -0.753312 12.2909 -0.267152 -0.00474475 0.00538173 0.0560603 0.998402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1407 1408 -0.751195 12.2752 -0.28216 -0.0181869 0.00818375 0.0601825 0.997988 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1408 1409 -0.75487 12.2655 -0.264073 -0.0185741 -0.00190228 0.0643858 0.99775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1409 1410 -0.746173 12.2653 -0.283337 -0.014915 -0.00950052 0.0632149 0.997843 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1410 1411 -0.760884 12.2803 -0.266843 -0.0108031 0.0043663 0.0584687 0.998221 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1411 1412 -0.740964 12.2625 -0.26801 -0.013018 0.00647342 0.0548284 0.99839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1412 1413 -0.754207 12.2578 -0.271065 -0.0185143 -0.00395623 0.0618684 0.997905 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1413 1414 -0.755533 12.2653 -0.287411 -0.0145642 0.00432393 0.0689148 0.997507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1414 1415 -0.754068 12.2603 -0.278747 -0.0200467 -0.0159983 0.0662343 0.997474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1415 1416 -0.736244 12.2588 -0.297037 -0.0134704 -0.00338877 0.0629283 0.997921 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1416 1417 -0.73511 12.234 -0.28733 -0.0174289 0.00208368 0.0569715 0.998221 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1417 1418 -0.753404 12.2412 -0.291183 -0.0120085 0.000235054 0.0634129 0.997915 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1418 1419 -0.75131 12.2431 -0.297711 -0.0200451 -0.000147126 0.0598428 0.998007 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1419 1420 -0.736303 12.25 -0.291715 -0.00960655 -0.0113204 0.0487348 0.998701 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1420 1421 -0.748981 12.2263 -0.302937 -0.0143679 -0.00714813 0.0579063 0.998193 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1421 1422 -0.758382 12.2423 -0.294633 -0.0152528 -0.00676482 0.059634 0.998081 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1422 1423 -0.751191 12.2455 -0.296583 -0.0135892 -0.00394004 0.064929 0.99779 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1423 1424 -0.744084 12.2282 -0.269245 -0.0132839 -0.00436141 0.0605138 0.998069 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1424 1425 -0.749824 12.2248 -0.297847 -0.0172354 -0.00724344 0.0512153 0.998513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1425 1426 -0.756421 12.2066 -0.287174 -0.0122108 0.00464713 0.0594196 0.998148 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1426 1427 -0.743229 12.2412 -0.279716 -0.0130648 0.0136795 0.0633871 0.99781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1427 1428 -0.736264 12.2236 -0.287984 -0.0178911 -0.00814796 0.0667806 0.997574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1428 1429 -0.734963 12.2391 -0.288983 -0.0288326 -0.00454648 0.0520019 0.99822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1429 1430 -0.74263 12.2213 -0.293783 -0.00944491 0.0084284 0.0647487 0.997821 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1430 1431 -0.754667 12.1971 -0.3044 -0.0174513 -0.00214877 0.0554411 0.998307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1431 1432 -0.76349 12.1973 -0.301183 -0.0105982 0.00871178 0.0648982 0.997798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1432 1433 -0.726094 12.203 -0.296579 -0.0144232 -0.00508882 0.0655121 0.997735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1433 1434 -0.765322 12.1935 -0.304837 -0.00910156 0.0106199 0.0623467 0.997957 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1434 1435 -0.743464 12.1891 -0.292005 -0.0170522 0.00672839 0.0701526 0.997368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1435 1436 -0.744505 12.1794 -0.31814 -0.0171662 -0.00234186 0.0704303 0.997366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1436 1437 -0.73395 12.179 -0.315763 -0.0127983 0.00223922 0.0560188 0.998345 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1437 1438 -0.743392 12.1832 -0.308211 -0.0192988 0.00395645 0.0617471 0.997897 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1438 1439 -0.741162 12.1761 -0.295853 -0.0129009 -0.00335802 0.0517309 0.998572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1439 1440 -0.74736 12.149 -0.301594 -0.0124038 -0.000618929 0.0541609 0.998455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1440 1441 -0.741795 12.1822 -0.310216 -0.014214 -0.00191285 0.0656387 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1441 1442 -0.755664 12.1782 -0.308334 -0.00752063 0.00171687 0.0646071 0.997881 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1442 1443 -0.745057 12.1692 -0.326861 -0.0113314 -0.0048457 0.0565856 0.998322 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1443 1444 -0.73381 12.1626 -0.331678 -0.0113897 -0.00355908 0.0609757 0.998068 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1444 1445 -0.728647 12.178 -0.304526 -0.0288009 0.00515783 0.0669313 0.997328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1445 1446 -0.738871 12.1447 -0.29902 -0.0210024 -0.00122924 0.0502977 0.998513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1446 1447 -0.746718 12.1367 -0.321775 -0.0181095 -0.00600744 0.0657943 0.997651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1447 1448 -0.732275 12.1493 -0.302046 -0.0106048 -0.0116893 0.0593872 0.99811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1448 1449 -0.75112 12.149 -0.306902 -0.0128799 0.00111972 0.0584239 0.998208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1449 1450 -0.749325 12.1216 -0.318126 -0.0183057 0.00129897 0.0574246 0.998181 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1450 1451 -0.727838 12.1415 -0.303424 -0.0231838 0.00615857 0.065389 0.997571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1451 1452 -0.733635 12.1117 -0.312766 -0.0259846 -0.00523628 0.0561783 0.998069 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1452 1453 -0.734769 12.1127 -0.321071 -0.0173488 0.00251229 0.0544005 0.998365 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1453 1454 -0.762231 12.1102 -0.321205 -0.0221959 0.00429352 0.063738 0.997711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1454 1455 -0.733372 12.1191 -0.320508 -0.0243461 0.00754665 0.063771 0.997639 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1455 1456 -0.71811 12.1104 -0.315243 -0.0198655 0.00779997 0.0700022 0.997319 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1456 1457 -0.727571 12.1049 -0.319376 -0.0241524 0.0101338 0.0643807 0.997582 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1457 1458 -0.727863 12.0986 -0.316018 -0.0166473 0.00327184 0.0612769 0.997977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1458 1459 -0.728741 12.0909 -0.31475 -0.020889 -0.00575771 0.0545337 0.998277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1459 1460 -0.732578 12.0896 -0.335634 -0.0225407 0.0131906 0.0564277 0.998065 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1460 1461 -0.736151 12.0834 -0.323234 -0.0160428 0.00617176 0.0580072 0.998168 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1461 1462 -0.734697 12.0858 -0.325745 -0.0223334 0.0028519 0.0584631 0.998036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1462 1463 -0.726491 12.0936 -0.339916 -0.0155062 -0.00116642 0.0637843 0.997843 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1463 1464 -0.734279 12.0804 -0.332914 -0.0214987 -0.00390699 0.0653473 0.997623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1464 1465 -0.737422 12.0821 -0.342201 -0.00508673 0.00562752 0.0670287 0.997722 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1465 1466 -0.742514 12.0869 -0.330662 -0.0187242 0.00120394 0.0564155 0.998231 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1466 1467 -0.741816 12.0575 -0.319342 -0.0154915 0.00379076 0.0646536 0.99778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1467 1468 -0.724233 12.0555 -0.326354 -0.0171794 -0.00236124 0.0622003 0.997913 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1468 1469 -0.7196 12.059 -0.342789 -0.0211407 0.0048334 0.0626104 0.997802 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1469 1470 -0.734785 12.0435 -0.331132 -0.0135083 0.00603205 0.0687583 0.997524 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1470 1471 -0.738812 12.0556 -0.334407 -0.0228418 0.012211 0.0540996 0.9982 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1471 1472 -0.715215 12.0388 -0.336655 -0.0194485 0.000269362 0.0553781 0.998276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1472 1473 -0.726406 12.0371 -0.333799 -0.00794418 -0.0040069 0.0668984 0.99772 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1473 1474 -0.726859 12.0281 -0.329365 -0.013456 -0.000138462 0.0646647 0.997816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1474 1475 -0.72448 12.0386 -0.33169 -0.00880015 6.86687e-06 0.0513867 0.99864 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1475 1476 -0.739198 12.0397 -0.33732 -0.0219139 4.96354e-05 0.0652267 0.99763 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1476 1477 -0.715861 12.0311 -0.331811 -0.0246519 -0.00723508 0.0674374 0.997393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1477 1478 -0.728341 12.0266 -0.350359 -0.0193843 0.00291391 0.0702373 0.997338 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1478 1479 -0.741178 12.0124 -0.356148 -0.00851278 -0.00407774 0.0553647 0.998422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1479 1480 -0.730099 12.0085 -0.339378 -0.0183386 -0.00466586 0.0574996 0.998166 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1480 1481 -0.728696 12.0054 -0.343936 -0.0177907 -0.00452428 0.0642222 0.997767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1481 1482 -0.731337 12.0099 -0.34218 -0.0207553 0.00710043 0.0580345 0.998074 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1482 1483 -0.72754 11.9997 -0.341264 -0.030013 0.0129145 0.0547813 0.997964 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1483 1484 -0.736261 12.0007 -0.33203 -0.022359 0.000776886 0.0478171 0.998606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1484 1485 -0.72661 11.9932 -0.341631 -0.0128534 0.00139323 0.0593183 0.998155 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1485 1486 -0.717814 11.9688 -0.348104 -0.0254991 0.00175458 0.0666377 0.99745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1486 1487 -0.712466 11.9778 -0.350858 -0.019601 -0.00280853 0.0561823 0.998224 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1487 1488 -0.718053 11.9771 -0.332774 -0.0189591 -0.00372512 0.0649296 0.997703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1488 1489 -0.693787 11.9663 -0.347493 -0.0178578 -0.00328247 0.0662043 0.997641 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1489 1490 -0.717195 11.9778 -0.348798 -0.00969485 0.00339495 0.0617801 0.998037 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1490 1491 -0.720981 11.9633 -0.351729 -0.0286009 0.00193446 0.0565559 0.997988 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1491 1492 -0.700877 11.9669 -0.363228 -0.020566 0.00127745 0.070896 0.997271 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1492 1493 -0.725395 11.9686 -0.350149 -0.0169982 -0.00771073 0.0550636 0.998308 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1493 1494 -0.696759 11.9423 -0.347126 -0.0243511 0.000656415 0.0592643 0.997945 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1494 1495 -0.711884 11.9399 -0.35385 -0.0243834 -0.00250331 0.0613797 0.997813 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1495 1496 -0.702937 11.9366 -0.364348 -0.029088 -0.00375714 0.060246 0.997753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1496 1497 -0.706624 11.93 -0.350257 -0.0158279 4.99102e-05 0.0578192 0.998202 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1497 1498 -0.707492 11.9227 -0.362408 -0.0168299 0.00713716 0.0658988 0.997659 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1498 1499 -0.693658 11.9344 -0.352048 -0.0183974 -0.00286884 0.0631731 0.997829 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1499 1500 -0.697979 11.9236 -0.359492 -0.0178268 0.00328023 0.0557857 0.998278 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1500 1501 -0.7067 11.9045 -0.356976 -0.0141728 -0.00517538 0.0468913 0.998786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1501 1502 -0.708569 11.9005 -0.365854 -0.0190936 0.00248219 0.0660079 0.997633 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1502 1503 -0.706976 11.9186 -0.37445 -0.0233549 -0.00048839 0.0578636 0.998051 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1503 1504 -0.716522 11.8838 -0.356873 -0.0200363 -0.00913201 0.0608657 0.997903 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1504 1505 -0.710278 11.8965 -0.359359 -0.0269985 0.00386931 0.0602332 0.997812 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1505 1506 -0.730472 11.8875 -0.370024 -0.0227252 0.00455706 0.0653949 0.99759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1506 1507 -0.705919 11.8838 -0.36623 -0.0199184 -0.000669536 0.0588296 0.998069 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1507 1508 -0.728688 11.8908 -0.357054 -0.0213779 -0.00324623 0.0645507 0.99768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1508 1509 -0.695005 11.8711 -0.346873 -0.0162243 -0.0032073 0.0594771 0.998093 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1509 1510 -0.7144 11.8739 -0.369893 -0.0204635 -0.00773326 0.059336 0.997998 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1510 1511 -0.698196 11.8677 -0.367256 -0.0230542 0.000783796 0.0649522 0.997622 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1511 1512 -0.707057 11.8702 -0.375497 -0.0079591 0.00465652 0.0618069 0.998046 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1512 1513 -0.694316 11.8408 -0.356071 -0.0205387 0.00911495 0.0653996 0.997606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1513 1514 -0.701275 11.8406 -0.368547 -0.0225676 0.00205857 0.0564123 0.99815 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1514 1515 -0.708926 11.831 -0.379672 -0.0155821 -0.00345771 0.0609422 0.998014 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1515 1516 -0.706712 11.8393 -0.364093 -0.0217805 0.0069201 0.061197 0.997864 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1516 1517 -0.702787 11.845 -0.360553 -0.0149595 0.00541646 0.0619178 0.997954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1517 1518 -0.704748 11.8297 -0.365012 -0.0203689 0.00222688 0.0600432 0.997985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1518 1519 -0.707445 11.8304 -0.364257 -0.0199539 -0.000677882 0.0618782 0.997884 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1519 1520 -0.712997 11.83 -0.373509 -0.0180436 0.0106502 0.0662559 0.997583 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1520 1521 -0.693348 11.8157 -0.358144 -0.0264055 0.00597326 0.0556318 0.998084 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1521 1522 -0.721077 11.7997 -0.380183 -0.016566 0.00421142 0.0517032 0.998516 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1522 1523 -0.710594 11.7913 -0.383714 -0.0161761 0.000323769 0.0572676 0.998228 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1523 1524 -0.694696 11.7946 -0.399965 -0.0155113 0.00643245 0.066832 0.997623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1524 1525 -0.705621 11.7823 -0.375546 -0.0234214 -0.0103551 0.0555002 0.99813 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1525 1526 -0.700447 11.7872 -0.376299 -0.0242806 0.00073322 0.055892 0.998141 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1526 1527 -0.711055 11.7767 -0.376366 -0.0175854 -0.00382169 0.0608211 0.997986 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1527 1528 -0.687831 11.7736 -0.37691 -0.0173037 -8.69818e-06 0.0533468 0.998426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1528 1529 -0.682407 11.7649 -0.37073 -0.0158413 -0.00473006 0.0540634 0.998401 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1529 1530 -0.700367 11.7532 -0.38943 -0.0250975 0.000462058 0.0552253 0.998158 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1530 1531 -0.699332 11.7575 -0.376153 -0.0183882 -0.00281414 0.0595562 0.998052 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1531 1532 -0.697503 11.7702 -0.390264 -0.0331669 -0.00317074 0.0541432 0.997977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1532 1533 -0.704067 11.733 -0.3925 -0.0229436 0.00150629 0.0605886 0.997898 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1533 1534 -0.690193 11.7162 -0.387149 -0.0130647 0.00533283 0.0564104 0.998308 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1534 1535 -0.693983 11.7397 -0.39541 -0.0203971 0.0100653 0.0539215 0.998286 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1535 1536 -0.693843 11.7219 -0.378707 -0.0286417 0.000348984 0.0550886 0.998071 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1536 1537 -0.684597 11.7101 -0.387415 -0.0256427 0.00129568 0.0638304 0.99763 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1537 1538 -0.677908 11.7276 -0.37214 -0.0210207 0.00811302 0.0599095 0.997949 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1538 1539 -0.696018 11.6971 -0.392397 -0.024923 -0.00268147 0.064128 0.997627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1539 1540 -0.682655 11.7082 -0.364279 -0.0178349 0.00995433 0.0650685 0.997672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1540 1541 -0.690486 11.6918 -0.399222 -0.0152521 0.00123791 0.0640059 0.997832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1541 1542 -0.690613 11.7168 -0.392708 -0.0151251 0.00655884 0.0652753 0.997731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1542 1543 -0.674406 11.6945 -0.386659 -0.0290951 0.00163975 0.0556832 0.998023 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1543 1544 -0.694665 11.6793 -0.390134 -0.0225654 0.00279073 0.0585248 0.998027 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1544 1545 -0.691798 11.6624 -0.384561 -0.0280154 -0.00379216 0.0527947 0.998205 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1545 1546 -0.67016 11.6716 -0.3963 -0.029083 0.00348093 0.0595941 0.997793 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1546 1547 -0.685304 11.6698 -0.382941 -0.0201519 -0.00340037 0.055228 0.998265 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1547 1548 -0.69653 11.6741 -0.393403 -0.0221495 0.00764882 0.0486245 0.998542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1548 1549 -0.675411 11.6649 -0.40889 -0.0181151 0.0111454 0.0634186 0.99776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1549 1550 -0.688243 11.6502 -0.400782 -0.0239749 0.00703652 0.0582055 0.997992 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1550 1551 -0.690811 11.6512 -0.400328 -0.0268891 -0.00606113 0.0549156 0.99811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1551 1552 -0.698148 11.6323 -0.40313 -0.019339 -0.00318146 0.0617659 0.997898 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1552 1553 -0.684822 11.642 -0.393887 -0.0232611 0.0019947 0.0626743 0.997761 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1553 1554 -0.687697 11.6152 -0.396117 -0.0260409 0.00150929 0.0601024 0.997851 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1554 1555 -0.673471 11.6101 -0.393859 -0.0165633 5.92821e-05 0.0677175 0.997567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1555 1556 -0.680073 11.6202 -0.381664 -0.0271134 -0.00503963 0.0525416 0.998238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1556 1557 -0.678042 11.6103 -0.399348 -0.0092466 -0.00317062 0.0543018 0.998477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1557 1558 -0.684095 11.6211 -0.404318 -0.0277804 -0.00195595 0.058913 0.997875 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1558 1559 -0.671598 11.6027 -0.407393 -0.0206193 0.0022946 0.0645032 0.997702 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1559 1560 -0.677709 11.5914 -0.395619 -0.0261255 0.000748014 0.053359 0.998233 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1560 1561 -0.673211 11.5703 -0.409033 -0.0118269 0.00136849 0.0567251 0.998319 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1561 1562 -0.673486 11.5721 -0.397411 -0.0213746 0.00124338 0.059652 0.99799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1562 1563 -0.679808 11.556 -0.400637 -0.020268 -0.00326704 0.0636614 0.99776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1563 1564 -0.667991 11.5431 -0.412145 -0.0221113 0.0026311 0.0584211 0.998044 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1564 1565 -0.676747 11.5861 -0.411126 -0.02608 0.00171949 0.0434621 0.998713 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1565 1566 -0.664352 11.5504 -0.394772 -0.0241306 0.00682277 0.0472421 0.998569 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1566 1567 -0.66601 11.5405 -0.409158 -0.0247657 0.00168631 0.0574908 0.998037 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1567 1568 -0.698665 11.5455 -0.412433 -0.0236349 -0.00494362 0.0495314 0.998481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1568 1569 -0.672434 11.5224 -0.40351 -0.026663 -0.00644249 0.0605301 0.997789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1569 1570 -0.67582 11.5294 -0.41786 -0.0293595 0.00216261 0.0557248 0.998012 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1570 1571 -0.664742 11.5278 -0.403053 -0.0252286 -0.00400275 0.0581611 0.99798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1571 1572 -0.662551 11.5302 -0.40468 -0.0319126 -0.00328136 0.0600821 0.997678 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1572 1573 -0.662958 11.5256 -0.41882 -0.0159566 0.00308325 0.0532733 0.998448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1573 1574 -0.661592 11.5068 -0.406235 -0.010178 0.000848063 0.0582972 0.998247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1574 1575 -0.660742 11.4981 -0.409499 -0.0357052 -2.8582e-05 0.0468459 0.998264 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1575 1576 -0.649618 11.4644 -0.416319 -0.0196879 0.0007175 0.0569177 0.998184 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1576 1577 -0.656 11.4809 -0.402896 -0.0170154 -0.00678733 0.0698026 0.997393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1577 1578 -0.661154 11.4923 -0.40716 -0.0282308 0.00522118 0.0503113 0.998321 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1578 1579 -0.666841 11.4639 -0.420948 -0.0304938 0.00242536 0.0546047 0.998039 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1579 1580 -0.646132 11.4676 -0.426838 -0.0276964 -0.00177071 0.0561687 0.998035 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1580 1581 -0.668358 11.4558 -0.415045 -0.0283971 0.010163 0.0519951 0.998192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1581 1582 -0.665753 11.4477 -0.414876 -0.0227114 -0.000377532 0.0568008 0.998127 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1582 1583 -0.654496 11.4521 -0.415506 -0.0218066 0.00332463 0.0597163 0.997972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1583 1584 -0.646196 11.4424 -0.422805 -0.0276023 -0.00184377 0.0564048 0.998025 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1584 1585 -0.661336 11.4178 -0.420176 -0.0230997 -0.00634487 0.0548416 0.998208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1585 1586 -0.654008 11.4452 -0.408733 -0.0290102 0.0016214 0.0675293 0.997294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1586 1587 -0.652326 11.4192 -0.416745 -0.0241325 0.0063281 0.0557526 0.998133 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1587 1588 -0.659287 11.4007 -0.399727 -0.0262098 -0.00340788 0.0553145 0.998119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1588 1589 -0.663551 11.3928 -0.419634 -0.0261641 -0.00506258 0.0602449 0.997828 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1589 1590 -0.639801 11.402 -0.436384 -0.0241549 0.00595205 0.0544466 0.998207 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1590 1591 -0.665806 11.3974 -0.41389 -0.021717 0.00958739 0.0547343 0.998219 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1591 1592 -0.651544 11.3874 -0.406632 -0.0220425 -0.00730082 0.0633678 0.99772 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1592 1593 -0.64528 11.3887 -0.437083 -0.0340849 1.98571e-05 0.0548217 0.997914 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1593 1594 -0.650076 11.3711 -0.430306 -0.0263736 -6.74106e-05 0.048618 0.998469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1594 1595 -0.657395 11.3739 -0.424857 -0.0336707 0.00309544 0.0633972 0.997415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1595 1596 -0.639414 11.3495 -0.43146 -0.02511 0.00614905 0.0521092 0.998307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1596 1597 -0.665366 11.3414 -0.423232 -0.0243318 0.0013571 0.0602032 0.997889 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1597 1598 -0.648025 11.3464 -0.438774 -0.0313715 -0.0115771 0.0585158 0.997726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1598 1599 -0.641832 11.3393 -0.432368 -0.0275839 -3.5443e-06 0.0592677 0.997861 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1599 1600 -0.645159 11.3278 -0.412083 -0.0354167 -0.00589249 0.0625436 0.997396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1600 1601 -0.645489 11.3288 -0.44094 -0.0229699 -0.00384894 0.051678 0.998392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1601 1602 -0.645554 11.3061 -0.425432 -0.0337766 0.00324194 0.0597301 0.997638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1602 1603 -0.651765 11.3148 -0.440717 -0.0240911 -0.00414522 0.0550734 0.998183 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1603 1604 -0.651544 11.3012 -0.433154 -0.0282196 -0.00217649 0.0505017 0.998323 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1604 1605 -0.636162 11.3124 -0.441238 -0.0271075 -0.013147 0.0518765 0.998199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1605 1606 -0.635112 11.2947 -0.437855 -0.0295349 0.00208915 0.0596207 0.997782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1606 1607 -0.646253 11.2796 -0.426383 -0.0230784 0.00655307 0.0503634 0.998443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1607 1608 -0.641961 11.2816 -0.429719 -0.0278805 0.00538083 0.0514767 0.99827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1608 1609 -0.653789 11.2575 -0.434709 -0.0263608 0.00876813 0.0597426 0.997827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1609 1610 -0.628145 11.2704 -0.454464 -0.0257303 -0.00511186 0.0523784 0.998283 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1610 1611 -0.640289 11.2625 -0.442256 -0.0278097 -0.00380101 0.0545106 0.998119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1611 1612 -0.642775 11.2529 -0.423158 -0.023456 -0.00340234 0.0583411 0.998015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1612 1613 -0.629971 11.234 -0.439417 -0.0213177 0.00269751 0.0550733 0.998251 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1613 1614 -0.640904 11.234 -0.442373 -0.0340435 0.00107779 0.0579529 0.997738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1614 1615 -0.613599 11.2252 -0.429858 -0.0305601 -0.00838024 0.0625732 0.997537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1615 1616 -0.617313 11.2148 -0.419144 -0.0260748 0.00320786 0.0535136 0.998221 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1616 1617 -0.638756 11.2305 -0.43367 -0.0277934 -0.00320718 0.0603818 0.997783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1617 1618 -0.63802 11.2299 -0.453525 -0.0300499 -0.00371594 0.0605445 0.997706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1618 1619 -0.637142 11.1819 -0.436488 -0.0331535 0.0027042 0.0606294 0.997606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1619 1620 -0.632328 11.2079 -0.436412 -0.0289838 0.0043247 0.0610827 0.997702 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1620 1621 -0.63882 11.1924 -0.44135 -0.0191787 0.00384959 0.0435508 0.99886 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1621 1622 -0.611879 11.1726 -0.443757 -0.023652 -0.00298278 0.0571322 0.998082 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1622 1623 -0.628119 11.1706 -0.452304 -0.0273905 0.00173509 0.0518739 0.998276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1623 1624 -0.62963 11.1682 -0.440815 -0.0326652 0.00476715 0.0492683 0.99824 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1624 1625 -0.617792 11.1585 -0.454083 -0.0315497 0.00310361 0.0596593 0.997715 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1625 1626 -0.62568 11.1587 -0.433242 -0.0292129 0.00477243 0.0617692 0.997651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1626 1627 -0.61252 11.1459 -0.465116 -0.0247175 -0.00636936 0.0545044 0.998187 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1627 1628 -0.61805 11.1262 -0.445295 -0.0400436 0.00362344 0.0575508 0.997533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1628 1629 -0.623326 11.1313 -0.453409 -0.0246524 -0.0119438 0.0560987 0.998049 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1629 1630 -0.617416 11.1175 -0.434543 -0.0320558 0.00328343 0.0595025 0.997708 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1630 1631 -0.620955 11.1204 -0.438288 -0.0242708 0.00284217 0.0575094 0.998046 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1631 1632 -0.616734 11.1118 -0.451483 -0.027474 -0.00670579 0.0476515 0.998464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1632 1633 -0.609763 11.1032 -0.45468 -0.0328762 0.00185292 0.0418478 0.998581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1633 1634 -0.622245 11.096 -0.448719 -0.0271292 -0.00107393 0.0540078 0.998171 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1634 1635 -0.61309 11.0623 -0.451823 -0.0278909 -0.00246903 0.0487607 0.998418 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1635 1636 -0.621272 11.0568 -0.43978 -0.0215563 0.00440784 0.05664 0.998152 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1636 1637 -0.630871 11.0857 -0.450903 -0.023915 -0.000142403 0.0548716 0.998207 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1637 1638 -0.614255 11.067 -0.443445 -0.0252494 0.00683548 0.0521252 0.998298 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1638 1639 -0.616104 11.0601 -0.460283 -0.0263176 0.00230956 0.0510905 0.998345 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1639 1640 -0.607071 11.0544 -0.463242 -0.0356559 -0.0108635 0.0480953 0.998147 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1640 1641 -0.609139 11.0332 -0.441142 -0.0268828 0.0145642 0.0582423 0.997834 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1641 1642 -0.615072 11.0215 -0.453722 -0.0236245 0.00617643 0.0499741 0.998452 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1642 1643 -0.617888 11.0251 -0.456915 -0.0345117 -0.00348455 0.0576052 0.997737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1643 1644 -0.609799 11.0116 -0.464346 -0.0432126 -0.0103183 0.0458179 0.997961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1644 1645 -0.613893 11.0075 -0.457785 -0.0289355 0.0111461 0.0572783 0.997877 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1645 1646 -0.604065 11.0064 -0.466908 -0.0310666 -0.00614613 0.0458756 0.998445 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1646 1647 -0.615889 11.0012 -0.460287 -0.0343975 0.00928355 0.0519286 0.998015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1647 1648 -0.609753 11.0014 -0.458158 -0.0243651 -0.00883445 0.0532361 0.998246 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1648 1649 -0.624586 10.9834 -0.450664 -0.0287149 -0.00346497 0.0490369 0.998378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1649 1650 -0.599807 10.9655 -0.463988 -0.027047 -0.000789277 0.0620279 0.997708 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1650 1651 -0.605329 10.9617 -0.461142 -0.0331824 0.000177582 0.0536839 0.998006 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1651 1652 -0.606721 10.9605 -0.465877 -0.0340382 0.0121257 0.051305 0.998029 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1652 1653 -0.599865 10.9515 -0.454086 -0.0301954 0.00206271 0.0542963 0.998066 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1653 1654 -0.601729 10.9387 -0.446244 -0.0347982 0.0101654 0.0507105 0.998055 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1654 1655 -0.610395 10.9404 -0.458476 -0.0398847 0.000886183 0.0538528 0.997752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1655 1656 -0.603616 10.9229 -0.451755 -0.0337609 0.00117973 0.0518883 0.998081 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1656 1657 -0.598856 10.915 -0.459355 -0.0362094 0.00460826 0.0521056 0.997974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1657 1658 -0.593123 10.9104 -0.464343 -0.023124 -0.00991702 0.0641369 0.997624 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1658 1659 -0.602618 10.9234 -0.451665 -0.0284464 0.00620391 0.0536771 0.998134 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1659 1660 -0.605192 10.9049 -0.454149 -0.0334041 0.00134067 0.061113 0.997571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1660 1661 -0.58004 10.8916 -0.467422 -0.028489 -0.000226624 0.0426519 0.998684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1661 1662 -0.58726 10.8904 -0.476301 -0.030564 0.00546481 0.0571396 0.997883 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1662 1663 -0.60049 10.8421 -0.459571 -0.0253673 -0.00830523 0.0577547 0.997974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1663 1664 -0.597321 10.8628 -0.466638 -0.0383059 0.00817478 0.0477231 0.998092 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1664 1665 -0.585101 10.8503 -0.474991 -0.029686 -0.00870736 0.0563212 0.997933 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1665 1666 -0.596246 10.8568 -0.477396 -0.0319823 -4.1163e-05 0.0543719 0.998008 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1666 1667 -0.589235 10.8484 -0.43722 -0.0308448 -0.00639544 0.0582482 0.997805 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1667 1668 -0.595281 10.8467 -0.467411 -0.0284188 0.00167441 0.0559685 0.998027 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1668 1669 -0.593777 10.8169 -0.460556 -0.0374422 -0.00479823 0.0454361 0.998254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1669 1670 -0.587358 10.8257 -0.479716 -0.0286039 0.00499952 0.0562738 0.997993 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1670 1671 -0.589661 10.8169 -0.464036 -0.0348351 -0.00973755 0.0605846 0.997507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1671 1672 -0.594647 10.8076 -0.4506 -0.032588 0.00188268 0.053065 0.998057 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1672 1673 -0.607603 10.7839 -0.483887 -0.0383221 -0.00211882 0.0662875 0.997062 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1673 1674 -0.572566 10.793 -0.470891 -0.0263808 0.00433375 0.0541077 0.998177 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1674 1675 -0.574344 10.7743 -0.476768 -0.0328111 0.00265915 0.0603549 0.997634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1675 1676 -0.58659 10.7766 -0.473673 -0.0301368 -0.00430296 0.0490645 0.998332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1676 1677 -0.575234 10.7667 -0.48403 -0.0408243 -0.00513971 0.0560598 0.997579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1677 1678 -0.595359 10.7525 -0.484715 -0.0287009 0.00457702 0.0484539 0.998402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1678 1679 -0.580199 10.7695 -0.473195 -0.0299753 0.00396136 0.0553277 0.99801 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1679 1680 -0.583631 10.7264 -0.502568 -0.0429602 0.0045467 0.0668837 0.996825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1680 1681 -0.579947 10.7206 -0.479052 -0.0359281 -0.00210279 0.04963 0.998119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1681 1682 -0.578173 10.726 -0.474496 -0.0367556 0.000933643 0.0503524 0.998055 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1682 1683 -0.569099 10.6989 -0.478637 -0.0323201 0.00441827 0.0527193 0.998076 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1683 1684 -0.559763 10.7253 -0.479285 -0.0239708 -0.00601904 0.0530124 0.998288 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1684 1685 -0.573944 10.6876 -0.476589 -0.0312003 -0.00101178 0.0536814 0.99807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1685 1686 -0.574817 10.7027 -0.450485 -0.0363401 -0.00218556 0.0586924 0.997612 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1686 1687 -0.573945 10.6827 -0.461278 -0.0303648 0.00631553 0.0566603 0.997912 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1687 1688 -0.565898 10.6828 -0.46891 -0.0334822 -0.000228094 0.0554672 0.997899 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1688 1689 -0.569194 10.6822 -0.48665 -0.0264559 -0.00224192 0.052284 0.998279 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1689 1690 -0.581445 10.6819 -0.474525 -0.0353034 -0.00212771 0.0534543 0.997944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1690 1691 -0.574585 10.6523 -0.488604 -0.0408768 0.0049921 0.0574967 0.997496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1691 1692 -0.56282 10.6335 -0.498013 -0.0333169 0.00271758 0.0577984 0.997768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1692 1693 -0.584476 10.6387 -0.483604 -0.0352198 0.00197417 0.0550904 0.997858 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1693 1694 -0.551766 10.6236 -0.480103 -0.0365104 0.00467133 0.0554926 0.99778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1694 1695 -0.557076 10.6293 -0.49566 -0.0349492 -0.00414922 0.0530979 0.997969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1695 1696 -0.56406 10.616 -0.478681 -0.0343184 0.0119387 0.0456031 0.998299 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1696 1697 -0.553004 10.6144 -0.476286 -0.023347 0.00135602 0.052357 0.998355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1697 1698 -0.556887 10.5836 -0.471333 -0.0347087 0.00427624 0.0488597 0.998193 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1698 1699 -0.562522 10.5902 -0.474864 -0.0288834 0.00656452 0.0585409 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1699 1700 -0.564818 10.5585 -0.479806 -0.0301208 -0.00174047 0.0618796 0.997627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1700 1701 -0.544729 10.5733 -0.473402 -0.0403612 -0.00902178 0.0579576 0.997462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1701 1702 -0.548305 10.552 -0.478932 -0.0334106 0.00117736 0.0562224 0.997858 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1702 1703 -0.571554 10.5445 -0.484338 -0.0294389 -0.0022199 0.0551411 0.998042 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1703 1704 -0.558563 10.5381 -0.486611 -0.0343085 0.00944477 0.0561327 0.997789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1704 1705 -0.554665 10.5436 -0.493169 -0.0310092 -0.0034068 0.0487604 0.998323 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1705 1706 -0.556187 10.5035 -0.478333 -0.0378803 -5.66782e-05 0.0517082 0.997944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1706 1707 -0.56031 10.5144 -0.487004 -0.0332285 0.00543838 0.0553468 0.997899 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1707 1708 -0.546522 10.5386 -0.471612 -0.0305299 -0.0101612 0.0539115 0.998027 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1708 1709 -0.569816 10.4995 -0.49408 -0.0279387 0.00725312 0.0595142 0.99781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1709 1710 -0.547306 10.503 -0.497413 -0.035416 -0.00480929 0.0468944 0.99826 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1710 1711 -0.549092 10.4845 -0.497623 -0.0399095 0.00182153 0.0589547 0.997461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1711 1712 -0.554692 10.4809 -0.497787 -0.037005 0.0079534 0.0536449 0.997842 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1712 1713 -0.547758 10.4675 -0.5177 -0.0338306 0.00295907 0.0569562 0.997799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1713 1714 -0.548668 10.4433 -0.472584 -0.0451465 -0.0002694 0.0541142 0.997514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1714 1715 -0.551685 10.4516 -0.488508 -0.0363969 -0.0103761 0.0448671 0.998276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1715 1716 -0.555412 10.4247 -0.49746 -0.0333804 0.00175608 0.0510777 0.998135 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1716 1717 -0.545767 10.422 -0.477971 -0.0349255 0.00510529 0.0481118 0.998218 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1717 1718 -0.530184 10.4212 -0.48623 -0.0331949 -0.00203938 0.0454127 0.998415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1718 1719 -0.545988 10.4118 -0.493909 -0.0363776 0.0015837 0.0495458 0.998108 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1719 1720 -0.54153 10.402 -0.496856 -0.041219 0.00874058 0.0474902 0.997983 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1720 1721 -0.534106 10.3845 -0.484418 -0.041185 -0.00291135 0.0614853 0.997254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1721 1722 -0.539793 10.3785 -0.481558 -0.033295 0.0115783 0.0477278 0.998238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1722 1723 -0.535571 10.3787 -0.491693 -0.0427559 0.00446148 0.0468221 0.997978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1723 1724 -0.544168 10.3533 -0.488185 -0.0353943 -0.00462139 0.0491054 0.998156 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1724 1725 -0.543205 10.3667 -0.489855 -0.0376722 -0.00400005 0.0517907 0.997939 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1725 1726 -0.544639 10.3398 -0.496173 -0.0384302 -0.000268678 0.0568971 0.99764 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1726 1727 -0.534602 10.3548 -0.480763 -0.0389714 0.00460531 0.0355996 0.998595 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1727 1728 -0.531892 10.321 -0.482798 -0.033499 -0.00647019 0.0501808 0.998157 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1728 1729 -0.536561 10.3365 -0.486955 -0.0421786 0.00124594 0.044975 0.998097 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1729 1730 -0.538834 10.3027 -0.492868 -0.0321575 0.00345083 0.0499931 0.998226 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1730 1731 -0.529417 10.2986 -0.490508 -0.039776 0.00166927 0.049559 0.997977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1731 1732 -0.541212 10.2861 -0.495685 -0.0351227 0.00554478 0.0416545 0.998499 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1732 1733 -0.512121 10.2682 -0.516307 -0.0287322 -0.00126535 0.0526259 0.9982 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1733 1734 -0.53916 10.2804 -0.486457 -0.0356425 -0.000779039 0.0575344 0.997707 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1734 1735 -0.542022 10.2685 -0.505954 -0.0341694 0.00636193 0.0373745 0.998697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1735 1736 -0.519637 10.265 -0.489836 -0.0254397 0.00175708 0.0537719 0.998228 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1736 1737 -0.528004 10.2474 -0.501893 -0.0363151 -0.00626843 0.044774 0.998317 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1737 1738 -0.524313 10.2308 -0.487227 -0.0306384 0.0075078 0.0513032 0.998185 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1738 1739 -0.52588 10.2416 -0.501669 -0.0369716 0.00361313 0.0463741 0.998233 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1739 1740 -0.538351 10.2242 -0.485903 -0.0297372 -2.03881e-05 0.0651525 0.997432 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1740 1741 -0.517917 10.2032 -0.512386 -0.0370236 0.00528741 0.0461985 0.998232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1741 1742 -0.516197 10.199 -0.511077 -0.0366216 0.00381802 0.0582296 0.997624 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1742 1743 -0.509855 10.2004 -0.497684 -0.0397891 0.00164285 0.0534332 0.997777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1743 1744 -0.525268 10.1804 -0.497618 -0.0416035 -0.00712513 0.0491844 0.997897 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1744 1745 -0.527838 10.1746 -0.497044 -0.0322063 -0.000280541 0.0518653 0.998135 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1745 1746 -0.522419 10.1601 -0.495162 -0.0378727 -0.00435524 0.0530051 0.997866 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1746 1747 -0.507475 10.1603 -0.490739 -0.0410125 0.000806545 0.0580704 0.997469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1747 1748 -0.503483 10.1458 -0.481432 -0.0400883 0.0113366 0.0536729 0.997689 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1748 1749 -0.509797 10.1309 -0.506723 -0.0357121 0.000677056 0.0484495 0.998187 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1749 1750 -0.507932 10.1418 -0.507079 -0.0441902 -0.0041438 0.0427695 0.998099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1750 1751 -0.507245 10.1119 -0.494545 -0.0249294 -5.56928e-05 0.03816 0.998961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1751 1752 -0.504994 10.1196 -0.505728 -0.0355658 -0.0121899 0.0485219 0.998114 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1752 1753 -0.5178 10.1155 -0.50651 -0.0358199 0.00381191 0.0477915 0.998208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1753 1754 -0.52 10.0928 -0.499161 -0.0345718 -0.00116055 0.0463973 0.998324 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1754 1755 -0.495794 10.0736 -0.513224 -0.0371263 0.000430232 0.0488016 0.998118 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1755 1756 -0.518216 10.0957 -0.494961 -0.0442123 -0.00247335 0.0482925 0.997851 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1756 1757 -0.515284 10.0571 -0.510176 -0.0408994 0.00194194 0.0485028 0.997983 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1757 1758 -0.510212 10.0437 -0.492642 -0.0408755 0.00897481 0.0489408 0.997925 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1758 1759 -0.497098 10.0388 -0.508949 -0.0347243 -0.00462719 0.042175 0.998496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1759 1760 -0.509884 10.0421 -0.491909 -0.0326584 0.00761755 0.0459183 0.998382 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1760 1761 -0.508013 10.021 -0.502229 -0.033877 -0.00556083 0.0571261 0.997777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1761 1762 -0.499394 10.012 -0.483943 -0.0360284 0.00456614 0.0568618 0.997721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1762 1763 -0.520102 10.0109 -0.504115 -0.0471218 0.00177587 0.053472 0.997455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1763 1764 -0.501012 9.99546 -0.485017 -0.0350283 0.0010799 0.0514066 0.998063 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1764 1765 -0.506353 9.99634 -0.501191 -0.0391681 -4.01611e-05 0.0530038 0.997826 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1765 1766 -0.51137 9.98117 -0.515278 -0.0364655 -0.00152134 0.048098 0.998176 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1766 1767 -0.483409 9.9716 -0.510137 -0.0332418 -0.00110792 0.0496154 0.998214 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1767 1768 -0.505438 9.94929 -0.520082 -0.052399 -0.00979399 0.0507672 0.997287 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1768 1769 -0.503464 9.95453 -0.51714 -0.0330421 0.00163944 0.0566452 0.997846 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1769 1770 -0.490457 9.93253 -0.51379 -0.0349012 -0.00050441 0.0419632 0.998509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1770 1771 -0.504144 9.92525 -0.528893 -0.0329992 -0.00295436 0.0507385 0.998162 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1771 1772 -0.497843 9.91851 -0.528365 -0.0370548 0.00117655 0.0561149 0.997736 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1772 1773 -0.483738 9.89394 -0.522053 -0.0351422 -0.00356533 0.054153 0.997908 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1773 1774 -0.499141 9.89742 -0.52429 -0.038212 0.00211585 0.0508758 0.997971 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1774 1775 -0.505033 9.89514 -0.500416 -0.0448481 0.00290595 0.057903 0.99731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1775 1776 -0.495977 9.88278 -0.504888 -0.0343118 0.00153216 0.0465325 0.998326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1776 1777 -0.482397 9.85877 -0.489839 -0.0445055 -0.0032915 0.0516817 0.997666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1777 1778 -0.488169 9.87094 -0.499671 -0.035167 -0.00077751 0.0422627 0.998487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1778 1779 -0.481892 9.84224 -0.511732 -0.0420966 0.00246845 0.0492818 0.997894 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1779 1780 -0.486078 9.84971 -0.519884 -0.0427361 -0.00514907 0.0519058 0.997724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1780 1781 -0.49458 9.84466 -0.498297 -0.0423108 -0.00205625 0.0504684 0.997827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1781 1782 -0.477915 9.82752 -0.494776 -0.0452391 -0.00549647 0.0452531 0.997936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1782 1783 -0.484058 9.8155 -0.51777 -0.0370955 0.00424671 0.0464058 0.998225 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1783 1784 -0.492471 9.80655 -0.536451 -0.0546229 -0.00132222 0.0506556 0.99722 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1784 1785 -0.455119 9.80876 -0.5174 -0.0346879 -0.011063 0.048569 0.998156 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1785 1786 -0.46748 9.77459 -0.528482 -0.0378236 -0.00470621 0.0492558 0.998059 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1786 1787 -0.463728 9.77803 -0.544033 -0.0397137 -0.00839612 0.0484861 0.997999 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1787 1788 -0.475875 9.7732 -0.531888 -0.0360396 -0.00168789 0.0380764 0.998623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1788 1789 -0.478347 9.74337 -0.529693 -0.0371891 0.0095496 0.0444326 0.998274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1789 1790 -0.467494 9.75009 -0.511543 -0.0274586 -0.000973208 0.0573217 0.997978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1790 1791 -0.471806 9.74241 -0.516707 -0.0359095 0.00336932 0.0493292 0.998131 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1791 1792 -0.459862 9.73046 -0.504619 -0.043313 0.00426979 0.0501752 0.997792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1792 1793 -0.474642 9.72258 -0.500519 -0.0361745 0.00719844 0.0488431 0.998125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1793 1794 -0.47251 9.7006 -0.517798 -0.0448109 0.00534465 0.0364845 0.998315 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1794 1795 -0.470832 9.6825 -0.524767 -0.0367677 -0.00468628 0.0510408 0.998009 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1795 1796 -0.459535 9.6978 -0.510643 -0.0426486 -0.00788266 0.0514234 0.997735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1796 1797 -0.464479 9.68001 -0.521312 -0.045438 -0.00174642 0.0483436 0.997795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1797 1798 -0.470273 9.65681 -0.535642 -0.0386373 -0.00283578 0.0535778 0.997812 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1798 1799 -0.481825 9.66911 -0.510574 -0.0432518 0.00109118 0.047073 0.997954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1799 1800 -0.463867 9.62462 -0.488173 -0.0427435 -0.000415094 0.0392446 0.998315 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1800 1801 -0.462636 9.6517 -0.50784 -0.0451594 0.00150443 0.0433792 0.998036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1801 1802 -0.464396 9.62483 -0.507845 -0.0373316 -0.00490814 0.0527644 0.997897 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1802 1803 -0.452241 9.59398 -0.496781 -0.0446778 0.00127907 0.0417002 0.99813 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1803 1804 -0.46428 9.60619 -0.52397 -0.0396935 0.00171541 0.053361 0.997785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1804 1805 -0.468165 9.59241 -0.513349 -0.0422617 0.0053753 0.0357822 0.998451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1805 1806 -0.459485 9.57334 -0.500493 -0.0383172 -0.00307592 0.0411832 0.998412 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1806 1807 -0.478113 9.57719 -0.523405 -0.0501575 -0.00482732 0.0503267 0.997461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1807 1808 -0.461354 9.57264 -0.524945 -0.0300362 0.00834414 0.0601933 0.9977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1808 1809 -0.453325 9.56602 -0.514167 -0.0378456 -0.00794253 0.0563868 0.99766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1809 1810 -0.456458 9.53851 -0.537522 -0.0434926 -0.00617819 0.0462895 0.997962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1810 1811 -0.462945 9.54323 -0.515203 -0.0397224 0.00251755 0.0490503 0.998003 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1811 1812 -0.44102 9.51914 -0.518148 -0.0468654 -0.00287065 0.0468001 0.9978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1812 1813 -0.460626 9.51271 -0.513752 -0.043089 0.00497505 0.0514488 0.997733 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1813 1814 -0.467414 9.50353 -0.503066 -0.0407569 0.00700815 0.0462367 0.998074 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1814 1815 -0.453382 9.47683 -0.52301 -0.0556093 0.00130816 0.0402979 0.997638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1815 1816 -0.45287 9.47757 -0.514279 -0.0347624 0.00221252 0.0494513 0.998169 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1816 1817 -0.439004 9.49288 -0.503583 -0.0333103 -0.00279268 0.055304 0.99791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1817 1818 -0.448544 9.46742 -0.521591 -0.0412567 -0.0059949 0.0576071 0.997468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1818 1819 -0.462091 9.43935 -0.515335 -0.046304 0.00122944 0.0551743 0.997402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1819 1820 -0.447324 9.45701 -0.515595 -0.042322 0.00214513 0.0511897 0.997789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1820 1821 -0.432478 9.40732 -0.51812 -0.0458902 0.00579474 0.0518078 0.997585 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1821 1822 -0.445883 9.42002 -0.515062 -0.0430337 -0.00719826 0.0571087 0.997414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1822 1823 -0.42596 9.42053 -0.524047 -0.0410875 0.00497318 0.0518884 0.997795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1823 1824 -0.436227 9.39935 -0.526378 -0.0468738 0.000883321 0.0280186 0.998507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1824 1825 -0.449049 9.39927 -0.517319 -0.0478363 0.0031123 0.0416369 0.997982 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1825 1826 -0.452622 9.36885 -0.512925 -0.0306415 0.0025388 0.051921 0.998178 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1826 1827 -0.449863 9.37172 -0.510157 -0.043344 0.000176795 0.0421388 0.998171 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1827 1828 -0.429213 9.35585 -0.516477 -0.0416891 0.0029113 0.0507972 0.997834 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1828 1829 -0.442871 9.33645 -0.507756 -0.0353792 0.00561769 0.048842 0.998164 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1829 1830 -0.448722 9.33301 -0.516219 -0.0454796 -0.0023549 0.0425313 0.998057 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1830 1831 -0.439338 9.30345 -0.504647 -0.0453542 0.00049845 0.0385481 0.998227 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1831 1832 -0.434794 9.34657 -0.524916 -0.0415388 -0.00351292 0.0564887 0.997533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1832 1833 -0.442866 9.30513 -0.526598 -0.0367872 -0.00134246 0.0437438 0.998364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1833 1834 -0.433951 9.30012 -0.502952 -0.0531014 0.00259605 0.0492039 0.997373 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1834 1835 -0.437787 9.28103 -0.503565 -0.0383496 0.000626372 0.0461238 0.998199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1835 1836 -0.408099 9.27579 -0.509453 -0.0499728 0.00271428 0.0465746 0.99766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1836 1837 -0.411534 9.24913 -0.513495 -0.044219 -0.0099935 0.0497455 0.997733 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1837 1838 -0.42227 9.24708 -0.513731 -0.049609 -0.00073931 0.0493204 0.99755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1838 1839 -0.430864 9.23902 -0.528654 -0.0473717 0.00141417 0.0352147 0.998255 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1839 1840 -0.432923 9.25153 -0.509161 -0.0443281 0.000867286 0.0453594 0.997986 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1840 1841 -0.431691 9.23624 -0.510984 -0.0428529 -0.00106974 0.0417096 0.99821 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1841 1842 -0.432603 9.22234 -0.521446 -0.0403609 -0.00288098 0.0626664 0.997214 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1842 1843 -0.453642 9.21524 -0.513725 -0.0423262 -0.00415518 0.0450417 0.998079 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1843 1844 -0.410181 9.1976 -0.485792 -0.044118 -0.00868444 0.0443211 0.998005 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1844 1845 -0.425693 9.17243 -0.518703 -0.0532715 0.00559187 0.0475953 0.997429 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1845 1846 -0.417017 9.16031 -0.525374 -0.0344402 -0.000678424 0.0354289 0.998778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1846 1847 -0.415924 9.14972 -0.510291 -0.0383814 -0.00543614 0.0419867 0.998366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1847 1848 -0.418613 9.14026 -0.524287 -0.053088 0.00576916 0.0550186 0.997056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1848 1849 -0.427177 9.1351 -0.510701 -0.0463433 -0.00251523 0.0438727 0.997958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1849 1850 -0.423758 9.12992 -0.536917 -0.0429758 -0.00314535 0.0556385 0.997521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1850 1851 -0.430741 9.11163 -0.514127 -0.0465181 0.0033999 0.0463007 0.997838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1851 1852 -0.436417 9.0993 -0.50288 -0.0336656 0.0016798 0.0378189 0.998716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1852 1853 -0.418459 9.10369 -0.537459 -0.0485531 0.00533328 0.043734 0.997848 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1853 1854 -0.399288 9.09277 -0.529368 -0.0431213 0.0080519 0.042793 0.99812 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1854 1855 -0.38351 9.06049 -0.518737 -0.0388252 -0.00327335 0.0478104 0.998096 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1855 1856 -0.411683 9.06415 -0.526679 -0.0486038 0.00314417 0.0490728 0.997607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1856 1857 -0.428928 9.04872 -0.519245 -0.041129 -0.00123789 0.0444626 0.998163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1857 1858 -0.405596 9.04408 -0.520816 -0.0476094 0.00226847 0.0495986 0.997631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1858 1859 -0.397809 9.03333 -0.529992 -0.0383434 0.000365298 0.0340887 0.998683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1859 1860 -0.422346 9.02486 -0.517965 -0.0457454 0.00122911 0.050956 0.997652 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1860 1861 -0.390331 9.00435 -0.523903 -0.0384704 0.0060215 0.0439255 0.998276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1861 1862 -0.40109 9.00965 -0.511968 -0.0436154 0.00700467 0.0425341 0.998118 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1862 1863 -0.414104 8.99841 -0.520702 -0.0415156 0.0101926 0.0513656 0.997765 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1863 1864 -0.424545 8.96797 -0.522623 -0.0389572 -0.00102026 0.0474524 0.998113 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1864 1865 -0.406724 8.96885 -0.532135 -0.0411113 0.00204083 0.0429258 0.99823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1865 1866 -0.404076 8.93637 -0.499555 -0.0408323 0.00340946 0.0456856 0.998115 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1866 1867 -0.384206 8.94666 -0.500216 -0.045822 -0.00701333 0.0483247 0.997755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1867 1868 -0.402421 8.92438 -0.522303 -0.0367026 0.00133984 0.0495641 0.998095 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1868 1869 -0.385884 8.92702 -0.505053 -0.037058 -0.00624055 0.0448042 0.998289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1869 1870 -0.395096 8.92685 -0.523131 -0.0371787 0.0043057 0.0463291 0.998225 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1870 1871 -0.407941 8.90325 -0.504645 -0.0484036 -0.00484332 0.0428925 0.997895 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1871 1872 -0.412498 8.8852 -0.52952 -0.0396104 0.00270498 0.042694 0.998299 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1872 1873 -0.377844 8.85932 -0.510678 -0.0367527 0.00190541 0.0382421 0.998591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1873 1874 -0.400379 8.86438 -0.524827 -0.0517532 0.00653281 0.0455853 0.997598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1874 1875 -0.404807 8.84849 -0.525063 -0.046416 -0.001225 0.0518223 0.997576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1875 1876 -0.395233 8.81768 -0.513709 -0.0521704 -0.00633681 0.0435641 0.997667 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1876 1877 -0.400351 8.8248 -0.50743 -0.0474658 -0.00547911 0.0398706 0.998062 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1877 1878 -0.383896 8.80958 -0.529451 -0.0422505 -0.00782641 0.0385684 0.998332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1878 1879 -0.392147 8.80734 -0.544875 -0.0441142 0.00623686 0.0474832 0.997878 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1879 1880 -0.381634 8.80033 -0.532787 -0.0476928 -0.00212048 0.0479943 0.997706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1880 1881 -0.383826 8.78049 -0.515572 -0.0381974 0.00128902 0.0411027 0.998424 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1881 1882 -0.385792 8.76279 -0.522705 -0.0487908 0.00591979 0.0456087 0.99775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1882 1883 -0.388175 8.75841 -0.511473 -0.0409133 -0.00499967 0.0411465 0.998303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1883 1884 -0.395905 8.74447 -0.531308 -0.0460075 -5.03154e-05 0.037049 0.998254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1884 1885 -0.389362 8.74527 -0.517467 -0.0401362 0.00533192 0.0366011 0.998509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1885 1886 -0.392867 8.72708 -0.539315 -0.0548205 -0.000660478 0.0434502 0.99755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1886 1887 -0.359618 8.7336 -0.5214 -0.0416118 0.00954227 0.0374812 0.998385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1887 1888 -0.398944 8.71575 -0.517365 -0.0476585 -0.000358042 0.0452507 0.997838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1888 1889 -0.377524 8.69051 -0.504633 -0.0513766 -0.0088091 0.0454586 0.997605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1889 1890 -0.372592 8.69667 -0.503978 -0.0471807 0.00717329 0.0382635 0.998127 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1890 1891 -0.377613 8.6749 -0.521735 -0.0419184 -0.00527012 0.048055 0.997951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1891 1892 -0.374597 8.66128 -0.498223 -0.0430535 -0.00433557 0.0465415 0.997979 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1892 1893 -0.390707 8.64498 -0.524289 -0.049075 0.00577193 0.0385774 0.998033 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1893 1894 -0.371258 8.63941 -0.531063 -0.0401675 0.000471675 0.0401679 0.998385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1894 1895 -0.386666 8.59673 -0.506667 -0.0529443 -0.00798821 0.0529459 0.997161 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1895 1896 -0.368387 8.61017 -0.500903 -0.0451088 -0.00273994 0.0388221 0.998224 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1896 1897 -0.39217 8.60449 -0.52028 -0.0551313 0.00304922 0.0369107 0.997792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1897 1898 -0.37287 8.5912 -0.52375 -0.0520467 -0.00064446 0.0415817 0.997778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1898 1899 -0.359538 8.59209 -0.501853 -0.0513374 0.00737976 0.0508735 0.997357 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1899 1900 -0.369693 8.5542 -0.515104 -0.0430618 -0.00727719 0.0491415 0.997837 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1900 1901 -0.351412 8.55038 -0.505465 -0.0539451 -0.000525595 0.0430791 0.997614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1901 1902 -0.356301 8.5455 -0.530497 -0.0478796 -0.00281886 0.0372682 0.998154 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1902 1903 -0.368822 8.52801 -0.513202 -0.056964 -0.0014307 0.0408119 0.997541 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1903 1904 -0.349919 8.50957 -0.520582 -0.0451546 0.00701847 0.0460891 0.997892 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1904 1905 -0.370764 8.50978 -0.505633 -0.0514532 0.000639534 0.0383728 0.997938 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1905 1906 -0.349282 8.51757 -0.518775 -0.0380056 0.00101836 0.0355644 0.998644 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1906 1907 -0.363322 8.50079 -0.506966 -0.0448729 0.00394578 0.0476371 0.997848 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1907 1908 -0.361296 8.49107 -0.517933 -0.0416431 -0.000465484 0.0404231 0.998314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1908 1909 -0.376968 8.45318 -0.518999 -0.0413004 -0.00489764 0.0485112 0.997956 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1909 1910 -0.354788 8.45805 -0.507232 -0.047445 -0.0115299 0.0478758 0.997659 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1910 1911 -0.370776 8.45028 -0.498501 -0.0412374 0.00176267 0.0378186 0.998432 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1911 1912 -0.350791 8.42275 -0.509588 -0.0450622 -0.00553696 0.0465874 0.997882 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1912 1913 -0.3538 8.4099 -0.520204 -0.0520962 0.00120306 0.0353083 0.998017 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1913 1914 -0.353453 8.40754 -0.502866 -0.0408211 0.00191045 0.0414044 0.998306 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1914 1915 -0.353548 8.40706 -0.508027 -0.052921 0.000456644 0.04339 0.997655 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1915 1916 -0.366064 8.36714 -0.508266 -0.0482906 -0.00418143 0.0451024 0.997806 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1916 1917 -0.34501 8.37244 -0.522042 -0.0400806 -0.00645595 0.047874 0.998028 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1917 1918 -0.356513 8.35064 -0.522046 -0.0473575 0.00414401 0.036516 0.998202 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1918 1919 -0.352572 8.35772 -0.500439 -0.0424419 0.00597346 0.0444266 0.998093 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1919 1920 -0.348343 8.32602 -0.516062 -0.0503138 0.00401927 0.0537229 0.997279 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1920 1921 -0.33823 8.33414 -0.513404 -0.0491736 0.00287071 0.0372385 0.998092 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1921 1922 -0.344296 8.32147 -0.504971 -0.0443595 0.00254292 0.0415356 0.998149 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1922 1923 -0.331243 8.31826 -0.530369 -0.0515555 0.00379026 0.0430207 0.997736 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1923 1924 -0.344606 8.30114 -0.513123 -0.0485408 0.000130282 0.0387364 0.99807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1924 1925 -0.374819 8.28237 -0.509462 -0.0420925 0.00188137 0.0439664 0.998144 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1925 1926 -0.340497 8.26591 -0.510039 -0.0482271 0.00277759 0.0380505 0.998108 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1926 1927 -0.357347 8.25053 -0.527602 -0.051825 -0.00245999 0.0390072 0.997891 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1927 1928 -0.341804 8.25118 -0.510342 -0.0495097 0.00223896 0.0383037 0.998036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1928 1929 -0.329747 8.21694 -0.514575 -0.0537747 0.00702256 0.0475257 0.997397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1929 1930 -0.347359 8.22285 -0.516191 -0.0482587 0.003231 0.0423818 0.99793 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1930 1931 -0.347279 8.20652 -0.522021 -0.0462467 0.000732055 0.0363854 0.998267 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1931 1932 -0.341816 8.20935 -0.505652 -0.0509512 0.00419753 0.037367 0.997993 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1932 1933 -0.339542 8.16973 -0.506159 -0.0476045 0.0124411 0.0418181 0.997913 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1933 1934 -0.333222 8.17558 -0.517006 -0.0396514 0.0084941 0.0423459 0.99828 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1934 1935 -0.347007 8.17707 -0.509607 -0.0428745 0.00321785 0.0361779 0.99842 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1935 1936 -0.33055 8.15048 -0.524249 -0.0508763 0.00579569 0.0469055 0.997586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1936 1937 -0.328838 8.1488 -0.520768 -0.0386148 0.00614719 0.0426089 0.998326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1937 1938 -0.338516 8.12763 -0.524885 -0.0396595 -0.00286357 0.043049 0.998281 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1938 1939 -0.343873 8.12502 -0.520598 -0.0411868 -0.00310911 0.0400521 0.998344 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1939 1940 -0.306241 8.08845 -0.520385 -0.0408348 0.00312065 0.0374318 0.99846 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1940 1941 -0.331086 8.08082 -0.512814 -0.0531161 0.0128624 0.0479093 0.997355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1941 1942 -0.343907 8.07668 -0.504648 -0.0495947 0.00738107 0.0363307 0.998081 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1942 1943 -0.330374 8.03684 -0.505208 -0.0425594 -0.00694382 0.0274125 0.998694 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1943 1944 -0.322013 8.05645 -0.522809 -0.0436777 -0.00135936 0.0493935 0.997823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1944 1945 -0.331568 8.03595 -0.518029 -0.0548399 -0.00888858 0.0424784 0.997552 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1945 1946 -0.324646 8.01027 -0.530993 -0.0561724 0.00379925 0.0441936 0.997435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1946 1947 -0.3129 8.02886 -0.505688 -0.0445367 -0.003093 0.0381706 0.998273 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1947 1948 -0.315391 7.99652 -0.50642 -0.0498037 0.00268588 0.0379676 0.998033 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1948 1949 -0.331406 7.98849 -0.506915 -0.0407104 -0.00298776 0.043542 0.998217 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1949 1950 -0.30594 7.94964 -0.522629 -0.0426977 0.00703103 0.0387528 0.998311 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1950 1951 -0.298605 7.97071 -0.499758 -0.0556761 -0.00239233 0.043603 0.997493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1951 1952 -0.334386 7.95056 -0.499279 -0.0570211 -0.00412793 0.0444558 0.997374 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1952 1953 -0.317274 7.95028 -0.506723 -0.0395643 0.00100818 0.0373227 0.998519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1953 1954 -0.320636 7.92077 -0.524227 -0.0488234 -0.00752386 0.0409367 0.99794 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1954 1955 -0.322634 7.91417 -0.49117 -0.0541747 -0.00561182 0.0435165 0.997567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1955 1956 -0.315569 7.91885 -0.499541 -0.0528596 0.00694007 0.0370376 0.997891 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1956 1957 -0.319733 7.88875 -0.49495 -0.0438413 -0.00080884 0.035743 0.998399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1957 1958 -0.292455 7.87485 -0.509503 -0.0559753 0.00502118 0.0357007 0.997781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1958 1959 -0.30838 7.85849 -0.515653 -0.0531957 0.0100904 0.0408133 0.997699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1959 1960 -0.322429 7.8548 -0.506592 -0.0459027 -0.00807701 0.0395555 0.99813 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1960 1961 -0.291751 7.84934 -0.497511 -0.0478912 0.000195053 0.0451468 0.997832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1961 1962 -0.311872 7.83619 -0.494594 -0.0468602 -0.000825026 0.042016 0.998017 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1962 1963 -0.290842 7.815 -0.508988 -0.0545913 0.00317203 0.0408858 0.997666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1963 1964 -0.304515 7.8043 -0.509833 -0.0507085 0.000462773 0.0449153 0.997703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1964 1965 -0.314032 7.78573 -0.489274 -0.0475372 -0.00190717 0.0360058 0.998218 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1965 1966 -0.298821 7.76493 -0.509964 -0.0528338 -0.0122879 0.0420348 0.997643 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1966 1967 -0.310899 7.78409 -0.505431 -0.0536853 -0.00259813 0.0405587 0.99773 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1967 1968 -0.2939 7.7476 -0.505302 -0.0591734 0.0114002 0.0314105 0.997688 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1968 1969 -0.300214 7.74255 -0.51578 -0.0501032 0.00258868 0.0404553 0.997921 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1969 1970 -0.294431 7.73193 -0.509195 -0.0509073 -0.00689742 0.0339366 0.998103 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1970 1971 -0.28828 7.72907 -0.494587 -0.0487528 0.00387192 0.0320787 0.998288 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1971 1972 -0.308739 7.70099 -0.516624 -0.050906 -0.00375253 0.040459 0.997877 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1972 1973 -0.303796 7.69037 -0.507286 -0.0559231 0.000885099 0.0424986 0.99753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1973 1974 -0.301686 7.67847 -0.500905 -0.0479588 -0.00145669 0.0438238 0.997886 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1974 1975 -0.295414 7.66658 -0.51608 -0.0594734 0.00515008 0.0392814 0.997443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1975 1976 -0.300557 7.64627 -0.508243 -0.0506863 0.000965615 0.0368445 0.998034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1976 1977 -0.293226 7.64436 -0.499413 -0.0535108 0.00206999 0.037794 0.99785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1977 1978 -0.282239 7.62831 -0.503365 -0.0420348 0.00463243 0.0346203 0.998505 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1978 1979 -0.296231 7.63231 -0.511453 -0.0583039 0.00404824 0.0385173 0.997547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1979 1980 -0.295926 7.60917 -0.521887 -0.0531535 -0.0010888 0.0370439 0.997898 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1980 1981 -0.259817 7.58551 -0.504371 -0.0491938 0.00972597 0.0557043 0.997187 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1981 1982 -0.281381 7.59682 -0.516253 -0.0416186 -0.00999698 0.0368404 0.998404 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1982 1983 -0.292101 7.57142 -0.511908 -0.0469778 0.0064041 0.0342774 0.998287 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1983 1984 -0.292777 7.55294 -0.506705 -0.0516675 0.00551522 0.0322261 0.998129 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1984 1985 -0.295593 7.54064 -0.502053 -0.046312 -0.00255771 0.0368579 0.998244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1985 1986 -0.273897 7.50753 -0.510079 -0.0474685 0.00292078 0.0340107 0.998289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1986 1987 -0.278318 7.52478 -0.485842 -0.0484612 0.00983115 0.0355213 0.998145 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1987 1988 -0.300005 7.49937 -0.503316 -0.050269 0.00697483 0.0466848 0.99762 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1988 1989 -0.276682 7.5051 -0.488693 -0.0585095 0.00626185 0.0368528 0.997587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1989 1990 -0.272825 7.4851 -0.511946 -0.0553834 -0.0029629 0.0322886 0.997939 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1990 1991 -0.276638 7.46329 -0.49646 -0.0577627 0.000527442 0.0446672 0.99733 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1991 1992 -0.289094 7.45536 -0.503183 -0.048593 -0.00328524 0.0339852 0.998235 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1992 1993 -0.277188 7.44373 -0.495601 -0.050602 9.84544e-05 0.0351837 0.998099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1993 1994 -0.275863 7.43609 -0.501462 -0.0483179 0.00469852 0.0345738 0.998222 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1994 1995 -0.274087 7.43511 -0.501484 -0.0627756 -0.00488547 0.0332518 0.997462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1995 1996 -0.271212 7.40159 -0.497262 -0.0624128 0.00525128 0.045339 0.997006 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1996 1997 -0.277885 7.3973 -0.503692 -0.0578328 0.00321916 0.0371958 0.997628 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1997 1998 -0.268284 7.36499 -0.485045 -0.0506754 -0.00437679 0.0354646 0.998076 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1998 1999 -0.289105 7.34983 -0.505116 -0.0551446 0.00294441 0.0344261 0.99788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1999 2000 -0.273619 7.35283 -0.501632 -0.04143 0.00243501 0.0353021 0.998515 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2000 2001 -0.290539 7.34803 -0.485547 -0.0471697 -0.000827222 0.0426386 0.997976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2001 2002 -0.272311 7.32794 -0.509627 -0.0491593 0.00210176 0.0276599 0.998406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2002 2003 -0.260975 7.31101 -0.511952 -0.0465706 -0.00275059 0.0414207 0.998052 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2003 2004 -0.282251 7.29181 -0.489345 -0.0429724 -0.00163629 0.0315907 0.998575 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2004 2005 -0.258634 7.27774 -0.513334 -0.053956 -0.00154128 0.0407068 0.997712 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2005 2006 -0.257136 7.29662 -0.518771 -0.0534264 -0.00599847 0.0375922 0.997846 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2006 2007 -0.276212 7.2753 -0.488621 -0.0560556 -0.00216722 0.019341 0.998238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2007 2008 -0.261244 7.22657 -0.496687 -0.053164 0.00372462 0.0330076 0.998033 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2008 2009 -0.285182 7.23414 -0.494678 -0.0541559 0.00037367 0.0408131 0.997698 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2009 2010 -0.241634 7.22161 -0.488817 -0.0513854 -0.00253869 0.0411393 0.997828 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2010 2011 -0.248609 7.21764 -0.511422 -0.0540522 -0.00985575 0.0358642 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2011 2012 -0.25609 7.21907 -0.472345 -0.050734 0.00399383 0.036444 0.998039 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2012 2013 -0.262541 7.19507 -0.495874 -0.0489547 -0.00215172 0.0331236 0.998249 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2013 2014 -0.256296 7.16981 -0.468817 -0.0458469 -0.00364373 0.0354153 0.998314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2014 2015 -0.252903 7.17318 -0.494665 -0.0501376 -0.000469708 0.0378015 0.998027 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2015 2016 -0.268941 7.15132 -0.49654 -0.0513808 0.00397011 0.0395529 0.997888 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2016 2017 -0.257323 7.13055 -0.504796 -0.0526921 -0.00883927 0.0293404 0.998141 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2017 2018 -0.265101 7.12335 -0.477402 -0.0546793 0.00525276 0.0398 0.997697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2018 2019 -0.248063 7.118 -0.505377 -0.0458655 -0.00657213 0.0369252 0.998243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2019 2020 -0.259109 7.1054 -0.498942 -0.0462873 -0.0065828 0.0384256 0.998167 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2020 2021 -0.235814 7.0953 -0.479091 -0.0459241 0.00693095 0.0266952 0.998564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2021 2022 -0.264985 7.0732 -0.500027 -0.0581617 0.00048583 0.0310338 0.997825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2022 2023 -0.2383 7.06006 -0.488998 -0.0568568 0.00357007 0.04394 0.997409 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2023 2024 -0.247181 7.03365 -0.482374 -0.0559061 -0.00119434 0.030374 0.997973 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2024 2025 -0.24767 7.03832 -0.4929 -0.0475772 -0.00213111 0.0350523 0.99825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2025 2026 -0.24587 7.02771 -0.503461 -0.0455469 -0.00142058 0.03487 0.998352 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2026 2027 -0.25136 7.01809 -0.501123 -0.0477556 0.00360098 0.0328672 0.998312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2027 2028 -0.253469 6.99029 -0.489243 -0.0553826 0.00321324 0.0286892 0.998048 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2028 2029 -0.236378 6.98029 -0.4838 -0.052813 0.00384039 0.025447 0.998273 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2029 2030 -0.244318 6.95475 -0.496136 -0.0584156 -0.00194734 0.0341644 0.997706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2030 2031 -0.242559 6.9545 -0.492994 -0.0551186 0.000935135 0.0355786 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2031 2032 -0.229464 6.94287 -0.487713 -0.0517605 0.00598998 0.0354737 0.998011 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2032 2033 -0.23836 6.91478 -0.479354 -0.0672866 -0.00125914 0.0266275 0.997378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2033 2034 -0.241773 6.90983 -0.467346 -0.060464 0.000770923 0.0326455 0.997636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2034 2035 -0.241469 6.9038 -0.500378 -0.0432517 -0.00473948 0.0281857 0.998655 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2035 2036 -0.237534 6.87961 -0.476182 -0.0467616 -0.00755292 0.030277 0.998419 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2036 2037 -0.220319 6.87177 -0.485301 -0.0558578 0.0126965 0.0314612 0.997862 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2037 2038 -0.228048 6.86241 -0.491021 -0.0540277 0.00301471 0.0241356 0.998243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2038 2039 -0.239574 6.86836 -0.47641 -0.0533323 0.00101145 0.0328564 0.998036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2039 2040 -0.217236 6.82788 -0.480447 -0.051102 0.00509435 0.0308044 0.998205 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2040 2041 -0.241264 6.84206 -0.496373 -0.0622099 0.00271127 0.0320577 0.997544 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2041 2042 -0.24234 6.79308 -0.494056 -0.058578 0.0098907 0.0339469 0.997656 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2042 2043 -0.233418 6.79057 -0.474724 -0.0597665 0.00253316 0.0309804 0.997728 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2043 2044 -0.23211 6.79447 -0.484028 -0.0483014 0.0112081 0.04292 0.997847 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2044 2045 -0.218705 6.75922 -0.490703 -0.0609717 0.00368587 0.0395407 0.997349 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2045 2046 -0.237959 6.75727 -0.469755 -0.0519698 -0.00201761 0.0348627 0.998038 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2046 2047 -0.215516 6.74872 -0.491212 -0.0480587 -0.00526654 0.0297708 0.998387 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2047 2048 -0.239272 6.73201 -0.485409 -0.0533347 -0.000468835 0.0282962 0.998176 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2048 2049 -0.225884 6.70498 -0.471201 -0.0548632 0.00456658 0.0296197 0.998044 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2049 2050 -0.203833 6.69427 -0.485228 -0.0493935 0.0135126 0.0300858 0.998235 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2050 2051 -0.224325 6.67762 -0.475138 -0.045639 -0.00304564 0.0437036 0.997997 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2051 2052 -0.217922 6.67757 -0.456802 -0.0572654 -0.00492405 0.0301397 0.997892 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2052 2053 -0.217428 6.67545 -0.482983 -0.0559287 2.98799e-05 0.0399194 0.997636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2053 2054 -0.223249 6.63784 -0.476289 -0.0477692 0.00419845 0.0297875 0.998405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2054 2055 -0.235002 6.64986 -0.478049 -0.0542601 -8.08753e-05 0.0352288 0.997905 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2055 2056 -0.230065 6.62791 -0.477865 -0.0540298 0.00155552 0.0287099 0.998125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2056 2057 -0.227687 6.60545 -0.493212 -0.0587717 -0.000128001 0.0371226 0.997581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2057 2058 -0.206605 6.59223 -0.467785 -0.0440939 -0.00251005 0.0445844 0.998029 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2058 2059 -0.223915 6.59886 -0.469047 -0.0509356 -0.00477213 0.0283776 0.998287 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2059 2060 -0.198179 6.56461 -0.480142 -0.0509122 -0.0020947 0.0255934 0.998373 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2060 2061 -0.229826 6.53498 -0.474958 -0.0573807 0.00540254 0.0416573 0.997468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2061 2062 -0.235976 6.54468 -0.481683 -0.0483571 0.00106634 0.0339071 0.998254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2062 2063 -0.221663 6.52688 -0.481947 -0.0602542 -0.00167136 0.0302439 0.997723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2063 2064 -0.222453 6.49948 -0.484693 -0.045531 0.00406346 0.0290779 0.998531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2064 2065 -0.224596 6.49008 -0.466649 -0.0622097 0.00768479 0.027897 0.997644 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2065 2066 -0.226708 6.49456 -0.461824 -0.0498218 -0.00912785 0.0225744 0.998461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2066 2067 -0.216127 6.45955 -0.450344 -0.0541053 -0.00198721 0.0344113 0.99794 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2067 2068 -0.216205 6.47065 -0.483345 -0.0565954 0.00898799 0.0239073 0.99807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2068 2069 -0.210681 6.45114 -0.465274 -0.0453152 0.00402082 0.0224 0.998713 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2069 2070 -0.204961 6.42891 -0.471044 -0.0511483 -0.00117405 0.0328028 0.998152 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2070 2071 -0.212736 6.43618 -0.475153 -0.0541664 -5.43777e-06 0.0364285 0.997867 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2071 2072 -0.213942 6.40516 -0.470166 -0.0568129 -0.0001354 0.0328584 0.997844 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2072 2073 -0.204811 6.4028 -0.455268 -0.0518187 0.0053308 0.0453775 0.997611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2073 2074 -0.189787 6.3906 -0.471915 -0.061755 0.00637044 0.0238018 0.997787 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2074 2075 -0.212263 6.36446 -0.482413 -0.0532986 0.00692541 0.0330567 0.998007 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2075 2076 -0.210476 6.35823 -0.46024 -0.0541396 -0.00290916 0.0270528 0.998163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2076 2077 -0.21663 6.33628 -0.459534 -0.047096 -0.000454604 0.0259505 0.998553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2077 2078 -0.189194 6.3208 -0.478087 -0.0570458 -0.00556743 0.0387046 0.997606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2078 2079 -0.191343 6.32816 -0.469013 -0.0575045 0.00354981 0.0326162 0.997806 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2079 2080 -0.19764 6.30436 -0.468654 -0.0466816 0.00562297 0.0331935 0.998342 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2080 2081 -0.206095 6.28317 -0.478852 -0.0445004 0.00288066 0.0358023 0.998363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2081 2082 -0.201732 6.28317 -0.456085 -0.0628116 0.00568225 0.0292613 0.99758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2082 2083 -0.206771 6.24744 -0.466873 -0.0552933 -0.00128634 0.0298381 0.998023 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2083 2084 -0.183372 6.25858 -0.475541 -0.0564829 0.00829933 0.0331391 0.997819 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2084 2085 -0.204883 6.22994 -0.475615 -0.0496257 0.00376874 0.03051 0.998295 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2085 2086 -0.18874 6.23161 -0.46414 -0.0475478 0.00420442 0.0326518 0.998326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2086 2087 -0.196117 6.21718 -0.467808 -0.0467532 -0.000868365 0.0239645 0.998619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2087 2088 -0.191538 6.19458 -0.458616 -0.0558265 0.000674775 0.0260859 0.998099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2088 2089 -0.183864 6.18318 -0.46096 -0.0531615 0.00605231 0.0332618 0.998013 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2089 2090 -0.197096 6.16786 -0.457917 -0.0537871 0.00587048 0.043797 0.997574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2090 2091 -0.183207 6.15661 -0.46809 -0.0504418 0.00244229 0.0298638 0.998277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2091 2092 -0.185385 6.14847 -0.460149 -0.0556716 0.000218186 0.0288462 0.998032 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2092 2093 -0.19092 6.12173 -0.464238 -0.0579801 0.00213596 0.0250024 0.998002 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2093 2094 -0.196645 6.11758 -0.463234 -0.0631923 -0.00224297 0.0318718 0.99749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2094 2095 -0.187192 6.08064 -0.467992 -0.05628 0.00207204 0.0336267 0.997846 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2095 2096 -0.188688 6.09768 -0.442789 -0.0480934 0.00111382 0.0258341 0.998508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2096 2097 -0.181101 6.06852 -0.465596 -0.0472851 -0.00208781 0.0292712 0.99845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2097 2098 -0.187291 6.07486 -0.460406 -0.0648924 0.00051667 0.0248945 0.997582 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2098 2099 -0.173823 6.03805 -0.468907 -0.0569299 0.000917327 0.0303699 0.997916 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2099 2100 -0.17636 6.03019 -0.469908 -0.0535273 -0.00112768 0.0258763 0.99823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2100 2101 -0.181679 6.03208 -0.450294 -0.0585856 0.00563789 0.022333 0.998017 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2101 2102 -0.169981 5.98512 -0.468962 -0.057092 0.0018517 0.0279446 0.997976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2102 2103 -0.183328 5.96847 -0.468313 -0.0583579 0.00202155 0.0279215 0.997903 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2103 2104 -0.177788 5.9818 -0.450272 -0.0514618 0.00154318 0.0312322 0.998185 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2104 2105 -0.173099 5.95101 -0.451551 -0.0519988 0.00283748 0.0310436 0.99816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2105 2106 -0.162584 5.94928 -0.447826 -0.056159 0.00111533 0.026988 0.998056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2106 2107 -0.183509 5.93225 -0.453476 -0.0625048 -0.0045744 0.0364794 0.997367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2107 2108 -0.185385 5.93835 -0.481434 -0.0532227 0.0034454 0.031817 0.99807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2108 2109 -0.180406 5.87996 -0.465265 -0.0491662 -0.000932474 0.0305487 0.998323 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2109 2110 -0.171333 5.89669 -0.467446 -0.0583506 0.00323854 0.0300484 0.997839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2110 2111 -0.142523 5.86435 -0.457478 -0.0532205 0.00749192 0.0266628 0.998199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2111 2112 -0.171606 5.86183 -0.450768 -0.0630115 -0.0072693 0.0365873 0.997315 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2112 2113 -0.18856 5.82974 -0.437417 -0.0633793 0.0091691 0.0319221 0.997437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2113 2114 -0.167492 5.82736 -0.439085 -0.0524471 0.00395042 0.0350946 0.997999 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2114 2115 -0.181854 5.82006 -0.451028 -0.063261 0.00122323 0.0215242 0.997764 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2115 2116 -0.179918 5.788 -0.450187 -0.0608726 -0.00580243 0.0242308 0.997835 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2116 2117 -0.164172 5.77324 -0.456685 -0.0580064 0.00468264 0.0264384 0.997955 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2117 2118 -0.166542 5.77784 -0.42967 -0.0548262 0.00490096 0.0368582 0.997803 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2118 2119 -0.174708 5.76497 -0.441987 -0.0545044 -0.0050132 0.0204855 0.998291 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2119 2120 -0.170369 5.74874 -0.433463 -0.0509602 -0.00264829 0.0353537 0.998071 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2120 2121 -0.166625 5.7289 -0.445645 -0.0544311 -0.00607853 0.0292605 0.99807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2121 2122 -0.146261 5.71157 -0.449871 -0.0483806 0.00124649 0.0254253 0.998505 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2122 2123 -0.159486 5.70386 -0.44223 -0.0576113 -3.70468e-05 0.0241273 0.998048 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2123 2124 -0.164988 5.67465 -0.448152 -0.0570763 -0.00268537 0.0270617 0.997999 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2124 2125 -0.161407 5.69125 -0.459583 -0.0606268 0.00286857 0.0395737 0.997372 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2125 2126 -0.178268 5.66326 -0.449722 -0.0545465 0.00418048 0.0336985 0.997934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2126 2127 -0.157138 5.63403 -0.474506 -0.0555151 -0.00011221 0.0308173 0.997982 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2127 2128 -0.17348 5.63835 -0.446571 -0.056792 0.00379812 0.0319871 0.997866 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2128 2129 -0.171051 5.61939 -0.418328 -0.0559938 0.0065868 0.0325139 0.99788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2129 2130 -0.157095 5.60491 -0.425742 -0.0554293 0.000127139 0.0384679 0.997721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2130 2131 -0.170715 5.6086 -0.437819 -0.0493344 -0.00181354 0.0338091 0.998208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2131 2132 -0.15405 5.57782 -0.438223 -0.0494624 -0.00371604 0.0285405 0.998361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2132 2133 -0.142236 5.54935 -0.424004 -0.0557081 -0.00252706 0.0279424 0.998053 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2133 2134 -0.163458 5.55052 -0.435528 -0.0524484 0.00614465 0.0291557 0.998179 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2134 2135 -0.146783 5.51438 -0.437625 -0.0537401 0.0043329 0.0237076 0.998264 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2135 2136 -0.143059 5.51214 -0.442358 -0.0481001 0.00112978 0.0223453 0.998592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2136 2137 -0.144853 5.50575 -0.446987 -0.0448138 -0.0028073 0.0251639 0.998674 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2137 2138 -0.151043 5.50728 -0.44014 -0.0596866 -0.00693181 0.0256802 0.997863 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2138 2139 -0.140587 5.49024 -0.448529 -0.065398 -0.00588388 0.0300742 0.997389 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2139 2140 -0.151709 5.46396 -0.424381 -0.0526947 -0.00641075 0.0234522 0.998315 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2140 2141 -0.139103 5.45638 -0.426481 -0.0616062 0.00340206 0.0203277 0.997888 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2141 2142 -0.145256 5.42618 -0.439308 -0.0499502 -0.00402422 0.0193292 0.998557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2142 2143 -0.146202 5.41239 -0.427829 -0.0579608 -0.00875877 0.0189662 0.9981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2143 2144 -0.151373 5.41878 -0.446725 -0.0495425 0.00377714 0.0222543 0.998517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2144 2145 -0.149911 5.399 -0.415528 -0.0584293 -0.00178872 0.035798 0.997648 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2145 2146 -0.139854 5.36483 -0.434631 -0.0585374 0.00372077 0.0312926 0.997788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2146 2147 -0.129554 5.3713 -0.433643 -0.0529877 0.00953977 0.028745 0.998136 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2147 2148 -0.149632 5.3545 -0.436095 -0.0595082 -0.000503971 0.0309139 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2148 2149 -0.160491 5.34264 -0.40434 -0.0515141 0.01253 0.0165265 0.998457 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2149 2150 -0.145229 5.3182 -0.41993 -0.060422 0.00881618 0.028819 0.997718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2150 2151 -0.149765 5.30699 -0.421528 -0.0606757 -0.00206291 0.0266637 0.997799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2151 2152 -0.1289 5.29206 -0.426708 -0.0553248 -0.00578954 0.0203224 0.998245 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2152 2153 -0.162267 5.28836 -0.431124 -0.0579897 -0.00908952 0.0280292 0.997882 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2153 2154 -0.12679 5.28137 -0.445383 -0.0521335 0.00236703 0.0289109 0.998219 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2154 2155 -0.121612 5.25538 -0.41164 -0.0576741 -0.00128714 0.0242677 0.99804 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2155 2156 -0.147484 5.23815 -0.417797 -0.0500047 0.00265834 0.023346 0.998473 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2156 2157 -0.130366 5.2356 -0.423209 -0.0608976 -0.00158434 0.0297613 0.997699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2157 2158 -0.149073 5.2127 -0.431036 -0.0558726 0.0031785 0.0355733 0.997799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2158 2159 -0.143407 5.17796 -0.431249 -0.0517064 0.000776399 0.0273643 0.998287 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2159 2160 -0.136401 5.17996 -0.411471 -0.0552558 0.0055634 0.0194385 0.998267 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2160 2161 -0.145664 5.16705 -0.405888 -0.0590329 -0.00579274 0.0244971 0.997939 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2161 2162 -0.141295 5.13653 -0.421468 -0.064615 -0.00417773 0.0288711 0.997484 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2162 2163 -0.125923 5.14682 -0.423235 -0.0561897 0.00181034 0.0214146 0.998189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2163 2164 -0.140284 5.11796 -0.418705 -0.0531368 0.00727789 0.0147807 0.998451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2164 2165 -0.122235 5.11978 -0.417239 -0.0556116 0.00450952 0.0343878 0.99785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2165 2166 -0.13189 5.10472 -0.425746 -0.0661068 0.00435086 0.0214481 0.997573 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2166 2167 -0.137012 5.09223 -0.449923 -0.0540979 -0.00881915 0.0271476 0.998128 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2167 2168 -0.126306 5.07078 -0.417496 -0.0579299 0.0105333 0.0257853 0.997932 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2168 2169 -0.124108 5.03373 -0.419147 -0.0492537 0.00611404 0.0226487 0.998511 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2169 2170 -0.136415 5.03498 -0.409714 -0.0522661 0.00503836 0.0220823 0.998376 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2170 2171 -0.132371 5.02689 -0.413089 -0.0607788 0.00395524 0.0166586 0.998004 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2171 2172 -0.122158 5.02545 -0.424427 -0.0547068 -0.000281183 0.0277456 0.998117 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2172 2173 -0.139674 5.01327 -0.417269 -0.0610675 -0.00640304 0.0279721 0.997721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2173 2174 -0.123838 4.96097 -0.424858 -0.0603691 0.00535462 0.0216859 0.997926 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2174 2175 -0.131384 4.96015 -0.41027 -0.0465358 -0.00372252 0.0204668 0.9987 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2175 2176 -0.118681 4.95419 -0.40955 -0.0566219 0.00717235 0.0310948 0.997886 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2176 2177 -0.12222 4.95378 -0.399765 -0.0478876 -0.00673235 0.0205871 0.998618 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2177 2178 -0.11453 4.95372 -0.417679 -0.0581624 -0.00165607 0.0190611 0.998124 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2178 2179 -0.123629 4.91639 -0.421383 -0.0572128 -0.00388877 0.0194241 0.998165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2179 2180 -0.115483 4.8819 -0.414328 -0.0653476 0.0102608 0.0207301 0.997594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2180 2181 -0.13989 4.86973 -0.417778 -0.0530104 -0.00661441 0.0204146 0.998363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2181 2182 -0.113274 4.85996 -0.403511 -0.0620066 0.00629761 0.029761 0.997612 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2182 2183 -0.104368 4.84202 -0.404574 -0.0550971 -0.000425993 0.0254079 0.998158 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2183 2184 -0.111985 4.82306 -0.39188 -0.0541751 0.00368956 0.0194703 0.998335 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2184 2185 -0.121495 4.8071 -0.387147 -0.0581081 -0.00452219 0.0307869 0.997825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2185 2186 -0.116449 4.79176 -0.409885 -0.0547756 -0.00672548 0.0255833 0.998148 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2186 2187 -0.121139 4.79926 -0.398999 -0.0641081 0.00621398 0.0219685 0.997682 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2187 2188 -0.0918711 4.77425 -0.402228 -0.0525316 0.00617456 0.0278623 0.998211 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2188 2189 -0.119454 4.76153 -0.385997 -0.0660597 0.000955237 0.023672 0.997534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2189 2190 -0.121752 4.75085 -0.389877 -0.0564288 -0.0135793 0.0254969 0.997989 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2190 2191 -0.105208 4.73085 -0.386698 -0.0610264 0.0032404 0.0289124 0.997712 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2191 2192 -0.109709 4.69993 -0.397309 -0.0635961 0.0060161 0.0186016 0.997784 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2192 2193 -0.115617 4.69297 -0.406975 -0.060085 -0.00147002 0.0263987 0.997843 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2193 2194 -0.10799 4.70259 -0.393432 -0.0506956 -0.00225575 0.0183505 0.998543 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2194 2195 -0.0965748 4.6709 -0.39137 -0.0637031 -0.00639593 0.0318211 0.997441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2195 2196 -0.0924092 4.65773 -0.40368 -0.0645029 0.00221497 0.0170196 0.99777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2196 2197 -0.112315 4.64585 -0.374747 -0.054672 0.00504717 0.0183268 0.998323 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2197 2198 -0.09794 4.61998 -0.380571 -0.0587312 0.0025799 0.0227976 0.99801 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2198 2199 -0.120483 4.61651 -0.408863 -0.0561039 0.00352944 0.0199945 0.998218 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2199 2200 -0.110039 4.59627 -0.395994 -0.0605534 0.00256232 0.0275702 0.997781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2200 2201 -0.101101 4.58591 -0.389551 -0.0597652 -0.00678867 0.0234945 0.997913 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2201 2202 -0.10788 4.56912 -0.392272 -0.0542451 0.00150782 0.0183748 0.998357 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2202 2203 -0.106145 4.55656 -0.393945 -0.0507991 0.00995424 0.0243932 0.998361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2203 2204 -0.103552 4.53939 -0.38743 -0.0517439 0.00531351 0.0205506 0.998435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2204 2205 -0.115339 4.52445 -0.401968 -0.0572056 0.000639438 0.027219 0.997991 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2205 2206 -0.109462 4.53112 -0.368683 -0.0538674 0.00587728 0.026054 0.998191 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2206 2207 -0.114944 4.4858 -0.393969 -0.0623824 0.0049432 0.0207097 0.997825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2207 2208 -0.106877 4.47408 -0.384072 -0.0655861 0.00745607 0.0179782 0.997657 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2208 2209 -0.0984416 4.48011 -0.380167 -0.0591527 0.00557088 0.028623 0.997823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2209 2210 -0.103531 4.44311 -0.388795 -0.064681 0.0010475 0.0152398 0.997789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2210 2211 -0.0952451 4.43608 -0.377304 -0.0649363 0.00329645 0.0268747 0.997522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2211 2212 -0.109043 4.43049 -0.394047 -0.0496283 0.0020589 0.0208657 0.998548 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2212 2213 -0.120928 4.4074 -0.3981 -0.0534579 -0.00576719 0.0282738 0.998153 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2213 2214 -0.0948237 4.39916 -0.391484 -0.0590056 0.00102506 0.0254486 0.997933 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2214 2215 -0.0898785 4.38126 -0.378008 -0.063858 -0.00680544 0.0164478 0.9978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2215 2216 -0.100879 4.3707 -0.38922 -0.0545492 -0.00832711 0.0288085 0.998061 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2216 2217 -0.115455 4.36592 -0.383645 -0.054146 -0.00646345 0.0220233 0.998269 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2217 2218 -0.0897244 4.33268 -0.375528 -0.0560044 -0.0126224 0.0177348 0.998193 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2218 2219 -0.0733101 4.33064 -0.380107 -0.0606195 -0.0035701 0.0149835 0.998042 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2219 2220 -0.0814809 4.29811 -0.383368 -0.0548166 -0.00662449 0.0250562 0.99816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2220 2221 -0.102904 4.29869 -0.386578 -0.0648977 0.00540472 0.0198121 0.997681 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2221 2222 -0.0876039 4.26112 -0.373952 -0.0571426 -0.000256213 0.0226353 0.998109 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2222 2223 -0.0855281 4.29411 -0.380603 -0.0576779 -0.00871264 0.0163099 0.998164 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2223 2224 -0.0982695 4.2615 -0.382578 -0.0600908 0.00469213 0.0211676 0.997957 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2224 2225 -0.0925279 4.21778 -0.365262 -0.0614637 0.000264958 0.021643 0.997875 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2225 2226 -0.0952108 4.21794 -0.375814 -0.0517371 -0.000680413 0.0209346 0.998441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2226 2227 -0.0855533 4.21127 -0.363678 -0.0522029 -0.00310904 0.0162377 0.9985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2227 2228 -0.0888005 4.18884 -0.36104 -0.0587414 -0.00273993 0.0268028 0.99791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2228 2229 -0.0945461 4.17139 -0.38032 -0.0615603 -0.00472459 0.0237255 0.99781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2229 2230 -0.0992634 4.16527 -0.362062 -0.0593501 -0.00217722 0.0208252 0.998018 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2230 2231 -0.084057 4.14671 -0.37537 -0.0572439 0.00125495 0.0162242 0.998228 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2231 2232 -0.0957693 4.13144 -0.35306 -0.0559662 0.00502736 0.0153122 0.998303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2232 2233 -0.0976228 4.11209 -0.37401 -0.0636228 0.000408182 0.0168019 0.997832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2233 2234 -0.0864957 4.08978 -0.364784 -0.0559777 0.00291117 0.0142406 0.998326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2234 2235 -0.0849934 4.08745 -0.357654 -0.0531513 -0.00392474 0.0294171 0.998145 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2235 2236 -0.0821916 4.04863 -0.358872 -0.054758 -0.00638969 0.0119782 0.998407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2236 2237 -0.0807705 4.04554 -0.364552 -0.0545815 -0.00221845 0.0229036 0.998244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2237 2238 -0.0851021 4.02596 -0.366985 -0.072479 -0.00448944 0.0186402 0.997186 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2238 2239 -0.0709005 4.01126 -0.34926 -0.0504163 -0.00204251 0.0172049 0.998578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2239 2240 -0.065396 4.00298 -0.35685 -0.0607011 0.00986061 0.0292496 0.997679 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2240 2241 -0.0871586 4.00743 -0.361499 -0.0610409 4.87791e-05 0.0231933 0.997866 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2241 2242 -0.0671156 3.98705 -0.359391 -0.0642389 -0.00154221 0.022806 0.997673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2242 2243 -0.0668869 3.94591 -0.363936 -0.0624063 0.00872118 0.0223786 0.997762 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2243 2244 -0.0838343 3.95289 -0.373097 -0.0596654 -0.00145376 0.0161148 0.998087 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2244 2245 -0.0777294 3.94094 -0.362436 -0.0549711 -0.00070833 0.0241268 0.998196 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2245 2246 -0.0764282 3.88915 -0.357781 -0.0677069 0.00129687 0.0140758 0.997605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2246 2247 -0.0791088 3.91397 -0.331749 -0.07166 -0.0049795 0.0123608 0.99734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2247 2248 -0.0704242 3.89025 -0.376713 -0.0616616 0.00279558 0.026658 0.997737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2248 2249 -0.080075 3.88254 -0.35166 -0.065079 0.0109738 0.0274666 0.997442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2249 2250 -0.0778114 3.8378 -0.357521 -0.0622738 0.000685953 0.0188591 0.997881 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2250 2251 -0.0740877 3.845 -0.364599 -0.0599592 0.00704898 0.0272549 0.997804 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2251 2252 -0.0679091 3.82898 -0.359099 -0.0551246 0.00175136 0.0106252 0.998421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2252 2253 -0.087056 3.83268 -0.35366 -0.0619339 -0.00778077 0.0254088 0.997726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2253 2254 -0.0603706 3.8128 -0.351775 -0.0615896 -0.00338274 0.0201594 0.997892 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2254 2255 -0.0725105 3.77697 -0.364421 -0.0746473 -0.00125196 0.0141451 0.997109 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2255 2256 -0.0753344 3.76588 -0.354946 -0.0500201 0.00223582 0.0184007 0.998576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2256 2257 -0.0809058 3.74538 -0.346883 -0.0618654 0.00573404 0.00821792 0.998034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2257 2258 -0.0719294 3.73876 -0.337362 -0.0641918 0.00122819 0.0188978 0.997758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2258 2259 -0.0676538 3.74055 -0.363082 -0.0625414 -0.00559347 0.0181597 0.997861 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2259 2260 -0.075715 3.68915 -0.322899 -0.0626726 -0.00547751 0.013917 0.997922 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2260 2261 -0.0664894 3.69472 -0.328663 -0.0535753 0.00230486 0.0240725 0.998271 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2261 2262 -0.0686533 3.6681 -0.348879 -0.0665145 -0.00123261 0.0270484 0.997418 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2262 2263 -0.0670549 3.66805 -0.344234 -0.0654535 -0.0121028 0.0111281 0.99772 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2263 2264 -0.0611912 3.6584 -0.337598 -0.0638842 -0.00774052 0.0193286 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2264 2265 -0.0668521 3.64938 -0.335611 -0.0658715 0.00283905 0.0234236 0.997549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2265 2266 -0.0619934 3.60941 -0.348138 -0.0539763 0.000107112 0.0239116 0.998256 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2266 2267 -0.0711863 3.61158 -0.347679 -0.063133 -0.00521966 0.0170706 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2267 2268 -0.0667243 3.59889 -0.344804 -0.0540057 0.00214363 0.00964519 0.998492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2268 2269 -0.0513645 3.57078 -0.336395 -0.0546946 0.00116324 0.0247278 0.998196 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2269 2270 -0.06182 3.5644 -0.357297 -0.0633247 0.00578825 0.0080421 0.997944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2270 2271 -0.0629617 3.54866 -0.337589 -0.0596105 -0.0064413 0.0263976 0.997852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2271 2272 -0.0746904 3.52724 -0.329226 -0.0580137 -0.0035799 0.0150101 0.998197 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2272 2273 -0.064777 3.52125 -0.335061 -0.0639661 0.00844212 0.00871933 0.997878 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2273 2274 -0.0715251 3.50893 -0.343694 -0.0677395 0.00697041 0.0252104 0.99736 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2274 2275 -0.0615075 3.49282 -0.345024 -0.0615204 0.00501161 0.0246633 0.997788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2275 2276 -0.0667124 3.46223 -0.334206 -0.0565353 0.000889924 0.0185661 0.998228 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2276 2277 -0.049005 3.45496 -0.34035 -0.0661985 0.00233287 0.0122517 0.997729 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2277 2278 -0.0560074 3.43308 -0.32609 -0.0671136 0.00499228 0.0214711 0.997502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2278 2279 -0.0626566 3.41592 -0.327501 -0.0590246 0.0022922 0.00586303 0.998237 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2279 2280 -0.0643623 3.39896 -0.34445 -0.0580805 -0.00723223 0.0173217 0.998135 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2280 2281 -0.0620294 3.39611 -0.328921 -0.0603733 0.00803038 0.0255083 0.997818 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2281 2282 -0.067108 3.37229 -0.336406 -0.0624619 -0.00742268 0.0201147 0.997817 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2282 2283 -0.0519478 3.36774 -0.335406 -0.063272 0.00175557 0.0260849 0.997654 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2283 2284 -0.033894 3.33719 -0.330883 -0.0610043 0.00354735 0.0182336 0.997965 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2284 2285 -0.0574798 3.34607 -0.316405 -0.0655149 -0.0011732 0.0174244 0.997699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2285 2286 -0.05098 3.33299 -0.337334 -0.0578687 -0.00506314 0.0255186 0.997985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2286 2287 -0.0651339 3.30214 -0.319265 -0.0636426 -0.00308465 0.0211004 0.997745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2287 2288 -0.0496511 3.29286 -0.322781 -0.0621562 0.00291245 0.0171393 0.997915 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2288 2289 -0.036251 3.27214 -0.318816 -0.0620069 0.000735841 0.0210619 0.997853 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2289 2290 -0.0673283 3.27315 -0.31174 -0.0583531 -0.00132592 0.0114278 0.99823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2290 2291 -0.0303621 3.24903 -0.334639 -0.0678265 0.00267978 0.0150541 0.99758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2291 2292 -0.0561317 3.22008 -0.328355 -0.0679622 -0.0102468 0.0197104 0.997441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2292 2293 -0.0469913 3.19563 -0.319749 -0.0747806 0.00691441 0.0179422 0.997015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2293 2294 -0.0455245 3.18011 -0.316687 -0.054835 -0.00739818 0.00854558 0.998431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2294 2295 -0.0595606 3.1663 -0.315643 -0.0542206 0.00410524 0.00484425 0.998509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2295 2296 -0.0658589 3.16482 -0.305011 -0.0657672 0.00607396 0.0166373 0.997678 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2296 2297 -0.0351195 3.14877 -0.328185 -0.0626504 0.0110849 0.0201346 0.997771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2297 2298 -0.0608521 3.14443 -0.32624 -0.0592543 0.00487121 0.00791086 0.9982 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2298 2299 -0.0623143 3.09414 -0.302406 -0.0572513 0.00958021 0.0164275 0.998179 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2299 2300 -0.0521085 3.1002 -0.327101 -0.0621844 0.0083723 0.0215178 0.997798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2300 2301 -0.0713071 3.08418 -0.312736 -0.0572617 0.00475543 0.0100523 0.998297 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2301 2302 -0.0504946 3.06078 -0.309325 -0.0660328 0.00285361 0.0154246 0.997694 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2302 2303 -0.0559844 3.04455 -0.289658 -0.0622851 0.00258268 0.0106601 0.997998 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2303 2304 -0.0508293 3.02526 -0.314736 -0.058887 0.0124704 0.0242907 0.997891 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2304 2305 -0.0599497 3.02061 -0.301136 -0.0584364 0.00184456 0.0213394 0.998061 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2305 2306 -0.0371413 3.01635 -0.297406 -0.068637 0.00645519 0.010718 0.997563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2306 2307 -0.0518599 2.98223 -0.308182 -0.0488352 -0.00695948 0.00687718 0.998759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2307 2308 -0.0457915 2.97686 -0.311431 -0.0595966 0.0070845 0.0120594 0.998125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2308 2309 -0.0192154 2.9716 -0.321313 -0.0533224 -0.00257234 0.0103779 0.99852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2309 2310 -0.0492627 2.93937 -0.305329 -0.0581155 0.0102269 0.0200992 0.998055 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2310 2311 -0.0547957 2.94081 -0.308213 -0.061856 0.00190503 0.0229363 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2311 2312 -0.0378219 2.92926 -0.312707 -0.058324 0.00738217 0.0136435 0.998177 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2312 2313 -0.0368678 2.88094 -0.294246 -0.0634553 0.0057452 0.0101176 0.997917 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2313 2314 -0.0507096 2.87577 -0.310746 -0.0582434 -0.000143151 0.0172047 0.998154 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2314 2315 -0.0517175 2.90158 -0.302324 -0.0625221 0.0082642 0.0179362 0.997848 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2315 2316 -0.0250061 2.83687 -0.303175 -0.0565278 0.00444276 0.0190454 0.998209 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2316 2317 -0.0339215 2.83076 -0.289298 -0.0575689 -0.00578847 0.00971977 0.998277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2317 2318 -0.0327742 2.81873 -0.288707 -0.0574556 -0.00329269 0.00596535 0.998325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2318 2319 -0.0334529 2.83586 -0.292665 -0.0628567 -0.00703974 0.00798527 0.997966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2319 2320 -0.0362619 2.7964 -0.281707 -0.0581772 -0.00157731 0.0106195 0.998249 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2320 2321 -0.0445138 2.78895 -0.288199 -0.0622499 -0.00187478 0.0156421 0.997936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2321 2322 -0.0295625 2.78006 -0.288867 -0.064004 0.0005677 0.0123147 0.997873 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2322 2323 -0.0325884 2.7402 -0.278232 -0.0518859 0.00143129 0.0116367 0.998584 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2323 2324 -0.0422504 2.72545 -0.284917 -0.0545045 -0.000220479 0.00286341 0.998509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2324 2325 -0.0443873 2.7151 -0.281096 -0.0674783 -0.00559832 0.0186261 0.997531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2325 2326 -0.0387183 2.70944 -0.279982 -0.0711376 0.00214989 0.000433429 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2326 2327 -0.0167167 2.67408 -0.296765 -0.0550954 0.00272952 0.0146715 0.99837 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2327 2328 -0.0290859 2.67385 -0.303249 -0.0607789 -0.0115301 0.00854693 0.998048 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2328 2329 -0.0318588 2.66956 -0.290387 -0.063704 0.000418535 0.017259 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2329 2330 -0.032713 2.64693 -0.277829 -0.0587311 0.00191063 0.017495 0.998119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2330 2331 -0.0400282 2.62764 -0.277528 -0.0548897 0.0014228 0.00914935 0.998449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2331 2332 -0.0375899 2.59397 -0.28029 -0.0614845 0.00360285 0.0128065 0.998019 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2332 2333 -0.0351257 2.60087 -0.290232 -0.0525361 -0.00130208 0.0194064 0.99843 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2333 2334 -0.0295028 2.57934 -0.302126 -0.0601003 -0.00289181 0.0132925 0.9981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2334 2335 -0.0268446 2.55223 -0.30214 -0.0658604 -0.00292026 0.01701 0.99768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2335 2336 -0.0395115 2.54864 -0.28772 -0.0664354 0.00460868 0.0211034 0.997557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2336 2337 -0.0279617 2.53737 -0.279567 -0.0699874 0.00813992 0.0113741 0.99745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2337 2338 -0.0272016 2.52398 -0.283211 -0.0632071 0.00235012 0.0177951 0.997839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2338 2339 -0.0338112 2.51007 -0.260452 -0.0630093 0.00204662 0.00993154 0.997961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2339 2340 -0.0319163 2.49845 -0.304027 -0.0585205 0.0038629 0.0113164 0.998215 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2340 2341 -0.0200596 2.47876 -0.254782 -0.0590498 0.0010379 0.0108989 0.998195 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2341 2342 -0.0261759 2.4572 -0.28524 -0.062931 0.0028043 0.0197641 0.997818 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2342 2343 -0.0341235 2.43951 -0.260431 -0.057864 0.00267739 0.0151167 0.998206 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2343 2344 -0.0326675 2.42794 -0.261474 -0.0616787 0.00497935 0.0111421 0.998021 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2344 2345 -0.0245061 2.41095 -0.263656 -0.0588472 -0.00128823 0.0126073 0.998187 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2345 2346 -0.0186142 2.39941 -0.264522 -0.0724225 0.00401621 0.00508689 0.997353 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2346 2347 -0.00847731 2.37981 -0.284915 -0.0613522 -0.00966846 0.00811872 0.998036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2347 2348 -0.0176206 2.36064 -0.263505 -0.0587076 -0.000199368 0.0130512 0.99819 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2348 2349 -0.0108987 2.35128 -0.257314 -0.0524836 -6.39762e-05 0.0099805 0.998572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2349 2350 -0.0139575 2.33818 -0.26136 -0.0579785 0.0025848 0.0153835 0.998196 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2350 2351 -0.0310959 2.32591 -0.251688 -0.0632376 0.00597728 0.019059 0.997799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2351 2352 -0.0327692 2.29893 -0.275091 -0.0633518 -0.00112311 0.0116215 0.997923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2352 2353 -0.0109873 2.27697 -0.280532 -0.0681116 -0.00447791 0.0114737 0.997602 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2353 2354 -0.0314599 2.27805 -0.258255 -0.0715389 0.000284546 0.00779306 0.997407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2354 2355 -0.0247185 2.23782 -0.274285 -0.0706622 0.00884833 0.0152834 0.997344 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2355 2356 -0.00918834 2.25314 -0.252897 -0.0605411 -0.00508015 0.00865533 0.998115 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2356 2357 -0.0194849 2.22043 -0.259406 -0.0606461 0.00142595 0.0171814 0.99801 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2357 2358 -0.020612 2.20893 -0.259977 -0.0716086 0.00408408 0.00268001 0.997421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2358 2359 -0.0465381 2.19942 -0.257459 -0.0599197 0.00145066 0.0207217 0.997987 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2359 2360 -0.0354248 2.17171 -0.266683 -0.056499 0.00344941 0.0106787 0.99834 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2360 2361 -0.0112407 2.15388 -0.257431 -0.0559922 0.0108843 0.00646277 0.998351 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2361 2362 -0.0331232 2.15656 -0.244521 -0.0553874 -0.00207177 0.0131518 0.998376 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2362 2363 -0.0184293 2.1222 -0.260981 -0.0686699 -0.00439991 0.0207284 0.997414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2363 2364 -0.0179019 2.12215 -0.257284 -0.0694718 0.00255754 0.0131541 0.997494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2364 2365 -0.0350554 2.09907 -0.239511 -0.0603101 -0.0052948 0.00220858 0.998163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2365 2366 -0.0437203 2.08347 -0.256401 -0.0610236 0.000626011 0.00614176 0.998117 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2366 2367 -0.0212081 2.06719 -0.247603 -0.0640018 0.000700675 0.00678166 0.997926 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2367 2368 -0.0347955 2.07135 -0.245606 -0.0556115 7.5333e-05 0.0126632 0.998372 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2368 2369 -0.0119365 2.04175 -0.230271 -0.060212 0.00442387 0.0170211 0.998031 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2369 2370 -0.0124187 2.02373 -0.245957 -0.0660233 0.00157086 0.0153709 0.997698 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2370 2371 -0.00698103 2.00062 -0.219039 -0.0484659 -0.00365977 0.00441686 0.998808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2371 2372 -0.0135081 1.98646 -0.243143 -0.0557158 -0.00522044 0.0211798 0.998208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2372 2373 0.00104626 1.9885 -0.232811 -0.0640068 0.00369306 0.0163742 0.997808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2373 2374 -0.0147271 1.96408 -0.227482 -0.0606041 -0.00113655 0.00456343 0.998151 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2374 2375 -0.030131 1.9339 -0.253128 -0.059856 0.000536797 0.0123098 0.998131 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2375 2376 -0.00228475 1.94397 -0.252307 -0.0623278 0.00274265 0.0104467 0.997997 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2376 2377 -0.0171012 1.91267 -0.240034 -0.0601929 0.00633557 -0.00332127 0.998161 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2377 2378 -0.00320846 1.90269 -0.250523 -0.0577459 0.000726551 0.0085879 0.998294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2378 2379 1.05598e-05 1.88709 -0.219795 -0.0648679 -0.000422593 0.0158529 0.997768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2379 2380 -0.0247504 1.86088 -0.2391 -0.0668138 0.00646111 0.0112073 0.997682 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2380 2381 -0.026229 1.86456 -0.2332 -0.0671535 0.00367474 0.00802957 0.997704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2381 2382 -0.0275728 1.85291 -0.236211 -0.0635826 -0.00446266 0.0127533 0.997885 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2382 2383 -0.0120487 1.81439 -0.244495 -0.0571843 -0.00107438 0.00496937 0.998351 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2383 2384 -0.0306147 1.81101 -0.249429 -0.063482 0.000531528 0.0146939 0.997875 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2384 2385 -0.00962479 1.78053 -0.24559 -0.0672471 -0.000554108 0.01029 0.997683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2385 2386 -0.00302005 1.78305 -0.232724 -0.0644844 0.00452016 0.0119014 0.997838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2386 2387 -0.0201111 1.76164 -0.259284 -0.0705391 0.00804926 0.00783623 0.997446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2387 2388 -0.0287873 1.74339 -0.214929 -0.0634073 0.00460973 0.00810555 0.997944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2388 2389 -0.0176869 1.74082 -0.224199 -0.0688835 0.0036334 0.00621373 0.997599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2389 2390 -0.0132377 1.72251 -0.235176 -0.0644005 -0.00529733 0.00845367 0.997874 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2390 2391 -0.00910474 1.68838 -0.238842 -0.0683009 -0.00282107 0.0118054 0.997591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2391 2392 -0.0166695 1.67142 -0.225656 -0.0661729 0.00988018 0.0109429 0.997699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2392 2393 -0.00698102 1.66992 -0.212514 -0.0665962 -0.00248529 0.00696031 0.997753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2393 2394 -0.0374605 1.6368 -0.229131 -0.0574692 0.00703333 0.0177379 0.998165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2394 2395 -0.0279955 1.63572 -0.211689 -0.0695404 -0.00124615 0.0159834 0.99745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2395 2396 -0.0249403 1.61453 -0.237822 -0.0724353 -0.0105818 0.0115312 0.99725 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2396 2397 -0.0153312 1.58436 -0.231248 -0.0608913 0.00348781 0.0117495 0.998069 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2397 2398 0.00307334 1.58689 -0.215936 -0.0624717 0.00120799 0.00736055 0.998019 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2398 2399 -0.0136429 1.56316 -0.224509 -0.0674953 0.000181046 0.00864317 0.997682 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2399 2400 -0.00453951 1.55895 -0.230468 -0.0672808 -0.00721585 0.00396941 0.9977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2400 2401 -0.0249525 1.55131 -0.226842 -0.0636633 0.00105285 0.00651301 0.99795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2401 2402 -0.012706 1.51815 -0.212145 -0.0714325 -0.00204387 0.00672156 0.997421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2402 2403 -0.000731215 1.513 -0.237939 -0.0587688 -0.000155 0.0129135 0.998188 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2403 2404 -0.0165711 1.48619 -0.217819 -0.0619334 0.00589158 0.00199312 0.998061 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2404 2405 -0.0251824 1.48396 -0.196044 -0.0580756 0.00978935 0.0126193 0.998184 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2405 2406 -0.0237338 1.46351 -0.204984 -0.0720636 0.0101697 0.00932109 0.997305 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2406 2407 -0.00168737 1.44782 -0.224776 -0.0581947 0.00288402 0.0117481 0.998232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2407 2408 -0.0114313 1.43435 -0.198191 -0.0596261 -0.00227794 0.00619598 0.998199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2408 2409 -0.0331815 1.41735 -0.217942 -0.0716923 -0.00559553 0.00505175 0.997398 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2409 2410 0.000324446 1.40753 -0.19731 -0.0589373 0.0157617 0.00699975 0.998113 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2410 2411 -0.019787 1.3813 -0.221955 -0.0582019 -0.00145241 0.00677603 0.998281 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2411 2412 -0.0165524 1.35056 -0.219595 -0.0649435 0.0135692 0.0161267 0.997666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2412 2413 -0.0109763 1.34948 -0.224082 -0.0622714 0.00592479 0.0063592 0.998021 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2413 2414 -0.0245026 1.32816 -0.217471 -0.0583295 -0.00190362 0.0100041 0.998245 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2414 2415 -0.0107509 1.33584 -0.213942 -0.0613586 -0.00174849 0.00246451 0.998111 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2415 2416 -0.00396607 1.30957 -0.18587 -0.0596353 -0.00151642 0.00652363 0.998198 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2416 2417 0.0123961 1.2831 -0.208445 -0.0537999 -0.00179716 0.00354032 0.998544 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2417 2418 -0.0159728 1.27426 -0.206173 -0.0656284 -0.000314691 0.00837286 0.997809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2418 2419 -0.0276632 1.25915 -0.212619 -0.0665035 0.0116921 0.0128886 0.997634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2419 2420 -0.0106698 1.24147 -0.21368 -0.0544724 0.000250058 0.0115746 0.998448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2420 2421 -0.0103035 1.22672 -0.211924 -0.0675873 0.00157981 0.0158763 0.997586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2421 2422 0.00345691 1.22069 -0.221334 -0.0688866 -0.000840879 -0.00386617 0.997617 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2422 2423 0.00193005 1.19092 -0.227719 -0.0595908 0.000724972 0.0050075 0.99821 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2423 2424 -0.00182281 1.19237 -0.182929 -0.0622892 0.00377673 0.00384716 0.998044 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2424 2425 0.00185336 1.15708 -0.18545 -0.0584276 0.00486689 0.0135503 0.998188 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2425 2426 -0.00653584 1.13404 -0.192469 -0.0641096 -0.00127488 -0.000479379 0.997942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2426 2427 -0.016596 1.13796 -0.214342 -0.0530662 0.000776419 0.00399708 0.998583 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2427 2428 -0.0154461 1.13844 -0.179603 -0.0611027 0.00686653 0.00240654 0.998105 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2428 2429 0.00650046 1.10016 -0.192405 -0.0621183 0.00151062 0.0133247 0.997979 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2429 2430 0.00299829 1.09624 -0.202766 -0.055551 0.00883404 0.00994274 0.998367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2430 2431 -0.0128351 1.05933 -0.206643 -0.0540465 -0.00163874 0.00276832 0.998533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2431 2432 0.0144428 1.05969 -0.182366 -0.064458 -0.00167781 0.00761433 0.99789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2432 2433 -0.0120358 1.05163 -0.194603 -0.0645388 -0.00523652 0.0127848 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2433 2434 -0.00514284 1.00566 -0.177526 -0.0650083 0.00727943 0.00032873 0.997858 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2434 2435 0.0015388 1.00492 -0.189001 -0.059619 -0.00526388 0.00818258 0.998174 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2435 2436 -0.00472849 0.994078 -0.191027 -0.0673342 0.0042672 0.00155172 0.99772 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2436 2437 -0.00856887 0.963742 -0.193124 -0.059112 -0.00663215 0.0130283 0.998144 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2437 2438 -0.00380726 0.957774 -0.187613 -0.0635057 -0.00166687 0.00249528 0.997977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2438 2439 0.00129605 0.937325 -0.195371 -0.0559123 -0.00259067 0.0128161 0.99835 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2439 2440 -0.0149306 0.927259 -0.195807 -0.0569728 0.00113557 0.0083826 0.99834 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2440 2441 0.00141719 0.898692 -0.184601 -0.0591088 -0.00352991 0.00419877 0.998236 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2441 2442 -0.020517 0.888308 -0.174515 -0.0619157 0.0051247 0.00471112 0.998057 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2442 2443 -0.0127522 0.855658 -0.199334 -0.0666383 0.000446605 0.00787865 0.997746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2443 2444 0.0033362 0.873099 -0.207558 -0.054159 0.00837822 0.00100584 0.998497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2444 2445 -0.0273777 0.857931 -0.19796 -0.0655807 -0.000147674 0.00753533 0.997819 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2445 2446 -0.0229509 0.83067 -0.194288 -0.0649545 0.00306768 0.00858183 0.997847 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2446 2447 -0.00125994 0.831779 -0.182219 -0.0592898 0.00203712 0.000236107 0.998239 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2447 2448 0.0120642 0.794886 -0.177115 -0.0636577 -0.000813708 0.0111847 0.997909 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2448 2449 -0.0129457 0.784197 -0.184153 -0.0558071 -0.00228111 0.00213574 0.998437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2449 2450 -0.0085844 0.771693 -0.166684 -0.0628574 -0.00216448 0.00756222 0.997992 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2450 2451 0.00660324 0.770968 -0.157219 -0.0675431 -0.000127101 0.00481167 0.997705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2451 2452 0.00528957 0.719502 -0.159974 -0.0630548 0.00695519 0.000675151 0.997986 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2452 2453 -0.00805983 0.718295 -0.172748 -0.0635118 -0.00278224 -0.00234617 0.997974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2453 2454 0.0113792 0.721264 -0.171398 -0.0555501 -0.0035976 0.0092691 0.998406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2454 2455 0.000737761 0.689814 -0.165207 -0.0539742 0.000581176 0.00904184 0.998501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2455 2456 -0.00916325 0.674218 -0.157724 -0.0657498 -0.000749201 0.00566122 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2456 2457 8.76612e-05 0.651126 -0.156424 -0.0550875 0.00149429 0.00231494 0.998478 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2457 2458 0.00227752 0.631809 -0.170131 -0.0669078 0.00308589 0.00309172 0.99775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2458 2459 -0.0145971 0.629485 -0.163177 -0.0662708 -0.00508454 0.00568115 0.997773 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2459 2460 0.00014494 0.635255 -0.16464 -0.0621061 6.93344e-05 0.00416161 0.998061 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2460 2461 -0.00444925 0.614087 -0.162881 -0.0640791 -0.00539392 0.00210622 0.997928 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2461 2462 -0.00727086 0.587625 -0.135117 -0.0619048 0.00247123 0.00461393 0.998068 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2462 2463 -0.00254095 0.578337 -0.164636 -0.0699608 -0.00212936 0.0041484 0.997539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2463 2464 0.0185403 0.556623 -0.160226 -0.0658124 0.00538051 -0.00394785 0.99781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2464 2465 0.0120114 0.510115 -0.154702 -0.0691847 -0.00222139 0.00982482 0.997553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2465 2466 -0.00563243 0.518615 -0.164631 -0.0638308 -0.00374548 0.00875366 0.997915 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2466 2467 -0.00206689 0.506357 -0.145554 -0.0555803 -0.00307136 0.00273264 0.998446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2467 2468 0.00175168 0.48578 -0.146489 -0.0584705 -0.00314801 0.00780622 0.998254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2468 2469 0.00458167 0.490527 -0.161359 -0.0619896 0.00018694 -0.0012125 0.998076 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2469 2470 -0.000628845 0.447949 -0.157802 -0.0534607 0.0104008 0.0129393 0.998432 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2470 2471 -0.0149297 0.440928 -0.155105 -0.0548525 0.00504482 0.00559656 0.998466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2471 2472 0.0232722 0.430848 -0.148466 -0.0569233 0.00721336 0.00739711 0.998325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2472 2473 0.0110318 0.403657 -0.14545 -0.0546444 0.00094029 -0.00477219 0.998494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2473 2474 -0.00698234 0.396116 -0.158854 -0.0796345 0.00124623 0.00554116 0.996808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2474 2475 -0.0175854 0.379299 -0.143034 -0.0613224 -0.00388068 0.00714827 0.998085 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2475 2476 0.013075 0.35158 -0.156754 -0.0646577 0.00059316 -0.00262377 0.997904 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2476 2477 -0.00645834 0.347384 -0.145339 -0.0621581 -0.00062973 0.000511581 0.998066 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2477 2478 0.0201673 0.327639 -0.150656 -0.0646106 -0.000985668 -0.0017836 0.997908 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2478 2479 0.0031719 0.313375 -0.142252 -0.0555276 -0.00166764 0.00445121 0.998446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2479 2480 0.00471341 0.29425 -0.135793 -0.0656436 0.000183657 0.00793498 0.997812 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2480 2481 -0.0195058 0.279942 -0.145439 -0.0678927 -0.00196451 0.000826965 0.99769 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2481 2482 0.00419484 0.252312 -0.156028 -0.0602429 0.00287834 0.00371631 0.998173 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2482 2483 -0.00217221 0.248205 -0.138791 -0.0672179 -0.00529898 0.00549988 0.997709 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2483 2484 -0.0189687 0.255171 -0.148241 -0.0586552 -0.00203916 -7.13742e-05 0.998276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2484 2485 -0.00557133 0.207305 -0.149876 -0.0617244 -0.00055917 0.00319056 0.998088 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2485 2486 -0.00213888 0.228391 -0.122391 -0.0718272 0.0117198 0.00994929 0.997299 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2486 2487 0.00769515 0.188124 -0.126855 -0.0646577 -0.00247716 -0.00579828 0.997888 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2487 2488 -0.000393853 0.187724 -0.125024 -0.0601012 0.00976057 0.00620577 0.998125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2488 2489 -0.00278706 0.164844 -0.13627 -0.071325 0.00135959 0.00202546 0.99745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2489 2490 0.0167329 0.136547 -0.141292 -0.0640144 0.0044557 -0.00932888 0.997895 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2490 2491 0.00516916 0.122688 -0.132069 -0.0691161 0.00379202 -0.00140615 0.9976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2491 2492 -0.00839165 0.124373 -0.127345 -0.0689061 0.00266713 0.00643724 0.997599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2492 2493 -0.011241 0.110057 -0.138553 -0.0675322 -0.00422545 0.00409273 0.9977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2493 2494 -0.000541241 0.0923869 -0.128459 -0.0691966 -0.00289259 -0.00331163 0.997593 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2494 2495 0.00390015 0.0635246 -0.130154 -0.0666107 -0.00417418 -0.00278427 0.997766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2495 2496 0.00348926 0.0642911 -0.133886 -0.0626206 -0.00591355 -0.00214941 0.998018 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2496 2497 0.0116473 0.034868 -0.119443 -0.0576614 -0.00454476 -0.00774931 0.998296 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2497 2498 -0.0136167 0.00633132 -0.125207 -0.0559637 0.000163591 -0.00208607 0.998431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2498 2499 -0.00957153 -0.00565329 -0.125318 -0.0663054 -0.00258254 -0.00322858 0.997791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 0 49 -0.18688 -0.785666 -6.10663 -0.0634389 0.0313134 0.00554102 0.997479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 0 50 -0.191715 -0.0168316 -6.28073 0.0095615 0.0327846 -0.00227844 0.999414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 0 51 -0.201274 0.837023 -6.34681 0.0690283 0.024843 -0.0112888 0.997241 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1 50 -0.191722 -0.819867 -6.10514 -0.0573867 0.0352294 0.00594449 0.997713 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1 51 -0.201528 -0.0217524 -6.27144 0.00493183 0.029743 -0.000142077 0.999545 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1 52 -0.215874 0.82727 -6.37016 0.0732192 0.0360505 -0.0034527 0.996658 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2 51 -0.181503 -0.822054 -6.1123 -0.0650427 0.0303852 -0.00416144 0.997411 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2 52 -0.18908 0.000212053 -6.28081 0.00125611 0.0210642 -0.00257388 0.999774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2 53 -0.193676 0.837063 -6.35056 0.0625562 0.0362898 0.000359254 0.997381 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 3 52 -0.215462 -0.808307 -6.09596 -0.0677375 0.0281708 -0.0100529 0.997255 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 3 53 -0.190249 -0.00808606 -6.27865 0.000774957 0.0309579 0.0027787 0.999517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 3 54 -0.224556 0.879206 -6.33942 0.0601618 0.0383999 0.00732957 0.997423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 4 53 -0.194921 -0.848132 -6.10744 -0.0599846 0.0236082 -0.00427687 0.997911 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 4 54 -0.2225 0.0108943 -6.28253 0.00204014 0.0252973 -0.0040248 0.99967 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 4 55 -0.204844 0.881356 -6.33544 0.065532 0.035438 0.00689811 0.997197 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 5 54 -0.188323 -0.854225 -6.08747 -0.068382 0.0313437 -0.0064405 0.997146 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 5 55 -0.201119 0.00183154 -6.27601 0.00104083 0.0275034 0.00804894 0.999589 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 5 56 -0.215396 0.89391 -6.35499 0.0587027 0.0354983 -0.00400623 0.997636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 6 55 -0.205272 -0.886845 -6.0905 -0.0683778 0.0384617 -0.00417681 0.996909 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 6 56 -0.202921 -0.00249254 -6.25593 0.00619368 0.0336276 -0.000986495 0.999415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 6 57 -0.22054 0.922247 -6.34398 0.0650948 0.0358822 0.00346229 0.997228 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 7 56 -0.199476 -0.902424 -6.10297 -0.0661339 0.0274632 0.0036125 0.997426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 7 57 -0.191174 -0.00159949 -6.27939 0.00686357 0.0276394 0.00563675 0.999579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 7 58 -0.187703 0.931404 -6.35843 0.055422 0.030164 0.00235085 0.998005 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 8 57 -0.194166 -0.889034 -6.10629 -0.0627376 0.0293799 -0.00136432 0.997597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 8 58 -0.202832 0.0323491 -6.27365 0.00108007 0.043306 -0.00674213 0.999039 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 8 59 -0.208174 0.923939 -6.34936 0.0675521 0.0354051 0.00340952 0.997082 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 9 58 -0.191627 -0.933621 -6.09277 -0.0664096 0.0239121 -0.000105256 0.997506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 9 59 -0.180942 0.00593056 -6.28324 0.00080697 0.0271192 -0.00302816 0.999627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 9 60 -0.216199 0.960628 -6.34725 0.0687796 0.0223735 0.00528952 0.997367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 10 59 -0.200962 -0.92273 -6.0857 -0.0664692 0.0326801 -0.00793356 0.997222 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 10 60 -0.197595 0.00711517 -6.27666 -0.00618841 0.035464 -0.0132697 0.999264 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 10 61 -0.208718 0.972059 -6.36035 0.0604622 0.0337144 -0.00322537 0.997596 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 11 60 -0.182273 -0.963164 -6.0966 -0.0648099 0.0297926 -0.00336903 0.997447 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 11 61 -0.206581 -0.0164949 -6.26986 0.00422065 0.0260259 -0.0163371 0.999519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 11 62 -0.188366 0.987093 -6.35157 0.0640534 0.0275194 0.000393845 0.997567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 12 61 -0.194003 -0.975849 -6.08053 -0.0636039 0.0340618 -0.00454818 0.997383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 12 62 -0.205487 -0.00455972 -6.27529 -0.00976208 0.031606 0.00803895 0.99942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 12 63 -0.187474 1.01472 -6.3449 0.0658709 0.0335993 0.00872786 0.997224 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 13 62 -0.198774 -1.00295 -6.09658 -0.0607965 0.036179 -0.000829264 0.997494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 13 63 -0.190128 0.00374673 -6.276 -0.00390946 0.0255091 -6.53739e-05 0.999667 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 13 64 -0.212924 1.03032 -6.36584 0.0526024 0.0370502 0.00646355 0.997907 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 14 63 -0.201383 -0.998452 -6.08613 -0.0615655 0.0314482 -0.007394 0.99758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 14 64 -0.188257 0.0028504 -6.29186 -0.00215053 0.0263744 0.00492419 0.999638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 14 65 -0.20583 1.04744 -6.33621 0.0643904 0.0302589 -0.000236517 0.997466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 15 64 -0.186204 -1.00189 -6.09392 -0.0638121 0.0370705 -0.00390584 0.997266 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 15 65 -0.211968 0.00588865 -6.2761 -0.0065415 0.0340622 -0.00147881 0.999397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 15 66 -0.194841 1.05425 -6.34815 0.068335 0.0392901 0.000954368 0.996888 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 16 65 -0.182257 -1.0533 -6.09902 -0.0650281 0.0352601 0.00293072 0.997256 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 16 66 -0.192668 -0.0184691 -6.27303 -0.00366828 0.036349 -0.00176074 0.999331 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 16 67 -0.202599 1.06741 -6.35273 0.0618217 0.0335508 -0.00141289 0.997522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 17 66 -0.187523 -1.05418 -6.07253 -0.0668575 0.0306219 -0.00269535 0.997289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 17 67 -0.197258 -0.0104699 -6.27889 -0.00620723 0.0364571 0.00514586 0.999303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 17 68 -0.20878 1.09022 -6.3463 0.0614335 0.036666 0.00266444 0.997434 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 18 67 -0.181957 -1.07153 -6.07535 -0.0660612 0.0299444 -9.23381e-05 0.997366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 18 68 -0.209801 0.00651952 -6.29626 -0.0003264 0.0374483 0.00360828 0.999292 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 18 69 -0.212371 1.08781 -6.34108 0.0651181 0.0342068 0.00521096 0.997277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 19 68 -0.205226 -1.09358 -6.09278 -0.0596309 0.0267311 -0.0131204 0.997776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 19 69 -0.209554 -0.000799323 -6.26978 0.00226498 0.0410247 -0.00640109 0.999135 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 19 70 -0.195891 1.10395 -6.33932 0.0642206 0.031466 0.00576658 0.997423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 20 69 -0.19739 -1.117 -6.08064 -0.0603232 0.0270008 -0.00234063 0.997811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 20 70 -0.200229 0.0115181 -6.28146 -0.00185141 0.0241226 0.0038666 0.9997 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 20 71 -0.21702 1.15897 -6.32387 0.0632967 0.0338132 0.00574194 0.997405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 21 70 -0.191078 -1.11393 -6.08664 -0.0596107 0.0278717 -0.00466438 0.997822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 21 71 -0.215468 0.0236066 -6.27326 0.00800245 0.0328949 0.00400498 0.999419 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 21 72 -0.21076 1.14314 -6.34782 0.0612059 0.0345082 -0.0020636 0.997526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 22 71 -0.19457 -1.13265 -6.0847 -0.0573723 0.030839 -0.00234897 0.997874 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 22 72 -0.207883 -0.00677492 -6.26688 -0.00209835 0.0286987 0.00464373 0.999575 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 22 73 -0.212733 1.15118 -6.32039 0.0605856 0.039478 0.00900134 0.997341 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 23 72 -0.194935 -1.1372 -6.09265 -0.0671319 0.0319163 -0.00125009 0.997233 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 23 73 -0.211175 0.00950392 -6.26431 0.014895 0.0284985 0.000187221 0.999483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 23 74 -0.209242 1.16974 -6.31811 0.0577727 0.0313282 -0.0105676 0.997782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 24 73 -0.195235 -1.16689 -6.07637 -0.0637996 0.0323487 -0.000900975 0.997438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 24 74 -0.18628 -0.00413338 -6.27122 0.0011828 0.0283127 -0.00205927 0.999596 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 24 75 -0.205799 1.20681 -6.34971 0.0601237 0.0351396 0.00633204 0.997552 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 25 74 -0.19804 -1.17015 -6.06617 -0.0573753 0.0320828 -0.00648535 0.997816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 25 75 -0.194525 -0.00739665 -6.28208 -0.00406287 0.0369486 -0.00044446 0.999309 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 25 76 -0.202103 1.19526 -6.32304 0.0558623 0.0389466 0.0137009 0.997585 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 26 75 -0.181981 -1.20245 -6.07601 -0.0672652 0.0301885 -0.0128801 0.997195 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 26 76 -0.198017 0.00435359 -6.27823 -0.00432198 0.0351608 0.000634631 0.999372 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 26 77 -0.202015 1.23053 -6.32362 0.0646235 0.0346525 0.0108854 0.997248 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 27 76 -0.185895 -1.22683 -6.09964 -0.0624888 0.0338681 -0.0102537 0.997418 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 27 77 -0.193677 0.00865083 -6.29072 0.00292846 0.0242979 0.0133971 0.999611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 27 78 -0.194871 1.24085 -6.3294 0.0617774 0.0317555 0.00900423 0.997544 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 28 77 -0.196756 -1.21337 -6.08756 -0.0642598 0.0349161 -0.00735139 0.997295 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 28 78 -0.205208 0.00445145 -6.26881 0.00413125 0.0265085 0.00873066 0.999602 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 28 79 -0.217373 1.2653 -6.33519 0.0571531 0.0313927 0.0123256 0.997796 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 29 78 -0.191342 -1.24254 -6.06521 -0.0528226 0.0382797 -0.0151759 0.997755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 29 79 -0.191498 -0.0123912 -6.2855 0.0045733 0.0260121 -0.00241453 0.999648 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 29 80 -0.21352 1.27417 -6.33794 0.0665946 0.0388597 -0.00162923 0.997022 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 30 79 -0.192594 -1.25483 -6.06476 -0.0625336 0.0200276 -0.00619011 0.997823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 30 80 -0.198029 -0.00374412 -6.27918 0.00536131 0.0307716 0.00304772 0.999507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 30 81 -0.212804 1.30262 -6.31029 0.0620411 0.0320737 0.00331125 0.997553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 31 80 -0.186467 -1.26075 -6.07586 -0.053398 0.0344326 0.000232546 0.997979 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 31 81 -0.206031 0.00100065 -6.29737 -0.00406951 0.0334057 -0.0076364 0.999404 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 31 82 -0.210914 1.29845 -6.29877 0.0576813 0.0344966 0.00564768 0.997723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 32 81 -0.191154 -1.27844 -6.07185 -0.0619218 0.0405383 -0.003865 0.99725 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 32 82 -0.195954 0.00640142 -6.2819 0.0011004 0.0228618 -0.00610665 0.999719 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 32 83 -0.201108 1.31651 -6.33175 0.061451 0.0380737 0.00276614 0.99738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 33 82 -0.196045 -1.30452 -6.06865 -0.060856 0.0278152 -0.0199908 0.997559 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 33 83 -0.201459 0.0163825 -6.28816 5.50053e-05 0.0273739 0.00652202 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 33 84 -0.208652 1.32988 -6.29886 0.0592055 0.0328323 0.00196612 0.997704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 34 83 -0.213147 -1.32169 -6.05758 -0.0715349 0.0276073 -0.00488553 0.997044 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 34 84 -0.192381 -0.0151653 -6.29065 -0.00549071 0.034762 -0.00233395 0.999378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 34 85 -0.195364 1.35362 -6.31852 0.0700711 0.0347746 -0.00141794 0.996935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 35 84 -0.20726 -1.32005 -6.07166 -0.0650707 0.0279555 -0.004155 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 35 85 -0.208366 -0.00824626 -6.27365 0.0065393 0.0278162 0.00823428 0.999558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 35 86 -0.220118 1.37187 -6.33423 0.0696144 0.0244847 0.0077389 0.997243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 36 85 -0.19916 -1.36422 -6.05652 -0.0559931 0.0245258 -0.00378533 0.998123 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 36 86 -0.193524 0.00536102 -6.25967 -0.00291946 0.0274615 -0.00421791 0.99961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 36 87 -0.202466 1.39299 -6.31948 0.0669224 0.0331162 0.00581195 0.997192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 37 86 -0.194159 -1.3655 -6.06518 -0.0666713 0.0348894 -0.00717746 0.997139 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 37 87 -0.197532 -0.000222589 -6.2835 0.0113684 0.0332473 0.00252254 0.999379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 37 88 -0.205942 1.3918 -6.32702 0.0667744 0.0271362 0.000619932 0.997399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 38 87 -0.204915 -1.38275 -6.06987 -0.0621694 0.0299673 -0.00325045 0.99761 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 38 88 -0.20287 -0.000805543 -6.2822 0.00711 0.0278609 -0.00468714 0.999576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 38 89 -0.208752 1.41334 -6.3218 0.063269 0.0289869 0.00816152 0.997542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 39 88 -0.206619 -1.40845 -6.05718 -0.0608631 0.0298767 -0.00777685 0.997669 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 39 89 -0.18849 0.0104824 -6.26375 0.00382273 0.0292353 0.00394266 0.999557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 39 90 -0.218201 1.42449 -6.31658 0.0524598 0.0279841 0.0116314 0.998163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 40 89 -0.201927 -1.40362 -6.05092 -0.0637554 0.0299916 0.00603747 0.997497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 40 90 -0.180176 -0.00530676 -6.28063 -0.00305045 0.0229874 -0.00525332 0.999717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 40 91 -0.2182 1.44369 -6.29309 0.0662815 0.023811 0.00731224 0.99749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 41 90 -0.190629 -1.42621 -6.07487 -0.0696284 0.032424 -0.0125068 0.996967 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 41 91 -0.203152 -0.00947094 -6.27063 -0.00312229 0.0342682 -0.00314907 0.999403 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 41 92 -0.211735 1.48245 -6.32162 0.0583648 0.0316424 0.0106313 0.997737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 42 91 -0.196966 -1.45065 -6.06187 -0.0668954 0.0306614 -0.00825131 0.997255 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 42 92 -0.201043 -0.00594881 -6.283 -0.00537304 0.0285902 -0.0040841 0.999568 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 42 93 -0.200164 1.46304 -6.3232 0.0636482 0.0252624 0.00418334 0.997644 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 43 92 -0.191808 -1.46228 -6.05948 -0.0631365 0.0350458 -0.00983015 0.997341 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 43 93 -0.169511 0.00875259 -6.25357 0.00173682 0.0303464 0.00274615 0.999534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 43 94 -0.203374 1.48924 -6.30375 0.0610052 0.0297843 0.00172093 0.997691 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 44 93 -0.196682 -1.46924 -6.05929 -0.0654701 0.040923 -0.00985015 0.996966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 44 94 -0.195133 -0.0101016 -6.27858 0.0104522 0.041751 -0.00164582 0.999072 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 44 95 -0.215638 1.5135 -6.31366 0.0670066 0.0372578 0.000554494 0.997056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 45 94 -0.207872 -1.50645 -6.06273 -0.0652725 0.0342531 -0.00759089 0.997251 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 45 95 -0.196126 -0.00319449 -6.27732 6.44678e-05 0.0215 0.00155525 0.999768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 45 96 -0.220407 1.52656 -6.31916 0.06606 0.0294866 -0.00783736 0.997349 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 46 95 -0.202491 -1.5031 -6.05052 -0.0741115 0.0369997 -0.0127287 0.996482 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 46 96 -0.196178 0.0159329 -6.28142 -0.00530659 0.0327307 -0.0073037 0.999423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 46 97 -0.215683 1.53681 -6.30195 0.0695497 0.0370682 0.0054806 0.996874 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 47 96 -0.19179 -1.52105 -6.06758 -0.0595459 0.0295275 -0.00502202 0.997776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 47 97 -0.192435 -0.00333299 -6.26643 0.000829472 0.0230722 -0.00311655 0.999729 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 47 98 -0.20865 1.55485 -6.30653 0.0676217 0.030089 0.00330795 0.997252 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 48 97 -0.191032 -1.52875 -6.05474 -0.0544516 0.0206883 -0.0113766 0.998237 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 48 98 -0.196765 -0.000498467 -6.28318 0.00838514 0.0245292 0.000286499 0.999664 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 48 99 -0.208309 1.55579 -6.3108 0.0686481 0.0335661 0.0123546 0.997 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 49 98 -0.198033 -1.57344 -6.05161 -0.0581171 0.0358091 0.00197605 0.997665 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 49 99 -0.196477 0.00555638 -6.27078 -0.0054298 0.0284617 -0.00904554 0.999539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 49 100 -0.21886 1.58938 -6.31605 0.0705371 0.0253247 0.00237943 0.997185 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 50 99 -0.209546 -1.56695 -6.05245 -0.0648521 0.0377135 -0.00854615 0.997145 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 50 100 -0.194543 0.0119318 -6.27841 -0.00299515 0.0350211 0.0017732 0.999381 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 50 101 -0.221134 1.61958 -6.30556 0.0598606 0.0290003 0.00202876 0.997783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 51 100 -0.188261 -1.56546 -6.06344 -0.0640243 0.0232521 -0.00280402 0.997673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 51 101 -0.202874 -0.00626525 -6.28666 0.00639858 0.0276065 -0.00394013 0.999591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 51 102 -0.199542 1.60833 -6.31888 0.0514968 0.02592 0.00947675 0.998292 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 52 101 -0.199432 -1.61047 -6.04271 -0.0625261 0.0315649 -0.00680941 0.997521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 52 102 -0.211732 0.0038948 -6.28501 0.00538963 0.0287904 -0.000651809 0.999571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 52 103 -0.210267 1.62072 -6.30678 0.0686108 0.0305876 0.0129557 0.99709 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 53 102 -0.177732 -1.6223 -6.05526 -0.0595758 0.0378999 -0.00214462 0.997502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 53 103 -0.207826 -0.00515829 -6.27185 -0.0029781 0.0388853 0.00417101 0.999231 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 53 104 -0.207882 1.63626 -6.2988 0.0600576 0.034961 0.0105292 0.997527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 54 103 -0.178067 -1.61508 -6.05499 -0.0551849 0.0249041 -0.0107471 0.998108 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 54 104 -0.208471 -0.0112628 -6.27693 -0.00446534 0.03007 -0.00141071 0.999537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 54 105 -0.209759 1.6721 -6.31367 0.0633087 0.0387537 -0.000682986 0.997241 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 55 104 -0.182384 -1.63153 -6.05715 -0.0635436 0.0372429 -0.00214161 0.997282 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 55 105 -0.191675 0.00256149 -6.28893 -0.000522853 0.0383645 -0.00696319 0.999239 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 55 106 -0.209797 1.67594 -6.28432 0.058676 0.0351673 0.00901804 0.997617 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 56 105 -0.214493 -1.66074 -6.029 -0.0546251 0.0379648 -0.00288902 0.997781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 56 106 -0.198959 -0.00881912 -6.27227 -0.000882006 0.0275581 0.00611495 0.999601 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 56 107 -0.196575 1.69384 -6.30198 0.0541621 0.0331767 0.0128809 0.997898 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 57 106 -0.194601 -1.68955 -6.0426 -0.0632075 0.0319393 -0.00556164 0.997474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 57 107 -0.194457 0.00366992 -6.27434 0.00447141 0.030832 -0.000109065 0.999515 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 57 108 -0.211438 1.72032 -6.28841 0.0678243 0.0238022 0.00658928 0.997392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 58 107 -0.214303 -1.69404 -6.0525 -0.0572001 0.0244497 -0.00547537 0.998048 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 58 108 -0.210272 -0.00995758 -6.27667 -0.00133909 0.0198672 -0.00790901 0.99977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 58 109 -0.216715 1.72337 -6.29496 0.0659077 0.0288094 0.00981203 0.997361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 59 108 -0.200187 -1.70851 -6.0619 -0.0581593 0.0232122 -0.0120835 0.997964 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 59 109 -0.204302 -0.00518483 -6.28242 -0.0026805 0.0259395 -0.000896928 0.99966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 59 110 -0.202534 1.73712 -6.28239 0.0573964 0.026324 0.0178107 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 60 109 -0.196423 -1.72834 -6.0409 -0.0684466 0.0318119 -0.0107552 0.997089 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 60 110 -0.184247 -0.00532749 -6.29041 0.00294829 0.03013 0.00515629 0.999528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 60 111 -0.223845 1.74549 -6.28541 0.0504252 0.0284476 0.00885418 0.998283 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 61 110 -0.200067 -1.7293 -6.04113 -0.0643731 0.026644 -0.00507647 0.997557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 61 111 -0.205878 -0.00881864 -6.2832 -0.000418995 0.0446834 0.0136229 0.998908 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 61 112 -0.218703 1.77309 -6.29117 0.0630173 0.0293224 0.013247 0.997494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 62 111 -0.203163 -1.77265 -6.04798 -0.0632695 0.0297039 -0.00343824 0.997548 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 62 112 -0.203748 -0.00312341 -6.27099 9.31079e-06 0.0324055 -0.00288072 0.999471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 62 113 -0.202317 1.79091 -6.30521 0.0668386 0.0206198 0.0147314 0.997442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 63 112 -0.202543 -1.75684 -6.0339 -0.0572372 0.0342221 -0.0054229 0.997759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 63 113 -0.189351 0.012399 -6.28501 0.000954498 0.0257302 -0.00316158 0.999663 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 63 114 -0.227979 1.80803 -6.29996 0.0648482 0.0296841 0.0129041 0.99737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 64 113 -0.197633 -1.7894 -6.04305 -0.0707177 0.0341941 -0.0111645 0.996848 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 64 114 -0.192397 -0.000770138 -6.27853 -0.000162579 0.0315227 0.00370093 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 64 115 -0.224406 1.83703 -6.28703 0.0565729 0.0321577 0.00661227 0.997859 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 65 114 -0.196057 -1.80117 -6.03734 -0.0591579 0.0273427 -0.0137987 0.997779 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 65 115 -0.19252 0.00239186 -6.28638 -0.00484306 0.0336904 -0.00657463 0.999399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 65 116 -0.216651 1.84564 -6.29604 0.0622973 0.0293789 0.0148585 0.997514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 66 115 -0.203092 -1.79979 -6.04125 -0.058916 0.0388462 -0.00582394 0.99749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 66 116 -0.205215 0.003432 -6.3047 0.00666229 0.0364703 0.00307447 0.999308 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 66 117 -0.223104 1.83711 -6.27866 0.0587691 0.0241149 0.0035857 0.997974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 67 116 -0.190689 -1.83489 -6.04508 -0.0642343 0.0370994 -0.00732209 0.997218 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 67 117 -0.207842 0.0105943 -6.26556 0.00956683 0.0359819 -0.00489586 0.999295 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 67 118 -0.217805 1.86469 -6.30596 0.0503197 0.0399785 0.00371665 0.997926 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 68 117 -0.204681 -1.84255 -6.05124 -0.0682415 0.0307855 0.00295255 0.997189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 68 118 -0.198605 0.00709446 -6.28707 0.00647919 0.0313402 -0.00593518 0.99947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 68 119 -0.213927 1.88394 -6.29653 0.0608334 0.0303338 -0.00570996 0.997671 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 69 118 -0.222125 -1.85604 -6.04064 -0.0581326 0.0325937 -0.00333986 0.997771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 69 119 -0.191741 -0.0078099 -6.3007 0.00418954 0.0238328 0.00458917 0.999697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 69 120 -0.195872 1.9004 -6.27673 0.0668983 0.0300279 0.00469554 0.997297 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 70 119 -0.201622 -1.85638 -6.04093 -0.0640242 0.0327387 -0.00627093 0.997391 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 70 120 -0.194936 0.00946878 -6.26857 -0.00026364 0.0418057 0.00650435 0.999105 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 70 121 -0.206978 1.92032 -6.30371 0.0597188 0.0322845 0.0116781 0.997625 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 71 120 -0.19991 -1.89799 -6.03523 -0.0606394 0.0347655 -0.0140925 0.997455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 71 121 -0.210748 0.00257532 -6.28108 -0.00299882 0.0259222 0.00690555 0.999636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 71 122 -0.220141 1.92773 -6.29111 0.0689931 0.0284706 0.0146543 0.997103 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 72 121 -0.207651 -1.90793 -6.03172 -0.0692555 0.033727 -0.0107562 0.996971 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 72 122 -0.194528 -0.0140587 -6.27819 -0.00406391 0.0268969 -0.00137621 0.999629 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 72 123 -0.219696 1.94364 -6.27691 0.0599065 0.0349002 0.00599293 0.997576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 73 122 -0.208829 -1.91723 -6.03843 -0.0637872 0.0274262 -0.0147637 0.997477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 73 123 -0.204232 0.00574155 -6.27561 -0.00400526 0.0384976 0.00350697 0.999245 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 73 124 -0.225775 1.95648 -6.2731 0.0595731 0.0309131 0.00234863 0.997742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 74 123 -0.197583 -1.94004 -6.04074 -0.065673 0.0356096 -0.0119959 0.997133 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 74 124 -0.202921 0.00827966 -6.2755 -0.00318629 0.0238345 0.0065305 0.99969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 74 125 -0.203074 1.97657 -6.29586 0.0578755 0.038011 0.014611 0.997493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 75 124 -0.213499 -1.97276 -6.0249 -0.0674562 0.0306211 -0.00938163 0.997208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 75 125 -0.192442 -0.000210687 -6.27945 -0.00554933 0.0328658 0.00991781 0.999395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 75 126 -0.211048 1.9949 -6.30521 0.0571029 0.0315688 0.00265971 0.997866 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 76 125 -0.191835 -1.98707 -6.04324 -0.0694619 0.0339941 -0.0110601 0.996944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 76 126 -0.179586 0.00819147 -6.27554 0.00211488 0.02907 0.00181877 0.999573 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 76 127 -0.214953 2.01319 -6.2743 0.0635394 0.027567 0.00263596 0.997595 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 77 126 -0.200957 -1.99055 -6.03749 -0.064671 0.0272427 -0.00480347 0.997523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 77 127 -0.207383 -0.00511375 -6.2879 -0.00435906 0.0306988 0.0075455 0.999491 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 77 128 -0.221753 2.02182 -6.25757 0.066771 0.0334005 0.000336371 0.997209 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 78 127 -0.203038 -2.00054 -6.01043 -0.0548467 0.024379 -0.0102154 0.998145 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 78 128 -0.201567 -0.00913586 -6.28938 -0.00356669 0.029969 -0.00243413 0.999542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 78 129 -0.212089 2.0367 -6.2699 0.0629765 0.0275433 0.00668956 0.997612 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 79 128 -0.195463 -2.02728 -6.02231 -0.0683077 0.0338733 -0.00695867 0.997065 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 79 129 -0.188984 0.000738704 -6.29326 0.00143293 0.0343309 0.000419762 0.999409 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 79 130 -0.22992 2.0605 -6.28872 0.0577694 0.0308741 0.00787248 0.997821 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 80 129 -0.19308 -2.03726 -6.01173 -0.0627946 0.0269256 -0.00675154 0.99764 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 80 130 -0.198235 -0.00425762 -6.27836 -0.00777758 0.0372624 -0.00822495 0.999241 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 80 131 -0.218461 2.06696 -6.28647 0.0656608 0.0369263 0.0120973 0.997085 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 81 130 -0.211385 -2.0477 -6.01898 -0.0675668 0.0336101 -0.0077012 0.997119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 81 131 -0.197397 -0.00418715 -6.27427 -0.00222573 0.0273372 -0.00584926 0.999607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 81 132 -0.227951 2.07544 -6.28886 0.0652863 0.027983 -0.0119356 0.997403 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 82 131 -0.213769 -2.09116 -6.02843 -0.0628429 0.0321869 -0.0119563 0.997433 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 82 132 -0.20834 0.0261899 -6.26841 -0.000198139 0.0353651 -0.00857872 0.999338 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 82 133 -0.227516 2.10792 -6.28733 0.0610472 0.039897 0.00634645 0.997317 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 83 132 -0.220959 -2.08756 -6.01952 -0.0641815 0.0282266 -0.00166991 0.997538 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 83 133 -0.19548 0.000704932 -6.28056 1.8813e-05 0.0274948 0.00298107 0.999618 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 83 134 -0.208507 2.12001 -6.25635 0.066576 0.0292106 0.00971873 0.997306 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 84 133 -0.207372 -2.12362 -6.01899 -0.0559433 0.0315067 -0.0122156 0.997862 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 84 134 -0.197267 -0.0128247 -6.27047 -0.00770022 0.0365192 -0.00708618 0.999278 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 84 135 -0.220438 2.14054 -6.2587 0.0659615 0.0260915 -0.000300808 0.997481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 85 134 -0.210648 -2.12461 -6.02009 -0.0691206 0.0451249 -0.0141512 0.996487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 85 135 -0.194551 -0.00185062 -6.27891 -0.00513151 0.035841 -0.000586875 0.999344 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 85 136 -0.216492 2.15568 -6.27854 0.0645764 0.0282667 0.0103416 0.997459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 86 135 -0.201205 -2.12182 -6.02107 -0.06639 0.0371418 -0.00792427 0.997071 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 86 136 -0.198676 0.00901284 -6.27778 0.00269299 0.0356917 -0.00536994 0.999345 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 86 137 -0.221426 2.15138 -6.27351 0.065889 0.0277042 -0.00211626 0.99744 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 87 136 -0.19154 -2.14686 -6.02258 -0.0630187 0.0335641 -0.00628296 0.997428 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 87 137 -0.191753 0.00922372 -6.27522 0.00629048 0.0250359 -0.00829528 0.999632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 87 138 -0.221549 2.18156 -6.28094 0.0621826 0.0240135 0.0111447 0.997714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 88 137 -0.191127 -2.15046 -6.01833 -0.0622953 0.0253678 -0.0075516 0.997707 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 88 138 -0.186825 -0.00637189 -6.28614 -0.00816799 0.0287349 -0.0057312 0.999537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 88 139 -0.215849 2.20679 -6.27278 0.0565426 0.0294253 0.0196272 0.997773 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 89 138 -0.196401 -2.18548 -6.02427 -0.0709066 0.032906 -0.0162044 0.996808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 89 139 -0.202961 -0.0013184 -6.27565 -0.00118805 0.0261496 0.00681216 0.999634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 89 140 -0.22766 2.21404 -6.24756 0.0638413 0.0280579 0.0170446 0.99742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 90 139 -0.216777 -2.19578 -6.02123 -0.0618372 0.0316435 -0.0157895 0.99746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 90 140 -0.187019 0.0220724 -6.27459 -0.000488214 0.0354239 0.00357997 0.999366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 90 141 -0.229068 2.22403 -6.26739 0.0698146 0.0376365 4.40233e-05 0.99685 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 91 140 -0.218968 -2.20863 -6.03026 -0.0715808 0.0331954 -0.0146777 0.996774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 91 141 -0.197316 0.00432701 -6.26981 0.000369766 0.0281471 -0.000454221 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 91 142 -0.238024 2.23754 -6.27621 0.0619904 0.0328799 0.0110128 0.997474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 92 141 -0.210681 -2.22942 -6.01572 -0.0584908 0.0373908 -0.00933318 0.997544 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 92 142 -0.200922 0.0211018 -6.25424 0.00270314 0.0323384 -0.00370732 0.999466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 92 143 -0.222219 2.25094 -6.23778 0.0560586 0.0286309 0.0174277 0.997865 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 93 142 -0.204353 -2.22818 -6.01751 -0.0636589 0.0259042 -0.0140161 0.997537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 93 143 -0.208694 0.00119595 -6.28 0.00507984 0.0359067 0.00772297 0.999312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 93 144 -0.212463 2.25258 -6.26109 0.0689815 0.0252589 0.00438311 0.997288 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 94 143 -0.207648 -2.27317 -6.01303 -0.0534015 0.0331614 -0.0163137 0.997889 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 94 144 -0.19292 0.0130309 -6.28494 0.00548683 0.0396359 -0.00200546 0.999197 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 94 145 -0.228522 2.26789 -6.26988 0.059396 0.0198902 0.00195504 0.998034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 95 144 -0.194649 -2.27583 -6.00316 -0.067888 0.0260092 -0.022451 0.997101 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 95 145 -0.198654 0.0145028 -6.27493 -0.00518296 0.0231737 0.00603188 0.9997 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 95 146 -0.237738 2.2972 -6.27301 0.0600848 0.0402131 0.00848286 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 96 145 -0.217701 -2.30294 -6.01702 -0.0593107 0.0339888 -0.0104074 0.997606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 96 146 -0.188281 0.0101441 -6.26628 -0.00426028 0.0295907 0.00187054 0.999551 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 96 147 -0.220596 2.31588 -6.26548 0.0613219 0.0327728 0.00799437 0.997548 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 97 146 -0.192795 -2.28123 -6.00969 -0.0637485 0.0323905 0.00230432 0.997438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 97 147 -0.182499 0.00796781 -6.28666 -0.00411371 0.0392884 0.00209485 0.999217 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 97 148 -0.209098 2.31668 -6.26341 0.0636742 0.0377562 0.00185516 0.997255 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 98 147 -0.205826 -2.31843 -6.00937 -0.0681861 0.029364 -0.00778541 0.99721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 98 148 -0.201498 -0.0015573 -6.29656 0.00448123 0.0229937 -0.00637363 0.999705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 98 149 -0.217116 2.35691 -6.2691 0.0607546 0.0300867 0.0215401 0.997467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 99 148 -0.184861 -2.32766 -6.00536 -0.0678027 0.0290696 -0.0113353 0.997211 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 99 149 -0.200119 -0.00942475 -6.29434 -0.000381178 0.0281233 -0.00921133 0.999562 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 99 150 -0.236463 2.36166 -6.25502 0.0606535 0.0202217 0.00101454 0.997954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 100 149 -0.20811 -2.36908 -5.99977 -0.0645917 0.0287373 -0.00842285 0.997462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 100 150 -0.19724 0.0142775 -6.27722 -0.00474692 0.0250958 0.00657234 0.999652 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 100 151 -0.228422 2.38128 -6.2525 0.0609814 0.0284246 0.00839827 0.997699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 101 150 -0.205139 -2.35758 -6.00817 -0.0703044 0.0340532 -0.0168386 0.996802 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 101 151 -0.193148 -0.00126417 -6.27405 3.07016e-05 0.0410918 -3.42665e-05 0.999155 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 101 152 -0.221027 2.39079 -6.25915 0.0652579 0.0301885 0.0146919 0.997303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 102 151 -0.19373 -2.39134 -6.00283 -0.065165 0.0327379 0.000533299 0.997337 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 102 152 -0.192854 0.00157587 -6.29624 -0.0018152 0.0265801 -0.00631542 0.999625 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 102 153 -0.236118 2.4004 -6.24869 0.0613863 0.0354562 0.011708 0.997415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 103 152 -0.198669 -2.38804 -6.01063 -0.0673251 0.0335731 -0.00734335 0.997139 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 103 153 -0.198023 -0.00187972 -6.28205 0.00813238 0.0320353 0.00134187 0.999453 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 103 154 -0.214335 2.4156 -6.24463 0.0658038 0.0253926 0.00336273 0.997504 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 104 153 -0.199531 -2.40843 -6.00523 -0.0584558 0.025045 -0.0148732 0.997865 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 104 154 -0.190634 0.0156117 -6.27045 0.00688772 0.0265113 0.00449286 0.999615 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 104 155 -0.226407 2.43047 -6.2474 0.0644651 0.0327809 0.00974604 0.997334 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 105 154 -0.208895 -2.43629 -5.98669 -0.062224 0.0298218 -0.00677503 0.997594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 105 155 -0.190301 -0.00251847 -6.27251 -0.00726459 0.0349076 -0.00830976 0.99933 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 105 156 -0.231922 2.44436 -6.25561 0.0642787 0.0427876 0.0166383 0.996875 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 106 155 -0.219455 -2.43565 -5.99894 -0.0599334 0.0352809 -0.0157363 0.997455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 106 156 -0.189623 -0.00585514 -6.29882 0.00753593 0.0380287 -0.00200059 0.999246 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 106 157 -0.220144 2.47528 -6.23954 0.0542639 0.031235 0.0151617 0.997923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 107 156 -0.210672 -2.45257 -5.99321 -0.0637563 0.0281132 -0.009357 0.997526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 107 157 -0.208533 -0.00595077 -6.28336 0.00784009 0.0340318 0.0084741 0.999354 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 107 158 -0.234901 2.48776 -6.23763 0.0589944 0.0348959 0.0129728 0.997564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 108 157 -0.216507 -2.48523 -5.98433 -0.0532716 0.0341342 -0.0156062 0.997874 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 108 158 -0.202403 -0.0118657 -6.28745 -0.00511032 0.0276019 0.00705868 0.999581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 108 159 -0.231747 2.50371 -6.24688 0.0620576 0.0270198 0.012036 0.997634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 109 158 -0.208775 -2.49049 -5.99129 -0.0565236 0.0296599 -0.00499091 0.997948 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 109 159 -0.189998 0.0149233 -6.2792 -0.000495269 0.0321817 -0.00500869 0.999469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 109 160 -0.233821 2.50256 -6.27937 0.0542396 0.0301427 0.00142962 0.998072 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 110 159 -0.209667 -2.49399 -5.99676 -0.0596119 0.0270522 -0.0146911 0.997747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 110 160 -0.192152 -0.00134715 -6.28702 -0.00491228 0.0334588 0.00601575 0.99941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 110 161 -0.225252 2.53679 -6.22825 0.0601802 0.0385272 0.0111496 0.997381 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 111 160 -0.196438 -2.52682 -5.99322 -0.0694497 0.0383559 -0.0058757 0.99683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 111 161 -0.19032 -0.00878429 -6.25998 -3.79925e-05 0.0366352 -0.00724403 0.999302 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 111 162 -0.227449 2.55162 -6.24664 0.0620114 0.0311882 0.0108804 0.997529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 112 161 -0.214232 -2.52985 -5.99544 -0.0618408 0.0272591 -0.0106085 0.997657 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 112 162 -0.198746 -0.0135162 -6.27972 0.00339793 0.0269692 -0.00651775 0.999609 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 112 163 -0.240219 2.56167 -6.24267 0.0616879 0.0324234 0.0100683 0.997518 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 113 162 -0.223619 -2.54337 -6.01844 -0.0663059 0.0311044 -0.00841259 0.997279 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 113 163 -0.210003 -0.0251441 -6.26239 0.00493863 0.0346432 -0.00185791 0.999386 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 113 164 -0.210182 2.57734 -6.25898 0.060329 0.0303706 0.00883314 0.997677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 114 163 -0.193342 -2.57175 -5.99039 -0.0549492 0.0264118 -0.00788031 0.998109 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 114 164 -0.203924 -0.00435839 -6.29344 0.00269513 0.0337362 0.00207552 0.999425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 114 165 -0.247075 2.592 -6.24912 0.0619162 0.0320103 0.00893546 0.997528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 115 164 -0.226986 -2.58072 -6.00218 -0.0592095 0.0211951 -0.0143689 0.997917 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 115 165 -0.195828 0.00709933 -6.27853 -0.00701329 0.0387034 -0.0028652 0.999222 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 115 166 -0.203582 2.6111 -6.25187 0.0584082 0.0333266 0.0147138 0.997628 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 116 165 -0.209744 -2.59723 -5.98488 -0.059933 0.0136548 -0.0143411 0.998006 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 116 166 -0.199648 -0.00782088 -6.29386 -0.000461216 0.0405804 0.00633696 0.999156 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 116 167 -0.225542 2.60628 -6.23996 0.0616661 0.0407696 0.00575401 0.997247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 117 166 -0.208124 -2.60728 -5.98332 -0.0582761 0.0351792 -0.00186101 0.997679 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 117 167 -0.188706 -0.00354341 -6.28502 -0.0010537 0.0302814 0.00267861 0.999537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 117 168 -0.228519 2.64495 -6.21452 0.0635451 0.0322703 0.00789299 0.997426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 118 167 -0.217914 -2.62174 -5.98344 -0.0550245 0.0290803 -0.00384154 0.998054 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 118 168 -0.181401 -0.00882977 -6.29605 0.00190209 0.0296773 -0.000276515 0.999558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 118 169 -0.24922 2.66794 -6.22582 0.0595147 0.0287759 0.0137825 0.997717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 119 168 -0.216634 -2.67136 -5.99742 -0.0599834 0.0323071 -0.0104547 0.997622 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 119 169 -0.195119 -0.0182192 -6.26485 0.00547646 0.02971 -0.00613942 0.999525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 119 170 -0.219343 2.68272 -6.22347 0.0734904 0.0347825 0.00810958 0.996656 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 120 169 -0.220486 -2.64985 -5.98229 -0.0628307 0.0380117 -0.0200291 0.997099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 120 170 -0.188245 -0.0067711 -6.284 0.00117319 0.0335793 -0.00382304 0.999428 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 120 171 -0.238964 2.67647 -6.24368 0.0608463 0.032185 0.0116917 0.99756 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 121 170 -0.218712 -2.66431 -5.97203 -0.0602533 0.0230321 -0.00967611 0.99787 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 121 171 -0.190551 0.00767831 -6.29468 0.00257031 0.0334921 0.000751317 0.999435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 121 172 -0.235391 2.70246 -6.24782 0.0650217 0.0356438 0.0112187 0.997184 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 122 171 -0.228331 -2.67937 -5.96521 -0.0680546 0.0393357 -0.0122216 0.996831 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 122 172 -0.196019 0.0117167 -6.26001 -0.00126215 0.0292692 0.00170283 0.999569 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 122 173 -0.24751 2.72143 -6.2538 0.0657833 0.0202466 0.0135245 0.997537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 123 172 -0.202067 -2.70763 -5.97352 -0.0632747 0.0330108 -0.00977819 0.997402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 123 173 -0.190492 0.0181367 -6.27598 0.00771943 0.0304739 -0.00333021 0.9995 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 123 174 -0.233093 2.72856 -6.24036 0.0578496 0.029109 0.0109953 0.99784 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 124 173 -0.212854 -2.70021 -5.98311 -0.0672295 0.0252913 -0.0042683 0.997408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 124 174 -0.199048 0.003903 -6.27593 0.00227893 0.0286373 -0.00192225 0.999585 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 124 175 -0.238398 2.73944 -6.22193 0.0601922 0.0304515 0.00995143 0.997673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 125 174 -0.228353 -2.74272 -5.97663 -0.0531875 0.0357683 -0.0179099 0.997783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 125 175 -0.199366 0.0015166 -6.27726 0.00193743 0.0334722 0.00576585 0.999421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 125 176 -0.244994 2.76811 -6.24053 0.0552121 0.0299328 0.0234556 0.99775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 126 175 -0.223744 -2.76796 -5.97928 -0.0592606 0.043011 -0.0187132 0.99714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 126 176 -0.205756 0.00479309 -6.28162 0.0201674 0.0283678 0.00324638 0.999389 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 126 177 -0.231718 2.76651 -6.23486 0.0614185 0.0269447 0.00197941 0.997746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 127 176 -0.216984 -2.76362 -5.9872 -0.0618817 0.0300786 -0.010317 0.997577 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 127 177 -0.19871 0.00920719 -6.27703 -0.00618524 0.0392654 -0.000874862 0.999209 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 127 178 -0.235194 2.81052 -6.22972 0.0612536 0.0348254 0.011153 0.997452 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 128 177 -0.210953 -2.77288 -5.99332 -0.0723297 0.0382943 -0.0144451 0.996541 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 128 178 -0.179078 0.00685147 -6.29022 -0.00217216 0.0316796 0.00480152 0.999484 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 128 179 -0.240953 2.80203 -6.2321 0.0672711 0.0291326 0.015155 0.997194 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 129 178 -0.21828 -2.78846 -5.98887 -0.0707458 0.0402344 -0.0225893 0.996427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 129 179 -0.194895 -2.48207e-05 -6.27043 -0.000416413 0.0348643 0.00736863 0.999365 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 129 180 -0.227757 2.80012 -6.21867 0.0662711 0.0316758 0.0115314 0.997232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 130 179 -0.222016 -2.79881 -5.96586 -0.0593972 0.0277584 -0.0134176 0.997758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 130 180 -0.191048 -0.0113478 -6.28171 0.00847173 0.0320981 -0.000591511 0.999449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 130 181 -0.230234 2.82054 -6.22548 0.0676275 0.0256186 0.0109359 0.997322 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 131 180 -0.232506 -2.83234 -5.99122 -0.0569109 0.0273602 -0.015957 0.997877 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 131 181 -0.189832 0.00959065 -6.28474 -0.0059472 0.0365673 0.00399199 0.999306 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 131 182 -0.233018 2.86505 -6.252 0.057728 0.0324573 0.00428707 0.997795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 132 181 -0.230735 -2.8448 -5.96907 -0.0604811 0.0249268 -0.0135656 0.997766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 132 182 -0.195176 0.00543258 -6.27832 -0.000483628 0.0284646 0.00618822 0.999576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 132 183 -0.224313 2.86743 -6.23732 0.0664398 0.0294528 0.0276006 0.996974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 133 182 -0.218125 -2.86206 -5.97467 -0.0708471 0.0382756 -0.0127101 0.996672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 133 183 -0.204728 -0.00672527 -6.28878 -0.00853385 0.0303202 0.00030509 0.999504 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 133 184 -0.248331 2.87346 -6.21368 0.0642564 0.0340646 0.0202524 0.997146 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 134 183 -0.217301 -2.86291 -5.96424 -0.0619319 0.0268516 -0.0128539 0.997636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 134 184 -0.185102 -0.0207616 -6.28925 -0.00580102 0.0338618 -0.010635 0.999353 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 134 185 -0.247818 2.89362 -6.21945 0.0574639 0.0360875 0.0108437 0.997636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 135 184 -0.218659 -2.89021 -5.97049 -0.0677317 0.0336685 -0.0185284 0.996963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 135 185 -0.198687 -0.0125691 -6.27566 -0.00601638 0.0291905 0.00360626 0.999549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 135 186 -0.230742 2.90626 -6.21562 0.0674333 0.0344177 0.0165877 0.996992 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 136 185 -0.198374 -2.89676 -5.99826 -0.0536022 0.0266251 -0.0187514 0.998031 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 136 186 -0.187886 -0.0155906 -6.26449 -0.00801606 0.0416311 -0.00326323 0.999096 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 136 187 -0.239931 2.9398 -6.21882 0.0609889 0.0298433 0.0176921 0.997535 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 137 186 -0.214322 -2.92476 -5.95849 -0.055664 0.028948 -0.00967105 0.997983 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 137 187 -0.18088 0.0186741 -6.26047 -0.0031579 0.0298218 0.00226243 0.999548 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 137 188 -0.25625 2.93424 -6.20215 0.065231 0.0382111 0.00764792 0.997109 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 138 187 -0.211659 -2.92584 -5.96325 -0.0596832 0.0289952 -0.0161058 0.997666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 138 188 -0.187954 -0.000445377 -6.27376 -0.00293145 0.0358568 -0.000451435 0.999353 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 138 189 -0.234913 2.96546 -6.21297 0.0675781 0.0356526 0.00173335 0.997075 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 139 188 -0.207289 -2.95855 -5.98285 -0.0651857 0.0252204 -0.0117388 0.997485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 139 189 -0.1969 -0.0122861 -6.27259 -0.00141472 0.034742 -0.00084293 0.999395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 139 190 -0.250505 2.96888 -6.19432 0.0609159 0.0301437 0.0159266 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 140 189 -0.226357 -2.97195 -5.96793 -0.0604483 0.0354015 -0.00555981 0.997528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 140 190 -0.197055 0.00156805 -6.26802 0.00184246 0.0357978 0.00591562 0.99934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 140 191 -0.230547 2.98976 -6.22094 0.0627458 0.0349013 0.00243301 0.997416 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 141 190 -0.215529 -2.99058 -5.96398 -0.0617989 0.0260882 -0.0127524 0.997666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 141 191 -0.176259 -0.0041036 -6.28004 -0.000908715 0.035321 -0.00401591 0.999368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 141 192 -0.246956 3.01204 -6.22191 0.0632844 0.0181217 0.0201394 0.997628 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 142 191 -0.220576 -2.98831 -5.96155 -0.0607343 0.020261 -0.0188909 0.997769 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 142 192 -0.198797 -0.0100236 -6.28761 0.00223412 0.0229739 0.00417422 0.999725 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 142 193 -0.224406 3.03474 -6.21878 0.0613518 0.033271 0.0208822 0.997343 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 143 192 -0.244659 -2.98638 -5.95912 -0.0506121 0.0272608 -0.0169227 0.998203 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 143 193 -0.212311 0.0130612 -6.28429 0.00108257 0.0362696 0.00434968 0.999332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 143 194 -0.249907 3.03698 -6.21478 0.0635784 0.0225329 0.013293 0.997634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 144 193 -0.210762 -3.03338 -5.97729 -0.0601292 0.0267093 -0.00650581 0.997812 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 144 194 -0.204494 0.00326038 -6.27309 -0.00281986 0.0357084 0.00416546 0.99935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 144 195 -0.233161 3.06432 -6.22605 0.061098 0.0324821 0.0134675 0.997512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 145 194 -0.249929 -3.04125 -5.97153 -0.0487853 0.0343006 -0.00629649 0.9982 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 145 195 -0.195951 0.00341673 -6.27265 -0.00595876 0.024266 -0.000787119 0.999687 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 145 196 -0.246822 3.0636 -6.20573 0.0591411 0.0295724 0.0126509 0.997731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 146 195 -0.207219 -3.05134 -5.95412 -0.0647841 0.0312944 -0.0201577 0.997205 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 146 196 -0.217114 0.00786449 -6.2691 -0.00349453 0.0241424 0.0054703 0.999687 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 146 197 -0.232522 3.10316 -6.21877 0.0541758 0.03282 0.0143318 0.997889 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 147 196 -0.239629 -3.08073 -5.94007 -0.0645172 0.0280677 -0.0189385 0.997342 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 147 197 -0.201965 -0.0119817 -6.28879 0.00344221 0.0318325 -0.00723583 0.999461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 147 198 -0.238936 3.09742 -6.21297 0.0638674 0.0322216 0.0109207 0.997378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 148 197 -0.2307 -3.09631 -5.94951 -0.06251 0.0259249 -0.0136743 0.997614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 148 198 -0.209248 0.0180817 -6.28954 -0.00863361 0.0319 0.00284303 0.99945 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 148 199 -0.258232 3.12975 -6.21017 0.0529176 0.0242889 0.0107152 0.998246 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 149 198 -0.234312 -3.09377 -5.9641 -0.0756227 0.0284514 -0.0139275 0.996633 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 149 199 -0.196315 0.00864759 -6.27841 -0.00827921 0.034088 -0.00173158 0.999383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 149 200 -0.236052 3.14938 -6.21285 0.0650081 0.0407763 0.0142691 0.996949 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 150 199 -0.217223 -3.13454 -5.95856 -0.0414588 0.0363735 -0.00443272 0.998468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 150 200 -0.198234 -0.00858107 -6.27986 -0.00542621 0.0311341 -0.00296791 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 150 201 -0.237041 3.15727 -6.22276 0.0655093 0.0257118 0.0107353 0.997463 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 151 200 -0.235343 -3.14682 -5.97508 -0.0673463 0.0244589 -0.0138606 0.997334 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 151 201 -0.197976 0.0139747 -6.26901 0.00204924 0.0314778 -0.00144216 0.999501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 151 202 -0.241634 3.15973 -6.20475 0.0687293 0.0305938 0.0124435 0.997088 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 152 201 -0.236709 -3.12746 -5.96224 -0.0541928 0.0211061 -0.012628 0.998228 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 152 202 -0.202805 0.0179034 -6.28928 0.00215494 0.0331809 -0.000180562 0.999447 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 152 203 -0.235725 3.16815 -6.22457 0.0562529 0.0302543 0.0100637 0.997907 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 153 202 -0.253644 -3.16408 -5.96873 -0.0603496 0.0332559 -0.0202254 0.997418 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 153 203 -0.189936 -0.0055143 -6.28487 0.00562028 0.0322154 0.00299724 0.999461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 153 204 -0.249934 3.19293 -6.21771 0.0594144 0.0312455 0.0137031 0.99765 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 154 203 -0.233543 -3.16997 -5.96243 -0.0628563 0.0223314 -0.0138261 0.997677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 154 204 -0.191734 -0.00451334 -6.26583 0.00905316 0.034057 -0.00822608 0.999345 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 154 205 -0.244793 3.20442 -6.21457 0.0600774 0.028778 0.0190537 0.997597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 155 204 -0.241883 -3.21491 -5.9309 -0.0666426 0.0356408 -0.0136792 0.997046 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 155 205 -0.19817 -0.0100136 -6.28395 0.00554473 0.02428 -0.00320933 0.999685 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 155 206 -0.238427 3.2155 -6.20431 0.0545186 0.0235583 0.0166253 0.998096 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 156 205 -0.226072 -3.23259 -5.96986 -0.0538157 0.0242342 -0.0173486 0.998106 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 156 206 -0.202319 0.0109327 -6.27816 -0.000908346 0.0380816 -0.00644819 0.999253 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 156 207 -0.255258 3.23734 -6.20972 0.0582897 0.0240445 0.0167853 0.997869 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 157 206 -0.255773 -3.23753 -5.95197 -0.0576922 0.029259 -0.0159131 0.997779 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 157 207 -0.194847 0.0131474 -6.27588 -0.00678022 0.0383144 -0.00375964 0.999236 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 157 208 -0.254926 3.25135 -6.21031 0.0585002 0.0378032 0.0110242 0.99751 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 158 207 -0.212922 -3.24655 -5.94595 -0.0550534 0.0313108 -0.0150383 0.997879 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 158 208 -0.193002 -0.00137119 -6.28781 0.00297259 0.0310481 -0.00268011 0.99951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 158 209 -0.25236 3.27888 -6.20105 0.0672267 0.0340213 0.0119393 0.997086 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 159 208 -0.230035 -3.25299 -5.9611 -0.0571477 0.0313228 -0.0142466 0.997773 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 159 209 -0.191546 0.0122589 -6.25352 0.00389142 0.0306524 0.000687157 0.999522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 159 210 -0.254474 3.30252 -6.19765 0.057674 0.0376783 0.0221025 0.997379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 160 209 -0.228566 -3.26547 -5.95059 -0.0623996 0.0363501 -0.0154846 0.997269 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 160 210 -0.187815 -0.0192739 -6.27518 -0.00497468 0.0383597 0.00175868 0.99925 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 160 211 -0.257747 3.293 -6.2039 0.0625877 0.0243708 0.0140483 0.997643 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 161 210 -0.217763 -3.28779 -5.95018 -0.0597617 0.0325838 -0.0177694 0.997522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 161 211 -0.204576 0.0218238 -6.26231 -0.00444925 0.0329563 0.00863364 0.99941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 161 212 -0.236643 3.31762 -6.21675 0.0621403 0.0346767 0.0148282 0.997355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 162 211 -0.22374 -3.30946 -5.95872 -0.0642282 0.0370964 -0.0128861 0.997162 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 162 212 -0.219119 -0.0106423 -6.27833 0.0002585 0.0355005 -0.00776674 0.999339 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 162 213 -0.247181 3.32883 -6.17961 0.0680606 0.0252422 0.0162733 0.997229 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 163 212 -0.222192 -3.32573 -5.95513 -0.0599448 0.0231341 -0.0210512 0.997712 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 163 213 -0.217513 0.00298169 -6.27502 -0.00532478 0.0437226 0.00530774 0.999015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 163 214 -0.247433 3.325 -6.20595 0.0516252 0.0241418 0.00991214 0.998325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 164 213 -0.229839 -3.32926 -5.93621 -0.0621095 0.0333116 -0.0176948 0.997356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 164 214 -0.200664 0.00667592 -6.28053 -0.000477374 0.029424 0.00108126 0.999566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 164 215 -0.237872 3.35641 -6.18944 0.0593827 0.0339575 0.00964511 0.997611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 165 214 -0.248311 -3.33955 -5.93538 -0.0670401 0.0269515 -0.0132112 0.997299 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 165 215 -0.206745 0.0124487 -6.27236 -0.0018874 0.0288034 0.00285552 0.999579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 165 216 -0.238816 3.37701 -6.20389 0.0547665 0.0339007 0.0217832 0.997686 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 166 215 -0.237801 -3.35362 -5.92691 -0.0546398 0.028028 -0.0102831 0.99806 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 166 216 -0.215351 0.00353555 -6.27382 0.0023566 0.0316167 0.000916896 0.999497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 166 217 -0.255544 3.38297 -6.18078 0.0600769 0.0319673 0.0117326 0.997613 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 167 216 -0.232276 -3.36564 -5.95753 -0.0618762 0.02612 -0.00807922 0.997709 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 167 217 -0.192852 -0.0254586 -6.27332 -0.00179754 0.0313538 -0.00528204 0.999493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 167 218 -0.243913 3.40702 -6.19157 0.0548468 0.0320939 0.0182951 0.997811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 168 217 -0.2431 -3.37797 -5.94182 -0.0588436 0.0278847 -0.0205824 0.997665 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 168 218 -0.213741 -0.00746184 -6.28076 0.000367777 0.0360268 0.01168 0.999282 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 168 219 -0.250271 3.41743 -6.18978 0.0595146 0.0309316 0.0105002 0.997693 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 169 218 -0.237719 -3.40758 -5.96353 -0.0594678 0.0264535 -0.0143719 0.997776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 169 219 -0.2007 0.00212136 -6.2849 0.000105249 0.0350236 0.00355359 0.99938 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 169 220 -0.250851 3.42229 -6.18595 0.0574607 0.0308369 0.018284 0.997704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 170 219 -0.220847 -3.41956 -5.94355 -0.065115 0.0234922 -0.0170143 0.997456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 170 220 -0.213143 -0.00517569 -6.27116 -0.00125942 0.0232189 -0.000169926 0.99973 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 170 221 -0.252743 3.46306 -6.21331 0.0649706 0.0273801 0.0202121 0.997307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 171 220 -0.248535 -3.4362 -5.94504 -0.0620919 0.0299645 -0.0134437 0.99753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 171 221 -0.204245 -0.00145623 -6.27609 0.00525057 0.0325669 0.0014332 0.999455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 171 222 -0.257317 3.46329 -6.19917 0.0683085 0.0341035 0.0186689 0.996906 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 172 221 -0.236418 -3.4414 -5.96201 -0.0589268 0.0254121 -0.00697457 0.997914 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 172 222 -0.19987 0.00727273 -6.28712 -0.00148476 0.0343383 0.00187349 0.999407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 172 223 -0.251738 3.48139 -6.17789 0.0645041 0.0374108 0.0192337 0.99703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 173 222 -0.231185 -3.46796 -5.95725 -0.054549 0.0351967 -0.0183151 0.997722 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 173 223 -0.201847 -0.000569591 -6.28637 -0.000492329 0.0291373 0.00110337 0.999575 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 173 224 -0.240609 3.49115 -6.18929 0.0660877 0.0380536 0.0169731 0.996943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 174 223 -0.237152 -3.47055 -5.93158 -0.0489785 0.0261688 -0.0131507 0.99837 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 174 224 -0.177038 0.0248604 -6.27266 0.000881543 0.0391688 3.61089e-05 0.999232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 174 225 -0.261977 3.51671 -6.19002 0.0605653 0.0305285 0.0164058 0.997562 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 175 224 -0.236093 -3.49596 -5.92246 -0.060175 0.0337153 -0.0198246 0.997421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 175 225 -0.195549 0.0122853 -6.2681 0.0047909 0.0289296 -0.00193936 0.999568 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 175 226 -0.233417 3.52297 -6.18476 0.0640565 0.0297582 0.0112218 0.997439 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 176 225 -0.231598 -3.51762 -5.93475 -0.0565964 0.0330383 -0.0194981 0.99766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 176 226 -0.195443 0.00939226 -6.2878 -0.00560345 0.0326993 0.0150432 0.999336 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 176 227 -0.255145 3.54508 -6.19199 0.0557341 0.0306583 0.0179653 0.997813 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 177 226 -0.241925 -3.52846 -5.92473 -0.054885 0.0299228 -0.017685 0.997888 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 177 227 -0.201201 0.00403294 -6.28233 -0.00616591 0.0395742 0.000241765 0.999198 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 177 228 -0.25714 3.56909 -6.17754 0.0657285 0.0284872 0.0123683 0.997354 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 178 227 -0.229146 -3.53659 -5.93637 -0.063773 0.0334606 -0.0221224 0.997158 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 178 228 -0.193801 0.00101801 -6.27595 0.00272559 0.0364718 -0.00312134 0.999326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 178 229 -0.270581 3.57389 -6.18793 0.0652997 0.0283373 0.00518699 0.99745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 179 228 -0.22206 -3.5555 -5.93835 -0.0609287 0.0324086 -0.0244811 0.997315 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 179 229 -0.188516 0.00524537 -6.28492 0.008018 0.0390893 -0.00917581 0.999161 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 179 230 -0.251875 3.59418 -6.16539 0.0612493 0.0348891 0.00962443 0.997466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 180 229 -0.243224 -3.55785 -5.94672 -0.0636368 0.0362338 -0.0152305 0.997199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 180 230 -0.193512 -0.0100473 -6.26769 0.00453878 0.0290954 0.0040868 0.999558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 180 231 -0.265917 3.59562 -6.17667 0.063945 0.0374172 0.0188646 0.997073 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 181 230 -0.257694 -3.57795 -5.92694 -0.0618537 0.0231063 -0.0137033 0.997724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 181 231 -0.198667 -0.0146181 -6.30043 -0.00410272 0.0381209 -0.00376395 0.999258 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 181 232 -0.272842 3.62737 -6.18391 0.0731486 0.0370841 0.0144722 0.996526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 182 231 -0.256912 -3.60613 -5.94447 -0.055104 0.0309241 -0.0182869 0.997834 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 182 232 -0.194945 0.0119453 -6.26859 -0.00293804 0.0325738 -0.00202959 0.999463 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 182 233 -0.255345 3.64816 -6.17819 0.0555794 0.0374438 0.0254011 0.997429 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 183 232 -0.24884 -3.62295 -5.95337 -0.0678268 0.0301842 -0.0153025 0.997123 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 183 233 -0.194446 -0.00751079 -6.28686 0.00261203 0.0335458 -0.00264805 0.99943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 183 234 -0.275626 3.64191 -6.18039 0.0594049 0.0263064 0.0205822 0.997675 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 184 233 -0.238865 -3.63885 -5.9345 -0.0607679 0.0274743 -0.0243859 0.997476 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 184 234 -0.192642 0.00715099 -6.28841 0.00803907 0.0405438 -0.0045005 0.999135 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 184 235 -0.264483 3.66613 -6.19473 0.0652158 0.0271968 0.017037 0.997355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 185 234 -0.231791 -3.63933 -5.9319 -0.0534231 0.0310733 -0.0243094 0.997792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 185 235 -0.197961 -0.0112425 -6.27098 -0.00292896 0.0301895 -0.00575352 0.999523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 185 236 -0.250604 3.68857 -6.19043 0.067813 0.0261325 0.0191749 0.997171 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 186 235 -0.248694 -3.67266 -5.91666 -0.0670585 0.0206163 -0.0073147 0.997509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 186 236 -0.202931 -0.00680171 -6.27882 -0.000303939 0.0326051 -0.00303501 0.999464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 186 237 -0.259357 3.68544 -6.18425 0.06184 0.0349855 0.0113784 0.997408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 187 236 -0.249027 -3.6715 -5.93593 -0.055276 0.040259 -0.014749 0.99755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 187 237 -0.204288 0.00115049 -6.2844 0.0105986 0.028647 -0.00460232 0.999523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 187 238 -0.253325 3.68509 -6.18363 0.0594319 0.028115 0.0151509 0.997721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 188 237 -0.245897 -3.70233 -5.93198 -0.063935 0.0271777 -0.023333 0.997311 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 188 238 -0.191112 -0.00198441 -6.27725 0.00677416 0.0322499 -0.00123776 0.999456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 188 239 -0.258389 3.72644 -6.18819 0.0664459 0.0295195 0.00891394 0.997313 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 189 238 -0.241575 -3.68971 -5.9186 -0.0602183 0.0196758 -0.0165499 0.997854 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 189 239 -0.189233 -0.0045782 -6.2772 0.00350955 0.0321785 -0.00511284 0.999463 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 189 240 -0.276595 3.74233 -6.1573 0.0593311 0.0281925 0.0224024 0.997589 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 190 239 -0.216233 -3.73215 -5.92871 -0.0616843 0.0322596 -0.016447 0.997439 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 190 240 -0.188024 -0.0129451 -6.27868 -0.00228473 0.0288775 -0.004375 0.999571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 190 241 -0.240277 3.74568 -6.17822 0.0631044 0.0340156 0.0167779 0.997286 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 191 240 -0.255734 -3.74474 -5.92377 -0.0648555 0.0345361 -0.0149791 0.997184 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 191 241 -0.201242 0.0101756 -6.27356 0.00186135 0.0199595 0.00167639 0.999798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 191 242 -0.255527 3.77135 -6.15964 0.0670801 0.0382239 0.00842521 0.99698 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 192 241 -0.238865 -3.75027 -5.9129 -0.0554797 0.0378495 -0.0169601 0.997598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 192 242 -0.202863 -0.00552604 -6.28555 -0.0026608 0.0353636 0.000195954 0.999371 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 192 243 -0.265436 3.79372 -6.18067 0.0587571 0.0305402 0.0142006 0.997704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 193 242 -0.238702 -3.75792 -5.906 -0.0581339 0.0358362 -0.00955757 0.99762 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 193 243 -0.190747 0.0131122 -6.2736 0.00237428 0.0247105 -0.00442016 0.999682 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 193 244 -0.255403 3.81241 -6.17245 0.0579077 0.0298496 0.0180612 0.997712 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 194 243 -0.229255 -3.77232 -5.92577 -0.0561896 0.0215262 -0.0191734 0.998004 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 194 244 -0.188398 0.0153436 -6.26851 0.00515383 0.0340199 0.00585429 0.999391 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 194 245 -0.260525 3.82653 -6.17556 0.0559505 0.0309017 0.0183317 0.997787 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 195 244 -0.240322 -3.81072 -5.919 -0.0642445 0.0279346 -0.0187795 0.997366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 195 245 -0.185427 -0.00567956 -6.26734 -0.00526157 0.0358659 0.00393921 0.999335 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 195 246 -0.263821 3.82859 -6.1666 0.0616065 0.0338155 0.0125854 0.997448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 196 245 -0.245854 -3.81298 -5.93026 -0.0635557 0.0298678 -0.021885 0.997291 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 196 246 -0.193654 -0.0108473 -6.28693 -0.00260451 0.0348566 -0.00452849 0.999379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 196 247 -0.265749 3.8315 -6.17706 0.0675403 0.0336412 0.0169035 0.997006 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 197 246 -0.237866 -3.84007 -5.91388 -0.0624285 0.0371584 -0.0161104 0.997227 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 197 247 -0.196689 0.00235306 -6.2651 -0.00537229 0.0278973 -0.00122585 0.999596 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 197 248 -0.269359 3.86309 -6.17738 0.0649149 0.0304055 0.023141 0.997159 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 198 247 -0.254245 -3.84965 -5.92123 -0.0622123 0.0291549 -0.0187629 0.997461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 198 248 -0.181925 0.00253297 -6.26486 -0.00218377 0.0291774 -0.00281641 0.999568 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 198 249 -0.263699 3.85394 -6.18214 0.0628386 0.0278258 0.0236466 0.997355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 199 248 -0.240742 -3.84705 -5.8986 -0.0542611 0.0330237 -0.0205885 0.997768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 199 249 -0.185471 0.0104177 -6.27237 0.00374915 0.0371322 -0.00422808 0.999294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 199 250 -0.247291 3.88709 -6.15472 0.0564478 0.035739 0.0144432 0.997661 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 200 249 -0.246015 -3.87303 -5.92453 -0.0606333 0.0322562 -0.0284227 0.997234 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 200 250 -0.207936 -0.00801959 -6.29171 0.0068342 0.0246069 -0.00182289 0.999672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 200 251 -0.267045 3.89586 -6.17678 0.0617873 0.0396843 0.0177883 0.997141 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 201 250 -0.254518 -3.88059 -5.92503 -0.0565947 0.0367779 -0.0209536 0.9975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 201 251 -0.187966 0.00670071 -6.29715 0.00144954 0.0252358 0.000476682 0.99968 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 201 252 -0.269048 3.91828 -6.16337 0.0621409 0.0394108 0.0191679 0.997105 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 202 251 -0.237372 -3.89413 -5.92148 -0.0709559 0.0323062 -0.023114 0.996688 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 202 252 -0.198655 -0.00507345 -6.27708 0.00503258 0.0293338 -0.00212197 0.999555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 202 253 -0.261631 3.93662 -6.17405 0.0585728 0.0354719 0.0125059 0.997574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 203 252 -0.240749 -3.9043 -5.91755 -0.0557558 0.0255592 -0.014661 0.99801 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 203 253 -0.206266 0.0187729 -6.27453 -0.000325212 0.0419074 0.00467322 0.999111 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 203 254 -0.272614 3.94022 -6.17475 0.0594769 0.031952 0.019301 0.997531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 204 253 -0.27195 -3.94435 -5.91713 -0.0573762 0.0282714 -0.0150275 0.997839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 204 254 -0.206165 0.0279351 -6.28799 0.00484585 0.0290382 -0.00266353 0.999563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 204 255 -0.279345 3.95498 -6.1648 0.0640463 0.0332076 0.020334 0.997187 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 205 254 -0.251712 -3.95617 -5.91823 -0.0627339 0.0366621 -0.0176819 0.9972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 205 255 -0.201643 0.00144396 -6.28723 0.00529981 0.0288877 -0.00506497 0.999556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 205 256 -0.276827 3.9842 -6.15991 0.0625474 0.0353262 0.0234864 0.99714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 206 255 -0.266518 -3.94997 -5.90907 -0.052272 0.0265044 -0.0166695 0.998142 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 206 256 -0.209192 -0.00442326 -6.27833 0.00543996 0.0368172 0.00788993 0.999276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 206 257 -0.252753 3.98327 -6.1649 0.0616409 0.0244618 0.0224589 0.997546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 207 256 -0.262829 -3.95369 -5.91174 -0.0533412 0.0291932 -0.0225902 0.997894 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 207 257 -0.203183 -0.00257858 -6.27843 0.00422119 0.0301316 0.000111715 0.999537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 207 258 -0.262766 4.01292 -6.16005 0.0540082 0.031899 0.0241197 0.997739 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 208 257 -0.260955 -3.98934 -5.9114 -0.0629962 0.0308378 -0.0118329 0.997467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 208 258 -0.178992 0.00712501 -6.28748 -0.00537368 0.028658 -0.00152205 0.999574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 208 259 -0.260637 4.03359 -6.16745 0.0590009 0.0317146 0.0264552 0.997403 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 209 258 -0.270888 -4.00323 -5.9065 -0.06272 0.0281333 -0.013508 0.997543 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 209 259 -0.196916 0.00103414 -6.27532 -0.00154782 0.0273107 0.000556965 0.999626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 209 260 -0.286706 4.03397 -6.1562 0.049003 0.0319822 0.0143307 0.998184 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 210 259 -0.263612 -4.05096 -5.91513 -0.0551161 0.025143 -0.0213943 0.997934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 210 260 -0.204371 0.0011218 -6.26635 -0.000632231 0.0264074 -0.000747404 0.999651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 210 261 -0.278618 4.03155 -6.15246 0.0623266 0.0279834 0.0118126 0.997593 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 211 260 -0.256744 -4.03802 -5.90641 -0.0605888 0.0285278 -0.0153997 0.997636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 211 261 -0.213284 -0.000683596 -6.27546 -0.00268369 0.033135 0.00407232 0.999439 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 211 262 -0.26115 4.06825 -6.16831 0.0623053 0.0288984 0.017502 0.997485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 212 261 -0.27308 -4.06903 -5.93753 -0.0673897 0.0303311 -0.0189518 0.997085 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 212 262 -0.202209 -0.00503391 -6.29294 -0.00441319 0.0281023 0.00621986 0.999576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 212 263 -0.270624 4.0872 -6.16103 0.0665423 0.0313599 0.00982575 0.997242 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 213 262 -0.257303 -4.07646 -5.90325 -0.0544038 0.0304748 -0.0161252 0.997924 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 213 263 -0.201036 -0.00398234 -6.2874 0.00842098 0.0386004 -0.0128648 0.999136 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 213 264 -0.283801 4.09538 -6.16512 0.0622315 0.0415942 0.0115787 0.997127 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 214 263 -0.247824 -4.08148 -5.90411 -0.0475206 0.0301763 -0.0242993 0.998119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 214 264 -0.208297 -0.0146326 -6.28609 0.00423991 0.0306121 0.00450547 0.999512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 214 265 -0.27028 4.11642 -6.15166 0.0530748 0.0363189 0.0173913 0.997778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 215 264 -0.269919 -4.07916 -5.90125 -0.0532367 0.0291213 -0.0180172 0.997995 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 215 265 -0.207214 -0.00861045 -6.27669 -0.000387894 0.022435 0.00419492 0.999739 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 215 266 -0.280811 4.15575 -6.15561 0.0622395 0.0235272 0.0250405 0.99747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 216 265 -0.252954 -4.11058 -5.90149 -0.0487597 0.0338934 -0.0235394 0.997958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 216 266 -0.21498 -0.0211522 -6.27859 -0.00114423 0.0379463 0.00250447 0.999276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 216 267 -0.281426 4.12038 -6.15039 0.0530638 0.0282124 0.0120506 0.99812 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 217 266 -0.257904 -4.11609 -5.90408 -0.0650479 0.0279633 -0.0212265 0.997264 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 217 267 -0.192643 -0.00132009 -6.26552 0.00142382 0.0278239 -0.0012348 0.999611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 217 268 -0.256737 4.17151 -6.16879 0.0583279 0.035488 0.0227656 0.997407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 218 267 -0.262953 -4.11783 -5.89644 -0.0616605 0.0246609 -0.0149639 0.99768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 218 268 -0.201476 -0.00546718 -6.26926 0.00246489 0.0298675 0.00604933 0.999533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 218 269 -0.291457 4.15727 -6.15136 0.0590245 0.0315869 0.0151977 0.997641 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 219 268 -0.250907 -4.16665 -5.89775 -0.0585706 0.0303117 -0.0227711 0.997563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 219 269 -0.194345 -0.0056301 -6.28492 0.00585396 0.032862 0.00225995 0.99944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 219 270 -0.27484 4.18121 -6.15552 0.06027 0.0291409 0.0178371 0.997597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 220 269 -0.252629 -4.17401 -5.88714 -0.0544607 0.0318757 -0.0228475 0.997745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 220 270 -0.193355 -0.00480379 -6.25962 -0.00555803 0.0308761 -0.000101713 0.999508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 220 271 -0.287243 4.19077 -6.15914 0.0612133 0.0332663 0.0143321 0.997467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 221 270 -0.262719 -4.18078 -5.90273 -0.0571461 0.0450195 -0.0179131 0.997189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 221 271 -0.17902 -0.00122914 -6.28603 -0.00909284 0.0287351 0.00323579 0.99954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 221 272 -0.267483 4.2236 -6.14467 0.0517958 0.0296849 0.0164214 0.998081 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 222 271 -0.281006 -4.19619 -5.8961 -0.0611971 0.0323381 -0.0178179 0.997443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 222 272 -0.193154 -0.00421857 -6.28369 0.00183469 0.0387953 -0.00363766 0.999239 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 222 273 -0.271219 4.22873 -6.13757 0.0570798 0.0350484 0.0199285 0.997555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 223 272 -0.25748 -4.2115 -5.91281 -0.0609315 0.0362145 -0.0165898 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 223 273 -0.201776 -0.00522656 -6.28383 0.00304734 0.0412774 0.00637694 0.999123 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 223 274 -0.277624 4.23917 -6.14606 0.0605222 0.0352289 0.0259689 0.997207 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 224 273 -0.264014 -4.21028 -5.89622 -0.0708809 0.029639 -0.0245841 0.996741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 224 274 -0.196468 0.00404179 -6.26786 0.00380613 0.0299118 0.0041713 0.999537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 224 275 -0.287022 4.25768 -6.14432 0.0506831 0.0214583 0.0120649 0.998411 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 225 274 -0.243105 -4.24656 -5.90511 -0.0575925 0.030302 -0.0255891 0.997552 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 225 275 -0.19251 -0.003956 -6.28401 0.00136772 0.0258656 -0.00144534 0.999663 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 225 276 -0.282802 4.27412 -6.15769 0.0605419 0.024763 0.0122173 0.997784 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 226 275 -0.268279 -4.25449 -5.90639 -0.0660995 0.0256361 -0.0140204 0.997385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 226 276 -0.207522 0.00438612 -6.26857 -0.00055043 0.034 -0.00339676 0.999416 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 226 277 -0.271656 4.28487 -6.13243 0.0631607 0.0220204 0.0146137 0.997653 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 227 276 -0.265598 -4.2654 -5.8783 -0.06463 0.025055 -0.0147379 0.997486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 227 277 -0.213812 -0.00422088 -6.29277 0.00342644 0.033568 -0.000625157 0.99943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 227 278 -0.272042 4.31202 -6.16112 0.0530688 0.0312705 0.0196356 0.997908 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 228 277 -0.260786 -4.27786 -5.89503 -0.0722863 0.0281731 -0.0295003 0.996549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 228 278 -0.201262 -0.0155454 -6.27925 0.00824555 0.0336307 -0.00604363 0.999382 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 228 279 -0.28078 4.31512 -6.13857 0.0542494 0.0393837 0.0185021 0.997579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 229 278 -0.279808 -4.30484 -5.89497 -0.0613568 0.0266653 -0.0179955 0.997597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 229 279 -0.214922 -0.0166742 -6.27929 0.00100169 0.0296739 0.00719202 0.999533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 229 280 -0.293214 4.3202 -6.13772 0.0643273 0.0276705 0.0238091 0.997261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 230 279 -0.268456 -4.30662 -5.90156 -0.0658768 0.0351134 -0.0203929 0.997001 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 230 280 -0.19058 0.00336871 -6.26801 0.00222828 0.030525 -0.00327171 0.999526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 230 281 -0.277055 4.33978 -6.13338 0.0512382 0.0353015 0.0243384 0.997766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 231 280 -0.285648 -4.32981 -5.89142 -0.062788 0.0314207 -0.0203953 0.997324 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 231 281 -0.189332 0.00662727 -6.29686 0.0053289 0.0323179 0.0078222 0.999433 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 231 282 -0.278461 4.35311 -6.1651 0.0587042 0.0343321 0.0229778 0.99742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 232 281 -0.276919 -4.34644 -5.89288 -0.0666911 0.0350755 -0.0204367 0.996948 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 232 282 -0.195809 -0.0018445 -6.28034 -0.0066058 0.040784 -0.00223211 0.999144 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 232 283 -0.274938 4.38344 -6.1365 0.0672839 0.0378315 0.0239669 0.996728 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 233 282 -0.272675 -4.38167 -5.90306 -0.0493124 0.0222623 -0.0147001 0.998427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 233 283 -0.202231 0.011046 -6.27894 -0.00508228 0.0272916 -0.00146406 0.999614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 233 284 -0.280845 4.40055 -6.14895 0.0487133 0.0197911 0.0212854 0.99839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 234 283 -0.24649 -4.38895 -5.89106 -0.0616853 0.0397577 -0.0296052 0.996864 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 234 284 -0.195204 -0.0133222 -6.27326 0.00894457 0.028006 0.0035144 0.999562 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 234 285 -0.296933 4.41422 -6.14094 0.0625018 0.0289776 0.0286799 0.997212 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 235 284 -0.27719 -4.38815 -5.899 -0.0542477 0.035245 -0.0354811 0.997274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 235 285 -0.199916 -0.00349108 -6.28784 0.00587107 0.0288118 -0.00703419 0.999543 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 235 286 -0.280813 4.42025 -6.14344 0.0540985 0.0276074 0.0145229 0.998048 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 236 285 -0.273821 -4.42051 -5.89784 -0.0605484 0.0333251 -0.0234678 0.997333 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 236 286 -0.197271 -0.00148436 -6.3059 0.00799224 0.0310511 -0.00375174 0.999479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 236 287 -0.289143 4.42747 -6.13229 0.0550366 0.0387279 0.0215608 0.9975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 237 286 -0.275642 -4.42734 -5.88472 -0.0515604 0.0249152 -0.0187114 0.998184 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 237 287 -0.198521 0.00612005 -6.2735 0.0070144 0.0284449 -0.0026855 0.999567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 237 288 -0.282255 4.46129 -6.1252 0.0567599 0.0324204 0.0146244 0.997754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 238 287 -0.265825 -4.44955 -5.89331 -0.0531414 0.0279145 -0.0159915 0.998069 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 238 288 -0.196516 -0.00051765 -6.26929 -0.00524498 0.0322114 0.00047389 0.999467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 238 289 -0.282576 4.45725 -6.13885 0.0600698 0.034953 0.0243902 0.997284 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 239 288 -0.276011 -4.44933 -5.87034 -0.0681652 0.0364625 -0.0172806 0.996858 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 239 289 -0.210764 0.00689919 -6.29451 0.00566979 0.0333026 0.00519728 0.999416 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 239 290 -0.288097 4.48458 -6.14657 0.0547738 0.0411827 0.0156638 0.997526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 240 289 -0.27971 -4.47545 -5.87597 -0.0560758 0.0359278 -0.0139084 0.997683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 240 290 -0.210985 -0.000999557 -6.28771 -0.00717855 0.0349806 -0.00219942 0.99936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 240 291 -0.27723 4.49239 -6.13796 0.0638484 0.0324978 0.0278308 0.997042 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 241 290 -0.283395 -4.47392 -5.89317 -0.0601483 0.0273431 -0.0199946 0.997615 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 241 291 -0.19423 0.00366082 -6.28584 0.000555878 0.0366066 0.000298594 0.99933 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 241 292 -0.299397 4.52403 -6.13021 0.0643312 0.0302238 0.0199989 0.99727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 242 291 -0.267725 -4.49888 -5.87859 -0.0551521 0.029365 -0.0211183 0.997823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 242 292 -0.205402 -0.0124176 -6.27755 -0.00713128 0.0365343 5.74366e-07 0.999307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 242 293 -0.288836 4.52912 -6.13938 0.0587633 0.0311629 0.0283376 0.997383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 243 292 -0.261093 -4.51755 -5.90087 -0.058707 0.0317702 -0.0172426 0.997621 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 243 293 -0.196585 0.0119707 -6.25902 0.00647414 0.031913 0.000440114 0.99947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 243 294 -0.26951 4.54446 -6.12704 0.0620493 0.0298271 0.0195303 0.997436 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 244 293 -0.268143 -4.53114 -5.86674 -0.0601511 0.0330863 -0.0242438 0.997346 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 244 294 -0.204156 -8.14166e-05 -6.28691 -0.00107099 0.0263126 0.00649877 0.999632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 244 295 -0.31638 4.56328 -6.13805 0.0561511 0.0317361 0.0299206 0.997469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 245 294 -0.283945 -4.54499 -5.89014 -0.0565581 0.0318646 -0.0244387 0.997591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 245 295 -0.198519 0.00845148 -6.28581 -0.00243603 0.0325871 -0.00205075 0.999464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 245 296 -0.27434 4.56008 -6.12615 0.0492074 0.0328757 0.0228941 0.997985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 246 295 -0.273452 -4.54614 -5.88741 -0.0592787 0.0334982 -0.0300326 0.997227 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 246 296 -0.190937 -0.00118779 -6.27191 0.00346435 0.0314959 -0.00550933 0.999483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 246 297 -0.292269 4.59463 -6.13246 0.0585206 0.0417769 0.0105724 0.997356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 247 296 -0.273876 -4.5516 -5.87394 -0.0549288 0.0377766 -0.02978 0.997331 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 247 297 -0.205161 -0.0245075 -6.28899 0.00718058 0.0400944 0.00187881 0.999168 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 247 298 -0.285103 4.60806 -6.13679 0.0600235 0.0294552 0.0199461 0.997563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 248 297 -0.270082 -4.58255 -5.863 -0.0590844 0.0264795 -0.0148976 0.997791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 248 298 -0.193089 0.00215059 -6.27673 -0.00479496 0.0376232 0.0195087 0.99909 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 248 299 -0.282502 4.60566 -6.12911 0.0534642 0.0264933 0.0281813 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 249 298 -0.266774 -4.60699 -5.8694 -0.05836 0.0343292 -0.0203805 0.997497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 249 299 -0.193304 -0.0130437 -6.2822 0.000577971 0.0289675 -0.00393386 0.999572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 249 300 -0.286951 4.62275 -6.12248 0.0587028 0.0345529 0.0201602 0.997474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 250 299 -0.262763 -4.60625 -5.86978 -0.0578387 0.0327675 -0.0197613 0.997592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 250 300 -0.206182 -0.000760013 -6.2711 0.00794695 0.033001 0.00859625 0.999387 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 250 301 -0.290129 4.65502 -6.12755 0.0571241 0.0343778 0.0139998 0.997677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 251 300 -0.288374 -4.62138 -5.89113 -0.0496816 0.0373836 -0.0236558 0.997785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 251 301 -0.200952 -0.00308889 -6.26749 -0.00184221 0.0338074 -0.00186389 0.999425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 251 302 -0.307873 4.63575 -6.11893 0.0597549 0.0325529 0.0203614 0.997474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 252 301 -0.290381 -4.63947 -5.87093 -0.0602376 0.035839 -0.0246992 0.997235 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 252 302 -0.204419 0.00683164 -6.3043 0.00227019 0.0314017 -0.00693322 0.99948 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 252 303 -0.297411 4.67225 -6.1261 0.057043 0.0282924 0.0168407 0.997829 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 253 302 -0.280851 -4.66373 -5.86999 -0.0564175 0.0166326 -0.0214327 0.998039 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 253 303 -0.184168 0.0076359 -6.27481 -0.00348137 0.0298974 0.00767626 0.999517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 253 304 -0.30668 4.69651 -6.1207 0.0504136 0.0352966 0.0202513 0.997899 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 254 303 -0.287101 -4.66864 -5.87475 -0.052351 0.0223487 -0.0207354 0.998163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 254 304 -0.191733 0.00230422 -6.29324 0.00308046 0.0312472 -0.00890839 0.999467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 254 305 -0.296281 4.68524 -6.12042 0.0583572 0.0313429 0.0244229 0.997505 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 255 304 -0.279616 -4.6942 -5.87026 -0.0584328 0.0213822 -0.0125504 0.997983 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 255 305 -0.219992 -0.0271364 -6.26959 0.000669927 0.0350303 -0.00325387 0.999381 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 255 306 -0.300658 4.72004 -6.12649 0.0601043 0.034847 0.0244469 0.997284 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 256 305 -0.286157 -4.70484 -5.87697 -0.0720385 0.0365221 -0.0275263 0.996353 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 256 306 -0.186815 0.00236627 -6.28494 0.00510956 0.0373474 0.0101281 0.999238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 256 307 -0.285445 4.71704 -6.11772 0.0647009 0.0370374 0.0257259 0.996885 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 257 306 -0.264567 -4.70038 -5.86581 -0.0606819 0.0301999 -0.0199151 0.997501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 257 307 -0.187379 0.00241414 -6.28355 -0.0111203 0.0228891 -0.00759472 0.999647 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 257 308 -0.290925 4.7561 -6.12356 0.058622 0.028611 0.0224432 0.997618 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 258 307 -0.260899 -4.73203 -5.88654 -0.0628169 0.0280346 -0.0181153 0.997467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 258 308 -0.203159 0.00902221 -6.26703 -0.00393138 0.0353335 -0.00366491 0.999361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 258 309 -0.306266 4.75364 -6.11984 0.0524992 0.0254672 0.0242162 0.998002 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 259 308 -0.283648 -4.73875 -5.86763 -0.056038 0.0326129 -0.018941 0.997716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 259 309 -0.205785 -0.00852206 -6.28084 -0.00159553 0.0364454 0.0090223 0.999294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 259 310 -0.302321 4.76129 -6.14148 0.0588183 0.0317476 0.0243073 0.997468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 260 309 -0.277042 -4.77492 -5.86371 -0.0530716 0.0367667 -0.0211688 0.997689 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 260 310 -0.192984 0.00697089 -6.2521 -0.000801944 0.031195 0.00799361 0.999481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 260 311 -0.303024 4.79556 -6.1157 0.0536846 0.0334173 0.0233761 0.997725 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 261 310 -0.285406 -4.76175 -5.85877 -0.0631019 0.038603 -0.0100823 0.997209 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 261 311 -0.167496 -0.0102526 -6.28229 -0.0027916 0.0382169 -0.000695894 0.999265 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 261 312 -0.295179 4.79375 -6.12625 0.0615616 0.0368827 0.0213064 0.997194 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 262 311 -0.284856 -4.7846 -5.87551 -0.0631799 0.0345262 -0.026168 0.997061 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 262 312 -0.167035 -0.0273052 -6.29848 -0.00262653 0.0345797 -0.00676784 0.999376 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 262 313 -0.313459 4.79903 -6.11735 0.053555 0.0406001 0.0237538 0.997456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 263 312 -0.291237 -4.80045 -5.84735 -0.0538532 0.0275693 -0.0223814 0.997917 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 263 313 -0.209879 0.00475715 -6.28359 -0.00300682 0.0299229 0.0102528 0.999495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 263 314 -0.314266 4.82986 -6.1297 0.053271 0.03997 0.0226963 0.997522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 264 313 -0.274636 -4.83688 -5.8627 -0.0603897 0.0299422 -0.0181028 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 264 314 -0.198107 -0.00759033 -6.26129 0.00135924 0.0338663 -0.00209567 0.999423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 264 315 -0.314267 4.84139 -6.12446 0.0631912 0.028328 0.0176295 0.997444 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 265 314 -0.299461 -4.82225 -5.88561 -0.0616028 0.0220221 -0.01419 0.997757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 265 315 -0.205802 -0.00422203 -6.28195 -2.40445e-05 0.0430769 -0.00151452 0.999071 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 265 316 -0.309306 4.86425 -6.12343 0.0630634 0.0331713 0.0272861 0.997085 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 266 315 -0.296706 -4.85936 -5.88424 -0.0600318 0.0332396 -0.0155091 0.997522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 266 316 -0.184008 0.00622874 -6.28263 0.00239297 0.0253752 -0.000938906 0.999675 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 266 317 -0.312399 4.89007 -6.10941 0.0570148 0.0307245 0.0218554 0.997661 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 267 316 -0.294117 -4.86738 -5.86545 -0.0606356 0.0312831 -0.0162913 0.997537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 267 317 -0.209713 -0.00258091 -6.28004 -0.00134013 0.0230766 0.00364997 0.999726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 267 318 -0.301842 4.88484 -6.09077 0.0668821 0.0293672 0.0278932 0.996938 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 268 317 -0.288801 -4.88267 -5.86742 -0.0554549 0.0256865 -0.0175084 0.997977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 268 318 -0.214201 0.000750177 -6.27619 -0.00625494 0.037486 0.00234458 0.999275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 268 319 -0.30119 4.90411 -6.11052 0.0563658 0.0304981 0.0201163 0.997741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 269 318 -0.291182 -4.89804 -5.84394 -0.047279 0.0310753 -0.0292219 0.99797 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 269 319 -0.193595 -0.00760679 -6.27896 -0.00168369 0.0260047 -0.00474491 0.999649 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 269 320 -0.310112 4.90141 -6.11101 0.0585962 0.0315737 0.0201419 0.997579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 270 319 -0.29861 -4.90708 -5.87216 -0.0532977 0.032022 -0.0250836 0.99775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 270 320 -0.204635 -0.00602061 -6.27744 -0.0072742 0.0312356 0.00975529 0.999438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 270 321 -0.303541 4.92847 -6.11534 0.0586067 0.0327719 0.0235618 0.997465 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 271 320 -0.308775 -4.93006 -5.85337 -0.0612914 0.0408702 -0.0125075 0.997204 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 271 321 -0.183433 -0.00497108 -6.27862 -0.00101154 0.0368307 -0.00350417 0.999315 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 271 322 -0.319582 4.96264 -6.13325 0.0598355 0.0367685 0.0232712 0.997259 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 272 321 -0.307945 -4.91623 -5.85597 -0.054885 0.033171 -0.0166988 0.997802 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 272 322 -0.193703 0.00548968 -6.2682 0.00674574 0.0377078 0.00512168 0.999253 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 272 323 -0.30509 4.96151 -6.11543 0.0631709 0.0301456 0.0281301 0.997151 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 273 322 -0.295117 -4.95344 -5.85928 -0.0563691 0.039028 -0.0171433 0.9975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 273 323 -0.202209 0.0129615 -6.2875 -0.00450169 0.029147 0.00197821 0.999563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 273 324 -0.307131 4.98258 -6.11091 0.053174 0.030868 0.0169435 0.997964 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 274 323 -0.301458 -4.98677 -5.84399 -0.0572069 0.0305717 -0.0250344 0.99758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 274 324 -0.208684 0.00159684 -6.26967 0.00700326 0.0344089 -0.00687947 0.99936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 274 325 -0.304159 4.99751 -6.10118 0.0537241 0.0400379 0.0160917 0.997623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 275 324 -0.30313 -4.96708 -5.87758 -0.0660216 0.0303582 -0.0230869 0.997089 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 275 325 -0.183458 0.00588205 -6.28535 0.0113548 0.0326118 -0.000781518 0.999403 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 275 326 -0.319316 4.99338 -6.09218 0.0584818 0.035513 0.0103508 0.997603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 276 325 -0.294141 -5.00487 -5.86238 -0.0673849 0.0313484 -0.0190989 0.997052 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 276 326 -0.191148 0.00220716 -6.2978 -0.0107139 0.0199359 -0.0120458 0.999671 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 276 327 -0.314165 5.02409 -6.10014 0.0500546 0.0371123 0.0227526 0.997797 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 277 326 -0.28883 -5.00774 -5.85894 -0.0613983 0.0313345 -0.0211448 0.997397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 277 327 -0.200482 -6.62655e-05 -6.28368 0.00579179 0.0300285 -0.0085437 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 277 328 -0.323991 5.03576 -6.12102 0.0581101 0.0372299 0.0231589 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 278 327 -0.312465 -5.0136 -5.85543 -0.0565207 0.0343842 -0.0339745 0.997231 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 278 328 -0.200365 0.0062798 -6.27741 0.004989 0.0316853 -0.00316233 0.99948 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 278 329 -0.318449 5.05313 -6.11147 0.051322 0.0282629 0.028464 0.997876 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 279 328 -0.318261 -5.04744 -5.86577 -0.0566134 0.0317987 -0.0185126 0.997718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 279 329 -0.197344 -0.0177893 -6.28379 0.00438989 0.0285836 -0.00781497 0.999551 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 279 330 -0.318451 5.07069 -6.09715 0.0542395 0.0329729 0.0136528 0.99789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 280 329 -0.295518 -5.04541 -5.85471 -0.0606849 0.0240217 -0.0356299 0.997232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 280 330 -0.197595 -0.00728123 -6.29955 0.00620735 0.0348306 0.00681704 0.999351 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 280 331 -0.317835 5.09059 -6.10701 0.0561745 0.0299132 0.0302193 0.997515 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 281 330 -0.302359 -5.06561 -5.85216 -0.0621115 0.0372246 -0.0199413 0.997175 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 281 331 -0.196774 -0.00207957 -6.28725 -0.00150291 0.0353476 -0.00110867 0.999373 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 281 332 -0.318418 5.07988 -6.10943 0.0615709 0.0287642 0.0268697 0.997326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 282 331 -0.290243 -5.05467 -5.87613 -0.0590047 0.0474393 -0.0217125 0.996893 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 282 332 -0.206613 0.0114089 -6.2723 -0.0180206 0.0347455 -0.00546705 0.999219 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 282 333 -0.331328 5.10766 -6.09109 0.059499 0.0271631 0.0243829 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 283 332 -0.286009 -5.09439 -5.84968 -0.0519106 0.0250896 -0.027063 0.99797 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 283 333 -0.200143 0.0127186 -6.26955 -0.00206031 0.0281666 -0.00172291 0.9996 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 283 334 -0.310815 5.12505 -6.1122 0.0660638 0.0259644 0.0244692 0.997177 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 284 333 -0.309378 -5.11745 -5.8563 -0.0591715 0.0352662 -0.025309 0.997304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 284 334 -0.195282 -0.017814 -6.28965 0.00374164 0.0290036 -0.00286168 0.999568 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 284 335 -0.311273 5.13995 -6.09496 0.0582546 0.036161 0.0298861 0.997199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 285 334 -0.31763 -5.11434 -5.84419 -0.0539962 0.0249754 -0.0143692 0.998125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 285 335 -0.194276 -0.0105829 -6.29317 -0.00167099 0.0203306 -0.00284163 0.999788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 285 336 -0.311696 5.15538 -6.09484 0.0536569 0.0421801 0.0183328 0.9975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 286 335 -0.313039 -5.13298 -5.85112 -0.0585664 0.0346029 -0.0250608 0.997369 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 286 336 -0.188972 -0.0205266 -6.27106 0.012144 0.0370595 0.00660409 0.999217 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 286 337 -0.339326 5.19081 -6.10457 0.070391 0.034999 0.0209896 0.996684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 287 336 -0.30753 -5.15774 -5.85535 -0.0510608 0.0292022 -0.0238152 0.997984 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 287 337 -0.194453 -0.00843082 -6.28039 0.00109296 0.0287378 -0.00373843 0.999579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 287 338 -0.33923 5.1707 -6.09844 0.0617871 0.0307889 0.022584 0.997359 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 288 337 -0.300407 -5.17154 -5.85032 -0.0538529 0.0230841 -0.0213705 0.998053 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 288 338 -0.211044 0.000844112 -6.27147 0.0100027 0.0246435 0.000492504 0.999646 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 288 339 -0.30807 5.19179 -6.09127 0.0577579 0.0318853 0.0303747 0.997359 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 289 338 -0.307413 -5.1628 -5.86318 -0.056163 0.0202547 -0.0329727 0.997671 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 289 339 -0.193037 -0.00172658 -6.26283 0.0101912 0.0375311 -0.00334437 0.999238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 289 340 -0.331823 5.21059 -6.10176 0.0639809 0.0311856 0.0213167 0.997236 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 290 339 -0.309306 -5.19349 -5.84733 -0.0621375 0.0427841 -0.0249675 0.996838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 290 340 -0.188416 -0.0074686 -6.28458 0.00415164 0.0303035 0.00408087 0.999524 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 290 341 -0.3372 5.23215 -6.09824 0.0617925 0.0406043 0.0215636 0.99703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 291 340 -0.311513 -5.2024 -5.83698 -0.0547935 0.0204345 -0.0332812 0.997734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 291 341 -0.200652 0.006576 -6.27966 0.00835808 0.03517 0.0102132 0.999294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 291 342 -0.321955 5.23516 -6.09871 0.0655713 0.029437 0.0126793 0.997333 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 292 341 -0.314238 -5.21827 -5.84055 -0.0653902 0.0253453 -0.0329813 0.996992 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 292 342 -0.204461 0.0125687 -6.28535 -0.00307841 0.0244092 0.00506771 0.999684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 292 343 -0.328865 5.24825 -6.09388 0.0608007 0.0269939 0.0263333 0.997437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 293 342 -0.306855 -5.24133 -5.85165 -0.0496254 0.0318949 -0.0239483 0.997971 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 293 343 -0.190102 -9.43458e-05 -6.28982 -0.0148688 0.0391415 0.0018761 0.999121 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 293 344 -0.330504 5.25007 -6.08638 0.0693956 0.0304645 0.0189148 0.996945 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 294 343 -0.319908 -5.24229 -5.85051 -0.0560319 0.032461 -0.0225582 0.997646 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 294 344 -0.224284 -0.000144846 -6.27518 -0.00499535 0.0372027 0.00743409 0.999268 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 294 345 -0.322691 5.2884 -6.08879 0.0606531 0.0376648 0.0260163 0.997109 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 295 344 -0.315527 -5.26894 -5.84226 -0.0605611 0.0260821 -0.0221396 0.997578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 295 345 -0.169843 0.00368976 -6.29551 -0.00700031 0.0272913 -0.00211483 0.999601 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 295 346 -0.340146 5.28763 -6.08597 0.0522959 0.0326396 0.0262107 0.997754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 296 345 -0.306761 -5.27461 -5.82899 -0.0559111 0.035795 -0.0245719 0.997491 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 296 346 -0.207299 -0.00369637 -6.28836 0.00792111 0.0296003 0.00100519 0.99953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 296 347 -0.319669 5.30739 -6.08435 0.063273 0.0320206 0.0341949 0.996896 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 297 346 -0.314409 -5.29421 -5.82079 -0.0475844 0.0379532 -0.0282296 0.997747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 297 347 -0.193617 -0.0141726 -6.27777 -0.00560906 0.0330101 0.00217578 0.999437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 297 348 -0.330225 5.34229 -6.0924 0.058065 0.0292658 0.020673 0.99767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 298 347 -0.306315 -5.30939 -5.83153 -0.0575157 0.0330502 -0.0226461 0.99754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 298 348 -0.197037 -0.00190832 -6.27141 -0.00313327 0.0325098 -0.000546144 0.999466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 298 349 -0.333399 5.32828 -6.08547 0.0569715 0.0305076 0.0269246 0.997546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 299 348 -0.309893 -5.31222 -5.83142 -0.0558987 0.0288189 -0.0255955 0.997692 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 299 349 -0.206531 0.011305 -6.27891 -0.00642689 0.0325234 0.00490133 0.999438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 299 350 -0.314107 5.35742 -6.09711 0.0562252 0.0450872 0.0247923 0.997091 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 300 349 -0.32505 -5.31898 -5.84468 -0.0601507 0.0302304 -0.026926 0.997368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 300 350 -0.206358 -0.0140947 -6.29771 0.00403405 0.0329692 -0.00111981 0.999448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 300 351 -0.343314 5.37419 -6.07465 0.056964 0.0362607 0.0230259 0.997452 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 301 350 -0.306978 -5.34984 -5.84012 -0.0526634 0.0317644 -0.0243679 0.997809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 301 351 -0.214648 0.00664519 -6.26739 -0.000277333 0.0272159 0.00309589 0.999625 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 301 352 -0.327539 5.38765 -6.09639 0.0589761 0.0352261 0.0206112 0.997425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 302 351 -0.316998 -5.36059 -5.85276 -0.0648646 0.0294126 -0.0239088 0.997174 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 302 352 -0.181404 0.000182321 -6.2618 -0.00626515 0.0346526 -0.00136688 0.999379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 302 353 -0.313151 5.40052 -6.08984 0.0522893 0.0329362 0.0291246 0.997664 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 303 352 -0.303756 -5.37359 -5.84764 -0.055166 0.0259287 -0.0340359 0.99756 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 303 353 -0.198833 -0.00827605 -6.27645 -0.00758151 0.0309436 0.00215323 0.99949 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 303 354 -0.321298 5.39994 -6.08966 0.0525671 0.0339861 0.0250604 0.997724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 304 353 -0.307686 -5.39546 -5.83875 -0.050585 0.0271855 -0.0298485 0.997903 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 304 354 -0.180948 0.0023076 -6.26978 0.00374793 0.0192527 -0.00220959 0.999805 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 304 355 -0.332713 5.42738 -6.09295 0.0606406 0.0239495 0.0239994 0.997584 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 305 354 -0.302117 -5.40144 -5.86002 -0.0616242 0.0360689 -0.025035 0.997133 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 305 355 -0.210952 0.00175754 -6.27102 0.000755394 0.022479 -0.00352036 0.999741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 305 356 -0.328584 5.44915 -6.07549 0.0579483 0.0209914 0.0271885 0.997728 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 306 355 -0.333874 -5.40768 -5.85376 -0.0489933 0.0202952 -0.0242379 0.998299 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 306 356 -0.190675 -0.00267228 -6.28932 -0.00488767 0.0305349 -0.0023704 0.999519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 306 357 -0.333443 5.43853 -6.08133 0.054341 0.0303314 0.03236 0.997537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 307 356 -0.337275 -5.44679 -5.83443 -0.0546799 0.041646 -0.0257922 0.997302 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 307 357 -0.207401 0.0128608 -6.27631 -0.00350481 0.0283288 0.000397298 0.999592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 307 358 -0.337995 5.46008 -6.07141 0.0554947 0.0251567 0.0261888 0.997798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 308 357 -0.324417 -5.44734 -5.84003 -0.0676063 0.0398342 -0.0240002 0.996628 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 308 358 -0.192092 0.0016296 -6.27481 -0.00310585 0.0253979 -0.000708808 0.999672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 308 359 -0.332522 5.48767 -6.08319 0.0600704 0.0300596 0.0205655 0.997529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 309 358 -0.31519 -5.48529 -5.8364 -0.0606204 0.0322059 -0.0302652 0.997182 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 309 359 -0.200293 0.0033762 -6.27862 0.0136965 0.0292125 0.00058774 0.999479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 309 360 -0.347893 5.48816 -6.10577 0.0608412 0.038678 0.0216183 0.997163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 310 359 -0.318986 -5.49403 -5.83843 -0.0537936 0.0355352 -0.0204252 0.997711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 310 360 -0.189092 0.00282845 -6.27686 -0.00669681 0.0339493 0.00237908 0.999398 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 310 361 -0.327447 5.50445 -6.09226 0.0549768 0.0405201 0.0288785 0.997247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 311 360 -0.333159 -5.49243 -5.8251 -0.0545233 0.0291575 -0.0304024 0.997624 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 311 361 -0.201062 -0.00794643 -6.27845 0.0011317 0.0318844 0.000851111 0.999491 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 311 362 -0.3318 5.52404 -6.08846 0.058314 0.0298232 0.0245789 0.99755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 312 361 -0.30783 -5.52054 -5.81836 -0.0557481 0.0268223 -0.0238212 0.9978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 312 362 -0.208937 -0.00276455 -6.27682 0.00167608 0.027907 -0.00288851 0.999605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 312 363 -0.333405 5.52993 -6.08427 0.0477723 0.0291902 0.0242285 0.998138 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 313 362 -0.328498 -5.53241 -5.81599 -0.0618311 0.038543 -0.0231829 0.997073 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 313 363 -0.192676 -0.00860369 -6.27696 -0.000326758 0.0335822 0.00390994 0.999428 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 313 364 -0.333214 5.53673 -6.08916 0.0514256 0.0325789 0.0206882 0.997931 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 314 363 -0.322334 -5.51674 -5.82373 -0.0615251 0.0387146 -0.0220186 0.997111 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 314 364 -0.191665 0.00476688 -6.25734 0.00995922 0.030476 -0.00395672 0.999478 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 314 365 -0.352632 5.55558 -6.07952 0.0552082 0.0336261 0.0243612 0.997611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 315 364 -0.327222 -5.56378 -5.82295 -0.0544255 0.0345362 -0.0325886 0.997388 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 315 365 -0.201019 -0.00996987 -6.27376 0.00734653 0.0378302 -0.0113969 0.999192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 315 366 -0.336346 5.57666 -6.09106 0.0653983 0.0260217 0.0203368 0.997313 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 316 365 -0.322035 -5.56939 -5.83525 -0.0575877 0.0264775 -0.0265711 0.997635 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 316 366 -0.198061 -0.00514268 -6.28799 -0.00560628 0.0379923 0.00579267 0.999246 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 316 367 -0.328487 5.591 -6.0844 0.0565462 0.0244505 0.0282363 0.997701 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 317 366 -0.326165 -5.58361 -5.83219 -0.0530576 0.0238217 -0.0246425 0.998003 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 317 367 -0.197484 0.00995572 -6.28559 -0.00128951 0.0339397 -0.00122611 0.999422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 317 368 -0.329733 5.59922 -6.07027 0.0582618 0.0345757 0.0360935 0.997049 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 318 367 -0.340314 -5.62318 -5.82716 -0.0598473 0.0307978 -0.029252 0.997303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 318 368 -0.197877 0.00328879 -6.29321 -0.00107665 0.025107 -0.00411488 0.999676 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 318 369 -0.333457 5.61606 -6.07457 0.0614982 0.0301458 0.0330855 0.997103 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 319 368 -0.338003 -5.61861 -5.82671 -0.0545767 0.0328785 -0.0259279 0.997631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 319 369 -0.20377 -0.013334 -6.28029 0.00836012 0.0211931 -0.00830984 0.999706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 319 370 -0.357087 5.64105 -6.07292 0.0522789 0.0275559 0.0233611 0.997979 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 320 369 -0.327336 -5.62291 -5.83288 -0.0685452 0.0292412 -0.0279814 0.996827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 320 370 -0.195379 -0.00795898 -6.27642 -0.0020999 0.0220644 -0.00171171 0.999753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 320 371 -0.344777 5.6438 -6.07359 0.0623245 0.0346529 0.0201373 0.997251 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 321 370 -0.344111 -5.63196 -5.81746 -0.0520307 0.0308754 -0.0380859 0.997441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 321 371 -0.225198 -0.0193298 -6.28772 -0.00238774 0.0228855 0.00129752 0.999734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 321 372 -0.346329 5.67584 -6.08157 0.053775 0.032986 0.0266633 0.997652 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 322 371 -0.335308 -5.64589 -5.80767 -0.0601437 0.0395184 -0.0332041 0.996854 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 322 372 -0.198954 0.000358236 -6.2823 -0.00335251 0.0433534 0.00802273 0.999022 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 322 373 -0.351877 5.68786 -6.08485 0.0542631 0.0224495 0.0233344 0.998002 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 323 372 -0.312115 -5.65773 -5.81444 -0.053802 0.0340698 -0.027359 0.997595 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 323 373 -0.202329 -0.0273584 -6.29132 -0.000948674 0.0337028 0.00172288 0.99943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 323 374 -0.352635 5.71107 -6.07476 0.05186 0.0342346 0.034124 0.997484 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 324 373 -0.32869 -5.67125 -5.81671 -0.0563608 0.0218735 -0.0249015 0.99786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 324 374 -0.191271 -0.00108852 -6.29219 0.0101542 0.0322024 -0.0100879 0.999379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 324 375 -0.344325 5.69047 -6.07522 0.0576059 0.0265724 0.0318738 0.997477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 325 374 -0.332386 -5.67835 -5.81221 -0.0523753 0.0254541 -0.0252641 0.997983 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 325 375 -0.196748 0.000437843 -6.2764 -0.0075706 0.0344508 0.00286322 0.999374 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 325 376 -0.351356 5.71692 -6.06813 0.0617054 0.0348421 0.0240275 0.997197 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 326 375 -0.322167 -5.71358 -5.82449 -0.054988 0.0337872 -0.0184855 0.997744 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 326 376 -0.190268 0.012774 -6.28198 -0.00962064 0.0371176 -0.000169381 0.999265 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 326 377 -0.328409 5.75945 -6.08711 0.0528545 0.0371238 0.0334949 0.99735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 327 376 -0.328614 -5.71887 -5.81434 -0.0493805 0.0266473 -0.0284421 0.998019 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 327 377 -0.195454 -0.00958048 -6.27281 0.0109121 0.0283807 0.00274024 0.999534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 327 378 -0.342901 5.74597 -6.0674 0.0613402 0.0253742 0.0184163 0.997624 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 328 377 -0.325112 -5.71776 -5.81636 -0.0614133 0.0291922 -0.0283974 0.997281 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 328 378 -0.200821 -0.00647312 -6.27687 0.00962226 0.0323542 0.0015392 0.999429 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 328 379 -0.341305 5.7648 -6.06017 0.0439053 0.0326826 0.0330618 0.997953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 329 378 -0.341386 -5.75684 -5.83744 -0.0520518 0.0230455 -0.0279297 0.997988 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 329 379 -0.186034 -0.00424877 -6.28297 -0.00944384 0.0313208 0.00248713 0.999462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 329 380 -0.345519 5.78273 -6.0743 0.0609156 0.0291894 0.0248313 0.997407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 330 379 -0.33528 -5.75843 -5.82957 -0.058879 0.0249191 -0.0253831 0.997631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 330 380 -0.207947 -0.00287994 -6.28897 0.00605219 0.0327 -0.00241161 0.999444 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 330 381 -0.350844 5.79173 -6.07431 0.0595922 0.0430135 0.0284753 0.996889 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 331 380 -0.344944 -5.78252 -5.82125 -0.0657156 0.0258158 -0.0345487 0.996906 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 331 381 -0.194891 0.0142302 -6.26799 0.00478414 0.0287594 -0.00366107 0.999568 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 331 382 -0.353071 5.79657 -6.04948 0.0506913 0.032562 0.024243 0.997889 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 332 381 -0.348099 -5.78168 -5.80679 -0.054962 0.0280599 -0.0286012 0.997684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 332 382 -0.191033 0.00233567 -6.2789 -0.00184729 0.0383843 0.00828951 0.999227 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 332 383 -0.349571 5.81121 -6.06327 0.0619103 0.0376137 0.0248755 0.997062 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 333 382 -0.332373 -5.81676 -5.82838 -0.0550022 0.0295906 -0.0308093 0.997572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 333 383 -0.192428 -0.0161593 -6.27128 -0.000134181 0.0305962 -0.0031042 0.999527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 333 384 -0.359866 5.85359 -6.07114 0.0518789 0.030269 0.0334093 0.997635 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 334 383 -0.356685 -5.84073 -5.81215 -0.0509123 0.0301804 -0.0234696 0.997971 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 334 384 -0.196507 0.00168412 -6.3043 -0.00584336 0.0350356 0.00109271 0.999368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 334 385 -0.354484 5.83862 -6.06007 0.0579203 0.0297113 0.0311545 0.997393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 335 384 -0.33767 -5.82695 -5.81265 -0.0611588 0.0395465 -0.0354096 0.996716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 335 385 -0.21382 -0.00543324 -6.28398 0.0016589 0.0308883 -0.00342624 0.999516 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 335 386 -0.330228 5.86281 -6.07179 0.0521623 0.0340462 0.0368287 0.997378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 336 385 -0.333089 -5.85231 -5.82652 -0.0532822 0.029495 -0.0296088 0.997705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 336 386 -0.177264 0.00025068 -6.27933 0.00107135 0.0269004 -9.58514e-05 0.999638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 336 387 -0.360205 5.86818 -6.05249 0.058056 0.0300941 0.0263695 0.997511 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 337 386 -0.350294 -5.87172 -5.82313 -0.0605956 0.0239698 -0.0178556 0.997715 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 337 387 -0.220291 -0.0045836 -6.28723 0.00612839 0.0295794 0.00385637 0.999536 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 337 388 -0.35707 5.87873 -6.06396 0.0460351 0.0262891 0.0319493 0.998083 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 338 387 -0.33679 -5.87544 -5.82343 -0.0607225 0.0272191 -0.0259562 0.997446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 338 388 -0.186696 -0.00595204 -6.26209 -0.000998748 0.0269889 -0.00473337 0.999624 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 338 389 -0.348532 5.89722 -6.06854 0.0603947 0.0296206 0.0222249 0.997487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 339 388 -0.343012 -5.88056 -5.82668 -0.0521782 0.0204378 -0.0298359 0.997983 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 339 389 -0.197233 -0.0165973 -6.26896 -0.00103598 0.0232945 -0.00170145 0.999727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 339 390 -0.353807 5.92382 -6.05221 0.0524353 0.0436067 0.0275743 0.997291 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 340 389 -0.349376 -5.90767 -5.81967 -0.0543245 0.0285102 -0.031964 0.997604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 340 390 -0.185962 0.00678938 -6.29217 -0.00539683 0.0310715 0.00510165 0.99949 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 340 391 -0.389046 5.9404 -6.06799 0.055092 0.029785 0.0240608 0.997747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 341 390 -0.355894 -5.9097 -5.80829 -0.0578483 0.0329079 -0.0269119 0.99742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 341 391 -0.196523 0.0134955 -6.27411 -0.0070986 0.0375677 0.00495394 0.999257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 341 392 -0.367671 5.9227 -6.06172 0.0593356 0.0335981 0.0251463 0.997356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 342 391 -0.347534 -5.92059 -5.83154 -0.0630052 0.0278924 -0.0275819 0.997242 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 342 392 -0.212422 0.00561492 -6.27853 0.00122583 0.0298009 0.00820712 0.999521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 342 393 -0.366366 5.95759 -6.06265 0.055591 0.0388255 0.0331454 0.997148 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 343 392 -0.348299 -5.94376 -5.81565 -0.0563202 0.0378665 -0.0266655 0.997338 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 343 393 -0.204735 0.00580478 -6.28392 -0.00357912 0.0365874 -0.000226729 0.999324 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 343 394 -0.372251 5.97161 -6.06776 0.0458724 0.0277536 0.0214538 0.998331 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 344 393 -0.34427 -5.959 -5.82448 -0.052349 0.0256752 -0.0331403 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 344 394 -0.199348 0.00932242 -6.28295 0.00303251 0.0369424 0.00212895 0.999311 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 344 395 -0.356185 5.98183 -6.04672 0.0546781 0.025746 0.0409969 0.99733 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 345 394 -0.359355 -5.99802 -5.83214 -0.0578167 0.0342432 -0.0241299 0.997448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 345 395 -0.188457 0.000923175 -6.28587 0.000653952 0.0267104 -0.00548741 0.999628 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 345 396 -0.383047 6.0067 -6.06131 0.0510547 0.0274129 0.0262638 0.997974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 346 395 -0.345243 -5.9692 -5.81826 -0.0542996 0.0271084 -0.0258307 0.997822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 346 396 -0.188896 0.00647016 -6.28102 0.00617188 0.0357381 0.00534144 0.999328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 346 397 -0.363795 5.99465 -6.05546 0.0608941 0.0261642 0.0318742 0.997292 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 347 396 -0.34803 -5.98643 -5.81956 -0.0552634 0.0351782 -0.0256399 0.997522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 347 397 -0.194517 0.00161576 -6.28745 0.00179514 0.0412866 0.00320163 0.999141 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 347 398 -0.367331 6.02672 -6.06064 0.055291 0.0383114 0.0314775 0.997238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 348 397 -0.366053 -5.99763 -5.81433 -0.0621394 0.0358654 -0.0193935 0.997234 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 348 398 -0.202339 0.00601228 -6.28802 0.0038344 0.0251787 -0.00326111 0.99967 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 348 399 -0.35198 6.04652 -6.05044 0.0539897 0.0278746 0.0330487 0.997605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 349 398 -0.376713 -6.02355 -5.80785 -0.0500856 0.019154 -0.0369213 0.997878 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 349 399 -0.19859 0.00258517 -6.28532 0.00777629 0.0259684 0.00414925 0.999624 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 349 400 -0.363726 6.03942 -6.05546 0.0557116 0.0369442 0.023507 0.997486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 350 399 -0.362195 -6.02132 -5.82323 -0.0576791 0.0274704 -0.0276557 0.997574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 350 400 -0.204997 0.00858702 -6.27744 0.003912 0.0339379 0.00625539 0.999397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 350 401 -0.372529 6.05963 -6.0644 0.0523866 0.0360289 0.0281571 0.997579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 351 400 -0.360288 -6.06381 -5.81689 -0.0540383 0.0240969 -0.0369347 0.997565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 351 401 -0.181356 0.00406414 -6.27146 -0.00660282 0.0338258 0.0104028 0.999352 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 351 402 -0.363174 6.08624 -6.06137 0.0570937 0.027537 0.0323617 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 352 401 -0.366211 -6.07993 -5.80809 -0.0612504 0.0349068 -0.0308093 0.997036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 352 402 -0.187075 -0.00645431 -6.27505 0.00110312 0.0239545 -0.00155056 0.999711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 352 403 -0.358015 6.09303 -6.05204 0.054781 0.0333286 0.0290902 0.997518 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 353 402 -0.350067 -6.08767 -5.81964 -0.0555718 0.0369926 -0.0304724 0.997304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 353 403 -0.206681 0.00464925 -6.27802 0.0050003 0.0340813 0.00385613 0.999399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 353 404 -0.348836 6.09978 -6.06273 0.0541778 0.035011 0.0254436 0.997593 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 354 403 -0.348468 -6.09097 -5.81624 -0.0644638 0.0381619 -0.0315065 0.996692 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 354 404 -0.204925 -0.0130322 -6.29024 -0.00255737 0.0331151 -0.00207918 0.999446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 354 405 -0.363592 6.11224 -6.04981 0.0606734 0.0334329 0.0272685 0.997225 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 355 404 -0.350293 -6.10268 -5.80001 -0.0661771 0.0360316 -0.0306365 0.996686 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 355 405 -0.204779 -0.00528654 -6.2789 0.0079447 0.0342241 0.00610971 0.999364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 355 406 -0.361424 6.10354 -6.05894 0.057665 0.0370653 0.0405888 0.996822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 356 405 -0.348019 -6.11775 -5.81588 -0.053396 0.0220966 -0.0264532 0.997978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 356 406 -0.203578 0.00764637 -6.30249 -0.00136707 0.0299121 -0.0038691 0.999544 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 356 407 -0.381876 6.14612 -6.02877 0.0656613 0.0314504 0.0288795 0.996928 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 357 406 -0.365042 -6.13214 -5.81683 -0.0562487 0.0258559 -0.0360266 0.997432 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 357 407 -0.197408 -1.45918e-05 -6.26522 0.000597817 0.0280088 -0.00271693 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 357 408 -0.368936 6.16002 -6.07313 0.0597299 0.0396668 0.0304656 0.996961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 358 407 -0.355267 -6.1498 -5.7889 -0.0599987 0.030172 -0.0305483 0.997275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 358 408 -0.211952 0.00631066 -6.28309 0.00285283 0.0262022 0.00270413 0.999649 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 358 409 -0.355186 6.15381 -6.0513 0.0532482 0.034991 0.0279646 0.997576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 359 408 -0.352586 -6.15658 -5.78719 -0.0528138 0.0260779 -0.0229332 0.998 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 359 409 -0.195896 -0.00816236 -6.27898 0.00355969 0.0261746 -0.00142805 0.99965 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 359 410 -0.365555 6.21262 -6.0592 0.0552724 0.031936 0.0226806 0.997703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 360 409 -0.35784 -6.15896 -5.79445 -0.0514715 0.0160733 -0.0287381 0.998131 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 360 410 -0.191129 0.00741869 -6.27399 -0.00769731 0.0229647 0.00866151 0.999669 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 360 411 -0.37525 6.20415 -6.04901 0.0541551 0.0318815 0.0277367 0.997638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 361 410 -0.366443 -6.19632 -5.79635 -0.0562121 0.0324571 -0.026325 0.997544 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 361 411 -0.190341 0.00312235 -6.26341 0.00843388 0.0285695 0.00650195 0.999535 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 361 412 -0.362719 6.22407 -6.04045 0.0548335 0.0372427 0.0301159 0.997346 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 362 411 -0.3627 -6.20212 -5.80338 -0.0588819 0.038421 -0.0364673 0.996859 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 362 412 -0.211096 -0.00959316 -6.26832 -0.00536543 0.0298194 -0.00174753 0.999539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 362 413 -0.383877 6.20663 -6.05151 0.053198 0.03662 0.0186139 0.997739 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 363 412 -0.364331 -6.21119 -5.81374 -0.051257 0.0325409 -0.0260176 0.997816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 363 413 -0.209782 0.0044133 -6.27729 0.00562157 0.0322598 -0.00376014 0.999457 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 363 414 -0.378355 6.23746 -6.06879 0.0559202 0.0335 0.0392104 0.997102 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 364 413 -0.360708 -6.22523 -5.79008 -0.0586346 0.0417779 -0.0373052 0.996707 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 364 414 -0.204002 -0.0112904 -6.28321 0.00314101 0.0309086 -0.00297911 0.999513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 364 415 -0.380193 6.25707 -6.04529 0.0561274 0.0278531 0.0338403 0.997461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 365 414 -0.372479 -6.2417 -5.80902 -0.0567479 0.0312922 -0.0323977 0.997372 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 365 415 -0.205331 0.00990618 -6.27964 -0.00742003 0.0277468 -0.00240927 0.999585 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 365 416 -0.369672 6.26477 -6.04957 0.0556269 0.0335211 0.0330852 0.99734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 366 415 -0.351768 -6.26018 -5.81419 -0.0545441 0.0345123 -0.0298324 0.997469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 366 416 -0.199689 -0.00538232 -6.28013 0.00498618 0.0275648 -0.00201774 0.999606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 366 417 -0.380556 6.26671 -6.0465 0.0500113 0.0373202 0.0318046 0.997544 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 367 416 -0.358168 -6.28111 -5.79791 -0.06435 0.0228027 -0.029297 0.997237 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 367 417 -0.188206 -0.00970118 -6.27493 0.0105817 0.0326504 -0.00312518 0.999406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 367 418 -0.377071 6.30355 -6.06142 0.0530332 0.0311423 0.0288089 0.997691 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 368 417 -0.363112 -6.27633 -5.79859 -0.0582334 0.0240975 -0.0315689 0.997513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 368 418 -0.200729 -0.00871699 -6.27682 0.00736074 0.0299177 -0.00476302 0.999514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 368 419 -0.408784 6.29923 -6.0367 0.0653371 0.0357137 0.0319436 0.996712 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 369 418 -0.383983 -6.29718 -5.79775 -0.0557827 0.0330543 -0.0200303 0.997695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 369 419 -0.200509 0.0104497 -6.2795 -0.0126061 0.0376165 0.00528026 0.999199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 369 420 -0.365409 6.32242 -6.03822 0.0586937 0.0321782 0.036537 0.997088 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 370 419 -0.376983 -6.33601 -5.80419 -0.0574312 0.0269819 -0.0298384 0.997539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 370 420 -0.210261 0.00384634 -6.28603 0.00561744 0.0285981 -0.000224667 0.999575 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 370 421 -0.388922 6.32533 -6.04579 0.0512235 0.0272862 0.0323787 0.997789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 371 420 -0.379519 -6.34534 -5.80838 -0.0613115 0.0342107 -0.0184268 0.997362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 371 421 -0.205359 0.00419425 -6.29626 0.00299767 0.0341841 -0.00464608 0.9994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 371 422 -0.373924 6.37413 -6.03449 0.0580947 0.034366 0.0231713 0.99745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 372 421 -0.372703 -6.3146 -5.79924 -0.0617057 0.0259084 -0.0299457 0.997309 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 372 422 -0.196659 0.00457797 -6.29689 -0.00289851 0.034178 0.00632355 0.999392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 372 423 -0.392501 6.3825 -6.04149 0.0548258 0.0272859 0.0336998 0.997554 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 373 422 -0.385288 -6.35911 -5.81037 -0.0606338 0.034776 -0.0328865 0.997012 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 373 423 -0.19005 -0.00363544 -6.27753 -0.00516791 0.028621 -0.00397174 0.999569 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 373 424 -0.382 6.38214 -6.04302 0.0505495 0.0321255 0.0281406 0.997808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 374 423 -0.346149 -6.36377 -5.80269 -0.0471387 0.0299588 -0.0292954 0.998009 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 374 424 -0.197945 -0.012412 -6.28533 -3.22464e-05 0.0225445 -0.00320949 0.999741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 374 425 -0.391602 6.39139 -6.03106 0.0519914 0.0344739 0.0338424 0.997478 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 375 424 -0.374729 -6.38406 -5.78768 -0.054034 0.0341333 -0.020975 0.997735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 375 425 -0.17958 0.00782481 -6.28464 0.000640501 0.03464 0.00238785 0.999397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 375 426 -0.404907 6.40797 -6.03277 0.0519308 0.0265372 0.0272657 0.997926 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 376 425 -0.366889 -6.39581 -5.80904 -0.0536398 0.0365761 -0.0304836 0.997425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 376 426 -0.223406 -0.028734 -6.27575 2.20385e-05 0.0282085 -0.00245799 0.999599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 376 427 -0.383169 6.40635 -6.0453 0.0562818 0.0322643 0.0316319 0.997392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 377 426 -0.370607 -6.39451 -5.79276 -0.0586091 0.0306495 -0.0249056 0.9975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 377 427 -0.187769 0.00391175 -6.27982 -0.00371614 0.0271523 -0.00138848 0.999623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 377 428 -0.390018 6.44912 -6.05259 0.0517826 0.0264464 0.031128 0.997823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 378 427 -0.36419 -6.40544 -5.78252 -0.0535955 0.0333123 -0.0237384 0.997725 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 378 428 -0.200583 -0.000912736 -6.29293 0.000914848 0.0320801 0.00653008 0.999464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 378 429 -0.39887 6.46721 -6.04236 0.0564273 0.0254712 0.0409563 0.997241 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 379 428 -0.369804 -6.44423 -5.79308 -0.0613794 0.0345994 -0.0322136 0.996994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 379 429 -0.193215 0.0155045 -6.29198 0.00442303 0.029845 -0.00191026 0.999543 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 379 430 -0.384607 6.45914 -6.04063 0.0590451 0.024866 0.0267551 0.997587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 380 429 -0.357507 -6.43983 -5.79274 -0.0527682 0.0330621 -0.0327711 0.997521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 380 430 -0.184828 -0.00861187 -6.26876 0.00245749 0.0345847 -0.0107746 0.999341 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 380 431 -0.408332 6.48405 -6.0282 0.0590974 0.0267311 0.0364104 0.99723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 381 430 -0.376016 -6.4652 -5.80915 -0.0473059 0.0245749 -0.0320674 0.998063 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 381 431 -0.199101 0.0188877 -6.27872 -0.011161 0.0282208 0.00625061 0.99952 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 381 432 -0.408594 6.48918 -6.0342 0.0439247 0.0277255 0.032598 0.998118 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 382 431 -0.368885 -6.46491 -5.77329 -0.0566386 0.034128 -0.0311979 0.997323 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 382 432 -0.193035 -0.010444 -6.2765 0.00578788 0.033923 0.000864002 0.999407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 382 433 -0.385884 6.46414 -6.03386 0.0546556 0.0352193 0.0292249 0.997456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 383 432 -0.369894 -6.50031 -5.78609 -0.060154 0.0243658 -0.0282216 0.997493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 383 433 -0.213397 -0.0105583 -6.28483 0.00396098 0.0313733 -0.00541274 0.999485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 383 434 -0.386336 6.53686 -6.03903 0.0639915 0.0345084 0.0348305 0.996745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 384 433 -0.371697 -6.49176 -5.80187 -0.0533635 0.0243079 -0.0328221 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 384 434 -0.181855 -0.00334474 -6.27939 0.00146911 0.0273621 0.0056295 0.999609 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 384 435 -0.39444 6.51884 -6.04943 0.047137 0.0294362 0.0252794 0.998135 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 385 434 -0.379324 -6.51476 -5.78681 -0.0614349 0.0291678 -0.0252668 0.997365 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 385 435 -0.196416 0.00791856 -6.26795 0.00945057 0.0357462 -0.00488729 0.999304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 385 436 -0.394877 6.55509 -6.03124 0.0504023 0.0354966 0.0295233 0.997661 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 386 435 -0.382235 -6.52416 -5.79405 -0.0570903 0.0185934 -0.0348152 0.997589 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 386 436 -0.190375 -0.00747155 -6.28427 0.00617143 0.0345974 -0.00389182 0.999375 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 386 437 -0.420053 6.54661 -6.05023 0.0600966 0.0218186 0.0368258 0.997274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 387 436 -0.387065 -6.54873 -5.78926 -0.0575271 0.0276603 -0.0329471 0.997417 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 387 437 -0.207148 -0.016279 -6.28103 0.0047526 0.0311899 -0.00346271 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 387 438 -0.393657 6.56918 -6.04838 0.0494888 0.0300562 0.0371366 0.997631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 388 437 -0.379267 -6.53633 -5.78792 -0.0445168 0.0330577 -0.0322892 0.997939 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 388 438 -0.200032 0.0102385 -6.2832 0.00306258 0.0285526 0.00558244 0.999572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 388 439 -0.415381 6.57622 -6.04632 0.0538074 0.0323358 0.0276528 0.997644 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 389 438 -0.400298 -6.5904 -5.78432 -0.0509631 0.0286419 -0.0378642 0.997571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 389 439 -0.194543 0.00534756 -6.2786 0.00414998 0.0312797 0.000983498 0.999502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 389 440 -0.404958 6.60314 -6.03867 0.0605613 0.0317275 0.0339518 0.997082 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 390 439 -0.393729 -6.58304 -5.79287 -0.0600441 0.0347495 -0.0332552 0.997036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 390 440 -0.19755 -0.0152287 -6.27421 -0.00326937 0.0331037 -0.000693566 0.999446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 390 441 -0.40398 6.60933 -6.01352 0.0464485 0.0366151 0.0266895 0.997893 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 391 440 -0.383059 -6.60045 -5.80907 -0.0637112 0.0347596 -0.0263168 0.997016 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 391 441 -0.196798 0.005658 -6.25914 -0.00459927 0.0339083 8.02354e-05 0.999414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 391 442 -0.404041 6.60774 -6.03964 0.0445721 0.0429627 0.0426452 0.99717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 392 441 -0.37768 -6.60324 -5.77932 -0.0508541 0.0273157 -0.040589 0.997507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 392 442 -0.207096 -0.00974824 -6.27611 -0.0101852 0.0342365 0.0156787 0.999239 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 392 443 -0.38234 6.61382 -6.03825 0.0599099 0.0328752 0.0273728 0.997287 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 393 442 -0.390774 -6.6261 -5.78629 -0.0510389 0.0340267 -0.0244336 0.997818 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 393 443 -0.20363 -0.00181634 -6.28349 0.0023306 0.0409054 -0.0041764 0.999152 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 393 444 -0.393836 6.64822 -6.03933 0.0452044 0.0326262 0.0260422 0.998105 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 394 443 -0.378203 -6.64485 -5.79072 -0.05344 0.0329486 -0.0347109 0.997424 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 394 444 -0.205315 0.00388963 -6.28752 0.00225264 0.0361315 -0.00280649 0.999341 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 394 445 -0.400743 6.69457 -6.04198 0.0466947 0.0308028 0.037093 0.997745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 395 444 -0.400938 -6.64894 -5.79548 -0.0627986 0.0326919 -0.0251333 0.997174 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 395 445 -0.20292 -0.0025556 -6.30717 -0.00751118 0.0244791 -0.00754514 0.999644 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 395 446 -0.40433 6.67203 -6.05353 0.0455791 0.0314563 0.031465 0.997969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 396 445 -0.397136 -6.66666 -5.7712 -0.054614 0.0278284 -0.0324908 0.997591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 396 446 -0.200594 -0.0204114 -6.26843 0.00201241 0.0333914 -0.00309247 0.999436 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 396 447 -0.406784 6.69265 -6.03706 0.0506733 0.031024 0.0241163 0.997942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 397 446 -0.372927 -6.65936 -5.78751 -0.0498314 0.0390809 -0.0272483 0.997621 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 397 447 -0.192486 -0.020912 -6.27351 -0.00392585 0.0262421 -0.0093162 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 397 448 -0.423305 6.71069 -6.04651 0.0486812 0.0333086 0.0397138 0.997469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 398 447 -0.399979 -6.69737 -5.77894 -0.0551806 0.0327021 -0.0317305 0.997436 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 398 448 -0.20752 -0.0196789 -6.26879 -0.00203587 0.0346883 -9.16432e-05 0.999396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 398 449 -0.414422 6.73423 -6.03198 0.0577802 0.0367747 0.0346011 0.997052 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 399 448 -0.382861 -6.70941 -5.78988 -0.0585969 0.0266106 -0.0321862 0.997408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 399 449 -0.212823 -0.00409323 -6.28663 0.00281386 0.0267134 -0.00385027 0.999632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 399 450 -0.42566 6.72866 -6.04177 0.0446745 0.0317511 0.0338531 0.997923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 400 449 -0.400305 -6.69642 -5.78879 -0.0561153 0.0301291 -0.0391321 0.997202 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 400 450 -0.195892 -0.00661808 -6.27328 -0.0124639 0.0319728 0.00186575 0.999409 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 400 451 -0.410195 6.74373 -6.04613 0.0577258 0.0313859 0.0290632 0.997416 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 401 450 -0.389534 -6.71016 -5.78127 -0.0563622 0.0186675 -0.0303124 0.997776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 401 451 -0.192597 -0.0153772 -6.29884 0.00350617 0.0289608 0.00314884 0.999569 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 401 452 -0.404794 6.74531 -6.02256 0.0507859 0.0451992 0.030576 0.997218 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 402 451 -0.388637 -6.74552 -5.78551 -0.0505545 0.0220124 -0.0450263 0.997463 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 402 452 -0.195014 0.000919714 -6.26412 0.00284608 0.0263875 0.000882068 0.999647 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 402 453 -0.425377 6.76401 -6.0167 0.0494106 0.0301369 0.0227045 0.998066 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 403 452 -0.403079 -6.74701 -5.79056 -0.0543384 0.0284514 -0.0361943 0.997461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 403 453 -0.212016 0.00429739 -6.2489 0.000318495 0.0362267 0.00532161 0.999329 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 403 454 -0.406722 6.77183 -6.02644 0.0475791 0.0368991 0.0341019 0.997603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 404 453 -0.395073 -6.76131 -5.78076 -0.0504755 0.028096 -0.0318706 0.997821 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 404 454 -0.206404 0.00438833 -6.28289 0.0058712 0.0310815 -0.00446689 0.99949 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 404 455 -0.416125 6.79332 -6.04837 0.0557188 0.03056 0.0356131 0.997343 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 405 454 -0.390178 -6.79015 -5.77802 -0.0519695 0.0281717 -0.0308367 0.997775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 405 455 -0.196897 0.00867874 -6.27396 0.00276697 0.0317015 -0.00209986 0.999491 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 405 456 -0.417212 6.81878 -6.03068 0.0493639 0.0328061 0.0290617 0.997819 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 406 455 -0.405385 -6.81738 -5.76893 -0.0470468 0.0256338 -0.0288424 0.998147 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 406 456 -0.188441 -0.0042749 -6.27816 0.00141205 0.0300608 0.00726514 0.999521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 406 457 -0.406768 6.83323 -6.04383 0.0559238 0.0309086 0.0305769 0.997488 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 407 456 -0.408599 -6.79777 -5.77002 -0.0467262 0.0214087 -0.031943 0.998167 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 407 457 -0.188603 -0.0019673 -6.26167 -0.0026031 0.0330138 -0.000816158 0.999451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 407 458 -0.41434 6.83568 -6.01688 0.0527791 0.0307234 0.039457 0.997353 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 408 457 -0.399886 -6.82626 -5.77426 -0.0497978 0.0301787 -0.0324488 0.997776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 408 458 -0.205208 0.00523652 -6.26092 -0.00943693 0.0262661 0.00121762 0.99961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 408 459 -0.40549 6.86148 -6.03765 0.0547947 0.0271964 0.0257267 0.997796 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 409 458 -0.411676 -6.82545 -5.78336 -0.0559572 0.0357093 -0.0246751 0.997489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 409 459 -0.197149 0.00475898 -6.29885 0.00854803 0.0334182 -0.0029816 0.9994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 409 460 -0.433741 6.86695 -6.02608 0.056787 0.0368292 0.0231395 0.997438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 410 459 -0.397698 -6.85201 -5.78195 -0.0533664 0.0330689 -0.0331251 0.997477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 410 460 -0.20185 0.00639834 -6.27387 -0.00150941 0.0394087 0.0093118 0.999179 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 410 461 -0.424565 6.87636 -6.02968 0.0587271 0.0401731 0.0317512 0.99696 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 411 460 -0.409802 -6.86568 -5.79379 -0.0472952 0.0274604 -0.0281417 0.998107 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 411 461 -0.188198 0.0062994 -6.26148 -0.00147646 0.0332366 -0.0027924 0.999443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 411 462 -0.421733 6.90223 -6.02758 0.0482728 0.0391695 0.0348118 0.997459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 412 461 -0.404326 -6.86493 -5.77971 -0.0543631 0.0270123 -0.0278051 0.997768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 412 462 -0.203171 0.0133182 -6.29326 -0.00374902 0.0350946 -0.00643775 0.999356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 412 463 -0.437405 6.9004 -6.01356 0.050945 0.029204 0.0398003 0.997481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 413 462 -0.406368 -6.87352 -5.77111 -0.053007 0.0273092 -0.0353051 0.997596 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 413 463 -0.2115 0.00363825 -6.27535 -0.00263319 0.0248133 0.0010791 0.999688 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 413 464 -0.435759 6.90514 -6.03735 0.0579166 0.0282784 0.037296 0.997224 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 414 463 -0.412303 -6.90466 -5.78731 -0.0596083 0.0370417 -0.0265845 0.99718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 414 464 -0.210046 0.00944117 -6.27518 0.002454 0.0367956 -0.00850358 0.999284 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 414 465 -0.4288 6.92359 -6.04226 0.0509775 0.0314187 0.0336391 0.997638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 415 464 -0.400311 -6.89884 -5.77433 -0.0620067 0.0287783 -0.032899 0.997118 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 415 465 -0.189673 -0.0122642 -6.26107 -0.00512549 0.0254648 -0.00426766 0.999653 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 415 466 -0.439786 6.92609 -6.01391 0.0568553 0.0294088 0.0332084 0.997397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 416 465 -0.414213 -6.92425 -5.78184 -0.0470803 0.0377881 -0.0339921 0.997597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 416 466 -0.223174 -0.00415001 -6.2832 0.00435457 0.0352853 0.00392854 0.99936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 416 467 -0.434872 6.96795 -6.03666 0.0542252 0.0394596 0.0365792 0.997078 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 417 466 -0.402784 -6.95604 -5.78887 -0.0525119 0.031497 -0.0293698 0.997691 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 417 467 -0.21482 -0.00207643 -6.28143 -0.00607284 0.0356281 0.00952528 0.999301 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 417 468 -0.436389 6.96009 -6.03671 0.0490561 0.0330441 0.0279631 0.997858 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 418 467 -0.411311 -6.96255 -5.7839 -0.0485819 0.0229137 -0.0359405 0.997909 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 418 468 -0.181162 0.00392493 -6.29546 -3.11114e-05 0.0309225 -0.00316805 0.999517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 418 469 -0.431888 6.9676 -6.01785 0.0523125 0.0383696 0.0214888 0.997662 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 419 468 -0.403693 -6.96488 -5.7642 -0.0577817 0.0235975 -0.0291857 0.997623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 419 469 -0.198449 0.00712588 -6.28131 -0.00528012 0.0260094 -0.000865982 0.999647 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 419 470 -0.44078 6.98637 -6.02993 0.0568675 0.0334048 0.030463 0.997358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 420 469 -0.397983 -6.97198 -5.76729 -0.0497739 0.0241588 -0.0312324 0.99798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 420 470 -0.185949 0.0131039 -6.27805 0.00622899 0.026692 0.00698795 0.9996 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 420 471 -0.425092 6.99986 -6.01988 0.0496498 0.0301663 0.0379887 0.997588 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 421 470 -0.406757 -7.00002 -5.76342 -0.0548014 0.0248628 -0.0309316 0.997708 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 421 471 -0.208117 0.00372103 -6.27793 -0.00395451 0.0345424 -0.0016107 0.999394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 421 472 -0.443986 7.02608 -6.03478 0.058359 0.0324579 0.0348562 0.997159 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 422 471 -0.42207 -7.01166 -5.77594 -0.0500634 0.0291119 -0.027989 0.997929 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 422 472 -0.203937 -0.00217329 -6.27969 -0.00676681 0.0252782 0.0032427 0.999652 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 422 473 -0.432597 7.01814 -6.03408 0.0640755 0.0347392 0.0288885 0.996922 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 423 472 -0.418047 -7.00866 -5.76374 -0.0568651 0.0360881 -0.0271623 0.99736 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 423 473 -0.193059 -0.0138657 -6.28447 0.00277726 0.0284913 -0.00443121 0.99958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 423 474 -0.441723 7.02528 -6.02435 0.0427589 0.0326928 0.0349094 0.99794 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 424 473 -0.424585 -7.03243 -5.78276 -0.0438917 0.0388376 -0.0349956 0.997668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 424 474 -0.193464 0.00767771 -6.2612 -0.00127891 0.0342997 -0.00248933 0.999408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 424 475 -0.42838 7.04629 -5.99992 0.0464447 0.0247175 0.030131 0.99816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 425 474 -0.416296 -7.04988 -5.7743 -0.055679 0.0278532 -0.027003 0.997695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 425 475 -0.191969 0.00312958 -6.29703 0.0100929 0.0345718 0.00299303 0.999347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 425 476 -0.42805 7.05776 -6.0401 0.0492978 0.0340212 0.0405581 0.99738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 426 475 -0.437427 -7.05491 -5.76954 -0.0504275 0.0273441 -0.0262134 0.998009 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 426 476 -0.188268 -0.00322862 -6.26546 0.00748083 0.027046 -0.00225989 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 426 477 -0.415676 7.07396 -6.01503 0.060447 0.0288216 0.031371 0.997262 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 427 476 -0.413858 -7.06461 -5.78396 -0.0457483 0.0182174 -0.0387113 0.998036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 427 477 -0.216013 0.0085594 -6.27867 0.00693567 0.0322017 0.00195027 0.999455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 427 478 -0.441023 7.10094 -6.03133 0.0598468 0.0218866 0.0303301 0.997507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 428 477 -0.421561 -7.07804 -5.76875 -0.0477772 0.0300702 -0.0389664 0.997645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 428 478 -0.195997 -0.00678997 -6.26812 0.000471181 0.0301039 -0.00312126 0.999542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 428 479 -0.439347 7.10076 -6.03528 0.0574074 0.0343317 0.037637 0.99705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 429 478 -0.433787 -7.08624 -5.77123 -0.0590418 0.0258278 -0.0301047 0.997467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 429 479 -0.196976 -0.00624865 -6.27528 0.000745578 0.0273075 0.00998908 0.999577 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 429 480 -0.43691 7.10732 -6.03737 0.0578957 0.0266633 0.0316266 0.997465 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 430 479 -0.422941 -7.09139 -5.78297 -0.0502432 0.0411432 -0.0331964 0.997337 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 430 480 -0.179169 0.000675066 -6.28538 0.00871775 0.0259286 -0.00225728 0.999623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 430 481 -0.4363 7.1267 -6.01511 0.0538807 0.0292426 0.0379925 0.997396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 431 480 -0.421266 -7.14127 -5.76378 -0.060381 0.0293801 -0.0358419 0.997099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 431 481 -0.189598 -0.0120391 -6.29916 0.000920006 0.0339437 -0.00457822 0.999413 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 431 482 -0.425362 7.13589 -6.02121 0.0620282 0.0333243 0.0365647 0.996848 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 432 481 -0.427375 -7.13874 -5.77133 -0.0483499 0.0324067 -0.0380695 0.997578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 432 482 -0.179819 -0.0105289 -6.26596 -0.00375787 0.0379651 0.000624115 0.999272 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 432 483 -0.431975 7.17773 -6.00842 0.0503079 0.0343787 0.0361732 0.997486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 433 482 -0.429525 -7.14391 -5.78553 -0.0611099 0.0355912 -0.0325225 0.996966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 433 483 -0.199965 0.0115264 -6.27965 -0.000672896 0.0313363 -0.00118648 0.999508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 433 484 -0.4521 7.15832 -6.02017 0.044379 0.0278718 0.0291484 0.9982 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 434 483 -0.421202 -7.16128 -5.75203 -0.0580404 0.037956 -0.029179 0.997166 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 434 484 -0.180261 -0.0041852 -6.28521 0.00622403 0.0294068 0.00206267 0.999546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 434 485 -0.437764 7.17601 -6.00735 0.0583836 0.0335737 0.0394412 0.99695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 435 484 -0.426922 -7.19641 -5.77127 -0.0539388 0.0343078 -0.0391938 0.997185 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 435 485 -0.196135 -0.00404677 -6.28175 -0.00311113 0.0355224 0.00525578 0.99935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 435 486 -0.439921 7.20251 -6.00548 0.0493692 0.0359502 0.0352587 0.99751 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 436 485 -0.420937 -7.18012 -5.75271 -0.0430219 0.0295369 -0.0252431 0.998318 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 436 486 -0.204154 -0.010677 -6.27818 -0.000139855 0.0287528 0.00122401 0.999586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 436 487 -0.461187 7.20466 -6.02399 0.0499756 0.0306711 0.0427636 0.997363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 437 486 -0.416196 -7.18416 -5.7668 -0.0556647 0.0203119 -0.0380858 0.997516 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 437 487 -0.207956 -0.0139162 -6.26517 -0.000838972 0.0327573 -0.00207315 0.999461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 437 488 -0.435063 7.22888 -6.01097 0.051786 0.0379972 0.0318774 0.997426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 438 487 -0.442231 -7.20275 -5.76829 -0.0511132 0.0303134 -0.0269545 0.997869 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 438 488 -0.202214 0.00904317 -6.28142 -0.00554403 0.0432061 0.0156674 0.998928 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 438 489 -0.447395 7.23468 -6.0167 0.0339872 0.0269156 0.0425855 0.998152 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 439 488 -0.402763 -7.21667 -5.77865 -0.0528916 0.0335153 -0.0393077 0.997263 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 439 489 -0.195198 0.011522 -6.29582 -0.00260669 0.0260847 -0.0106629 0.999599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 439 490 -0.438627 7.24851 -6.04056 0.0486013 0.0359218 0.0381148 0.997444 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 440 489 -0.432356 -7.22915 -5.76194 -0.0511904 0.0248456 -0.0346859 0.997777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 440 490 -0.199988 0.0103499 -6.27682 -0.00542074 0.0349153 0.00534695 0.999361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 440 491 -0.45069 7.25576 -6.02837 0.0478438 0.0305962 0.0257044 0.998055 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 441 490 -0.423259 -7.24956 -5.7787 -0.0594068 0.0340395 -0.0374577 0.99695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 441 491 -0.18587 0.00802038 -6.2726 0.00478802 0.0310779 -0.00477001 0.999494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 441 492 -0.433709 7.2664 -6.01319 0.0534206 0.0299644 0.0285322 0.997715 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 442 491 -0.436511 -7.27819 -5.76314 -0.0524652 0.0334811 -0.0353289 0.997436 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 442 492 -0.204907 0.0114983 -6.27692 0.00483902 0.0415422 0.00720613 0.999099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 442 493 -0.45197 7.28888 -6.01324 0.0551537 0.0247825 0.0363895 0.997507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 443 492 -0.42799 -7.29001 -5.76514 -0.0534496 0.0347553 -0.0461534 0.996898 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 443 493 -0.20899 0.00259863 -6.27832 -0.00305756 0.033817 -0.00974862 0.999376 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 443 494 -0.452841 7.29937 -6.02437 0.0471566 0.031381 0.047382 0.997269 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 444 493 -0.436827 -7.28457 -5.7776 -0.0517956 0.0274906 -0.0360403 0.997628 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 444 494 -0.159497 0.0124827 -6.29413 -0.0029508 0.0272185 -0.00491235 0.999613 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 444 495 -0.450114 7.32686 -6.007 0.0512567 0.0306565 0.0410394 0.997371 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 445 494 -0.438693 -7.30392 -5.75693 -0.0524366 0.0364317 -0.0371513 0.997268 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 445 495 -0.182708 -0.0103812 -6.28424 -0.00302135 0.0375819 -0.0040277 0.999281 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 445 496 -0.467415 7.33773 -6.00393 0.0590499 0.0342336 0.0390499 0.996903 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 446 495 -0.436322 -7.31024 -5.76631 -0.0529406 0.032501 -0.0353263 0.997443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 446 496 -0.180012 -0.00660217 -6.27319 -0.000662437 0.0427377 -0.000821249 0.999086 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 446 497 -0.431973 7.36528 -6.01254 0.0629237 0.0299553 0.035481 0.996938 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 447 496 -0.437268 -7.33291 -5.75865 -0.046954 0.0338802 -0.0397776 0.99753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 447 497 -0.197996 -0.00871684 -6.26891 -0.00705435 0.0400939 0.00357303 0.999165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 447 498 -0.457991 7.35952 -6.00958 0.0473096 0.0328232 0.0382984 0.997606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 448 497 -0.445957 -7.34149 -5.76025 -0.0506931 0.0366828 -0.0415758 0.997174 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 448 498 -0.195048 -0.00876591 -6.27253 0.00314273 0.0290544 0.00627655 0.999553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 448 499 -0.456282 7.37001 -5.99766 0.0460695 0.0324573 0.0463303 0.997335 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 449 498 -0.429878 -7.35711 -5.76358 -0.0564091 0.0233724 -0.0348103 0.997527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 449 499 -0.207577 -0.00565749 -6.27824 0.003993 0.031583 -0.00443307 0.999483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 449 500 -0.463565 7.38974 -6.01061 0.0519715 0.0297103 0.0345944 0.997607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 450 499 -0.438682 -7.36188 -5.79299 -0.0583725 0.0287844 -0.0395712 0.997095 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 450 500 -0.206106 -0.00189607 -6.27437 -0.00467732 0.0280414 -0.0043556 0.999586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 450 501 -0.456174 7.38583 -6.00913 0.0470827 0.0339714 0.0412859 0.997459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 451 500 -0.45831 -7.38902 -5.76777 -0.0503229 0.0345751 -0.0256695 0.997804 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 451 501 -0.204914 -0.00498445 -6.29393 0.00625851 0.026825 -0.00374792 0.999614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 451 502 -0.452375 7.40078 -6.00806 0.0572925 0.0302972 0.0388211 0.997142 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 452 501 -0.436515 -7.3982 -5.7622 -0.0651032 0.0205142 -0.0372836 0.996971 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 452 502 -0.207415 -0.0122612 -6.26649 0.00230091 0.028731 -0.00246034 0.999582 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 452 503 -0.446303 7.4308 -6.00061 0.0478855 0.0364082 0.0314158 0.997695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 453 502 -0.450316 -7.40661 -5.75639 -0.0505949 0.0270469 -0.0417755 0.997479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 453 503 -0.207727 0.00260962 -6.28688 0.00310158 0.0338868 -0.0110181 0.99936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 453 504 -0.469531 7.43287 -6.01046 0.0569292 0.0357772 0.04899 0.996534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 454 503 -0.446209 -7.42723 -5.76991 -0.0562152 0.0289945 -0.0370219 0.997311 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 454 504 -0.199915 -0.00657492 -6.27134 -0.00359148 0.0385367 0.00444955 0.999241 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 454 505 -0.452131 7.43612 -6.01491 0.0473258 0.0347954 0.0334111 0.997714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 455 504 -0.431152 -7.42965 -5.73758 -0.0501838 0.0361395 -0.0438657 0.997122 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 455 505 -0.211887 0.00269652 -6.28201 -0.000127954 0.0250156 -0.00360998 0.999681 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 455 506 -0.471902 7.47214 -5.99556 0.0453779 0.0203978 0.0294341 0.998328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 456 505 -0.445224 -7.43968 -5.75809 -0.0485609 0.0292504 -0.0349512 0.99778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 456 506 -0.210783 0.00970518 -6.27386 0.00835535 0.0358454 -0.00447135 0.999312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 456 507 -0.479758 7.45933 -6.02234 0.0573814 0.0387406 0.0355361 0.996967 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 457 506 -0.458114 -7.46174 -5.75021 -0.057664 0.0325776 -0.0391541 0.997036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 457 507 -0.190146 0.0125267 -6.27596 0.00431381 0.0218629 0.000664729 0.999751 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 457 508 -0.465546 7.49961 -5.99963 0.0572396 0.0207297 0.0417309 0.997272 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 458 507 -0.450976 -7.46434 -5.75595 -0.0505108 0.0341087 -0.0360763 0.997489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 458 508 -0.214642 0.0158367 -6.28683 -0.00160895 0.0351461 0.00492658 0.999369 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 458 509 -0.457324 7.498 -6.0161 0.0487965 0.0278125 0.0410727 0.997576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 459 508 -0.436164 -7.46818 -5.76731 -0.0543886 0.0336503 -0.0313208 0.997461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 459 509 -0.189021 -0.00157447 -6.29221 0.0036413 0.0282615 -0.00484225 0.999582 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 459 510 -0.475865 7.52059 -6.00426 0.0482246 0.037284 0.027719 0.997755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 460 509 -0.44924 -7.4998 -5.7356 -0.0548784 0.0263738 -0.0330728 0.997597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 460 510 -0.20352 -0.00925254 -6.25528 -0.00159251 0.0389532 0.00353948 0.999233 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 460 511 -0.448692 7.53466 -6.01092 0.0504887 0.0307696 0.0369969 0.997565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 461 510 -0.45582 -7.50896 -5.74485 -0.0472709 0.0313577 -0.0281729 0.997992 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 461 511 -0.196419 -0.00757594 -6.29518 -0.0040642 0.035797 -0.000581052 0.999351 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 461 512 -0.458522 7.54183 -6.02234 0.0561075 0.0334665 0.0367221 0.997188 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 462 511 -0.443795 -7.54528 -5.76199 -0.0517009 0.0354602 -0.0292376 0.997605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 462 512 -0.200427 0.0085548 -6.28419 -0.00644265 0.0314415 0.00557426 0.999469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 462 513 -0.45278 7.56183 -6.00411 0.0526911 0.028807 0.0389014 0.997437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 463 512 -0.445182 -7.54555 -5.77653 -0.0516521 0.032002 -0.0401202 0.997346 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 463 513 -0.205158 0.00342707 -6.28577 0.0125344 0.0284458 -0.000394552 0.999517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 463 514 -0.463919 7.54115 -6.00106 0.0469116 0.0189211 0.0394189 0.997942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 464 513 -0.462657 -7.53597 -5.75852 -0.0458369 0.0310141 -0.0461483 0.9974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 464 514 -0.209305 0.0071094 -6.28654 0.00580758 0.027017 -0.01031 0.999565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 464 515 -0.466019 7.56492 -5.99726 0.0609884 0.0285308 0.0483504 0.996558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 465 514 -0.446509 -7.55952 -5.75299 -0.0579732 0.0332825 -0.0381099 0.997035 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 465 515 -0.18626 -0.00407695 -6.27252 6.63193e-05 0.0245877 0.000448765 0.999698 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 465 516 -0.467258 7.59667 -6.01502 0.0541485 0.0290475 0.0402967 0.997297 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 466 515 -0.444476 -7.56272 -5.76754 -0.0412235 0.0213484 -0.0391742 0.998153 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 466 516 -0.177361 0.0118333 -6.26671 0.00220823 0.030323 0.000282343 0.999538 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 466 517 -0.477217 7.5925 -5.99257 0.0536163 0.035949 0.0363034 0.997254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 467 516 -0.471102 -7.5964 -5.76252 -0.0524975 0.038687 -0.0409516 0.997031 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 467 517 -0.202683 0.00700612 -6.25865 -0.00583086 0.0278376 -0.00328924 0.99959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 467 518 -0.459774 7.58962 -6.01544 0.0430374 0.0367947 0.0285628 0.997987 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 468 517 -0.436511 -7.58572 -5.77279 -0.0565369 0.0327893 -0.030366 0.9974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 468 518 -0.17235 0.017864 -6.27877 -0.00661503 0.0348973 0.00813453 0.999336 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 468 519 -0.485413 7.61447 -6.00618 0.0523513 0.0357434 0.0364062 0.997325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 469 518 -0.443088 -7.60796 -5.77236 -0.0477158 0.0253233 -0.0439924 0.99757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 469 519 -0.186004 0.00157017 -6.2836 0.0121652 0.0259844 0.00402531 0.99958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 469 520 -0.481494 7.62043 -6.01792 0.0500365 0.0384914 0.0369946 0.997319 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 470 519 -0.443594 -7.61239 -5.76332 -0.0501436 0.0300673 -0.0420703 0.997402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 470 520 -0.197115 -0.00773845 -6.26597 0.0052781 0.0355424 -0.00975438 0.999307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 470 521 -0.468589 7.63986 -6.00675 0.048473 0.0332828 0.0307817 0.997795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 471 520 -0.460511 -7.62221 -5.75835 -0.0449759 0.0351817 -0.0346408 0.997767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 471 521 -0.197764 -0.00774574 -6.28561 0.000303317 0.0274595 0.00670751 0.9996 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 471 522 -0.47958 7.64299 -5.9954 0.0508242 0.0374308 0.0368707 0.997325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 472 521 -0.433025 -7.65146 -5.73542 -0.0587592 0.0243617 -0.0304326 0.997511 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 472 522 -0.191525 -0.0078687 -6.26015 0.00995912 0.0316901 0.0087655 0.99941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 472 523 -0.471452 7.67295 -6.00184 0.0489897 0.0278129 0.0366117 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 473 522 -0.439452 -7.65158 -5.77233 -0.0501624 0.0326196 -0.0362999 0.997548 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 473 523 -0.205603 -0.000505437 -6.29121 0.0109883 0.0230159 0.00378125 0.999668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 473 524 -0.466663 7.68381 -6.0059 0.0555624 0.0254512 0.0424273 0.997229 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 474 523 -0.463415 -7.65778 -5.737 -0.0587208 0.0358577 -0.0390626 0.996865 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 474 524 -0.19377 0.00414441 -6.28238 -0.00510411 0.0282023 0.00526669 0.999575 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 474 525 -0.467831 7.69954 -6.00763 0.0600131 0.0296906 0.0377671 0.997041 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 475 524 -0.467181 -7.69259 -5.74893 -0.0525761 0.0323505 -0.0349055 0.997482 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 475 525 -0.194734 0.0036177 -6.26252 -0.00882473 0.021311 -0.00675549 0.999711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 475 526 -0.493637 7.70339 -6.00455 0.0567268 0.0305756 0.0365513 0.997252 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 476 525 -0.464474 -7.68273 -5.75205 -0.0506564 0.0308205 -0.0442904 0.997257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 476 526 -0.186686 0.00303337 -6.28391 0.0075092 0.0374893 0.00653874 0.999247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 476 527 -0.487619 7.71268 -6.01208 0.057544 0.0364186 0.0419386 0.996797 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 477 526 -0.445597 -7.71482 -5.77909 -0.050668 0.0220145 -0.0407253 0.997642 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 477 527 -0.204938 0.00472279 -6.2734 -0.0127236 0.0287295 -0.00213401 0.999504 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 477 528 -0.476626 7.72236 -6.0094 0.0602257 0.0256354 0.0379848 0.997132 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 478 527 -0.470379 -7.71615 -5.76073 -0.0541181 0.0356626 -0.0368633 0.997216 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 478 528 -0.198812 -0.0185946 -6.25641 -0.00187276 0.0208175 0.00924222 0.999739 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 478 529 -0.492013 7.73021 -5.99424 0.0490087 0.0315673 0.0413942 0.997441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 479 528 -0.456699 -7.73281 -5.74924 -0.0534131 0.0412655 -0.0362842 0.99706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 479 529 -0.210889 0.00344248 -6.27768 -0.00122756 0.027859 -0.00714133 0.999586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 479 530 -0.481349 7.75266 -6.01689 0.0460994 0.0252777 0.0391702 0.997848 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 480 529 -0.472046 -7.75413 -5.74657 -0.0507786 0.0274728 -0.0368059 0.997653 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 480 530 -0.195717 0.0016538 -6.27203 -0.00507693 0.0265061 0.00432556 0.999626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 480 531 -0.48427 7.75575 -5.99093 0.0538108 0.0332791 0.0423222 0.997099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 481 530 -0.440706 -7.75937 -5.76123 -0.0506356 0.0310392 -0.0351114 0.997617 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 481 531 -0.208798 0.00319049 -6.2891 0.0106001 0.027572 0.00404403 0.999555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 481 532 -0.485475 7.76825 -6.0014 0.0469722 0.0309796 0.0328089 0.997876 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 482 531 -0.47863 -7.76076 -5.75823 -0.0453371 0.0230838 -0.042133 0.997816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 482 532 -0.211881 0.00305695 -6.28383 0.00337023 0.0284061 -0.00259834 0.999587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 482 533 -0.483426 7.80361 -6.00664 0.0613861 0.0369695 0.0304114 0.996965 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 483 532 -0.465956 -7.80007 -5.74229 -0.0530327 0.0267308 -0.0328652 0.997694 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 483 533 -0.197419 0.00211111 -6.27865 0.00109068 0.032548 -0.00173151 0.999468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 483 534 -0.47529 7.80364 -6.00054 0.0473961 0.0242255 0.0320589 0.998068 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 484 533 -0.466504 -7.79632 -5.7573 -0.0480553 0.03375 -0.0351435 0.997656 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 484 534 -0.218836 -0.00741291 -6.27584 0.00297141 0.027267 -0.0063976 0.999603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 484 535 -0.498578 7.81701 -6.00049 0.0503217 0.0235059 0.0420143 0.997572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 485 534 -0.463142 -7.78992 -5.74363 -0.0579582 0.0225992 -0.0341408 0.997479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 485 535 -0.199434 -0.00684106 -6.26835 0.00131717 0.0393808 -0.00771813 0.999194 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 485 536 -0.505257 7.81367 -5.9935 0.0469046 0.0233237 0.0351781 0.998007 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 486 535 -0.488428 -7.81693 -5.75529 -0.052771 0.0298818 -0.0296374 0.997719 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 486 536 -0.196268 -0.00665275 -6.28211 0.00385787 0.0381114 0.00623408 0.999247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 486 537 -0.497515 7.84017 -6.0055 0.0484947 0.0263537 0.0312868 0.997985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 487 536 -0.462366 -7.82821 -5.73473 -0.0446406 0.0417212 -0.0296542 0.997691 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 487 537 -0.188391 0.0354585 -6.2488 0.00305453 0.033036 0.000685141 0.999449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 487 538 -0.482877 7.87049 -6.02176 0.0497781 0.0339259 0.0342024 0.997598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 488 537 -0.474062 -7.84589 -5.74275 -0.0435949 0.0274147 -0.0322175 0.998153 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 488 538 -0.194152 0.00649804 -6.26747 -0.00565255 0.0307588 -0.000265902 0.999511 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 488 539 -0.474816 7.86034 -6.004 0.0486933 0.0298464 0.03669 0.997693 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 489 538 -0.479279 -7.85757 -5.73985 -0.045359 0.0203504 -0.0381698 0.998034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 489 539 -0.196359 -0.0107433 -6.28462 0.00581392 0.0334731 -7.87683e-05 0.999423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 489 540 -0.500346 7.88665 -6.0063 0.054804 0.028678 0.0437833 0.997124 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 490 539 -0.459291 -7.86931 -5.75928 -0.0484199 0.0384862 -0.0377872 0.99737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 490 540 -0.194097 0.00555839 -6.27433 -0.00620987 0.0361995 -0.00218688 0.999323 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 490 541 -0.479742 7.88431 -5.98811 0.0439375 0.024934 0.0389744 0.997962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 491 540 -0.483689 -7.87515 -5.73139 -0.0571739 0.0222539 -0.0376763 0.997405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 491 541 -0.191629 -0.00340011 -6.27302 0.00275087 0.0382811 -0.0016429 0.999262 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 491 542 -0.492616 7.90419 -5.98762 0.0334232 0.0212561 0.0379369 0.998495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 492 541 -0.481081 -7.87303 -5.76602 -0.0577402 0.0320107 -0.0448687 0.996809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 492 542 -0.206486 -0.0158348 -6.26723 0.00223333 0.030021 -0.00370962 0.99954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 492 543 -0.498926 7.91516 -5.99322 0.0513444 0.0372453 0.0353496 0.99736 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 493 542 -0.489845 -7.91401 -5.75536 -0.0439707 0.0283953 -0.037289 0.997933 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 493 543 -0.193906 -0.0106994 -6.27038 -0.00240647 0.0321211 -0.00188105 0.999479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 493 544 -0.491543 7.91358 -5.9991 0.0473239 0.0346726 0.0368351 0.997598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 494 543 -0.486114 -7.90171 -5.74497 -0.0466974 0.0291759 -0.0393849 0.997706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 494 544 -0.223946 0.00341766 -6.28662 0.000393694 0.0255215 -0.00756996 0.999646 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 494 545 -0.50061 7.93324 -6.00796 0.0504103 0.0373045 0.0348842 0.997422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 495 544 -0.491971 -7.92845 -5.74945 -0.044574 0.0300236 -0.0316075 0.998054 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 495 545 -0.207854 -0.0043157 -6.27759 -0.00294775 0.0317295 0.00533986 0.999478 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 495 546 -0.493457 7.95732 -5.99002 0.0471001 0.037782 0.0361556 0.99752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 496 545 -0.462234 -7.94533 -5.74653 -0.0523492 0.0298992 -0.0315818 0.997681 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 496 546 -0.184785 -0.0244484 -6.28862 0.00257842 0.0364518 0.00465256 0.999321 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 496 547 -0.494192 7.95646 -5.99529 0.0420999 0.0380165 0.0459637 0.997331 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 497 546 -0.486131 -7.97551 -5.73898 -0.0424023 0.0320184 -0.0409163 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 497 547 -0.196232 0.0166642 -6.27445 -0.00256417 0.0377666 0.000804509 0.999283 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 497 548 -0.485813 7.96288 -5.99206 0.0483995 0.0336044 0.0402574 0.997451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 498 547 -0.485098 -7.96421 -5.75088 -0.046727 0.0273313 -0.0325565 0.998003 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 498 548 -0.197566 -0.000255266 -6.28884 0.00115946 0.0356835 -0.00288055 0.999358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 498 549 -0.493348 7.98548 -5.99182 0.0546552 0.0400554 0.0399105 0.996903 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 499 548 -0.475059 -7.98541 -5.74244 -0.0542192 0.0328794 -0.0354476 0.997358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 499 549 -0.189621 -0.0047494 -6.29518 0.00189752 0.0298889 -0.00872689 0.999513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 499 550 -0.501855 8.01992 -5.99416 0.0552722 0.0356951 0.0402011 0.997023 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 500 549 -0.481351 -7.99199 -5.74895 -0.0473958 0.0327269 -0.0418463 0.997463 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 500 550 -0.195887 0.00721186 -6.28279 0.00400187 0.0437751 0.00241204 0.99903 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 500 551 -0.498073 8.0247 -6.01641 0.0546769 0.0343829 0.0403446 0.997096 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 501 550 -0.483349 -7.99754 -5.74342 -0.0469926 0.0285766 -0.0337078 0.997917 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 501 551 -0.180384 -0.0178484 -6.28121 -0.00734431 0.0265034 0.00185025 0.99962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 501 552 -0.501644 8.03384 -6.00422 0.0478879 0.032905 0.0464347 0.99723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 502 551 -0.492712 -8.00424 -5.73864 -0.0410853 0.0307753 -0.044619 0.997684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 502 552 -0.187266 0.0157798 -6.2836 0.0119551 0.0317371 0.000710364 0.999424 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 502 553 -0.492483 8.02728 -6.01046 0.0451842 0.0299876 0.0404213 0.99771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 503 552 -0.480286 -8.03135 -5.75116 -0.0462062 0.0341324 -0.0379783 0.997626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 503 553 -0.209149 0.0080401 -6.27035 0.0105 0.0404839 0.00719099 0.999099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 503 554 -0.499492 8.04445 -6.00932 0.0503142 0.0286529 0.0373591 0.997623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 504 553 -0.4945 -8.03596 -5.73714 -0.0579898 0.0390925 -0.0425677 0.996643 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 504 554 -0.192247 -0.00978933 -6.28246 -0.00332458 0.0319979 -0.00115708 0.999482 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 504 555 -0.510225 8.02782 -6.00676 0.0463537 0.0318094 0.0379275 0.997698 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 505 554 -0.499917 -8.05325 -5.73954 -0.0449926 0.0313835 -0.039268 0.997722 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 505 555 -0.21389 -0.00635122 -6.27577 -0.00388587 0.0340781 -0.00606544 0.999393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 505 556 -0.524872 8.06782 -5.99654 0.0472729 0.0281174 0.0455135 0.997448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 506 555 -0.48447 -8.05267 -5.76753 -0.0554367 0.0387885 -0.0310428 0.997225 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 506 556 -0.178877 -0.000461283 -6.28583 -0.00415536 0.0312699 -0.000714447 0.999502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 506 557 -0.520741 8.09515 -5.97453 0.0485579 0.042527 0.0400718 0.99711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 507 556 -0.497885 -8.07983 -5.76619 -0.0509473 0.0263093 -0.0412303 0.997503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 507 557 -0.195974 -0.00165783 -6.26594 0.000254273 0.0297842 -0.00923169 0.999514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 507 558 -0.529754 8.09926 -5.98871 0.0483767 0.0362342 0.0437452 0.997213 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 508 557 -0.488006 -8.0847 -5.74078 -0.0390605 0.0333633 -0.043037 0.997752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 508 558 -0.197411 0.00471958 -6.28445 -0.00605524 0.0287154 0.00286147 0.999565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 508 559 -0.504545 8.10367 -5.99778 0.0447688 0.0312911 0.0358656 0.997863 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 509 558 -0.4925 -8.08689 -5.75407 -0.0489994 0.0262537 -0.0413639 0.997597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 509 559 -0.1847 -0.0015606 -6.27642 0.00359079 0.0195612 -0.0055624 0.999787 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 509 560 -0.502427 8.12441 -5.99736 0.0480457 0.0271124 0.0419638 0.997595 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 510 559 -0.497268 -8.10611 -5.73994 -0.0382894 0.0263217 -0.0302624 0.998461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 510 560 -0.188206 0.000561356 -6.2728 -0.00221793 0.0284695 -0.00414433 0.999584 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 510 561 -0.509339 8.14147 -6.00653 0.0376322 0.0371907 0.0329764 0.998055 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 511 560 -0.48206 -8.12457 -5.76276 -0.051913 0.0312415 -0.0408601 0.997326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 511 561 -0.207522 -0.0136864 -6.28023 -0.00121186 0.0351692 -0.000125632 0.999381 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 511 562 -0.517396 8.14 -5.98548 0.0494582 0.027438 0.0395754 0.997615 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 512 561 -0.497199 -8.12516 -5.75449 -0.0524746 0.0305279 -0.034253 0.997568 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 512 562 -0.198748 0.0110263 -6.29383 0.0024619 0.0329604 0.000925263 0.999453 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 512 563 -0.497509 8.15947 -5.988 0.049682 0.032531 0.0404756 0.997414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 513 562 -0.473479 -8.13546 -5.75932 -0.0478109 0.0346401 -0.0304132 0.997792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 513 563 -0.193043 0.00487165 -6.2848 0.00700881 0.0315492 0.00696002 0.999453 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 513 564 -0.506073 8.18169 -5.98109 0.0553843 0.0305105 0.0343951 0.997406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 514 563 -0.489458 -8.17448 -5.72755 -0.0335725 0.0334001 -0.0322279 0.998358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 514 564 -0.206734 -0.0125834 -6.27843 -0.000508971 0.033692 0.000522491 0.999432 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 514 565 -0.513661 8.17281 -6.00728 0.0445225 0.0335962 0.0391592 0.997675 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 515 564 -0.501154 -8.17937 -5.73868 -0.0523007 0.0191224 -0.0470933 0.997337 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 515 565 -0.212584 0.017229 -6.26676 -0.00480055 0.027899 0.00284327 0.999595 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 515 566 -0.509455 8.18546 -5.99642 0.0481858 0.0268493 0.0402242 0.997667 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 516 565 -0.506901 -8.19159 -5.74127 -0.0529011 0.0312045 -0.026905 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 516 566 -0.192236 0.00852315 -6.28481 0.000178523 0.0295321 -0.00964065 0.999517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 516 567 -0.51875 8.20471 -5.99232 0.0506515 0.0272388 0.0412186 0.997494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 517 566 -0.509916 -8.18082 -5.74803 -0.0486888 0.0271781 -0.0352948 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 517 567 -0.185954 -0.000871786 -6.2771 -0.00345722 0.0413223 0.000204909 0.99914 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 517 568 -0.50922 8.22607 -5.98735 0.0514865 0.0406278 0.0325897 0.997315 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 518 567 -0.502203 -8.20962 -5.7478 -0.0503736 0.0297941 -0.0417696 0.997412 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 518 568 -0.186645 -0.00633741 -6.27304 0.00183458 0.0293582 -0.00157468 0.999566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 518 569 -0.529429 8.21683 -6.00047 0.0471607 0.0327159 0.0448497 0.997343 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 519 568 -0.507448 -8.2184 -5.73576 -0.0473182 0.0306914 -0.0365154 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 519 569 -0.188379 -0.0185632 -6.27036 0.00264642 0.0374872 0.00344184 0.999288 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 519 570 -0.52918 8.22849 -5.99738 0.0438698 0.0317735 0.0350173 0.997918 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 520 569 -0.497905 -8.23098 -5.74311 -0.0488854 0.0312849 -0.0396441 0.997527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 520 570 -0.20979 -0.00576795 -6.27831 0.0071696 0.0487321 -0.000418229 0.998786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 520 571 -0.494457 8.25439 -5.99192 0.0482148 0.0293766 0.0365823 0.997734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 521 570 -0.503759 -8.23971 -5.73221 -0.0517971 0.0259422 -0.0437403 0.997362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 521 571 -0.184325 0.00189177 -6.26619 -0.00243938 0.0311716 -0.00219359 0.999509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 521 572 -0.514509 8.23519 -5.99425 0.048458 0.0352791 0.0307988 0.997727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 522 571 -0.500931 -8.26902 -5.73951 -0.0384583 0.0304719 -0.0431592 0.997863 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 522 572 -0.187676 -0.0160892 -6.278 -0.00311589 0.0249959 -0.000729308 0.999682 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 522 573 -0.527191 8.27264 -5.99349 0.0458038 0.025226 0.0317105 0.998128 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 523 572 -0.518463 -8.24705 -5.75291 -0.0453695 0.0309039 -0.0429268 0.997569 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 523 573 -0.204636 -0.0132448 -6.28094 0.00489211 0.0238365 0.00147228 0.999703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 523 574 -0.539324 8.29913 -6.00812 0.0479716 0.0308742 0.0474598 0.997243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 524 573 -0.498257 -8.2859 -5.74104 -0.0489122 0.0285681 -0.0404838 0.997573 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 524 574 -0.207201 -0.00584718 -6.25472 0.00165387 0.0242397 -0.00805684 0.999672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 524 575 -0.522649 8.29556 -5.97439 0.0549554 0.0265122 0.0418212 0.99726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 525 574 -0.512755 -8.29121 -5.73611 -0.0524466 0.0320382 -0.0470289 0.997001 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 525 575 -0.198257 -0.0200565 -6.27025 0.000594655 0.0278125 0.00300411 0.999608 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 525 576 -0.537892 8.31054 -5.99068 0.042142 0.0279714 0.0359603 0.998072 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 526 575 -0.499715 -8.30316 -5.74544 -0.0466225 0.0280673 -0.0352059 0.997897 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 526 576 -0.201286 0.00332073 -6.26993 0.00176014 0.0315681 0.00590413 0.999483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 526 577 -0.530986 8.31739 -5.97367 0.0530401 0.0347088 0.0382534 0.997256 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 527 576 -0.519645 -8.33083 -5.73664 -0.0470911 0.0240254 -0.0339239 0.998025 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 527 577 -0.183129 -0.00401391 -6.28618 -0.00523642 0.0328105 0.00708059 0.999423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 527 578 -0.528258 8.32456 -5.97259 0.0489753 0.0318761 0.0358792 0.997646 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 528 577 -0.50457 -8.32322 -5.75057 -0.0486588 0.0422123 -0.0367837 0.997245 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 528 578 -0.187057 -0.0138156 -6.27448 0.0037392 0.0409815 0.00524681 0.999139 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 528 579 -0.516139 8.34142 -5.99221 0.0447782 0.0318747 0.0335922 0.997923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 529 578 -0.507784 -8.32609 -5.72169 -0.0484732 0.0312713 -0.0388444 0.997579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 529 579 -0.188065 0.0186495 -6.27974 0.00306193 0.0219985 -0.000327125 0.999753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 529 580 -0.52143 8.34312 -5.98494 0.0495205 0.028897 0.0316986 0.997852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 530 579 -0.521795 -8.33593 -5.72929 -0.0483702 0.0271201 -0.0458717 0.997407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 530 580 -0.207466 0.00160748 -6.28448 -0.00410421 0.0292839 0.011469 0.999497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 530 581 -0.547859 8.37249 -5.99912 0.0409573 0.0265187 0.0386398 0.998061 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 531 580 -0.506544 -8.34984 -5.7525 -0.0430931 0.0326366 -0.0416623 0.997668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 531 581 -0.199714 -0.00863263 -6.26585 -0.00405934 0.0291171 0.00320589 0.999563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 531 582 -0.53825 8.38172 -5.99218 0.0559798 0.033809 0.0450249 0.996843 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 532 581 -0.513244 -8.38175 -5.75222 -0.0446956 0.0268652 -0.0410148 0.997797 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 532 582 -0.199555 -0.00343696 -6.27068 0.000974831 0.0316592 -0.00225799 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 532 583 -0.530649 8.38659 -5.9894 0.049756 0.0306338 0.0416691 0.997421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 533 582 -0.533585 -8.37447 -5.7151 -0.0450995 0.0298121 -0.0431077 0.997607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 533 583 -0.194386 -0.005603 -6.25686 -0.00793765 0.0289904 0.00130556 0.999547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 533 584 -0.546289 8.42032 -5.99907 0.0451202 0.0396577 0.0433858 0.997251 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 534 583 -0.519095 -8.37459 -5.73963 -0.0464925 0.0325697 -0.0329746 0.997843 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 534 584 -0.204538 -0.00858791 -6.28942 -0.000734912 0.0271167 0.00477911 0.999621 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 534 585 -0.53191 8.4104 -5.9838 0.0540208 0.0278588 0.042624 0.997241 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 535 584 -0.513395 -8.41149 -5.74196 -0.0496639 0.0302524 -0.0369707 0.997623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 535 585 -0.189999 0.0128585 -6.27314 0.007481 0.0290954 -0.00467392 0.999538 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 535 586 -0.54063 8.44031 -5.98287 0.0559887 0.0291299 0.0282013 0.997608 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 536 585 -0.519305 -8.42428 -5.74091 -0.0558421 0.0289327 -0.0287788 0.997605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 536 586 -0.214154 -0.00207974 -6.2806 -0.00339886 0.0318231 -0.00561481 0.999472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 536 587 -0.532641 8.44472 -6.00324 0.039235 0.0308728 0.0389781 0.997992 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 537 586 -0.518025 -8.43065 -5.73759 -0.0497808 0.0309227 -0.0435358 0.997332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 537 587 -0.194455 -0.00885125 -6.28845 -0.000324533 0.0299095 -0.00212911 0.99955 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 537 588 -0.552403 8.44165 -5.99121 0.0478158 0.0287912 0.0389066 0.997683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 538 587 -0.524936 -8.43308 -5.74771 -0.0521159 0.034925 -0.0460148 0.996969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 538 588 -0.19155 0.0180278 -6.28704 0.0101666 0.0277422 0.00314233 0.999558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 538 589 -0.534815 8.48648 -5.97721 0.0403214 0.0302557 0.0437807 0.997769 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 539 588 -0.52198 -8.44795 -5.75002 -0.0532427 0.036164 -0.0487612 0.996735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 539 589 -0.191166 -0.00976321 -6.28496 0.00318027 0.03472 -0.0029191 0.999388 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 539 590 -0.536029 8.48068 -5.99412 0.0468338 0.0274039 0.0387545 0.997774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 540 589 -0.519073 -8.47902 -5.72056 -0.05019 0.0286854 -0.041339 0.997471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 540 590 -0.228416 -0.0074306 -6.2703 -0.000612584 0.0266703 -0.00533472 0.99963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 540 591 -0.552014 8.50525 -6.00279 0.0502327 0.0268223 0.0404976 0.997556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 541 590 -0.530824 -8.46544 -5.73894 -0.0513568 0.0221411 -0.0392796 0.997662 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 541 591 -0.187826 0.00222088 -6.29968 -0.00241502 0.0349299 0.0019203 0.999385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 541 592 -0.556779 8.48555 -5.99291 0.046727 0.0393181 0.0346805 0.997531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 542 591 -0.519981 -8.49255 -5.74641 -0.0420403 0.0299301 -0.0526833 0.997277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 542 592 -0.210969 0.0162754 -6.2724 0.00779859 0.0294023 -0.0107978 0.999479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 542 593 -0.553854 8.50375 -5.99778 0.0439361 0.0295046 0.047963 0.997446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 543 592 -0.537523 -8.51539 -5.7241 -0.0493063 0.0291017 -0.0407007 0.99753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 543 593 -0.199366 -0.00852538 -6.29094 0.00141034 0.0253063 0.00174299 0.999677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 543 594 -0.538872 8.52914 -6.00717 0.0501991 0.0307816 0.039977 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 544 593 -0.516853 -8.53118 -5.75381 -0.044296 0.0336091 -0.0408685 0.997616 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 544 594 -0.219716 -0.000902106 -6.28444 -0.000359601 0.0255376 0.00469912 0.999663 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 544 595 -0.555719 8.5372 -5.99382 0.0511297 0.0349382 0.0452573 0.997054 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 545 594 -0.525085 -8.52707 -5.72123 -0.050181 0.0368469 -0.0361665 0.997405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 545 595 -0.200154 -0.0158724 -6.28518 -0.00205939 0.0329903 -0.00450988 0.999443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 545 596 -0.540517 8.56221 -5.98131 0.0541775 0.0276713 0.0339385 0.997571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 546 595 -0.509882 -8.55286 -5.74015 -0.0467176 0.0288309 -0.0353676 0.997865 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 546 596 -0.191715 0.00530143 -6.28287 -0.00316594 0.0304711 0.00209574 0.999528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 546 597 -0.535081 8.55753 -5.98501 0.0427249 0.026117 0.0461518 0.997679 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 547 596 -0.542366 -8.54573 -5.74023 -0.0436488 0.0272476 -0.0449987 0.997661 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 547 597 -0.205332 0.00834564 -6.28434 0.000858784 0.0306953 0.00213219 0.999526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 547 598 -0.542277 8.56239 -5.98966 0.0545863 0.0367484 0.0410333 0.996989 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 548 597 -0.539096 -8.55529 -5.74577 -0.0563392 0.0250898 -0.0322727 0.997574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 548 598 -0.216885 0.00450248 -6.27135 0.00333448 0.0268821 -0.000314666 0.999633 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 548 599 -0.562194 8.60638 -5.98722 0.0463194 0.034477 0.038735 0.99758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 549 598 -0.533017 -8.58305 -5.72559 -0.0443231 0.0364011 -0.0421295 0.997465 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 549 599 -0.20546 -0.0155365 -6.264 -0.00113114 0.0388738 -0.000363346 0.999243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 549 600 -0.547691 8.59304 -5.97567 0.0501586 0.0244665 0.0412809 0.997588 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 550 599 -0.528726 -8.57673 -5.74644 -0.0465154 0.0287595 -0.0468881 0.997402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 550 600 -0.18405 -0.000268793 -6.28555 0.0122062 0.0339899 0.00754113 0.999319 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 550 601 -0.546473 8.59266 -5.99524 0.0477022 0.0320316 0.047198 0.997232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 551 600 -0.524417 -8.57718 -5.73999 -0.0492862 0.0320945 -0.0387298 0.997517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 551 601 -0.205939 -0.0116963 -6.29344 -0.00592712 0.0279232 -0.00816414 0.999559 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 551 602 -0.557237 8.60794 -6.00057 0.0510143 0.0269553 0.0364857 0.997667 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 552 601 -0.543409 -8.58943 -5.72573 -0.0553959 0.0301161 -0.0413085 0.997155 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 552 602 -0.194827 -0.00635504 -6.27314 -0.00222325 0.0279439 -0.00423369 0.999598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 552 603 -0.550847 8.6277 -5.97847 0.0446054 0.0316631 0.0390291 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 553 602 -0.541978 -8.59869 -5.72856 -0.0511706 0.0376897 -0.0470902 0.996867 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 553 603 -0.202027 0.00370116 -6.27704 0.00251073 0.0248857 0.00654199 0.999666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 553 604 -0.534518 8.65642 -5.98414 0.0489866 0.0345172 0.0383426 0.997466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 554 603 -0.522407 -8.61678 -5.74499 -0.0411782 0.0386564 -0.0524201 0.997027 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 554 604 -0.179228 -0.0164614 -6.2683 0.00092232 0.0365037 0.0031261 0.999328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 554 605 -0.572768 8.64452 -5.99122 0.0435869 0.0339216 0.0382081 0.997742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 555 604 -0.543624 -8.63881 -5.74115 -0.0512008 0.0293884 -0.0403208 0.997441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 555 605 -0.190826 -0.00328593 -6.28875 0.00360554 0.0336622 -0.00856651 0.99939 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 555 606 -0.560703 8.65606 -5.97218 0.0471127 0.0274053 0.04012 0.997707 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 556 605 -0.548871 -8.64384 -5.72462 -0.0498447 0.0314017 -0.0416554 0.997394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 556 606 -0.187047 0.00982584 -6.27304 0.00835309 0.0218672 -0.00239571 0.999723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 556 607 -0.55166 8.66993 -5.99672 0.0474998 0.0406791 0.0410354 0.997199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 557 606 -0.538861 -8.64566 -5.73086 -0.0453626 0.0303518 -0.0385389 0.997765 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 557 607 -0.196717 0.00329442 -6.27329 0.00277172 0.0302977 0.00379529 0.99953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 557 608 -0.564092 8.69779 -5.98975 0.046911 0.0337596 0.0492151 0.997115 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 558 607 -0.541118 -8.68537 -5.73972 -0.0509657 0.026282 -0.0531773 0.996937 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 558 608 -0.197732 -0.00245664 -6.27834 -0.00184522 0.0285086 -0.00213638 0.99959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 558 609 -0.539313 8.68394 -5.98573 0.0378767 0.0292062 0.0438255 0.997894 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 559 608 -0.526471 -8.67921 -5.72672 -0.0512752 0.0365926 -0.0408939 0.997176 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 559 609 -0.184058 0.00513288 -6.27097 -0.00140863 0.0336226 0.00132234 0.999433 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 559 610 -0.551907 8.70709 -5.97801 0.042429 0.0381097 0.0391214 0.997606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 560 609 -0.544972 -8.6678 -5.74305 -0.0458032 0.0271232 -0.0460882 0.997518 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 560 610 -0.190934 0.00859471 -6.2756 0.00487616 0.0232757 0.00222456 0.999715 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 560 611 -0.564075 8.7147 -5.97975 0.0491777 0.0324271 0.0419885 0.99738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 561 610 -0.554527 -8.707 -5.7375 -0.0449379 0.0350417 -0.0424543 0.997472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 561 611 -0.176449 -0.00387159 -6.27504 0.00221404 0.0336697 -0.00289594 0.999426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 561 612 -0.557007 8.72149 -5.98289 0.0532335 0.0393234 0.0381743 0.997077 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 562 611 -0.542705 -8.72757 -5.73922 -0.0451121 0.0308938 -0.0335983 0.997939 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 562 612 -0.203546 -0.0168111 -6.28436 -0.00124678 0.0345412 0.00027145 0.999402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 562 613 -0.567778 8.74122 -5.99554 0.0498444 0.039633 0.0455671 0.996929 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 563 612 -0.537331 -8.73053 -5.73414 -0.0516821 0.0354934 -0.0462735 0.996959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 563 613 -0.193709 0.00626561 -6.27938 0.00946613 0.0280713 0.0019866 0.999559 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 563 614 -0.572239 8.76388 -5.98546 0.0537093 0.0280911 0.0403728 0.997345 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 564 613 -0.535995 -8.74824 -5.73934 -0.0420109 0.0349011 -0.0418181 0.997631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 564 614 -0.198317 0.0150166 -6.28476 0.0057932 0.034899 -0.00319875 0.999369 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 564 615 -0.565055 8.75901 -5.98235 0.0522974 0.0330417 0.0533596 0.996657 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 565 614 -0.544312 -8.76997 -5.73561 -0.0479622 0.0269011 -0.0453938 0.997454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 565 615 -0.19382 -0.0107721 -6.282 -0.00421429 0.0353756 0.000403348 0.999365 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 565 616 -0.564899 8.76903 -5.98566 0.0408189 0.0395209 0.0431749 0.997451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 566 615 -0.546931 -8.76139 -5.72682 -0.0481221 0.0373386 -0.0334487 0.997583 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 566 616 -0.198807 0.00293242 -6.28215 0.00276449 0.0319205 0.00335803 0.999481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 566 617 -0.583846 8.77528 -5.97995 0.0444943 0.0313119 0.0433309 0.997578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 567 616 -0.55044 -8.77948 -5.72545 -0.0442702 0.0341791 -0.0427454 0.997519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 567 617 -0.205939 -0.0148995 -6.2789 0.00379138 0.0314882 0.000618134 0.999497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 567 618 -0.565103 8.79147 -5.98339 0.0574678 0.0302468 0.0385553 0.997144 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 568 617 -0.567826 -8.78821 -5.72532 -0.0418045 0.0294843 -0.0434366 0.997746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 568 618 -0.195469 -0.00629231 -6.27586 -0.00286607 0.0217771 -0.00111678 0.999758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 568 619 -0.573688 8.80255 -5.98927 0.0472145 0.0354172 0.0403773 0.99744 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 569 618 -0.537979 -8.78784 -5.73481 -0.0400295 0.0357673 -0.047938 0.997407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 569 619 -0.202385 0.00266901 -6.27751 0.00476236 0.0235253 0.00240968 0.999709 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 569 620 -0.562169 8.82431 -5.98196 0.0464254 0.0211128 0.0447024 0.997698 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 570 619 -0.547594 -8.80396 -5.73078 -0.0429268 0.0325601 -0.0520748 0.997189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 570 620 -0.193448 -0.00173541 -6.27772 -0.00118514 0.0338174 -0.00313673 0.999422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 570 621 -0.571451 8.82338 -5.97087 0.0418214 0.0333546 0.0358972 0.997923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 571 620 -0.545425 -8.83234 -5.7467 -0.0444038 0.0355429 -0.0454519 0.997346 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 571 621 -0.204307 0.0127856 -6.28571 0.00182217 0.0355132 -0.00196623 0.999366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 571 622 -0.58244 8.84448 -5.98065 0.0407666 0.0317636 0.0479912 0.99751 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 572 621 -0.564139 -8.82433 -5.74541 -0.0478804 0.0353057 -0.0392211 0.997458 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 572 622 -0.206828 0.012265 -6.28262 -0.00601128 0.0320392 0.00534381 0.999454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 572 623 -0.589114 8.85297 -5.99103 0.0519801 0.0329941 0.0540223 0.99664 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 573 622 -0.554577 -8.84579 -5.73067 -0.0418182 0.0348518 -0.0357848 0.997876 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 573 623 -0.200742 0.00134449 -6.27601 0.00254608 0.0347867 -0.0128596 0.999309 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 573 624 -0.575039 8.86725 -5.97198 0.0544486 0.0323601 0.0367009 0.997317 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 574 623 -0.54395 -8.85603 -5.70488 -0.0431832 0.032709 -0.0519561 0.997179 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 574 624 -0.216781 -0.0153613 -6.29496 -0.0061994 0.0344726 0.000928203 0.999386 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 574 625 -0.571882 8.88689 -5.98457 0.0467864 0.0320283 0.050493 0.997114 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 575 624 -0.57676 -8.87746 -5.71883 -0.0380071 0.0389178 -0.0384926 0.997777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 575 625 -0.19508 0.0061113 -6.2957 -0.00411915 0.0363245 -0.00219279 0.999329 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 575 626 -0.600397 8.89101 -5.97988 0.0470211 0.0321141 0.0407439 0.997546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 576 625 -0.558487 -8.86156 -5.73219 -0.0452726 0.0256896 -0.0421526 0.997754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 576 626 -0.192333 -0.0151088 -6.27659 -0.0126061 0.0407046 -0.00423627 0.999083 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 576 627 -0.567055 8.88071 -5.99715 0.0453051 0.0365467 0.0389315 0.997545 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 577 626 -0.545144 -8.89538 -5.74761 -0.0456681 0.0322736 -0.0445546 0.997441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 577 627 -0.199307 -0.0103356 -6.2895 0.00280448 0.0356184 -0.00148473 0.99936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 577 628 -0.571268 8.90243 -5.97705 0.0559145 0.0313903 0.0363943 0.997278 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 578 627 -0.560269 -8.90044 -5.7312 -0.0430672 0.0291422 -0.0420487 0.997761 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 578 628 -0.217453 0.00196337 -6.27152 -0.00278409 0.0310985 -9.86919e-05 0.999512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 578 629 -0.573312 8.93401 -5.98417 0.0491947 0.0342667 0.0452863 0.997173 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 579 628 -0.555492 -8.90466 -5.74592 -0.0293497 0.0278649 -0.046115 0.998116 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 579 629 -0.196071 -0.0172479 -6.28673 -0.00973535 0.0396969 -0.000353104 0.999164 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 579 630 -0.595232 8.93832 -5.9929 0.0474702 0.035091 0.0402229 0.997445 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 580 629 -0.546294 -8.90534 -5.73972 -0.0432239 0.0316973 -0.0434271 0.997618 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 580 630 -0.202229 0.00237636 -6.29248 0.0062761 0.0303128 -0.00300703 0.999516 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 580 631 -0.584581 8.94028 -5.98658 0.0471294 0.0396457 0.0469596 0.996996 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 581 630 -0.575384 -8.91407 -5.73437 -0.0467432 0.0365954 -0.0383839 0.997498 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 581 631 -0.201342 -0.00639696 -6.2607 0.00279667 0.0384507 0.00284153 0.999253 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 581 632 -0.583108 8.9476 -5.98605 0.0498513 0.0240457 0.0356137 0.997832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 582 631 -0.566621 -8.949 -5.73117 -0.0438248 0.032889 -0.0393919 0.99772 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 582 632 -0.184497 -0.00247131 -6.28541 -0.00161046 0.0343162 0.0032262 0.999405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 582 633 -0.573296 8.95875 -5.98727 0.0443419 0.0222171 0.0425445 0.997863 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 583 632 -0.556586 -8.9602 -5.73199 -0.0513013 0.030154 -0.0519053 0.996878 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 583 633 -0.204577 0.0221734 -6.27826 0.0030102 0.0294471 0.00369782 0.999555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 583 634 -0.590623 8.97613 -5.97887 0.0461579 0.0317626 0.0481119 0.997269 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 584 633 -0.57025 -8.95115 -5.75227 -0.0425007 0.031344 -0.0432422 0.997668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 584 634 -0.190355 0.0009873 -6.28083 -0.00293075 0.0258936 0.00208748 0.999658 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 584 635 -0.584924 8.98892 -5.98175 0.0475048 0.0307662 0.0442821 0.997415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 585 634 -0.565883 -8.97434 -5.72944 -0.0470236 0.0319718 -0.037934 0.997661 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 585 635 -0.200487 0.00776491 -6.29273 0.0082425 0.036909 0.0126737 0.999204 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 585 636 -0.583517 8.99556 -5.97385 0.0425876 0.0307033 0.0377792 0.997906 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 586 635 -0.561661 -8.97481 -5.74737 -0.041401 0.0339731 -0.0497083 0.997327 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 586 636 -0.184281 0.0013344 -6.28123 0.00896905 0.0320627 0.00233143 0.999443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 586 637 -0.572816 9.0264 -5.98402 0.0498669 0.0286024 0.0379521 0.997625 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 587 636 -0.567182 -8.98161 -5.74115 -0.0443334 0.0288114 -0.0473753 0.997477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 587 637 -0.19725 0.0111203 -6.29235 -0.000898481 0.0374052 -0.00452696 0.99929 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 587 638 -0.566339 9.0301 -5.99415 0.0411899 0.0416329 0.0389124 0.997525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 588 637 -0.568741 -9.00537 -5.73269 -0.0407146 0.0417872 -0.0425664 0.997389 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 588 638 -0.191521 0.000901726 -6.28536 -0.00264547 0.0376253 -0.00519184 0.999275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 588 639 -0.58697 9.02758 -5.97148 0.0458221 0.027158 0.0539496 0.997122 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 589 638 -0.560057 -9.00901 -5.72466 -0.0387831 0.0321602 -0.0331852 0.998179 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 589 639 -0.194201 0.00322888 -6.28746 -0.00732755 0.0324428 0.00330833 0.999441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 589 640 -0.5864 9.04413 -5.9774 0.0456033 0.038351 0.0424695 0.997319 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 590 639 -0.588556 -9.03551 -5.72774 -0.0487324 0.029065 -0.0337441 0.997818 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 590 640 -0.177202 0.0164101 -6.27791 0.00404296 0.0255702 0.00743393 0.999637 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 590 641 -0.593177 9.03915 -5.97462 0.0563045 0.028699 0.0445725 0.997005 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 591 640 -0.579079 -9.01607 -5.74233 -0.0433151 0.0375279 -0.0391718 0.997588 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 591 641 -0.184038 -0.00525464 -6.27121 -0.0121813 0.0276031 -0.00277937 0.999541 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 591 642 -0.58403 9.05369 -5.99959 0.046574 0.040426 0.0449903 0.997082 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 592 641 -0.575677 -9.05424 -5.7343 -0.0514458 0.032072 -0.0510697 0.996853 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 592 642 -0.206715 -0.0180756 -6.29171 -0.00250574 0.025263 0.00209128 0.999676 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 592 643 -0.586125 9.07586 -5.97445 0.0385956 0.0409781 0.0408708 0.997577 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 593 642 -0.574444 -9.05341 -5.74884 -0.0464439 0.0341279 -0.0440452 0.997366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 593 643 -0.196248 -0.00863184 -6.28041 -0.000108864 0.0334569 0.00659644 0.999418 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 593 644 -0.588383 9.07241 -5.97843 0.042573 0.0327908 0.0335498 0.997991 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 594 643 -0.568149 -9.08501 -5.72467 -0.0479065 0.028073 -0.0433717 0.997515 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 594 644 -0.194577 0.0128647 -6.2877 0.00176444 0.0397061 5.81378e-05 0.99921 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 594 645 -0.585544 9.07695 -5.98143 0.0391979 0.0274826 0.0435272 0.997905 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 595 644 -0.579361 -9.08549 -5.75264 -0.0381728 0.026279 -0.0458535 0.997873 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 595 645 -0.189022 -0.0172836 -6.27723 0.00515242 0.018479 -0.000420092 0.999816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 595 646 -0.611031 9.11824 -5.97857 0.0510208 0.0246984 0.0411227 0.997545 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 596 645 -0.580409 -9.10246 -5.73924 -0.0289848 0.0347049 -0.0441459 0.998001 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 596 646 -0.18662 -0.00367734 -6.28472 0.00301978 0.0273579 -0.00398057 0.999613 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 596 647 -0.605422 9.13185 -5.98838 0.0457367 0.0372019 0.0388143 0.997506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 597 646 -0.587427 -9.10751 -5.72936 -0.0536554 0.0324069 -0.0442609 0.997052 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 597 647 -0.195985 0.00891051 -6.27319 0.00408748 0.0286323 0.00226783 0.999579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 597 648 -0.600051 9.13349 -5.96774 0.050818 0.0379064 0.0460435 0.996926 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 598 647 -0.583842 -9.11019 -5.71972 -0.0536096 0.0314194 -0.0445321 0.997074 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 598 648 -0.178724 -0.00554687 -6.28161 -0.00622883 0.0253833 -0.000419331 0.999658 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 598 649 -0.588023 9.14437 -5.9904 0.0434788 0.0323494 0.055295 0.996998 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 599 648 -0.575989 -9.11455 -5.71086 -0.0418198 0.0302571 -0.0421496 0.997777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 599 649 -0.208971 -0.018803 -6.29613 -0.000665915 0.0296631 0.00248323 0.999557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 599 650 -0.609211 9.14047 -5.9688 0.0410404 0.0341058 0.0356609 0.997938 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 600 649 -0.576981 -9.13127 -5.73769 -0.0369949 0.0307286 -0.0463431 0.997767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 600 650 -0.182426 -0.00773976 -6.2842 -0.00744262 0.0365593 -0.000149217 0.999304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 600 651 -0.594658 9.15771 -5.99283 0.0509177 0.029539 0.050031 0.997011 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 601 650 -0.587371 -9.14437 -5.74718 -0.0445448 0.0241771 -0.0480947 0.997556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 601 651 -0.189804 -0.0130648 -6.26683 -0.000881329 0.0370941 -0.00750941 0.999283 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 601 652 -0.594024 9.16606 -6.00428 0.0405033 0.0317375 0.0454776 0.997639 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 602 651 -0.596826 -9.15597 -5.75701 -0.0404141 0.0326928 -0.0401675 0.99784 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 602 652 -0.195683 0.00969894 -6.27614 0.00368473 0.0352989 -0.00485992 0.999358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 602 653 -0.635318 9.18456 -5.97214 0.0396462 0.0356114 0.0373909 0.997879 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 603 652 -0.588564 -9.17012 -5.73866 -0.0464142 0.0297383 -0.044994 0.997465 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 603 653 -0.1908 -0.00434678 -6.26181 0.00654184 0.0264913 -0.00179924 0.999626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 603 654 -0.597133 9.2042 -5.98099 0.0449905 0.0366096 0.041879 0.997438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 604 653 -0.600247 -9.18499 -5.74451 -0.0473393 0.0286034 -0.0483172 0.997299 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 604 654 -0.203325 -0.00776567 -6.28365 -0.00329627 0.0354402 -0.00128989 0.999366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 604 655 -0.609015 9.20766 -5.978 0.0412887 0.0313029 0.042756 0.997741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 605 654 -0.57191 -9.18761 -5.73123 -0.0513947 0.0293802 -0.0409959 0.997404 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 605 655 -0.196138 0.0189747 -6.29153 -0.00319022 0.0320732 -7.70876e-05 0.99948 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 605 656 -0.588377 9.22232 -5.98513 0.0444176 0.0325376 0.0437933 0.997522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 606 655 -0.585838 -9.19822 -5.74272 -0.0408719 0.0279968 -0.0450099 0.997757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 606 656 -0.184336 0.00406374 -6.26864 -0.000943813 0.0296503 -0.00782371 0.999529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 606 657 -0.615236 9.20978 -5.98632 0.048577 0.0255047 0.0418309 0.997617 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 607 656 -0.595504 -9.2155 -5.74765 -0.0444529 0.0263617 -0.0392494 0.997892 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 607 657 -0.186584 -0.00353044 -6.29036 0.00945253 0.0370357 0.00181153 0.999268 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 607 658 -0.606957 9.21793 -5.9945 0.0406496 0.0294485 0.0470078 0.997633 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 608 657 -0.588093 -9.21672 -5.74288 -0.0458883 0.0221931 -0.0457167 0.997653 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 608 658 -0.193191 0.00221108 -6.27626 -0.00354479 0.0378199 -0.00651195 0.999257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 608 659 -0.622708 9.23497 -5.97811 0.0443448 0.0265012 0.0467502 0.99757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 609 658 -0.58327 -9.22426 -5.72109 -0.0340524 0.0317519 -0.0453797 0.997884 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 609 659 -0.19453 -0.0207634 -6.28721 -0.0017917 0.0293505 -0.000739752 0.999567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 609 660 -0.602538 9.25767 -5.97849 0.0383869 0.0266935 0.0488497 0.997711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 610 659 -0.566398 -9.22571 -5.72609 -0.042896 0.0329968 -0.0512538 0.997218 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 610 660 -0.191166 -0.0171456 -6.27079 0.000985301 0.0272406 0.00615148 0.999609 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 610 661 -0.626732 9.25706 -5.98635 0.0437995 0.031583 0.0425906 0.997632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 611 660 -0.59553 -9.24808 -5.75429 -0.0460013 0.0244779 -0.0497098 0.997403 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 611 661 -0.204603 0.00222279 -6.28615 -0.00025869 0.0316514 0.00254789 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 611 662 -0.61431 9.27481 -5.96558 0.0386225 0.0171324 0.0459988 0.998048 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 612 661 -0.595258 -9.26286 -5.73242 -0.0461917 0.0305781 -0.0403393 0.997649 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 612 662 -0.190125 0.016534 -6.26832 0.0035813 0.0293414 -0.00347857 0.999557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 612 663 -0.618737 9.28122 -5.98083 0.0390573 0.0348694 0.0436533 0.997674 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 613 662 -0.591118 -9.26473 -5.72649 -0.0517086 0.0258267 -0.0397443 0.997537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 613 663 -0.215803 -0.00580828 -6.28775 -0.00587021 0.0318358 -0.00175293 0.999474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 613 664 -0.616235 9.29021 -5.97749 0.0451449 0.0327858 0.0562925 0.996854 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 614 663 -0.586623 -9.30241 -5.74075 -0.0439048 0.034496 -0.0549891 0.996925 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 614 664 -0.205411 0.00560965 -6.2813 0.00353349 0.032743 0.00302394 0.999453 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 614 665 -0.619226 9.31216 -5.98114 0.0424474 0.0370993 0.0392784 0.997637 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 615 664 -0.588196 -9.30378 -5.74948 -0.0473655 0.0314724 -0.040154 0.997574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 615 665 -0.191471 0.00500078 -6.29319 -0.00937265 0.0187511 -0.00100394 0.99978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 615 666 -0.597739 9.31234 -5.9754 0.0514029 0.0239135 0.0489368 0.997192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 616 665 -0.59536 -9.31302 -5.73447 -0.0458227 0.0294434 -0.0478554 0.997368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 616 666 -0.209225 0.0217596 -6.28767 -0.00568755 0.0381023 -0.00117894 0.999257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 616 667 -0.598505 9.31886 -5.99262 0.0462261 0.0295722 0.0462986 0.997419 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 617 666 -0.58855 -9.31521 -5.72331 -0.0385688 0.0266071 -0.0424216 0.998 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 617 667 -0.196844 0.0131519 -6.27436 -0.00603639 0.0285082 -0.0044522 0.999565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 617 668 -0.621342 9.35768 -5.99988 0.0428847 0.0259494 0.0390404 0.99798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 618 667 -0.595093 -9.33718 -5.7351 -0.0517702 0.0364298 -0.0437064 0.997037 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 618 668 -0.177128 -0.000941015 -6.28292 -0.00452693 0.0318085 0.00715529 0.999458 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 618 669 -0.61246 9.3377 -5.97802 0.0418362 0.0326938 0.0515303 0.997259 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 619 668 -0.61668 -9.33773 -5.74396 -0.0337222 0.0335394 -0.0481884 0.997705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 619 669 -0.203759 -0.0108065 -6.28146 -0.00266327 0.0280114 -0.00054827 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 619 670 -0.631389 9.34514 -5.96568 0.04348 0.0308313 0.0492621 0.997363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 620 669 -0.611768 -9.35552 -5.73061 -0.0332929 0.0339461 -0.0555278 0.997324 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 620 670 -0.190243 0.00921801 -6.29314 -0.00030482 0.0370071 0.00443573 0.999305 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 620 671 -0.626423 9.36122 -6.00562 0.0440419 0.0337588 0.0366113 0.997788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 621 670 -0.599786 -9.36759 -5.72488 -0.0466034 0.0340434 -0.0346247 0.997733 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 621 671 -0.197858 0.0112867 -6.27324 0.00523472 0.0315332 -0.000903103 0.999489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 621 672 -0.618421 9.38604 -5.98793 0.043186 0.0242314 0.0486554 0.997587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 622 671 -0.626291 -9.36803 -5.72173 -0.0302831 0.0261957 -0.0501708 0.997938 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 622 672 -0.200026 0.00761333 -6.27261 -0.00208331 0.0333898 0.00377359 0.999433 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 622 673 -0.632436 9.38183 -5.97995 0.0382466 0.0361535 0.0443902 0.997627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 623 672 -0.602297 -9.38111 -5.74674 -0.0413301 0.0323401 -0.0508891 0.997325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 623 673 -0.199668 0.0125067 -6.28359 8.19093e-05 0.0243294 0.00376952 0.999697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 623 674 -0.608746 9.40739 -6.00058 0.0340014 0.0263528 0.0510535 0.997769 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 624 673 -0.612794 -9.38888 -5.73604 -0.0453257 0.0294957 -0.053608 0.997097 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 624 674 -0.200045 -0.0118387 -6.26747 -0.00692556 0.0322965 -0.00590927 0.999437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 624 675 -0.629756 9.40837 -5.99134 0.0395604 0.0262354 0.0491549 0.997663 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 625 674 -0.599908 -9.3902 -5.72565 -0.0396381 0.0305485 -0.0503182 0.997479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 625 675 -0.200722 0.0083664 -6.25607 -0.0140828 0.0293507 0.0105948 0.999414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 625 676 -0.644516 9.40633 -5.98477 0.0434126 0.0391416 0.0468036 0.997192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 626 675 -0.629227 -9.41216 -5.74127 -0.0453577 0.0324968 -0.0434332 0.997497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 626 676 -0.208762 0.00261745 -6.30728 0.000775122 0.0287236 0.00186791 0.999585 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 626 677 -0.630336 9.43426 -5.99418 0.0515006 0.0318751 0.0508818 0.996866 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 627 676 -0.600957 -9.42785 -5.73132 -0.0403368 0.0224099 -0.0434128 0.997991 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 627 677 -0.199295 0.0105771 -6.27149 -0.00315124 0.02855 -0.00028881 0.999587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 627 678 -0.633155 9.43241 -5.97446 0.0494349 0.027504 0.0415969 0.997532 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 628 677 -0.621347 -9.44195 -5.73375 -0.0383413 0.0208042 -0.0482652 0.997882 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 628 678 -0.192789 -0.0038901 -6.28346 0.00672506 0.0312605 -0.00376646 0.999482 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 628 679 -0.638847 9.45862 -5.99026 0.0466483 0.0311108 0.0491411 0.997217 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 629 678 -0.635811 -9.42812 -5.74164 -0.0437215 0.0365137 -0.0346806 0.997774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 629 679 -0.189602 -0.0105637 -6.27635 -0.000486953 0.0287267 -0.0014433 0.999586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 629 680 -0.613209 9.45245 -6.00067 0.051114 0.0268232 0.0448828 0.997323 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 630 679 -0.614822 -9.43755 -5.72283 -0.0389417 0.0261474 -0.0385261 0.998156 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 630 680 -0.190139 -0.0122607 -6.27489 0.000712006 0.0277398 0.00117333 0.999614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 630 681 -0.638596 9.46155 -5.96927 0.0357416 0.0282014 0.0552106 0.997436 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 631 680 -0.598245 -9.45616 -5.72718 -0.0468361 0.024722 -0.0541234 0.997129 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 631 681 -0.201727 -0.00934609 -6.28273 -0.000145124 0.0315168 -0.000822232 0.999503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 631 682 -0.628177 9.48354 -5.9823 0.0498903 0.0311211 0.0498737 0.997023 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 632 681 -0.609985 -9.47455 -5.7264 -0.036151 0.0284852 -0.0505202 0.997662 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 632 682 -0.194985 0.00465475 -6.27302 -0.00279374 0.0277821 0.0127545 0.999529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 632 683 -0.611837 9.48858 -5.99955 0.0412681 0.0303365 0.0464334 0.997607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 633 682 -0.600661 -9.48846 -5.73308 -0.0433696 0.0391032 -0.0353469 0.997668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 633 683 -0.195762 0.00915234 -6.28249 0.00277132 0.0302869 0.00286921 0.999533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 633 684 -0.62204 9.50179 -6.00112 0.0472216 0.0329734 0.0450437 0.997323 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 634 683 -0.616655 -9.49441 -5.73177 -0.040667 0.0288351 -0.0396931 0.997968 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 634 684 -0.215025 0.00843228 -6.27697 0.00488108 0.0367542 0.00133717 0.999312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 634 685 -0.639409 9.50611 -5.98915 0.0505434 0.0198019 0.0455767 0.997485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 635 684 -0.599624 -9.48918 -5.7188 -0.0421988 0.0238855 -0.0461922 0.997755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 635 685 -0.203188 0.00410056 -6.28062 -0.00826391 0.0287182 -0.00111631 0.999553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 635 686 -0.623318 9.53895 -5.97738 0.047311 0.0238077 0.0445197 0.997604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 636 685 -0.607069 -9.51894 -5.73641 -0.0475896 0.0320663 -0.0452777 0.997325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 636 686 -0.170698 0.00264099 -6.27961 -0.00923933 0.0338866 -0.000445596 0.999383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 636 687 -0.633292 9.54449 -5.9988 0.044655 0.0343459 0.0373213 0.997714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 637 686 -0.626214 -9.51574 -5.72706 -0.0437933 0.0341848 -0.0451497 0.997434 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 637 687 -0.191123 0.00737627 -6.28595 -0.000113506 0.0229675 0.00469099 0.999725 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 637 688 -0.632738 9.5384 -5.97784 0.0447937 0.0288348 0.0408107 0.997746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 638 687 -0.619502 -9.5387 -5.74999 -0.0539346 0.0304467 -0.0466813 0.996988 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 638 688 -0.201781 -0.0134816 -6.26473 -0.000977608 0.0234883 -0.00193268 0.999722 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 638 689 -0.637293 9.54783 -5.99253 0.0447757 0.0329101 0.0460674 0.997392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 639 688 -0.607432 -9.54654 -5.72796 -0.0494525 0.0317999 -0.052446 0.996891 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 639 689 -0.195823 0.0128756 -6.27692 -0.0016407 0.0241382 0.00848724 0.999671 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 639 690 -0.637096 9.55426 -5.98506 0.0446492 0.0364239 0.0478836 0.99719 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 640 689 -0.640744 -9.56993 -5.74076 -0.047766 0.0251698 -0.0514776 0.997214 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 640 690 -0.194387 -0.0122756 -6.27403 -0.00680331 0.0376709 -0.00768647 0.999237 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 640 691 -0.630133 9.58574 -5.98308 0.0383466 0.0254857 0.0598797 0.997143 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 641 690 -0.624554 -9.54798 -5.73466 -0.0358693 0.041213 -0.0454502 0.997471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 641 691 -0.220608 -0.00247362 -6.28949 -0.00656803 0.027222 0.00209338 0.999606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 641 692 -0.638641 9.59666 -6.00078 0.049231 0.0330496 0.0381184 0.997512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 642 691 -0.621089 -9.56488 -5.76033 -0.0481692 0.0353832 -0.0454196 0.997178 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 642 692 -0.198214 -0.000421484 -6.27865 -0.00557186 0.039954 -0.0043129 0.999177 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 642 693 -0.62907 9.6034 -5.98483 0.0405224 0.0289233 0.0420753 0.997873 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 643 692 -0.626332 -9.59674 -5.75128 -0.0388001 0.0265683 -0.0546098 0.9974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 643 693 -0.181708 -0.0117765 -6.27229 0.000145919 0.0295721 -0.00374901 0.999556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 643 694 -0.648061 9.61479 -6.00606 0.0424619 0.0359117 0.0474697 0.997323 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 644 693 -0.63862 -9.58399 -5.74245 -0.0454034 0.0211414 -0.0474104 0.997619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 644 694 -0.200478 0.00908173 -6.29331 0.00363601 0.0299719 -0.00398036 0.999536 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 644 695 -0.630447 9.61637 -6.00763 0.0445082 0.0358151 0.0557582 0.996809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 645 694 -0.62737 -9.60154 -5.76342 -0.0414924 0.0264975 -0.0434685 0.997841 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 645 695 -0.19072 -0.00944912 -6.27407 -0.00760128 0.029733 0.00376735 0.999522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 645 696 -0.645775 9.62339 -5.99509 0.0428911 0.0342835 0.0463594 0.997415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 646 695 -0.629092 -9.63056 -5.71704 -0.0443336 0.0265444 -0.0504903 0.997387 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 646 696 -0.206212 0.00789197 -6.29398 -0.00334074 0.0342318 -0.000429668 0.999408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 646 697 -0.640302 9.64297 -5.97582 0.0410379 0.0361779 0.0509198 0.997203 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 647 696 -0.622051 -9.63845 -5.72799 -0.0421341 0.026148 -0.0474446 0.997642 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 647 697 -0.209518 -0.00283432 -6.28918 -0.00111453 0.0309634 0.00351249 0.999514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 647 698 -0.65392 9.65074 -5.98985 0.0414331 0.0375367 0.0437044 0.997479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 648 697 -0.630843 -9.63474 -5.73349 -0.0351666 0.0402756 -0.0462914 0.997496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 648 698 -0.198837 0.00231374 -6.29696 0.00752576 0.0297952 0.00241452 0.999525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 648 699 -0.638558 9.64598 -5.98202 0.037475 0.0280246 0.0472847 0.997785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 649 698 -0.628243 -9.64892 -5.73001 -0.0390304 0.0282974 -0.0434726 0.997891 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 649 699 -0.207832 0.000203407 -6.28645 0.000605657 0.0243844 0.00214185 0.9997 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 649 700 -0.655879 9.66237 -5.98879 0.0358839 0.0307615 0.0505109 0.997604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 650 699 -0.642547 -9.65631 -5.74056 -0.0419267 0.0434765 -0.0435466 0.997224 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 650 700 -0.178068 0.0146179 -6.28193 -0.00424139 0.0304169 -0.00136109 0.999527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 650 701 -0.662618 9.67654 -5.99384 0.0413128 0.0355318 0.0473562 0.997391 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 651 700 -0.64394 -9.65349 -5.74551 -0.041252 0.0269783 -0.0450487 0.997768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 651 701 -0.193207 -0.0100337 -6.27562 0.00811119 0.02569 -0.000930975 0.999637 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 651 702 -0.671524 9.68783 -5.99575 0.0376261 0.0390191 0.0421995 0.997638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 652 701 -0.624914 -9.66604 -5.73897 -0.0429639 0.0291849 -0.0436902 0.997694 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 652 702 -0.197693 -0.00493709 -6.2899 0.0106274 0.036346 0.0045883 0.999272 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 652 703 -0.648836 9.70204 -5.99532 0.0479045 0.0302642 0.0538984 0.996937 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 653 702 -0.644559 -9.68751 -5.74424 -0.0429608 0.0251887 -0.0416621 0.99789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 653 703 -0.19599 -0.000401721 -6.2912 0.000790299 0.0313581 0.00910317 0.999466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 653 704 -0.639992 9.71114 -5.98694 0.0354381 0.0296212 0.0465366 0.997848 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 654 703 -0.648034 -9.70612 -5.73636 -0.0330385 0.0247357 -0.0482813 0.997981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 654 704 -0.189185 0.0067767 -6.26984 0.00191261 0.0281935 0.00255669 0.999597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 654 705 -0.646629 9.70687 -5.99867 0.0354257 0.029736 0.0442761 0.997948 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 655 704 -0.610632 -9.7157 -5.73874 -0.0415426 0.0327922 -0.0465042 0.997515 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 655 705 -0.191073 -0.00763499 -6.29142 -0.00328546 0.0350404 0.00325467 0.999375 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 655 706 -0.667954 9.73377 -5.98378 0.0411853 0.0262376 0.0458012 0.997756 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 656 705 -0.632942 -9.72932 -5.74092 -0.0332651 0.0352261 -0.0444701 0.997835 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 656 706 -0.200444 0.0120558 -6.28933 0.00438394 0.0366035 -0.00276028 0.999316 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 656 707 -0.643336 9.754 -5.99002 0.0344227 0.0288805 0.0435769 0.998039 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 657 706 -0.626817 -9.7181 -5.75225 -0.0369441 0.0204609 -0.0561488 0.997529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 657 707 -0.19353 -0.0174737 -6.27782 0.00177841 0.0271983 -0.00834385 0.999594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 657 708 -0.660708 9.7563 -5.99534 0.0443448 0.0315517 0.0428735 0.997597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 658 707 -0.637867 -9.73217 -5.73732 -0.0407903 0.0242416 -0.0496243 0.99764 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 658 708 -0.184645 -0.0259856 -6.28841 -0.00153171 0.0298335 -0.000502424 0.999554 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 658 709 -0.655792 9.75294 -5.99224 0.0353856 0.0238039 0.04809 0.997932 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 659 708 -0.634358 -9.729 -5.74479 -0.0418501 0.0269389 -0.0532125 0.997342 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 659 709 -0.206051 -0.00622462 -6.26835 -0.00684714 0.0353472 -0.00668655 0.999329 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 659 710 -0.643446 9.76451 -5.97233 0.0387592 0.0299123 0.0472323 0.997683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 660 709 -0.645191 -9.73762 -5.72405 -0.0458087 0.0225927 -0.0442769 0.997713 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 660 710 -0.203277 -0.00309762 -6.28051 0.00496757 0.0289061 0.00622132 0.99955 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 660 711 -0.679132 9.78267 -5.99641 0.0355787 0.0226577 0.0539054 0.997655 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 661 710 -0.659464 -9.77607 -5.74426 -0.041607 0.0341235 -0.0528628 0.997151 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 661 711 -0.201833 0.00538825 -6.26637 0.0007243 0.0354795 -0.00338159 0.999364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 661 712 -0.663839 9.78096 -5.97397 0.0376856 0.036479 0.0350429 0.998009 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 662 711 -0.625303 -9.77058 -5.72764 -0.044749 0.0323086 -0.0507019 0.997188 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 662 712 -0.188847 -0.000236375 -6.28275 0.00264612 0.0439374 -0.000842277 0.99903 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 662 713 -0.647622 9.78854 -5.99518 0.0451273 0.0319112 0.0400863 0.997666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 663 712 -0.641562 -9.77715 -5.74346 -0.03974 0.031276 -0.0510069 0.997417 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 663 713 -0.187515 0.00853932 -6.27876 -0.000907836 0.0287745 0.00780936 0.999555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 663 714 -0.661242 9.78998 -5.98782 0.0460396 0.0367899 0.0464415 0.997181 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 664 713 -0.649886 -9.8071 -5.73927 -0.0419597 0.0362595 -0.0478215 0.997315 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 664 714 -0.193327 -0.0238946 -6.28876 0.000569532 0.0421793 -0.0109254 0.99905 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 664 715 -0.673918 9.80089 -5.99255 0.0367815 0.0368933 0.0562874 0.997055 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 665 714 -0.631206 -9.80984 -5.73691 -0.0468169 0.0287732 -0.0397006 0.997699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 665 715 -0.199587 0.0144127 -6.27322 -0.00202297 0.0322035 -0.000993133 0.999479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 665 716 -0.667942 9.81528 -5.97081 0.0344116 0.0280304 0.0450005 0.998001 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 666 715 -0.651998 -9.79873 -5.74501 -0.0414197 0.0252966 -0.0516485 0.997485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 666 716 -0.206481 -0.0050799 -6.27878 -0.00318008 0.0264537 -0.00123609 0.999644 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 666 717 -0.66972 9.83431 -5.99333 0.0497153 0.0344234 0.056643 0.996562 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 667 716 -0.646474 -9.82574 -5.72901 -0.0347813 0.0183193 -0.0381234 0.9985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 667 717 -0.205968 0.0165046 -6.27863 -0.000734579 0.0262742 -0.00419051 0.999646 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 667 718 -0.65994 9.85437 -5.98771 0.0426891 0.0286746 0.040753 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 668 717 -0.657414 -9.85217 -5.73492 -0.0310141 0.0365041 -0.0484626 0.997676 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 668 718 -0.199962 -0.00457218 -6.29632 -0.00584458 0.0356794 -0.00381995 0.999339 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 668 719 -0.666339 9.8662 -6.00465 0.0384129 0.0301094 0.0488536 0.997613 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 669 718 -0.668146 -9.84874 -5.74914 -0.0272024 0.0267656 -0.0424685 0.998369 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 669 719 -0.193694 0.0016993 -6.26665 -0.0087699 0.0314818 0.000466597 0.999466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 669 720 -0.650897 9.83528 -5.99369 0.038453 0.0248655 0.0444158 0.997963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 670 719 -0.649635 -9.86454 -5.74158 -0.0386059 0.0302438 -0.056351 0.997206 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 670 720 -0.200319 0.0196006 -6.27618 -0.00994987 0.0276258 -0.00677555 0.999546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 670 721 -0.677577 9.8734 -5.995 0.0314953 0.0320349 0.0431752 0.998057 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 671 720 -0.637146 -9.86821 -5.73005 -0.0440808 0.0392975 -0.0570913 0.996621 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 671 721 -0.196772 -0.0203508 -6.28889 -0.00341909 0.03782 0.00413379 0.99927 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 671 722 -0.657098 9.87543 -5.99014 0.0412305 0.0293718 0.0480239 0.997563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 672 721 -0.646595 -9.8739 -5.74306 -0.0399176 0.0246448 -0.0554428 0.997359 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 672 722 -0.20115 -0.00539831 -6.29123 -0.000485077 0.0269679 -0.00152939 0.999635 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 672 723 -0.674002 9.89182 -5.98937 0.0374689 0.0367385 0.0453849 0.99759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 673 722 -0.656706 -9.88952 -5.75324 -0.0343034 0.0254214 -0.044416 0.9981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 673 723 -0.208124 -0.010025 -6.28539 0.000376048 0.0369348 -0.00926428 0.999275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 673 724 -0.673065 9.91605 -5.98941 0.0386412 0.0344787 0.0546258 0.997163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 674 723 -0.660321 -9.88246 -5.73967 -0.0322458 0.0300143 -0.0404584 0.99821 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 674 724 -0.208466 -0.0129851 -6.28351 0.006728 0.0266456 0.00307937 0.999618 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 674 725 -0.680358 9.92966 -5.99242 0.0353758 0.0318093 0.0489325 0.997668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 675 724 -0.66291 -9.9144 -5.76615 -0.0363195 0.0298123 -0.0538832 0.997441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 675 725 -0.204445 -0.0157697 -6.27841 0.000993752 0.0363254 -1.96711e-05 0.99934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 675 726 -0.665008 9.91464 -6.00874 0.0415583 0.0341811 0.0477235 0.99741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 676 725 -0.663549 -9.91189 -5.73642 -0.03352 0.0279319 -0.055196 0.997522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 676 726 -0.199519 -0.0114432 -6.27508 -0.0107971 0.0307029 -0.00233293 0.999468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 676 727 -0.670327 9.9427 -5.99266 0.0471395 0.0283405 0.0514321 0.997161 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 677 726 -0.657829 -9.91041 -5.7445 -0.0407983 0.0297983 -0.0463915 0.997645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 677 727 -0.20246 0.0113202 -6.275 0.00540675 0.0308883 -0.00492451 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 677 728 -0.682638 9.93557 -6.00396 0.0450016 0.0271223 0.0465874 0.997531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 678 727 -0.669593 -9.93487 -5.74844 -0.0333866 0.0344175 -0.0539667 0.997391 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 678 728 -0.194469 0.0122618 -6.27528 -0.00458208 0.0305331 0.00558478 0.999508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 678 729 -0.679097 9.93499 -5.99457 0.036581 0.0324334 0.0578835 0.997126 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 679 728 -0.66833 -9.93088 -5.74289 -0.0397152 0.0306629 -0.051541 0.99741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 679 729 -0.201688 0.0135078 -6.26601 0.000792676 0.0317503 0.000168129 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 679 730 -0.673248 9.95492 -5.98152 0.0408322 0.0311651 0.0376359 0.99797 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 680 729 -0.648135 -9.9701 -5.7411 -0.0471173 0.0354029 -0.0473815 0.997137 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 680 730 -0.191434 0.000922552 -6.29405 0.00198179 0.0332223 -0.00375691 0.999439 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 680 731 -0.693169 9.98663 -5.99283 0.0312557 0.0253416 0.0421865 0.998299 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 681 730 -0.682322 -9.95661 -5.75145 -0.0402806 0.0184506 -0.0430969 0.998088 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 681 731 -0.202838 -0.00586201 -6.29095 -0.00350603 0.0220295 -0.00835339 0.999716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 681 732 -0.692574 9.97296 -5.97679 0.056374 0.0307556 0.0373106 0.997238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 682 731 -0.653074 -9.9871 -5.74607 -0.0411807 0.0367781 -0.049067 0.997268 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 682 732 -0.193199 -0.0145642 -6.2672 -0.00393074 0.038195 0.0040263 0.999254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 682 733 -0.684824 10.0054 -6.0034 0.0418747 0.0218835 0.0546128 0.997389 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 683 732 -0.649161 -9.98228 -5.73589 -0.0355747 0.038974 -0.0401016 0.997801 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 683 733 -0.191952 0.0147488 -6.27937 -0.000339436 0.0232922 0.00863842 0.999691 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 683 734 -0.677717 10.0066 -5.99355 0.0453217 0.0279315 0.0481266 0.997421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 684 733 -0.67798 -9.98717 -5.75001 -0.0438198 0.029317 -0.0463608 0.997532 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 684 734 -0.182129 -0.011549 -6.27486 0.00298967 0.0251111 -0.00310279 0.999675 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 684 735 -0.680827 9.99866 -5.98289 0.0397119 0.0329492 0.0413184 0.997813 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 685 734 -0.662381 -10.0123 -5.73581 -0.0394516 0.0355315 -0.0511853 0.997277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 685 735 -0.201911 0.00887684 -6.27545 0.000769572 0.0224719 -0.00323987 0.999742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 685 736 -0.684271 10.0208 -5.98964 0.0404719 0.0221812 0.0458292 0.997883 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 686 735 -0.640103 -10.0306 -5.74795 -0.0359677 0.0251759 -0.0382419 0.998304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 686 736 -0.199019 0.00437201 -6.29472 -0.00275102 0.0288304 0.00207276 0.999578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 686 737 -0.682146 10.0269 -6.00024 0.0410732 0.0285685 0.0510281 0.997443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 687 736 -0.656577 -10.0176 -5.731 -0.0354934 0.0253538 -0.0427082 0.998135 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 687 737 -0.205171 0.0176379 -6.28303 -0.00639034 0.0331285 0.00455514 0.99942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 687 738 -0.682314 10.0326 -6.0109 0.0347092 0.0276835 0.0446095 0.998017 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 688 737 -0.661371 -10.0221 -5.75439 -0.0353939 0.0357123 -0.0508321 0.997441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 688 738 -0.207142 -0.00553614 -6.27783 -0.00716542 0.0260159 -0.00796017 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 688 739 -0.692422 10.0647 -5.98981 0.0339858 0.0314936 0.0533976 0.997498 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 689 738 -0.670625 -10.0378 -5.73938 -0.0301237 0.0308729 -0.048736 0.99788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 689 739 -0.231056 0.00321191 -6.25644 -0.000162538 0.0269057 0.00204312 0.999636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 689 740 -0.715265 10.0457 -5.99859 0.0461156 0.0248586 0.0467157 0.997533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 690 739 -0.673216 -10.0451 -5.74674 -0.0380993 0.0201895 -0.0593042 0.997308 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 690 740 -0.192851 0.00507982 -6.29144 0.000409999 0.0301009 -0.00887833 0.999507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 690 741 -0.687166 10.0819 -5.99082 0.0308307 0.0287751 0.0465155 0.998027 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 691 740 -0.658251 -10.062 -5.75329 -0.0361148 0.0289552 -0.0452958 0.997901 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 691 741 -0.183112 0.00854487 -6.2892 -0.00408688 0.0408752 0.00182687 0.999154 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 691 742 -0.678429 10.0714 -5.99103 0.0395199 0.0333948 0.0549823 0.997146 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 692 741 -0.663769 -10.0635 -5.74088 -0.0347383 0.0247558 -0.0465781 0.998003 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 692 742 -0.198255 -0.00280486 -6.27935 -0.000703307 0.0296633 0.000339484 0.99956 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 692 743 -0.688448 10.0931 -5.97806 0.0400918 0.0251326 0.0482766 0.997713 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 693 742 -0.672348 -10.07 -5.7493 -0.0370353 0.0347848 -0.0542967 0.997231 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 693 743 -0.200746 -0.00998875 -6.2929 -0.0027097 0.0341861 -0.00649087 0.999391 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 693 744 -0.691839 10.079 -5.99157 0.0310693 0.0314674 0.0439501 0.998055 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 694 743 -0.675155 -10.086 -5.72355 -0.0444068 0.0256598 -0.048613 0.9975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 694 744 -0.204973 -0.0147879 -6.30066 0.000492492 0.0284705 0.000546177 0.999594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 694 745 -0.675357 10.1082 -5.99989 0.035518 0.0293818 0.0554132 0.997399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 695 744 -0.676375 -10.1208 -5.73382 -0.0384108 0.0185866 -0.0552607 0.99756 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 695 745 -0.191399 0.0043645 -6.27405 -0.0066242 0.0320107 -0.00944786 0.999421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 695 746 -0.694202 10.1232 -6.0116 0.0385037 0.0352416 0.0557789 0.997078 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 696 745 -0.66782 -10.1182 -5.74066 -0.0326605 0.0231769 -0.0424235 0.998297 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 696 746 -0.201175 0.0130013 -6.27107 -0.000335728 0.023182 -0.00895615 0.999691 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 696 747 -0.68417 10.0996 -6.00527 0.0412098 0.0235845 0.0501226 0.997614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 697 746 -0.680144 -10.1216 -5.73602 -0.0397349 0.0362102 -0.0513561 0.997232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 697 747 -0.212845 0.00215681 -6.29438 -0.000672329 0.0325138 0.000484006 0.999471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 697 748 -0.702307 10.127 -5.97679 0.0337113 0.0365825 0.0449605 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 698 747 -0.681101 -10.1113 -5.7322 -0.0389004 0.0244588 -0.052272 0.997575 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 698 748 -0.178572 0.00319754 -6.26976 0.00424789 0.0307691 0.00436272 0.999508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 698 749 -0.691671 10.1247 -6.0085 0.0390192 0.0266722 0.0521751 0.997519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 699 748 -0.667904 -10.1231 -5.72987 -0.0293107 0.02883 -0.0566426 0.997548 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 699 749 -0.180845 0.00260818 -6.29228 -0.0031102 0.0289806 0.00444015 0.999565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 699 750 -0.703022 10.1464 -5.98282 0.0408706 0.0408497 0.0500097 0.997076 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 700 749 -0.701413 -10.127 -5.75112 -0.0461745 0.0232146 -0.0523836 0.997289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 700 750 -0.183469 0.00726865 -6.27033 0.00828489 0.0274409 -0.00471623 0.999578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 700 751 -0.683907 10.1479 -6.02088 0.0378259 0.044479 0.0482916 0.997125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 701 750 -0.671946 -10.1591 -5.74329 -0.0449137 0.025514 -0.0412129 0.997814 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 701 751 -0.19342 0.000273926 -6.28189 -0.00068138 0.030169 0.0104758 0.99949 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 701 752 -0.702846 10.1647 -5.99346 0.0425714 0.0318924 0.0575524 0.996924 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 702 751 -0.67694 -10.1672 -5.75691 -0.0458446 0.029464 -0.0448077 0.997508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 702 752 -0.210865 0.00429829 -6.2569 0.00303691 0.028773 -0.000103309 0.999581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 702 753 -0.694036 10.1957 -6.00232 0.035852 0.0293123 0.0550451 0.997409 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 703 752 -0.678693 -10.1624 -5.74677 -0.0365714 0.0267728 -0.0546735 0.997475 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 703 753 -0.197229 0.0123328 -6.29275 -0.0087914 0.0254231 -0.00402122 0.99963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 703 754 -0.693943 10.1707 -5.98619 0.0423117 0.0330751 0.0480298 0.997401 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 704 753 -0.704887 -10.1846 -5.73998 -0.0406184 0.0302745 -0.0496839 0.997479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 704 754 -0.199917 0.0236903 -6.29333 -0.00587872 0.0236175 0.000145418 0.999704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 704 755 -0.704597 10.178 -6.00526 0.0382633 0.0374598 0.0565267 0.996964 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 705 754 -0.690927 -10.1828 -5.73578 -0.04032 0.0277409 -0.0505013 0.997524 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 705 755 -0.19008 -0.00497734 -6.27998 0.00292057 0.0317475 0.00078628 0.999491 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 705 756 -0.708038 10.2192 -6.00499 0.040263 0.0287559 0.0465384 0.99769 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 706 755 -0.672893 -10.2042 -5.72395 -0.032367 0.0387472 -0.0439262 0.997758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 706 756 -0.190389 0.00600818 -6.26083 -1.13065e-06 0.0365918 0.000404925 0.99933 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 706 757 -0.708505 10.2248 -6.00456 0.0401617 0.0376743 0.0556791 0.996929 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 707 756 -0.676879 -10.2057 -5.74785 -0.040841 0.0381629 -0.043645 0.997482 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 707 757 -0.182849 0.0163954 -6.29035 -0.00127985 0.0339792 -0.00105163 0.999421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 707 758 -0.719614 10.228 -5.98609 0.0337733 0.0427446 0.046546 0.99743 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 708 757 -0.688377 -10.2144 -5.74444 -0.0438543 0.0342631 -0.0465578 0.997364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 708 758 -0.200247 -0.00457888 -6.2683 -0.0060358 0.0270412 0.0105405 0.999561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 708 759 -0.685136 10.2232 -5.99405 0.0415347 0.0330987 0.0514964 0.99726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 709 758 -0.707468 -10.2167 -5.75188 -0.0366197 0.0282128 -0.0590818 0.997182 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 709 759 -0.208163 0.00527406 -6.28761 0.000431958 0.0285548 0.0019745 0.99959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 709 760 -0.695912 10.2379 -5.98532 0.0384616 0.0238081 0.0509095 0.997678 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 710 759 -0.702018 -10.2236 -5.76022 -0.0435286 0.0330023 -0.0459949 0.997447 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 710 760 -0.194734 0.00923939 -6.27219 -0.00838906 0.0340005 0.00293981 0.999382 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 710 761 -0.702736 10.2594 -5.98406 0.0439034 0.0353918 0.0453791 0.997377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 711 760 -0.685565 -10.2336 -5.76273 -0.0392077 0.031389 -0.0533177 0.997314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 711 761 -0.204706 -0.00979391 -6.27214 0.000443269 0.0363654 -0.00694511 0.999314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 711 762 -0.707553 10.2659 -6.00746 0.0327449 0.0371968 0.0393634 0.997995 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 712 761 -0.688587 -10.2664 -5.74314 -0.0449422 0.0294255 -0.0546242 0.997061 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 712 762 -0.166169 -0.00352368 -6.29341 -0.00394597 0.0315964 0.000148367 0.999493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 712 763 -0.715091 10.2546 -5.99438 0.0351444 0.0381222 0.0548561 0.997147 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 713 762 -0.691459 -10.2527 -5.75508 -0.0373131 0.0173061 -0.0443586 0.998169 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 713 763 -0.209733 -0.00707111 -6.27579 -0.000869321 0.0334169 -0.00178686 0.99944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 713 764 -0.705621 10.2746 -6.00631 0.0349652 0.0304831 0.0424306 0.998022 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 714 763 -0.69173 -10.2647 -5.75674 -0.034557 0.0381977 -0.0529262 0.997269 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 714 764 -0.185365 -0.005528 -6.2789 0.00591425 0.0379323 -0.0035923 0.999256 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 714 765 -0.719373 10.2826 -5.99234 0.0422242 0.0339718 0.0474525 0.997402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 715 764 -0.704761 -10.2581 -5.75 -0.0439387 0.0275017 -0.0531122 0.997242 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 715 765 -0.202106 -0.00420826 -6.2734 0.0162557 0.0232264 -0.0097628 0.99955 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 715 766 -0.707739 10.3081 -6.00227 0.0376385 0.0303378 0.0560988 0.997254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 716 765 -0.689184 -10.3073 -5.75632 -0.0435179 0.031382 -0.0560781 0.996984 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 716 766 -0.199025 -0.0124701 -6.29179 -0.00351284 0.0179702 0.000750775 0.999832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 716 767 -0.692802 10.3128 -6.00901 0.0343343 0.0293618 0.0564516 0.997383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 717 766 -0.709426 -10.314 -5.74733 -0.0379358 0.0255188 -0.0452761 0.997928 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 717 767 -0.191108 -0.0256357 -6.2808 -0.0012987 0.0221135 -0.00949112 0.99971 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 717 768 -0.69309 10.3251 -5.99844 0.0343769 0.0301747 0.0519018 0.997604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 718 767 -0.70632 -10.3011 -5.73262 -0.033537 0.0298481 -0.0486414 0.997807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 718 768 -0.189459 0.000788013 -6.30243 -0.00756895 0.0237389 0.00098338 0.999689 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 718 769 -0.71278 10.3105 -5.99554 0.03637 0.0355761 0.0599476 0.996904 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 719 768 -0.708891 -10.3174 -5.75358 -0.0387938 0.0181259 -0.0549006 0.997573 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 719 769 -0.195702 0.00774304 -6.27518 -0.00167881 0.0225372 0.00455479 0.999734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 719 770 -0.718055 10.3358 -6.00093 0.0338375 0.0352084 0.0432995 0.997868 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 720 769 -0.702507 -10.3131 -5.75044 -0.029191 0.0381866 -0.0435244 0.997895 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 720 770 -0.20111 0.0129499 -6.27715 0.00293263 0.0293775 1.97611e-05 0.999564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 720 771 -0.713703 10.3315 -6.00831 0.0423932 0.0314081 0.0432407 0.997671 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 721 770 -0.72595 -10.3306 -5.74738 -0.0390794 0.0220399 -0.0533735 0.997566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 721 771 -0.181482 -0.000257864 -6.28214 0.00474355 0.0275998 -0.00105199 0.999607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 721 772 -0.713867 10.3659 -6.0083 0.0352757 0.0346798 0.046034 0.997714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 722 771 -0.687541 -10.3271 -5.75467 -0.0294119 0.0345573 -0.0521468 0.997608 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 722 772 -0.206223 0.00257659 -6.28612 0.00206365 0.0341907 0.00377093 0.999406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 722 773 -0.723631 10.3574 -5.99959 0.0373821 0.0390715 0.0617311 0.996627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 723 772 -0.712203 -10.3572 -5.76137 -0.0378103 0.0318542 -0.0405548 0.997953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 723 773 -0.195487 0.00774194 -6.2726 0.00424532 0.0379909 -0.00497601 0.999257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 723 774 -0.719188 10.3563 -5.99711 0.0382706 0.0227596 0.0442383 0.998028 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 724 773 -0.705261 -10.3403 -5.76086 -0.0448427 0.0368691 -0.0545885 0.99682 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 724 774 -0.200162 -0.0166578 -6.26384 0.00537376 0.0312575 0.00128645 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 724 775 -0.726081 10.3731 -5.99985 0.03414 0.0396474 0.0608773 0.996773 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 725 774 -0.706071 -10.3694 -5.75172 -0.0332317 0.0327242 -0.0563576 0.997321 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 725 775 -0.189834 0.0104138 -6.27414 0.00154083 0.0229088 -0.00389675 0.999729 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 725 776 -0.725441 10.3808 -6.00152 0.0303267 0.0300578 0.0490526 0.997883 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 726 775 -0.719434 -10.38 -5.75695 -0.0375527 0.0252009 -0.0450965 0.997958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 726 776 -0.187888 0.00609179 -6.27255 -0.00343355 0.0368084 -0.00676257 0.999294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 726 777 -0.709142 10.3906 -6.0056 0.0383294 0.0427864 0.0529965 0.996941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 727 776 -0.717496 -10.3787 -5.75423 -0.0286029 0.0358052 -0.0549696 0.997436 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 727 777 -0.187706 -0.00298568 -6.26816 0.0046274 0.0351647 0.00463085 0.99936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 727 778 -0.705216 10.3987 -6.00189 0.0447799 0.0288125 0.0506505 0.997296 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 728 777 -0.700065 -10.3776 -5.7511 -0.0353768 0.0314501 -0.0565598 0.997276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 728 778 -0.181787 0.00744847 -6.27542 0.0024704 0.0346472 -0.00065234 0.999396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 728 779 -0.7333 10.416 -6.00958 0.0395663 0.0296676 0.0398758 0.99798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 729 778 -0.703436 -10.4014 -5.74702 -0.03976 0.0299826 -0.0574111 0.997108 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 729 779 -0.174735 -0.00155204 -6.28191 0.00117729 0.0371345 -0.00357093 0.999303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 729 780 -0.750124 10.4244 -6.0099 0.0365904 0.033213 0.0524546 0.9974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 730 779 -0.703236 -10.4094 -5.7512 -0.0372825 0.0287794 -0.0586904 0.997165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 730 780 -0.192304 -0.0212622 -6.27127 -0.00316985 0.032376 0.00445805 0.999461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 730 781 -0.722444 10.4144 -5.99584 0.0406091 0.0271264 0.0539583 0.997348 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 731 780 -0.697831 -10.4186 -5.77631 -0.0348555 0.028925 -0.0538758 0.99752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 731 781 -0.178398 -0.00883886 -6.25884 0.00111963 0.0389682 0.00348345 0.999234 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 731 782 -0.737449 10.4422 -6.00846 0.0293089 0.0350553 0.0491411 0.997746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 732 781 -0.711694 -10.4254 -5.74607 -0.0352601 0.0219075 -0.0487503 0.997948 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 732 782 -0.207931 0.018221 -6.28041 0.007802 0.0294347 0.00242051 0.999533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 732 783 -0.73361 10.4414 -5.98988 0.0369789 0.0318572 0.0454992 0.997771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 733 782 -0.706681 -10.4289 -5.75374 -0.0234563 0.0353628 -0.0584599 0.997387 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 733 783 -0.195445 0.0074991 -6.26543 -0.00203773 0.0259174 0.00406932 0.999654 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 733 784 -0.72593 10.4508 -5.99755 0.0441102 0.0331761 0.0459935 0.997416 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 734 783 -0.692732 -10.4298 -5.76129 -0.0335973 0.0300571 -0.055027 0.997467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 734 784 -0.211217 -0.00331255 -6.28251 -0.0023365 0.0336757 0.0058697 0.999413 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 734 785 -0.721076 10.4623 -6.0135 0.0323575 0.0322342 0.0526775 0.997567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 735 784 -0.730708 -10.4666 -5.76771 -0.042623 0.0320074 -0.0528344 0.99718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 735 785 -0.194824 -0.000664381 -6.26354 0.00101628 0.0344489 0.00336054 0.9994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 735 786 -0.739591 10.4517 -6.00793 0.0293138 0.0345883 0.0472314 0.997854 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 736 785 -0.723514 -10.4697 -5.76339 -0.0412021 0.0298746 -0.0553696 0.997168 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 736 786 -0.203346 -0.0174543 -6.26313 -0.0106489 0.029938 -0.00228016 0.999492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 736 787 -0.744321 10.4885 -6.00718 0.0397899 0.0436084 0.0522946 0.996885 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 737 786 -0.70153 -10.4688 -5.76944 -0.0336565 0.0324966 -0.0507839 0.997613 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 737 787 -0.214418 -0.00587036 -6.2628 0.00343872 0.0321945 -0.00469185 0.999465 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 737 788 -0.749434 10.4907 -6.00777 0.0390179 0.0264736 0.0463113 0.997814 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 738 787 -0.72132 -10.4678 -5.75314 -0.0424007 0.0263264 -0.0572724 0.99711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 738 788 -0.198314 -0.0193081 -6.271 -0.00427254 0.0274965 -0.00441897 0.999603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 738 789 -0.715254 10.4808 -6.0048 0.032859 0.0377043 0.05259 0.997363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 739 788 -0.723193 -10.4846 -5.75869 -0.0330266 0.0277551 -0.0438813 0.998105 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 739 789 -0.18608 0.019263 -6.30119 -0.00237999 0.0263741 -0.00485483 0.999638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 739 790 -0.737409 10.5163 -6.00376 0.0451015 0.0334204 0.0514787 0.997095 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 740 789 -0.723968 -10.4972 -5.77079 -0.0369807 0.0326324 -0.0524045 0.997407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 740 790 -0.189238 0.0117973 -6.25842 0.00897986 0.0313789 0.000371866 0.999467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 740 791 -0.748757 10.5067 -5.99713 0.0298167 0.0286398 0.0499289 0.997897 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 741 790 -0.718635 -10.4928 -5.76555 -0.0331751 0.0323023 -0.0500243 0.997674 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 741 791 -0.184028 0.0043379 -6.28879 0.000907579 0.0347861 -0.00059164 0.999394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 741 792 -0.732782 10.5092 -6.02095 0.0381287 0.0336021 0.0521219 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 742 791 -0.730566 -10.4951 -5.7555 -0.0397079 0.0407621 -0.0467286 0.997285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 742 792 -0.179304 -0.0150532 -6.27538 -0.00820045 0.0317846 0.000134801 0.999461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 742 793 -0.719077 10.5365 -6.00549 0.0368784 0.0428354 0.0520531 0.997043 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 743 792 -0.721867 -10.5197 -5.77118 -0.0408207 0.0405399 -0.0578742 0.996665 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 743 793 -0.191704 -0.0172307 -6.29172 -0.00419395 0.0337114 -0.00584237 0.999406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 743 794 -0.731757 10.5416 -6.01015 0.0263748 0.0308983 0.053566 0.997738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 744 793 -0.695321 -10.5399 -5.78248 -0.0358083 0.0351164 -0.0536024 0.997302 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 744 794 -0.19378 -0.00414016 -6.27842 -0.0015363 0.0280937 -0.00489556 0.999592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 744 795 -0.739229 10.5411 -6.01049 0.0345788 0.0291936 0.0578377 0.9973 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 745 794 -0.715776 -10.5273 -5.76268 -0.0380007 0.0293314 -0.0502451 0.997583 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 745 795 -0.187985 0.00456115 -6.29243 0.00204209 0.0289182 0.000633323 0.999579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 745 796 -0.730017 10.5603 -6.00472 0.0377255 0.0324545 0.0495605 0.997531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 746 795 -0.705984 -10.5345 -5.75237 -0.042076 0.0288451 -0.0617111 0.996789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 746 796 -0.195427 -0.00808298 -6.27774 0.00491342 0.0325616 0.00608554 0.999439 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 746 797 -0.746114 10.5757 -6.00337 0.0396494 0.0274259 0.0479401 0.997686 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 747 796 -0.718984 -10.5303 -5.76989 -0.0308405 0.032072 -0.0522075 0.997645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 747 797 -0.188958 -0.0116873 -6.26557 0.00488324 0.0330986 0.00196214 0.999438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 747 798 -0.735219 10.586 -6.02509 0.0364435 0.0332866 0.04913 0.997572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 748 797 -0.724919 -10.5441 -5.75561 -0.0323704 0.026741 -0.0457845 0.998069 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 748 798 -0.195866 -0.00395291 -6.27373 -0.00325473 0.033173 0.0042851 0.999435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 748 799 -0.736692 10.5954 -5.99157 0.0421786 0.0358681 0.056493 0.996867 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 749 798 -0.724581 -10.571 -5.76548 -0.0349012 0.0260671 -0.0546303 0.997556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 749 799 -0.200231 -0.0107331 -6.27425 -0.00453676 0.0355251 0.0023369 0.999356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 749 800 -0.759588 10.595 -6.01335 0.0423283 0.0247335 0.0507143 0.997509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 750 799 -0.753623 -10.5772 -5.77388 -0.0381474 0.0280673 -0.0566943 0.997268 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 750 800 -0.19756 -0.000544996 -6.27492 0.00171405 0.0315454 0.00027026 0.999501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 750 801 -0.74771 10.6008 -5.99655 0.0297082 0.024129 0.0485678 0.998086 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 751 800 -0.725824 -10.5869 -5.75056 -0.0313921 0.0310858 -0.055402 0.997486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 751 801 -0.192091 -0.0247875 -6.27754 -0.00342314 0.0293674 -0.00142449 0.999562 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 751 802 -0.727496 10.6161 -6.01332 0.0394783 0.0352725 0.0527074 0.997206 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 752 801 -0.737842 -10.601 -5.7486 -0.0453147 0.0347278 -0.0542436 0.996894 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 752 802 -0.180092 -0.00560137 -6.28187 -0.00385337 0.0343479 -0.00457727 0.999392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 752 803 -0.74531 10.6284 -5.99589 0.0369466 0.0353599 0.0585438 0.996974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 753 802 -0.733956 -10.6168 -5.75266 -0.0386904 0.031585 -0.0558022 0.997192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 753 803 -0.201788 0.00431177 -6.28608 0.0014202 0.0279587 0.00763528 0.999579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 753 804 -0.753558 10.6142 -6.008 0.0389596 0.0326067 0.0535246 0.997273 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 754 803 -0.728927 -10.618 -5.77325 -0.0383955 0.0250997 -0.0551161 0.997426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 754 804 -0.215513 -0.00304155 -6.28955 0.00835141 0.0280018 0.0094231 0.999529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 754 805 -0.761111 10.6389 -6.0251 0.0280657 0.0324104 0.0500983 0.997824 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 755 804 -0.727728 -10.6144 -5.76778 -0.0383306 0.0277739 -0.0571454 0.997243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 755 805 -0.180059 -0.00851821 -6.27424 0.0036387 0.0325936 0.00206977 0.99946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 755 806 -0.74696 10.6382 -6.01591 0.0359229 0.0307206 0.0562735 0.997296 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 756 805 -0.725651 -10.6214 -5.77925 -0.038877 0.0319089 -0.0562433 0.997149 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 756 806 -0.18607 -0.0102012 -6.28146 0.0049209 0.0343463 -0.00509464 0.999385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 756 807 -0.752968 10.6516 -6.00877 0.0392897 0.030679 0.053072 0.997346 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 757 806 -0.734079 -10.6455 -5.75819 -0.0375041 0.0331692 -0.059068 0.996998 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 757 807 -0.210338 0.00639016 -6.26606 -0.00306379 0.0315797 -0.00136191 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 757 808 -0.769058 10.641 -6.0009 0.0254085 0.0382121 0.0458754 0.997893 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 758 807 -0.743385 -10.6503 -5.77035 -0.0378667 0.0278829 -0.0598553 0.997099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 758 808 -0.199076 -0.00238883 -6.27103 0.00103311 0.0373152 -0.00176434 0.999301 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 758 809 -0.748721 10.665 -6.02953 0.0325931 0.0233549 0.0536567 0.997754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 759 808 -0.727676 -10.6708 -5.75998 -0.0368904 0.0291028 -0.0547869 0.997392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 759 809 -0.195445 -0.00453676 -6.28155 0.00735181 0.0380542 0.00212547 0.999246 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 759 810 -0.752021 10.6696 -6.02828 0.0373695 0.0296076 0.0536982 0.997418 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 760 809 -0.727024 -10.6668 -5.76507 -0.0344811 0.0214728 -0.0478844 0.998027 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 760 810 -0.206781 -0.0121854 -6.28618 -0.000174336 0.0292313 0.000234268 0.999573 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 760 811 -0.756389 10.6884 -6.01144 0.0280202 0.0305261 0.049138 0.997932 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 761 810 -0.754374 -10.6818 -5.7491 -0.0287134 0.0262957 -0.0474971 0.998112 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 761 811 -0.200178 0.00605264 -6.28134 0.00298106 0.0371081 0.00118933 0.999306 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 761 812 -0.745636 10.6818 -6.0233 0.0362932 0.0377124 0.0563341 0.997039 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 762 811 -0.748508 -10.6855 -5.76039 -0.040883 0.0230214 -0.0534282 0.997469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 762 812 -0.176397 0.00951653 -6.26766 0.0045132 0.0408774 0.00296493 0.99915 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 762 813 -0.74267 10.7181 -6.04137 0.0371885 0.0293234 0.0485208 0.997699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 763 812 -0.736195 -10.705 -5.77246 -0.0325992 0.0266886 -0.048129 0.997952 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 763 813 -0.191261 0.0150969 -6.29345 0.00490855 0.0285646 -0.00275039 0.999576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 763 814 -0.752942 10.6867 -6.04045 0.0298536 0.0349654 0.0553883 0.997406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 764 813 -0.738722 -10.6935 -5.77992 -0.0233893 0.0289419 -0.0528694 0.997908 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 764 814 -0.193729 0.00278594 -6.27385 -0.00192782 0.0293578 0.00253234 0.999564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 764 815 -0.757316 10.7228 -6.02081 0.0289837 0.0341807 0.0508069 0.997703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 765 814 -0.712957 -10.7073 -5.76748 -0.0283211 0.0302603 -0.052843 0.997742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 765 815 -0.208915 -0.00117746 -6.26314 -0.00369468 0.0404561 -0.00294855 0.99917 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 765 816 -0.753815 10.7129 -6.01986 0.0283164 0.0326196 0.0535048 0.997633 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 766 815 -0.743377 -10.7137 -5.77018 -0.034414 0.0352484 -0.0519592 0.997433 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 766 816 -0.197444 -0.00999984 -6.294 0.00361531 0.0347084 0.000946148 0.99939 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 766 817 -0.739275 10.7228 -6.01157 0.0398512 0.0281955 0.0616978 0.9969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 767 816 -0.758773 -10.726 -5.7685 -0.0355961 0.0368122 -0.0558579 0.997125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 767 817 -0.191295 -0.00241658 -6.29191 -0.00325864 0.028255 0.00256776 0.999592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 767 818 -0.766251 10.7214 -6.0248 0.0211164 0.0342743 0.0480442 0.998034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 768 817 -0.748202 -10.7336 -5.77078 -0.0374485 0.0320999 -0.0598389 0.996989 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 768 818 -0.186019 0.00706342 -6.28132 0.00995306 0.0259182 -0.00245437 0.999612 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 768 819 -0.77532 10.7581 -6.0093 0.038336 0.0304401 0.0488259 0.997607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 769 818 -0.745633 -10.7387 -5.75924 -0.0357509 0.0356253 -0.0579053 0.997045 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 769 819 -0.217415 -0.0102919 -6.28424 0.00345993 0.0183954 -0.000466133 0.999825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 769 820 -0.765556 10.7643 -6.00321 0.0335662 0.0340037 0.0560973 0.997281 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 770 819 -0.714039 -10.7363 -5.78479 -0.0310453 0.0320052 -0.0537925 0.997556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 770 820 -0.199936 -0.0190651 -6.26036 0.000712606 0.0260414 0.00538135 0.999646 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 770 821 -0.768086 10.7689 -6.03383 0.0369367 0.0297304 0.0602259 0.997058 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 771 820 -0.753446 -10.7474 -5.7673 -0.0298431 0.0357642 -0.053566 0.997477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 771 821 -0.194488 0.00913841 -6.27005 0.00714873 0.0302828 -0.00164551 0.999514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 771 822 -0.77394 10.7773 -6.02711 0.0383219 0.0429283 0.0578595 0.996665 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 772 821 -0.765439 -10.7662 -5.77255 -0.0374216 0.0341842 -0.054883 0.997206 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 772 822 -0.194235 -0.0185324 -6.29095 0.00314817 0.0262708 -0.0103023 0.999597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 772 823 -0.753507 10.7751 -6.04479 0.0314676 0.0322784 0.0673867 0.996708 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 773 822 -0.74441 -10.7649 -5.74229 -0.0384459 0.0351715 -0.0429386 0.997718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 773 823 -0.224753 0.00176994 -6.26872 0.000310114 0.0330923 0.00657997 0.999431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 773 824 -0.764366 10.7963 -6.02643 0.0317076 0.0303243 0.0623507 0.997089 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 774 823 -0.744467 -10.7806 -5.78241 -0.0388767 0.0257791 -0.0549577 0.997398 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 774 824 -0.199028 -0.00485505 -6.25472 -0.00336784 0.0343035 0.00405934 0.999398 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 774 825 -0.774925 10.8157 -6.02966 0.0278676 0.0285036 0.0535013 0.997772 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 775 824 -0.74853 -10.7876 -5.76227 -0.0360064 0.0428994 -0.058279 0.996728 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 775 825 -0.202191 -0.000240601 -6.28067 -0.00381467 0.029893 -0.00385204 0.999538 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 775 826 -0.763791 10.8121 -6.02859 0.0311835 0.030802 0.0465577 0.997954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 776 825 -0.754819 -10.7898 -5.78862 -0.0296135 0.0247126 -0.0539865 0.997796 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 776 826 -0.185635 0.002126 -6.28326 0.00428513 0.033747 0.00369647 0.999414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 776 827 -0.770106 10.8033 -6.02535 0.0262644 0.0325508 0.0492893 0.997908 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 777 826 -0.747966 -10.7984 -5.77798 -0.0304988 0.0260423 -0.0507441 0.997906 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 777 827 -0.200677 -0.000370599 -6.27429 -0.00586222 0.0297405 0.00863854 0.999503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 777 828 -0.769882 10.837 -6.0285 0.041443 0.0339134 0.0446153 0.997568 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 778 827 -0.752349 -10.8181 -5.7532 -0.0388877 0.0265798 -0.0518712 0.997542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 778 828 -0.218164 -0.00633873 -6.28113 0.00232342 0.034224 0.0104846 0.999356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 778 829 -0.776687 10.8316 -6.03204 0.0411 0.022346 0.0557961 0.997346 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 779 828 -0.74872 -10.8278 -5.75351 -0.0259212 0.0262629 -0.0542147 0.997847 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 779 829 -0.186752 0.0142607 -6.29859 0.000756029 0.0321234 -0.00608762 0.999465 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 779 830 -0.771974 10.8516 -6.02633 0.0272418 0.0287454 0.0543501 0.997736 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 780 829 -0.772355 -10.8174 -5.77773 -0.0318241 0.0188375 -0.0560411 0.997743 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 780 830 -0.188609 -0.0101285 -6.27831 0.000608666 0.032172 -0.00151575 0.999481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 780 831 -0.785876 10.8629 -6.02784 0.0418126 0.0282475 0.0521624 0.997363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 781 830 -0.760856 -10.8484 -5.777 -0.0362964 0.0286161 -0.0524265 0.997555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 781 831 -0.194504 -0.0198547 -6.26806 0.00368881 0.0342129 0.00371829 0.999401 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 781 832 -0.763699 10.8574 -6.02541 0.0368855 0.0299295 0.0620484 0.996942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 782 831 -0.744468 -10.8457 -5.76658 -0.0351878 0.0349 -0.0470362 0.997663 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 782 832 -0.180066 0.000477363 -6.27253 0.00885315 0.0396148 0.0124872 0.999098 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 782 833 -0.767857 10.8556 -6.02081 0.0245903 0.0223575 0.0562932 0.997861 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 783 832 -0.76831 -10.8434 -5.76891 -0.0312067 0.0267298 -0.054004 0.997695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 783 833 -0.213586 0.0157125 -6.27023 0.00105644 0.0222205 0.00994566 0.999703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 783 834 -0.783699 10.8641 -6.02955 0.0300487 0.0377791 0.0585021 0.99712 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 784 833 -0.751095 -10.8721 -5.77649 -0.0258341 0.0292711 -0.0606621 0.997395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 784 834 -0.198793 0.0187837 -6.27865 -0.0072674 0.0327989 0.00254126 0.999432 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 784 835 -0.777215 10.8717 -6.03701 0.0346235 0.0364071 0.0530751 0.997326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 785 834 -0.740375 -10.8644 -5.76443 -0.0351848 0.0260701 -0.0573261 0.997395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 785 835 -0.189131 -0.00562094 -6.28807 -0.00132924 0.0288249 0.00826732 0.999549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 785 836 -0.786091 10.8838 -6.02669 0.0358861 0.0353443 0.0594856 0.996958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 786 835 -0.756651 -10.8596 -5.76488 -0.0259636 0.0366032 -0.0527206 0.9976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 786 836 -0.206876 0.0139379 -6.26349 0.00645576 0.034416 -0.00584512 0.99937 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 786 837 -0.795822 10.9006 -6.01884 0.025219 0.0386221 0.0586401 0.997213 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 787 836 -0.769595 -10.8661 -5.78232 -0.0291894 0.0295897 -0.0662666 0.996936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 787 837 -0.202624 -0.0054777 -6.28598 -0.00304683 0.027889 -0.00194682 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 787 838 -0.764133 10.8947 -6.03322 0.0365473 0.0322733 0.0546732 0.997313 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 788 837 -0.743819 -10.8865 -5.75835 -0.0244413 0.0226929 -0.0597793 0.997654 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 788 838 -0.190988 -0.0039851 -6.29156 0.00102125 0.0214653 -0.0021832 0.999767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 788 839 -0.785314 10.9205 -6.03529 0.0312794 0.0331539 0.0499639 0.99771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 789 838 -0.750465 -10.9033 -5.76519 -0.0435229 0.0314178 -0.0487096 0.99737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 789 839 -0.196846 -0.00874241 -6.27879 0.000609739 0.0423067 -0.00584067 0.999087 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 789 840 -0.784369 10.9199 -6.04137 0.0337894 0.0307723 0.0458803 0.997901 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 790 839 -0.766184 -10.9009 -5.77265 -0.0369774 0.0316128 -0.0525422 0.997433 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 790 840 -0.198632 -0.00940105 -6.27136 -0.00146441 0.0290416 -0.000659072 0.999577 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 790 841 -0.788769 10.9154 -6.02938 0.0353062 0.0356517 0.0557163 0.997185 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 791 840 -0.759562 -10.9072 -5.79526 -0.0365559 0.0266939 -0.0545849 0.997483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 791 841 -0.211809 0.0150947 -6.28269 0.0025655 0.0332578 0.00516419 0.99943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 791 842 -0.799655 10.9277 -6.03446 0.0316691 0.030666 0.0530074 0.997621 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 792 841 -0.743832 -10.9267 -5.77938 -0.0369274 0.0317767 -0.0586098 0.997092 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 792 842 -0.182667 0.0132229 -6.28647 -0.00200218 0.0320347 -0.00563125 0.999469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 792 843 -0.778068 10.9527 -6.02473 0.0276268 0.0240629 0.0649622 0.997215 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 793 842 -0.754296 -10.9183 -5.78032 -0.0198954 0.0288377 -0.0541886 0.997916 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 793 843 -0.195472 0.00738766 -6.2895 -0.00177813 0.0416802 -0.00782579 0.999099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 793 844 -0.777953 10.9518 -6.03936 0.0301158 0.0301776 0.055562 0.997545 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 794 843 -0.77382 -10.9385 -5.77553 -0.0341551 0.0343845 -0.052676 0.997435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 794 844 -0.208978 0.00145696 -6.27014 -0.00249268 0.0244331 -0.00105708 0.999698 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 794 845 -0.779043 10.9535 -6.04792 0.0362513 0.0337602 0.0530354 0.997363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 795 844 -0.752648 -10.9529 -5.7825 -0.0324783 0.0259234 -0.0599457 0.997336 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 795 845 -0.212366 0.00677421 -6.28776 0.00594462 0.0269405 0.0064447 0.999599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 795 846 -0.772477 10.977 -6.01642 0.0337026 0.0337335 0.0467887 0.997766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 796 845 -0.761962 -10.9582 -5.77497 -0.0261248 0.0320033 -0.0575457 0.997488 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 796 846 -0.21673 -0.00587388 -6.28097 0.000344516 0.0236603 0.00851999 0.999684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 796 847 -0.773836 10.9742 -6.05613 0.0280055 0.0376369 0.0461525 0.997832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 797 846 -0.77095 -10.9648 -5.77837 -0.0376623 0.0230028 -0.0581501 0.997332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 797 847 -0.174321 0.00896516 -6.29837 -0.00456426 0.0292889 0.0114778 0.999495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 797 848 -0.796701 10.9822 -6.02974 0.0255885 0.0263783 0.0523819 0.997951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 798 847 -0.771273 -10.9754 -5.78091 -0.0287081 0.0328112 -0.0638907 0.997004 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 798 848 -0.216542 -0.00201393 -6.28279 -0.000273437 0.0190762 0.000798591 0.999818 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 798 849 -0.782757 10.997 -6.01804 0.0404202 0.0342688 0.0547097 0.997095 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 799 848 -0.784389 -10.9618 -5.78922 -0.0317146 0.0265329 -0.0577867 0.997472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 799 849 -0.190589 -0.0040137 -6.28875 -0.0012567 0.0337891 -0.0117039 0.99936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 799 850 -0.789352 10.9902 -6.03996 0.0306677 0.0448698 0.0573376 0.996874 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 800 849 -0.792734 -10.9761 -5.78957 -0.0404072 0.0236369 -0.0504174 0.997631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 800 850 -0.198791 -0.00971766 -6.28064 -0.00430545 0.0220653 -0.00398991 0.999739 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 800 851 -0.809703 11 -6.02483 0.0238418 0.0283039 0.0458032 0.998265 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 801 850 -0.778804 -10.9913 -5.77166 -0.0303646 0.0323312 -0.0569806 0.99739 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 801 851 -0.202344 -0.00529879 -6.27088 0.00548225 0.0269894 -0.000929161 0.99962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 801 852 -0.800777 11.0041 -6.04092 0.0290238 0.0263151 0.0604698 0.997401 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 802 851 -0.781614 -11.0105 -5.79036 -0.0249763 0.0403521 -0.0575799 0.997212 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 802 852 -0.205168 0.0141164 -6.28816 -0.00318114 0.0313181 -0.00685499 0.999481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 802 853 -0.788809 11.024 -6.02137 0.0288321 0.0387221 0.0568385 0.997215 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 803 852 -0.776243 -10.9884 -5.7864 -0.0273117 0.0422392 -0.0456405 0.997691 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 803 853 -0.189052 0.0109324 -6.27577 0.00237936 0.0374109 -0.00450112 0.999287 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 803 854 -0.785658 11.0146 -6.03888 0.0366386 0.0272958 0.0539899 0.997496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 804 853 -0.77391 -11.009 -5.79277 -0.0233454 0.0232488 -0.0636005 0.997431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 804 854 -0.183174 0.0151437 -6.27726 0.00514184 0.0327751 0.000659574 0.999449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 804 855 -0.788071 11.0263 -6.03396 0.0380923 0.032531 0.0496584 0.997509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 805 854 -0.770463 -11.0291 -5.7816 -0.0236779 0.0216224 -0.0576812 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 805 855 -0.208017 -5.67949e-05 -6.27455 -0.00333575 0.029945 -0.000263347 0.999546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 805 856 -0.811628 11.0286 -6.04847 0.032737 0.0281869 0.0542978 0.99759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 806 855 -0.772903 -11.024 -5.7995 -0.0294091 0.0310575 -0.0560613 0.997511 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 806 856 -0.194075 0.00120962 -6.2803 -0.000530013 0.0300827 0.000336207 0.999547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 806 857 -0.772764 11.0452 -6.03519 0.0348776 0.0317561 0.0513485 0.997566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 807 856 -0.766714 -11.0385 -5.79933 -0.032903 0.0310442 -0.0579628 0.997293 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 807 857 -0.188773 -0.00259737 -6.28158 -0.00647894 0.0265281 0.00566345 0.999611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 807 858 -0.804795 11.0523 -6.03439 0.028498 0.0336991 0.0512538 0.99771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 808 857 -0.780206 -11.0397 -5.79345 -0.0281502 0.0276093 -0.0610547 0.997355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 808 858 -0.209218 -0.01441 -6.28463 -0.00424728 0.0382703 -0.00190755 0.999257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 808 859 -0.801065 11.0602 -6.03915 0.0333493 0.0244262 0.0539502 0.997688 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 809 858 -0.791159 -11.0567 -5.77824 -0.0354213 0.0288433 -0.0592253 0.997199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 809 859 -0.197156 -0.0127638 -6.25886 0.00208137 0.0293018 0.000249479 0.999568 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 809 860 -0.807265 11.0526 -6.04532 0.0191606 0.0266587 0.0509496 0.998161 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 810 859 -0.786136 -11.0444 -5.77543 -0.0347942 0.0237771 -0.0521918 0.997747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 810 860 -0.188693 -0.0022154 -6.28847 -0.00454841 0.0325569 0.00856196 0.999423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 810 861 -0.782499 11.0844 -6.04351 0.0312976 0.0323551 0.0545344 0.997497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 811 860 -0.786911 -11.0512 -5.79689 -0.030735 0.0301683 -0.0554819 0.99753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 811 861 -0.189015 -0.00011907 -6.27973 -0.000853771 0.0401642 -0.00203459 0.999191 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 811 862 -0.785144 11.0887 -6.04801 0.0318448 0.0332811 0.0524375 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 812 861 -0.789598 -11.0628 -5.78694 -0.024478 0.0334596 -0.0536609 0.997698 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 812 862 -0.194592 0.00150968 -6.27948 0.0102666 0.0300959 -0.00748458 0.999466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 812 863 -0.795303 11.0803 -6.03454 0.0371975 0.0379572 0.0463035 0.997513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 813 862 -0.788852 -11.0619 -5.77268 -0.0405589 0.0332654 -0.0657105 0.996459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 813 863 -0.194336 0.0220436 -6.27852 0.00735192 0.0362671 0.00517892 0.999302 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 813 864 -0.787074 11.1106 -6.03258 0.0243369 0.0346629 0.0604424 0.997273 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 814 863 -0.792579 -11.0804 -5.80486 -0.0363886 0.0219518 -0.0630801 0.997103 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 814 864 -0.18445 0.011578 -6.26671 0.000471858 0.0297036 0.00940866 0.999514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 814 865 -0.797851 11.1134 -6.01708 0.0248874 0.0384428 0.0560649 0.997376 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 815 864 -0.780135 -11.0788 -5.7901 -0.0296562 0.0279774 -0.0548262 0.997663 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 815 865 -0.212132 -0.013508 -6.26707 -0.00571965 0.0410484 -0.00588597 0.999123 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 815 866 -0.82261 11.0762 -6.04104 0.0358193 0.0260805 0.0507757 0.997727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 816 865 -0.787474 -11.0952 -5.79814 -0.0265968 0.0272144 -0.0545497 0.997786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 816 866 -0.202162 0.00283447 -6.28864 0.00817826 0.0316873 0.00724842 0.999438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 816 867 -0.813985 11.1266 -6.05916 0.0314414 0.0356745 0.0506638 0.997583 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 817 866 -0.800275 -11.1133 -5.79206 -0.032018 0.0294345 -0.0589622 0.997312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 817 867 -0.199496 -0.00890084 -6.26521 0.00124645 0.0315061 -0.00636661 0.999483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 817 868 -0.806138 11.1253 -6.04526 0.0321605 0.0312929 0.0597597 0.997204 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 818 867 -0.778915 -11.1195 -5.79882 -0.0288201 0.0291908 -0.0548972 0.997649 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 818 868 -0.209957 -0.00367906 -6.28182 0.00671646 0.0335712 0.00311727 0.999409 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 818 869 -0.816265 11.1242 -6.02261 0.0434785 0.0339669 0.0502716 0.99721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 819 868 -0.791529 -11.1097 -5.79851 -0.0349779 0.0348017 -0.050433 0.997508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 819 869 -0.193709 0.00533302 -6.27528 -0.00644004 0.0353511 0.00110965 0.999354 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 819 870 -0.802847 11.1328 -6.04562 0.033829 0.0389636 0.0491845 0.997456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 820 869 -0.780174 -11.1187 -5.78885 -0.0290832 0.0361087 -0.0643703 0.996848 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 820 870 -0.206122 -0.0102082 -6.2841 -0.000726557 0.0247707 0.0028605 0.999689 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 820 871 -0.805125 11.1442 -6.06348 0.0264926 0.0303897 0.0543395 0.997708 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 821 870 -0.783897 -11.1335 -5.79046 -0.0228373 0.0356384 -0.054783 0.997601 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 821 871 -0.202147 0.00492713 -6.2744 -0.00496315 0.0285914 -0.000160214 0.999579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 821 872 -0.801677 11.1441 -6.05724 0.0400635 0.0337386 0.0557559 0.99707 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 822 871 -0.776513 -11.1382 -5.79691 -0.0273406 0.0304113 -0.0582692 0.997463 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 822 872 -0.196074 0.00821534 -6.2842 -0.000137788 0.0339054 0.00546755 0.99941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 822 873 -0.808215 11.1572 -6.06412 0.0289046 0.0248736 0.0455102 0.998236 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 823 872 -0.77382 -11.1508 -5.79831 -0.0419138 0.0262516 -0.0547596 0.997274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 823 873 -0.213455 0.003927 -6.28428 0.0060741 0.039272 -0.00881861 0.999171 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 823 874 -0.795104 11.1494 -6.02536 0.0362493 0.0393294 0.0556853 0.997015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 824 873 -0.779362 -11.1413 -5.79805 -0.0310026 0.0278786 -0.0515186 0.997801 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 824 874 -0.204895 -0.00372902 -6.28435 0.00630475 0.0320683 0.0110432 0.999405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 824 875 -0.816014 11.1606 -6.03862 0.0379613 0.0283188 0.0509237 0.997579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 825 874 -0.786783 -11.162 -5.77937 -0.0328229 0.031689 -0.056726 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 825 875 -0.205052 0.0116003 -6.2792 0.000107086 0.0368764 0.00557287 0.999304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 825 876 -0.808739 11.1646 -6.04581 0.0274371 0.0340469 0.0566372 0.997437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 826 875 -0.806919 -11.172 -5.79985 -0.0379261 0.0239242 -0.0592201 0.997237 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 826 876 -0.183523 -0.00242382 -6.27024 -0.00669235 0.0350609 -0.0056906 0.999347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 826 877 -0.825774 11.1692 -6.03073 0.0262897 0.0391226 0.05657 0.997285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 827 876 -0.797668 -11.1941 -5.79128 -0.0289333 0.0408651 -0.0565843 0.997141 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 827 877 -0.19742 -0.00372795 -6.27371 0.00246468 0.0305757 -0.00273494 0.999526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 827 878 -0.819579 11.1836 -6.04488 0.0313102 0.0320221 0.0540629 0.997533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 828 877 -0.808737 -11.1768 -5.80659 -0.0351019 0.0266839 -0.0532226 0.997609 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 828 878 -0.179003 -0.00944711 -6.28911 0.00290105 0.0316803 -0.000974077 0.999493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 828 879 -0.803431 11.2093 -6.05984 0.0347159 0.0273787 0.0551148 0.997501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 829 878 -0.793098 -11.2085 -5.80539 -0.0319951 0.0329812 -0.0546184 0.997449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 829 879 -0.177225 -0.00786167 -6.27948 -0.00351501 0.0400107 -0.0015106 0.999192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 829 880 -0.819388 11.2022 -6.0584 0.0347143 0.0334115 0.0589702 0.997096 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 830 879 -0.79884 -11.2096 -5.79543 -0.0276213 0.030609 -0.0564093 0.997556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 830 880 -0.188965 0.000333867 -6.29171 0.00833501 0.0259849 0.00507744 0.999615 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 830 881 -0.814753 11.2113 -6.04624 0.026885 0.0369297 0.0572644 0.997313 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 831 880 -0.796121 -11.1997 -5.8092 -0.0353691 0.0257989 -0.0531582 0.997626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 831 881 -0.191997 -0.0163298 -6.26732 -0.00308996 0.0370188 -0.0126096 0.99923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 831 882 -0.82497 11.2375 -6.05101 0.0354304 0.0255775 0.057886 0.997366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 832 881 -0.792836 -11.2213 -5.81406 -0.0321143 0.0335029 -0.0596708 0.997139 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 832 882 -0.205644 -0.00700135 -6.28501 -0.00260451 0.0238419 0.00332355 0.999707 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 832 883 -0.826702 11.224 -6.0604 0.0256781 0.0250857 0.0522752 0.997987 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 833 882 -0.813393 -11.2257 -5.80084 -0.029178 0.0280567 -0.0589167 0.997442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 833 883 -0.19258 0.0149871 -6.27635 -0.0016852 0.0360195 -0.00695544 0.999325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 833 884 -0.834967 11.257 -6.04874 0.0296894 0.0291039 0.0535108 0.997701 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 834 883 -0.789765 -11.2348 -5.79601 -0.0193611 0.036515 -0.0532582 0.997725 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 834 884 -0.191814 0.01316 -6.29471 -0.00636674 0.0336118 0.00601214 0.999397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 834 885 -0.811614 11.2199 -6.04793 0.0266439 0.0392997 0.0528764 0.997472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 835 884 -0.802007 -11.2278 -5.79426 -0.0284694 0.0191905 -0.0582252 0.997713 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 835 885 -0.176111 0.0167495 -6.28113 -0.005182 0.0285736 -0.0109015 0.999519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 835 886 -0.823869 11.2616 -6.05589 0.0291045 0.0313053 0.0537409 0.99764 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 836 885 -0.797773 -11.2448 -5.80693 -0.0427233 0.0384581 -0.053793 0.996896 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 836 886 -0.194256 0.021101 -6.27171 0.00177251 0.0348735 -0.0020298 0.999388 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 836 887 -0.817094 11.2478 -6.06357 0.0265634 0.0290133 0.0514413 0.997901 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 837 886 -0.788853 -11.2563 -5.8037 -0.0269317 0.0275368 -0.0505523 0.997978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 837 887 -0.197725 -0.00414514 -6.27085 9.64817e-05 0.0310817 0.00425076 0.999508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 837 888 -0.828064 11.2683 -6.07416 0.0289356 0.0299126 0.0603711 0.997308 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 838 887 -0.803829 -11.2637 -5.79559 -0.0339908 0.0295455 -0.0575839 0.997324 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 838 888 -0.213679 -0.000229251 -6.27071 0.00104736 0.0310632 -0.0037044 0.99951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 838 889 -0.820314 11.2682 -6.04242 0.0381988 0.0249736 0.0573464 0.997311 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 839 888 -0.802433 -11.2751 -5.80847 -0.0223169 0.0305672 -0.0544065 0.997801 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 839 889 -0.209693 -0.0160455 -6.30473 -8.85905e-05 0.0302771 0.000262511 0.999542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 839 890 -0.81991 11.2808 -6.05571 0.0328994 0.0327473 0.0623434 0.996975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 840 889 -0.801709 -11.2669 -5.79788 -0.0318619 0.0349191 -0.0524967 0.997502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 840 890 -0.189886 -0.00539106 -6.2657 -0.00558247 0.0290642 0.00572087 0.999546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 840 891 -0.823913 11.2952 -6.07435 0.0311839 0.0356876 0.0544363 0.997392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 841 890 -0.806423 -11.2737 -5.81937 -0.030012 0.0260035 -0.0509316 0.997912 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 841 891 -0.191121 -0.00457529 -6.28412 -0.00210074 0.0284678 0.000120757 0.999592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 841 892 -0.821409 11.2974 -6.06807 0.0307294 0.0292612 0.0618385 0.997184 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 842 891 -0.818447 -11.2941 -5.83126 -0.0301426 0.0335842 -0.0612535 0.997102 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 842 892 -0.203826 0.00529707 -6.27162 -0.00268459 0.0270398 -0.00940714 0.999586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 842 893 -0.822847 11.3086 -6.0557 0.0264657 0.032092 0.0505042 0.997857 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 843 892 -0.805382 -11.3041 -5.80493 -0.0331566 0.0249965 -0.0616887 0.997231 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 843 893 -0.194214 -0.00826217 -6.27745 -0.000955646 0.0344606 0.000165852 0.999406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 843 894 -0.810353 11.3083 -6.06482 0.0242365 0.032767 0.0633278 0.99716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 844 893 -0.817964 -11.2839 -5.81102 -0.0330922 0.028053 -0.0547275 0.997558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 844 894 -0.184332 -0.00757642 -6.27288 0.000549178 0.0323301 0.00520568 0.999464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 844 895 -0.826867 11.3 -6.06732 0.0309737 0.0378866 0.0567368 0.997189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 845 894 -0.809016 -11.3179 -5.79229 -0.0340115 0.0283986 -0.0563377 0.997428 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 845 895 -0.197236 -0.00272752 -6.29432 0.00616496 0.0309463 0.00726188 0.999476 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 845 896 -0.823267 11.3327 -6.05381 0.0396364 0.0267538 0.0523586 0.997483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 846 895 -0.804225 -11.3151 -5.81397 -0.0355504 0.035527 -0.0507171 0.997448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 846 896 -0.192203 0.00467842 -6.27118 0.000658256 0.0315926 0.0085772 0.999464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 846 897 -0.821067 11.3285 -6.07353 0.0264188 0.0329738 0.0626385 0.997142 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 847 896 -0.814245 -11.3274 -5.81618 -0.0294137 0.0327472 -0.0474029 0.997906 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 847 897 -0.216873 0.0116141 -6.28844 -0.00509314 0.0372977 0.00230393 0.999289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 847 898 -0.815247 11.347 -6.06685 0.0243529 0.026213 0.0536271 0.99792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 848 897 -0.805349 -11.3155 -5.80338 -0.0237857 0.0393962 -0.0553434 0.997406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 848 898 -0.196904 -0.0145324 -6.28267 0.000818109 0.0264716 -0.00038078 0.999649 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 848 899 -0.816374 11.3397 -6.04177 0.0240668 0.0343456 0.0489708 0.997919 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 849 898 -0.814347 -11.3338 -5.81295 -0.0294593 0.0246313 -0.0559188 0.997697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 849 899 -0.217659 0.00237745 -6.28305 -0.00722895 0.0316083 0.0102009 0.999422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 849 900 -0.824228 11.3497 -6.03705 0.0323435 0.0309377 0.0659637 0.996818 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 850 899 -0.811604 -11.3537 -5.8162 -0.0266335 0.0308035 -0.062994 0.997183 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 850 900 -0.20433 0.00958899 -6.27216 0.00456298 0.0283876 -0.00475604 0.999575 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 850 901 -0.842999 11.3551 -6.06333 0.0341219 0.0278676 0.0634602 0.997011 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 851 900 -0.811398 -11.3546 -5.8251 -0.0374129 0.0311902 -0.0534187 0.997384 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 851 901 -0.197384 0.00410537 -6.28043 -0.000172474 0.03929 -0.00522756 0.999214 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 851 902 -0.848173 11.3623 -6.07025 0.0211554 0.0313313 0.0642212 0.997219 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 852 901 -0.808227 -11.3598 -5.79548 -0.030533 0.0335215 -0.0619278 0.99705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 852 902 -0.191134 0.011743 -6.2977 -0.00153025 0.0345886 0.0015081 0.999399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 852 903 -0.843417 11.3737 -6.07244 0.0314701 0.0286929 0.0627504 0.99712 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 853 902 -0.824213 -11.3677 -5.80793 -0.0268224 0.0266608 -0.0474245 0.998159 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 853 903 -0.200311 -0.0101603 -6.28968 -0.0157392 0.0263532 0.00038898 0.999529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 853 904 -0.821303 11.3624 -6.05489 0.0309015 0.0281035 0.0544102 0.997645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 854 903 -0.816493 -11.3937 -5.81331 -0.0248962 0.0270004 -0.0534174 0.997897 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 854 904 -0.197731 -0.00409571 -6.27636 0.00313788 0.0287782 0.00495591 0.999569 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 854 905 -0.83212 11.3679 -6.06605 0.0334245 0.031768 0.0542999 0.997459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 855 904 -0.819311 -11.3779 -5.81543 -0.0232816 0.0274245 -0.0575451 0.997695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 855 905 -0.196396 -0.00122012 -6.2709 0.000240674 0.0282338 -0.00350873 0.999595 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 855 906 -0.81954 11.3963 -6.07465 0.019568 0.0374769 0.0603546 0.997281 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 856 905 -0.841971 -11.4122 -5.82348 -0.0317715 0.0386188 -0.0595867 0.99697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 856 906 -0.192671 0.00277487 -6.28823 -0.00458104 0.0369331 -0.00433154 0.999298 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 856 907 -0.85534 11.3891 -6.0468 0.0224131 0.0453943 0.0570297 0.997088 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 857 906 -0.822504 -11.3887 -5.80799 -0.0275985 0.0320162 -0.0609759 0.997244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 857 907 -0.194177 -0.00279859 -6.28254 -0.00350207 0.0289935 -0.00725753 0.999547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 857 908 -0.829588 11.3803 -6.06488 0.0323638 0.0303013 0.0589744 0.997275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 858 907 -0.820741 -11.3783 -5.82359 -0.0324272 0.0327252 -0.0612511 0.997059 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 858 908 -0.189267 0.00593462 -6.27513 -0.00231266 0.0315924 0.00106173 0.999498 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 858 909 -0.843213 11.4179 -6.04701 0.0294532 0.0288872 0.0524607 0.99777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 859 908 -0.818302 -11.3965 -5.80547 -0.0273249 0.0351383 -0.0554764 0.997467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 859 909 -0.190941 0.00517418 -6.28721 -0.00649644 0.035106 0.0034231 0.999357 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 859 910 -0.852047 11.4054 -6.0782 0.0240918 0.0305049 0.0644835 0.997161 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 860 909 -0.791072 -11.407 -5.80943 -0.0297998 0.0403693 -0.0598391 0.996946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 860 910 -0.193816 -0.0201664 -6.26859 0.00150707 0.0275472 -5.03632e-05 0.999619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 860 911 -0.830519 11.425 -6.07357 0.033241 0.0307806 0.0573896 0.997323 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 861 910 -0.816817 -11.4106 -5.81525 -0.0291263 0.0264574 -0.0542756 0.99775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 861 911 -0.194498 -0.00833703 -6.28973 -0.00910513 0.0281598 -0.00225988 0.999559 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 861 912 -0.841752 11.4216 -6.07768 0.0283599 0.0279497 0.0634266 0.997192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 862 911 -0.829116 -11.41 -5.80877 -0.0297679 0.0373601 -0.0516484 0.997522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 862 912 -0.198217 0.00355358 -6.2829 -0.00412914 0.0269894 0.00100076 0.999627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 862 913 -0.845632 11.4261 -6.06759 0.0234082 0.0324206 0.0544385 0.997716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 863 912 -0.844348 -11.4284 -5.80576 -0.0238059 0.0329209 -0.0634956 0.997155 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 863 913 -0.201872 -0.000688598 -6.27445 -0.00481801 0.0404495 0.00799497 0.999138 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 863 914 -0.839874 11.4262 -6.06363 0.0256176 0.0452411 0.0630548 0.996655 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 864 913 -0.842612 -11.436 -5.8337 -0.0320679 0.0434231 -0.0595624 0.996764 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 864 914 -0.195433 0.0113981 -6.26488 -0.00293337 0.0344526 0.00576589 0.999385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 864 915 -0.82981 11.4404 -6.05772 0.0360383 0.0241031 0.0600963 0.997251 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 865 914 -0.837294 -11.4441 -5.81146 -0.0238148 0.0414815 -0.0509586 0.997555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 865 915 -0.193645 0.0127 -6.2704 -0.00211326 0.0314769 -0.00644469 0.999481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 865 916 -0.858215 11.4447 -6.06031 0.0295654 0.041766 0.0578102 0.997015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 866 915 -0.846063 -11.4492 -5.81563 -0.0298938 0.0307375 -0.053688 0.997637 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 866 916 -0.19328 -0.00143265 -6.27651 -0.00806353 0.0318143 -0.0105933 0.999405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 866 917 -0.8466 11.4486 -6.06661 0.0250366 0.0296033 0.0516669 0.997911 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 867 916 -0.827254 -11.4602 -5.82119 -0.0254482 0.0327971 -0.0592369 0.99738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 867 917 -0.193343 0.00103572 -6.27556 0.00127398 0.0397002 0.00187286 0.999209 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 867 918 -0.846 11.452 -6.06136 0.0272272 0.0345303 0.0573333 0.997386 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 868 917 -0.833701 -11.4485 -5.82145 -0.0259083 0.0330889 -0.0668978 0.996874 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 868 918 -0.206168 -0.00241704 -6.26982 0.00388661 0.0281486 -0.00157647 0.999595 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 868 919 -0.831949 11.4688 -6.07392 0.0224936 0.0297874 0.0569056 0.997682 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 869 918 -0.823241 -11.4716 -5.82411 -0.0274578 0.0283434 -0.0533608 0.997795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 869 919 -0.185576 0.00632445 -6.26989 -0.000371324 0.0314857 -0.00388895 0.999497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 869 920 -0.847619 11.4765 -6.0606 0.0265608 0.0388036 0.0564839 0.997296 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 870 919 -0.847015 -11.4639 -5.83523 -0.0294224 0.0314042 -0.0549259 0.997563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 870 920 -0.201921 0.0047582 -6.27441 0.00130818 0.0255623 -0.000819719 0.999672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 870 921 -0.830535 11.4869 -6.07865 0.0357483 0.0356976 0.0576263 0.997059 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 871 920 -0.84672 -11.4707 -5.83006 -0.0305452 0.0294251 -0.0584879 0.997387 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 871 921 -0.188344 -0.0192776 -6.29305 0.0108305 0.0287586 -0.004295 0.999518 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 871 922 -0.845825 11.4948 -6.05483 0.0235012 0.0230787 0.053232 0.998039 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 872 921 -0.828921 -11.4962 -5.83624 -0.0301591 0.0192223 -0.0664293 0.99715 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 872 922 -0.177736 0.00291843 -6.2798 -0.0101594 0.0332123 0.00124223 0.999396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 872 923 -0.847774 11.5007 -6.06331 0.0289338 0.0327468 0.055154 0.997521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 873 922 -0.833563 -11.4853 -5.83218 -0.0213453 0.0289499 -0.0614191 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 873 923 -0.175716 0.00215976 -6.2851 -0.00294115 0.0326424 -0.00652591 0.999441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 873 924 -0.860643 11.4986 -6.08957 0.0288459 0.0394834 0.0591936 0.997048 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 874 923 -0.837335 -11.4887 -5.82817 -0.0312347 0.0365481 -0.0673637 0.996569 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 874 924 -0.200105 0.00111502 -6.27513 0.000221106 0.0268067 0.00072709 0.99964 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 874 925 -0.844335 11.5127 -6.08559 0.0324952 0.033632 0.0544975 0.997418 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 875 924 -0.838386 -11.4963 -5.83143 -0.0281848 0.0282296 -0.0548019 0.9977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 875 925 -0.213727 -0.00214723 -6.27867 0.00874953 0.0371243 0.000107725 0.999272 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 875 926 -0.869894 11.5306 -6.07343 0.0349993 0.0390555 0.0589359 0.996883 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 876 925 -0.83538 -11.5003 -5.84467 -0.0292905 0.0327058 -0.0547329 0.997535 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 876 926 -0.19347 -0.0025328 -6.27475 -0.00139497 0.0331639 -0.00290687 0.999445 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 876 927 -0.845674 11.5093 -6.08048 0.0192718 0.0253741 0.0676116 0.997203 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 877 926 -0.839857 -11.5045 -5.82709 -0.0240081 0.0334516 -0.0603723 0.997326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 877 927 -0.184947 0.00311278 -6.28205 0.00601056 0.0381004 -0.00286804 0.999252 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 877 928 -0.870671 11.5229 -6.08304 0.0266015 0.031554 0.055467 0.997607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 878 927 -0.831561 -11.5121 -5.83836 -0.0220543 0.0311737 -0.0548771 0.997763 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 878 928 -0.20865 -0.0043775 -6.26355 0.00368586 0.02779 -0.00460058 0.999596 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 878 929 -0.852437 11.5427 -6.08361 0.02501 0.0304752 0.0567615 0.997609 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 879 928 -0.859097 -11.5364 -5.82641 -0.0291918 0.033612 -0.044551 0.998015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 879 929 -0.184944 0.00498327 -6.28229 0.00513182 0.0313293 0.0036888 0.999489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 879 930 -0.865759 11.569 -6.08466 0.0293458 0.0373566 0.0693283 0.996462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 880 929 -0.835149 -11.5323 -5.84293 -0.0281347 0.0330978 -0.0539147 0.9976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 880 930 -0.202616 -0.00874887 -6.28209 0.00589293 0.0444771 -0.00571792 0.998977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 880 931 -0.8689 11.5172 -6.08128 0.027482 0.0293314 0.0608695 0.997336 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 881 930 -0.8389 -11.5422 -5.82687 -0.0284186 0.0339967 -0.0488035 0.997825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 881 931 -0.210442 0.00610151 -6.28247 0.00215903 0.0297788 -0.0103277 0.999501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 881 932 -0.871333 11.5545 -6.08639 0.0310079 0.0331601 0.0578657 0.997292 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 882 931 -0.827687 -11.5499 -5.81933 -0.0319167 0.0271661 -0.0593278 0.997358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 882 932 -0.202637 -0.0051739 -6.27246 -0.0012504 0.0280356 0.00116331 0.999605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 882 933 -0.84968 11.5622 -6.079 0.0386869 0.0276594 0.0532653 0.997447 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 883 932 -0.83257 -11.5413 -5.82798 -0.0315641 0.0296394 -0.0648683 0.996954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 883 933 -0.185172 -0.00447001 -6.28515 -0.00485908 0.0305865 -0.000370101 0.99952 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 883 934 -0.855759 11.5561 -6.07051 0.0265882 0.0305205 0.0636948 0.997148 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 884 933 -0.849939 -11.5592 -5.82887 -0.0253554 0.0319359 -0.0453623 0.998138 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 884 934 -0.19546 -0.0139387 -6.26409 -0.000709414 0.0366476 -0.000496019 0.999328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 884 935 -0.852683 11.5879 -6.07648 0.0288462 0.0219265 0.0555005 0.997801 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 885 934 -0.843288 -11.5728 -5.8323 -0.0229965 0.0327614 -0.0585858 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 885 935 -0.185246 -0.017772 -6.26897 -0.00315484 0.0366525 -0.00189066 0.999321 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 885 936 -0.852172 11.5676 -6.07535 0.0241002 0.0310051 0.0602362 0.997411 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 886 935 -0.843387 -11.5692 -5.83366 -0.0256707 0.0238162 -0.0547156 0.997888 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 886 936 -0.198646 0.00352705 -6.27291 -0.00266959 0.0347433 -0.000228302 0.999393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 886 937 -0.859391 11.5954 -6.07757 0.0238501 0.024813 0.0553782 0.997872 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 887 936 -0.831962 -11.5756 -5.82662 -0.0335753 0.0296463 -0.0542462 0.997523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 887 937 -0.207056 -0.0117148 -6.27275 -0.000853727 0.0374989 -0.0113075 0.999232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 887 938 -0.864814 11.5932 -6.09814 0.030457 0.0318059 0.0518262 0.997685 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 888 937 -0.85367 -11.5557 -5.83063 -0.0292159 0.0307028 -0.0536949 0.997658 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 888 938 -0.172479 -0.00203997 -6.27889 0.00541861 0.0376842 -0.00732661 0.999248 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 888 939 -0.862308 11.6038 -6.07161 0.0128015 0.0385989 0.0631365 0.997176 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 889 938 -0.846319 -11.5914 -5.82623 -0.0303257 0.0298201 -0.0515089 0.997766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 889 939 -0.198527 -0.00579497 -6.28348 0.00331352 0.033729 0.0058423 0.999408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 889 940 -0.856496 11.6079 -6.09515 0.0152234 0.0352027 0.0541017 0.997799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 890 939 -0.841239 -11.5768 -5.84348 -0.0230068 0.0275401 -0.0578457 0.99768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 890 940 -0.191567 -0.0113963 -6.27918 -0.00717117 0.0298746 0.00134477 0.999527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 890 941 -0.874072 11.6218 -6.0953 0.0294331 0.0320259 0.0503915 0.997782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 891 940 -0.84855 -11.5804 -5.82002 -0.0227373 0.0342757 -0.0519947 0.9978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 891 941 -0.201559 -0.0198283 -6.27793 0.008159 0.0348505 -0.00278883 0.999355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 891 942 -0.876851 11.6214 -6.09749 0.0233032 0.0301588 0.0612463 0.997395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 892 941 -0.845564 -11.6107 -5.8311 -0.0230022 0.0225943 -0.0571312 0.997846 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 892 942 -0.211206 0.0083172 -6.2662 0.00289227 0.0285641 0.00526449 0.999574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 892 943 -0.872467 11.6056 -6.09264 0.0275234 0.0347018 0.0526791 0.997629 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 893 942 -0.844073 -11.6117 -5.85849 -0.0240776 0.032292 -0.0571989 0.99755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 893 943 -0.202637 -0.00489814 -6.27905 0.00145053 0.0312338 -0.00551462 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 893 944 -0.862629 11.6344 -6.08937 0.0254357 0.0271516 0.0505464 0.998028 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 894 943 -0.845472 -11.6117 -5.83896 -0.0276983 0.0253139 -0.049978 0.998045 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 894 944 -0.191321 -0.00110886 -6.279 -0.00441119 0.0320845 0.00193646 0.999474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 894 945 -0.872041 11.6275 -6.09312 0.0281084 0.0284006 0.0623971 0.997251 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 895 944 -0.858662 -11.606 -5.83213 -0.0254351 0.0315027 -0.0522126 0.997815 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 895 945 -0.190526 0.0102744 -6.27278 0.0035225 0.031156 -0.0065161 0.999487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 895 946 -0.87023 11.6281 -6.08548 0.019519 0.0297107 0.0625275 0.99741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 896 945 -0.845082 -11.6452 -5.8483 -0.03493 0.0313956 -0.0593767 0.99713 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 896 946 -0.194208 -0.00988486 -6.27388 0.00669444 0.0276381 0.00136459 0.999595 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 896 947 -0.860013 11.6431 -6.09243 0.0266383 0.0419478 0.0524752 0.997385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 897 946 -0.847435 -11.6345 -5.82094 -0.0304055 0.0294825 -0.0621168 0.99717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 897 947 -0.197568 0.00257767 -6.27733 0.00159046 0.0303971 -0.00271578 0.999533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 897 948 -0.846148 11.6499 -6.10772 0.0227117 0.033 0.0602295 0.99738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 898 947 -0.840971 -11.6536 -5.83957 -0.0207377 0.0325326 -0.0536416 0.997815 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 898 948 -0.172062 -0.00212917 -6.26717 0.00900733 0.0330696 0.000900973 0.999412 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 898 949 -0.866696 11.6487 -6.08383 0.0240906 0.0183544 0.0663772 0.997335 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 899 948 -0.848629 -11.643 -5.84542 -0.0280512 0.0213594 -0.0549123 0.997869 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 899 949 -0.209945 -0.0304623 -6.28207 0.00422082 0.0356026 0.00219033 0.999355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 899 950 -0.877936 11.6587 -6.10016 0.0272094 0.0238403 0.0568459 0.997727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 900 949 -0.845432 -11.6402 -5.84643 -0.0280531 0.0369411 -0.0632661 0.996918 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 900 950 -0.168623 -0.00661424 -6.27767 -0.00387136 0.0328734 0.00652392 0.999431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 900 951 -0.861453 11.659 -6.09259 0.0269124 0.021948 0.0530521 0.997988 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 901 950 -0.851033 -11.6766 -5.84917 -0.0219752 0.0316856 -0.0529062 0.997855 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 901 951 -0.184154 -0.00131964 -6.29903 0.00567067 0.0350691 0.00149156 0.999368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 901 952 -0.873225 11.6597 -6.08684 0.0170363 0.040812 0.0603738 0.997196 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 902 951 -0.851633 -11.6697 -5.83872 -0.0290174 0.0239117 -0.0636424 0.997264 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 902 952 -0.197081 0.0152286 -6.27432 -0.00198398 0.0342692 0.00391804 0.999403 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 902 953 -0.885955 11.6641 -6.08052 0.0179427 0.0304241 0.0555767 0.997829 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 903 952 -0.84808 -11.6754 -5.84994 -0.0203401 0.0400746 -0.0663512 0.996784 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 903 953 -0.206721 0.000724226 -6.29299 0.00215283 0.0307739 -0.00262924 0.999521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 903 954 -0.857303 11.6944 -6.10199 0.0273443 0.0373356 0.0522008 0.997564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 904 953 -0.848174 -11.6595 -5.85607 -0.0214466 0.0401321 -0.0550929 0.997444 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 904 954 -0.205812 0.0136197 -6.29353 -5.69042e-05 0.0387292 -0.00112895 0.999249 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 904 955 -0.852806 11.6947 -6.10649 0.0254814 0.0307603 0.0518395 0.997856 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 905 954 -0.853665 -11.6688 -5.85807 -0.0189263 0.0326866 -0.0542141 0.997815 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 905 955 -0.200087 0.00173981 -6.28474 -0.00616135 0.0344151 0.00322245 0.999383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 905 956 -0.884137 11.6878 -6.1041 0.0232006 0.044036 0.0576019 0.997098 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 906 955 -0.871277 -11.6962 -5.84261 -0.0242214 0.0342295 -0.0555526 0.997575 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 906 956 -0.193366 0.00858528 -6.2767 0.000816446 0.0296543 0.00706006 0.999535 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 906 957 -0.87627 11.7009 -6.09007 0.0211473 0.0324162 0.0569884 0.997624 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 907 956 -0.855275 -11.7014 -5.83857 -0.0174484 0.0408115 -0.0606436 0.997172 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 907 957 -0.21125 -0.00419743 -6.27959 -0.000680746 0.0343827 0.00558157 0.999393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 907 958 -0.882517 11.7269 -6.094 0.0190309 0.0367333 0.059925 0.997345 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 908 957 -0.865862 -11.6933 -5.848 -0.0274572 0.0394325 -0.0602644 0.997025 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 908 958 -0.184209 0.00852719 -6.28921 -0.00515951 0.0306899 -0.00750903 0.999487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 908 959 -0.874622 11.7024 -6.09478 0.00516015 0.0350493 0.0539312 0.997916 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 909 958 -0.860086 -11.7039 -5.85021 -0.0218477 0.0394528 -0.0602598 0.997163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 909 959 -0.196513 0.00342609 -6.29019 0.000840207 0.0336381 0.00369802 0.999427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 909 960 -0.894188 11.7302 -6.10606 0.0226454 0.0259459 0.055599 0.997859 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 910 959 -0.859876 -11.7191 -5.85473 -0.0272687 0.0315576 -0.0541686 0.99766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 910 960 -0.175937 0.00113017 -6.28461 -0.000969673 0.0307608 -0.00274435 0.999523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 910 961 -0.880065 11.728 -6.09882 0.0317526 0.0284991 0.0549346 0.997578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 911 960 -0.856246 -11.7122 -5.85122 -0.0237409 0.0304 -0.0494996 0.998029 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 911 961 -0.198993 -0.00535413 -6.29173 -0.00809651 0.0213922 0.000467442 0.999738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 911 962 -0.864952 11.7344 -6.10475 0.0192432 0.0284148 0.0572704 0.997769 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 912 961 -0.852991 -11.7134 -5.84175 -0.0165361 0.0312303 -0.0651854 0.997247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 912 962 -0.20522 -0.0204644 -6.28605 -0.00168611 0.0275077 0.00730961 0.999593 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 912 963 -0.8981 11.7451 -6.10951 0.0233379 0.0290134 0.0488423 0.998112 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 913 962 -0.875535 -11.73 -5.85412 -0.0221179 0.0347805 -0.0531826 0.997734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 913 963 -0.193578 0.0219345 -6.28688 0.000122808 0.0316777 0.010021 0.999448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 913 964 -0.866196 11.7324 -6.11851 0.0197362 0.0327021 0.0608906 0.997413 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 914 963 -0.855702 -11.7431 -5.83484 -0.024036 0.0351598 -0.0559416 0.997525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 914 964 -0.20027 0.00712153 -6.29497 0.00785067 0.0223965 0.000686637 0.999718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 914 965 -0.888232 11.7489 -6.11075 0.027626 0.0319195 0.0569257 0.997486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 915 964 -0.855467 -11.7517 -5.84847 -0.0204448 0.0305149 -0.057311 0.99768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 915 965 -0.200686 -0.0145736 -6.27542 0.00566303 0.028769 0.00190408 0.999568 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 915 966 -0.903436 11.7431 -6.09755 0.0225064 0.0396398 0.0517231 0.997621 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 916 965 -0.876839 -11.7501 -5.85922 -0.028662 0.0354215 -0.0603553 0.997136 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 916 966 -0.198219 -0.00869148 -6.27902 -0.00216112 0.033022 -0.00210323 0.99945 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 916 967 -0.873525 11.7649 -6.10554 0.0172533 0.0294116 0.0577437 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 917 966 -0.860489 -11.7575 -5.85389 -0.0210716 0.027907 -0.0618205 0.997475 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 917 967 -0.194219 -0.0060939 -6.28159 0.00914427 0.0261548 -0.00636291 0.999596 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 917 968 -0.879596 11.7496 -6.11026 0.0252939 0.0358268 0.0502339 0.997774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 918 967 -0.866704 -11.763 -5.85853 -0.0267693 0.0276342 -0.0542233 0.997787 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 918 968 -0.195954 0.0021491 -6.29252 0.0106352 0.0351744 -0.00406756 0.999316 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 918 969 -0.879544 11.7639 -6.09522 0.0290607 0.0395044 0.0659877 0.996615 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 919 968 -0.866287 -11.761 -5.8464 -0.0361218 0.0386637 -0.0696504 0.996167 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 919 969 -0.183752 -0.00828745 -6.27626 0.00547768 0.0355679 0.0115712 0.999285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 919 970 -0.863968 11.7742 -6.10821 0.0225427 0.0327023 0.0529545 0.997807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 920 969 -0.863072 -11.7599 -5.82843 -0.0230511 0.028499 -0.0578325 0.997653 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 920 970 -0.201398 -0.00287709 -6.28387 -0.00770186 0.027885 0.00084214 0.999581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 920 971 -0.903284 11.769 -6.09969 0.0179972 0.03626 0.0510369 0.997876 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 921 970 -0.888496 -11.7765 -5.83629 -0.0148033 0.0290752 -0.0616728 0.997563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 921 971 -0.184513 -0.00754844 -6.28097 -3.20026e-05 0.0328958 0.00609237 0.99944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 921 972 -0.882502 11.8023 -6.08712 0.032415 0.0362228 0.0599836 0.997015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 922 971 -0.873671 -11.7789 -5.85548 -0.0176553 0.0319776 -0.0506138 0.99805 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 922 972 -0.201378 0.00925956 -6.26924 -0.00395502 0.0280622 -0.000948318 0.999598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 922 973 -0.893416 11.7768 -6.11322 0.0203888 0.0299617 0.0601072 0.997534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 923 972 -0.870513 -11.787 -5.85114 -0.0219781 0.0227338 -0.0615027 0.997606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 923 973 -0.202851 -0.00377159 -6.29198 0.00531008 0.0259852 -0.00142675 0.999647 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 923 974 -0.876103 11.7924 -6.12859 0.0245652 0.0308356 0.0621383 0.997289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 924 973 -0.867513 -11.7839 -5.85792 -0.0186334 0.0289904 -0.0499965 0.998155 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 924 974 -0.176335 0.00777291 -6.28564 -0.00422526 0.0291299 0.00589814 0.999549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 924 975 -0.888744 11.7717 -6.11925 0.0256098 0.0381496 0.0556314 0.997394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 925 974 -0.870714 -11.8149 -5.84669 -0.0230655 0.0314169 -0.0620515 0.997312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 925 975 -0.201521 -0.0138858 -6.28643 0.000326522 0.0305079 0.00382397 0.999527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 925 976 -0.875962 11.7929 -6.10778 0.0210115 0.0374565 0.057064 0.997446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 926 975 -0.882389 -11.8125 -5.85941 -0.0245186 0.0339787 -0.0541137 0.997655 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 926 976 -0.202694 0.0140357 -6.26905 -0.00967969 0.023317 -0.00391203 0.999674 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 926 977 -0.877173 11.8076 -6.1158 0.015701 0.0214199 0.059235 0.997891 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 927 976 -0.869649 -11.7971 -5.86373 -0.0237672 0.0290298 -0.0559242 0.99773 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 927 977 -0.196226 0.00140985 -6.27555 -0.00332477 0.0350313 0.00720481 0.999355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 927 978 -0.881246 11.8154 -6.12839 0.0178392 0.0415451 0.055723 0.997422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 928 977 -0.861279 -11.8144 -5.85712 -0.0185641 0.0324902 -0.0595506 0.997524 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 928 978 -0.18957 0.0102809 -6.28314 -0.000813254 0.023161 -0.00422024 0.999723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 928 979 -0.898527 11.8144 -6.11004 0.0245696 0.0276978 0.0587552 0.997586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 929 978 -0.894483 -11.7971 -5.88175 -0.0195699 0.0278191 -0.0536598 0.99798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 929 979 -0.186741 -0.0117304 -6.27461 -0.00514768 0.0289342 -0.00421969 0.999559 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 929 980 -0.868951 11.8406 -6.12694 0.0210985 0.0311062 0.0664709 0.99708 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 930 979 -0.880118 -11.8177 -5.86291 -0.0269653 0.0291327 -0.0625148 0.997254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 930 980 -0.210771 0.0117963 -6.27514 -0.00315982 0.0290683 -0.00367557 0.999566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 930 981 -0.8926 11.8423 -6.11098 0.0184449 0.031975 0.0521573 0.997956 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 931 980 -0.870701 -11.8159 -5.85509 -0.0255281 0.0334992 -0.0590935 0.997364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 931 981 -0.208427 0.0163925 -6.28143 0.00101888 0.0293569 0.00186463 0.999567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 931 982 -0.886473 11.8243 -6.12062 0.0299271 0.0349396 0.05071 0.997653 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 932 981 -0.875192 -11.8475 -5.86409 -0.0121244 0.0405659 -0.0566509 0.997496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 932 982 -0.192685 0.0160326 -6.29269 -0.00062491 0.0241884 3.8478e-05 0.999707 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 932 983 -0.899718 11.8339 -6.12282 0.0237419 0.0307815 0.0501274 0.997986 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 933 982 -0.872849 -11.8391 -5.85152 -0.0171707 0.0374177 -0.0605336 0.997317 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 933 983 -0.215642 -0.00442316 -6.29275 -0.0013704 0.0308049 0.00468416 0.999513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 933 984 -0.888203 11.8387 -6.10907 0.0262167 0.0240962 0.0503497 0.998097 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 934 983 -0.87954 -11.8363 -5.86363 -0.0253762 0.0393276 -0.0609547 0.997043 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 934 984 -0.18696 -0.00505232 -6.28544 -0.00363197 0.0297857 0.00135036 0.999549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 934 985 -0.890931 11.8422 -6.12638 0.0336095 0.0339199 0.0575544 0.9972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 935 984 -0.885057 -11.8479 -5.88236 -0.0294513 0.0358492 -0.0642498 0.996855 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 935 985 -0.204979 0.00535995 -6.27128 -0.000260844 0.0285758 -0.00491143 0.99958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 935 986 -0.90799 11.868 -6.12528 0.0273546 0.0242016 0.0579667 0.99765 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 936 985 -0.867689 -11.8573 -5.87344 -0.0165999 0.0316689 -0.0501938 0.998099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 936 986 -0.196871 -0.0220392 -6.29048 -0.00365323 0.02737 -0.0029116 0.999614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 936 987 -0.889702 11.8668 -6.10608 0.0319097 0.0287522 0.0648646 0.996969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 937 986 -0.868382 -11.8551 -5.86687 -0.0232085 0.0239031 -0.0577698 0.997774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 937 987 -0.177353 -0.0013001 -6.28226 -0.00451048 0.035407 0.00299405 0.999358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 937 988 -0.867887 11.876 -6.12443 0.0143252 0.0308436 0.0631378 0.997425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 938 987 -0.880678 -11.8611 -5.88379 -0.0239974 0.0330678 -0.0639598 0.997116 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 938 988 -0.199163 0.0117155 -6.28101 -0.0042192 0.0242673 -0.000293614 0.999697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 938 989 -0.892295 11.8842 -6.1181 0.0236264 0.0435403 0.0511427 0.997462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 939 988 -0.876445 -11.8598 -5.85639 -0.0244439 0.0305938 -0.0601221 0.997423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 939 989 -0.175125 0.00905537 -6.26037 0.00292108 0.029711 -0.00112903 0.999554 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 939 990 -0.902965 11.8692 -6.10589 0.0296964 0.0319999 0.0633768 0.997034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 940 989 -0.891517 -11.8622 -5.88137 -0.0220552 0.0306703 -0.0599967 0.997483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 940 990 -0.214915 -0.00503588 -6.27257 -0.00293919 0.0270064 0.00588456 0.999614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 940 991 -0.907262 11.8883 -6.11702 0.0192732 0.0365354 0.0596899 0.997362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 941 990 -0.877848 -11.8605 -5.8825 -0.0236045 0.0393481 -0.0652591 0.996813 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 941 991 -0.194134 -0.00912504 -6.26051 -0.00407793 0.0257804 0.000504702 0.999659 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 941 992 -0.898065 11.8766 -6.12489 0.0309507 0.0362974 0.0543192 0.997384 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 942 991 -0.887679 -11.8834 -5.88352 -0.0216654 0.0289099 -0.0579138 0.997668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 942 992 -0.197262 0.00222184 -6.26652 -0.000698775 0.0345551 -0.0039243 0.999395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 942 993 -0.909892 11.8757 -6.1202 0.0246011 0.0286274 0.057011 0.99766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 943 992 -0.885439 -11.8879 -5.86074 -0.0205258 0.0243814 -0.0513153 0.998174 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 943 993 -0.18931 0.00905288 -6.26463 -0.00862606 0.0347534 0.000803174 0.999358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 943 994 -0.911948 11.8947 -6.10994 0.0158362 0.0391391 0.0643965 0.997031 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 944 993 -0.86926 -11.9042 -5.86823 -0.0282365 0.0281545 -0.0569809 0.997579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 944 994 -0.20058 -0.00764747 -6.27236 0.00143396 0.0305295 0.000773644 0.999533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 944 995 -0.910914 11.9048 -6.12155 0.0280723 0.0325403 0.0553432 0.997542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 945 994 -0.887148 -11.8801 -5.8607 -0.0240178 0.0300809 -0.056272 0.997673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 945 995 -0.19788 0.00833969 -6.29653 0.00331581 0.0386066 0.00409806 0.999241 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 945 996 -0.890457 11.9031 -6.13289 0.0202345 0.0297532 0.0625315 0.997394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 946 995 -0.872345 -11.8882 -5.87703 -0.0231231 0.0435226 -0.0584745 0.997072 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 946 996 -0.20157 -0.0168056 -6.27581 -0.00509844 0.0262152 0.00802144 0.999611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 946 997 -0.909071 11.9221 -6.10964 0.0229525 0.0309799 0.0509967 0.997954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 947 996 -0.897964 -11.9068 -5.87385 -0.0315253 0.0249481 -0.0619205 0.997271 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 947 997 -0.178971 0.00196943 -6.27644 -0.00421607 0.0293217 -0.00815642 0.999528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 947 998 -0.896004 11.9239 -6.12791 0.0179091 0.0363013 0.0510415 0.997876 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 948 997 -0.874713 -11.9101 -5.87404 -0.0159365 0.0239969 -0.0654815 0.997438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 948 998 -0.198299 0.010536 -6.29526 -0.00273882 0.0336801 -0.00231529 0.999426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 948 999 -0.911386 11.9213 -6.12582 0.0155886 0.0359369 0.0673422 0.996961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 949 998 -0.878622 -11.9046 -5.89018 -0.0197642 0.0359368 -0.0591132 0.997408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 949 999 -0.191901 0.00172803 -6.29594 0.00403713 0.0321996 -0.00322247 0.999468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 949 1000 -0.909615 11.9226 -6.15105 0.0246795 0.0421846 0.0516251 0.99747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 950 999 -0.884078 -11.9356 -5.89138 -0.0200323 0.0350832 -0.059284 0.997423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 950 1000 -0.206232 0.00666195 -6.28498 0.00131521 0.0166962 0.0050942 0.999847 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 950 1001 -0.892073 11.9365 -6.13242 0.0134963 0.0332619 0.0696818 0.996923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 951 1000 -0.896824 -11.9158 -5.89333 -0.028509 0.0355434 -0.0564654 0.997364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 951 1001 -0.181495 -0.0113844 -6.28161 0.00740052 0.0299082 -0.00138108 0.999524 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 951 1002 -0.899244 11.9291 -6.14069 0.0175379 0.0338034 0.065368 0.997134 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 952 1001 -0.881547 -11.9315 -5.88694 -0.0170082 0.0266333 -0.0556215 0.997952 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 952 1002 -0.181842 -0.010722 -6.28877 -0.0114436 0.0308967 -0.00259731 0.999454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 952 1003 -0.914382 11.9614 -6.11956 0.0183254 0.0423811 0.0569603 0.997308 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 953 1002 -0.884293 -11.9462 -5.87813 -0.0238685 0.0278515 -0.0550556 0.997809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 953 1003 -0.209844 -0.00820387 -6.27764 -0.00208384 0.0375308 -0.0142771 0.999191 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 953 1004 -0.904651 11.9495 -6.1339 0.0287162 0.0249289 0.0621662 0.997341 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 954 1003 -0.872114 -11.9288 -5.86843 -0.0240781 0.0344281 -0.0536141 0.997678 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 954 1004 -0.190344 -0.0239031 -6.28564 -0.00263057 0.032348 0.00140546 0.999472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 954 1005 -0.904961 11.9525 -6.1422 0.0220213 0.0247374 0.0657801 0.997284 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 955 1004 -0.913733 -11.9479 -5.89062 -0.0242336 0.0363503 -0.063021 0.997056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 955 1005 -0.184932 0.00281957 -6.28107 0.00163548 0.0366998 0.000871411 0.999325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 955 1006 -0.913318 11.9518 -6.10682 0.0162523 0.0302133 0.0556621 0.99786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 956 1005 -0.902457 -11.9221 -5.8916 -0.0276358 0.0241277 -0.0548067 0.997823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 956 1006 -0.196852 0.000763239 -6.28353 0.0063917 0.0318759 0.00228086 0.999469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 956 1007 -0.918583 11.9712 -6.13839 0.0223003 0.0365168 0.0557543 0.997527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 957 1006 -0.894855 -11.9554 -5.88629 -0.0180762 0.0366489 -0.0548804 0.997656 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 957 1007 -0.198158 0.00668261 -6.28395 0.000741281 0.0381866 -0.00929378 0.999227 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 957 1008 -0.904177 11.9631 -6.13246 0.00992824 0.0303201 0.0684737 0.997143 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 958 1007 -0.896456 -11.964 -5.89102 -0.0181635 0.0297252 -0.0673499 0.997121 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 958 1008 -0.188431 0.00808821 -6.30049 -0.00317705 0.0246296 0.00713073 0.999666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 958 1009 -0.886094 11.9846 -6.12334 0.0165758 0.0448648 0.058385 0.997148 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 959 1008 -0.894248 -11.9528 -5.87857 -0.0229949 0.0304957 -0.0588854 0.997534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 959 1009 -0.217401 0.00381665 -6.28311 -0.00106709 0.0250654 -0.000537685 0.999685 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 959 1010 -0.923318 11.9744 -6.14729 0.0282942 0.027549 0.0657199 0.997056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 960 1009 -0.894276 -11.9738 -5.87818 -0.0210179 0.0288003 -0.0625884 0.997402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 960 1010 -0.199083 0.00447765 -6.28289 0.00261145 0.0319998 -0.00514902 0.999471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 960 1011 -0.905549 11.989 -6.15034 0.0307549 0.0308222 0.0550664 0.997533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 961 1010 -0.887968 -11.9886 -5.87964 -0.0293267 0.0280984 -0.0605498 0.997339 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 961 1011 -0.195983 -0.0082214 -6.27798 0.00660781 0.0296962 -0.0057839 0.99952 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 961 1012 -0.916626 11.981 -6.13734 0.0252032 0.0338337 0.0628321 0.997132 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 962 1011 -0.88543 -11.9696 -5.88279 -0.0183829 0.0252687 -0.0557026 0.997958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 962 1012 -0.183628 -0.0115355 -6.27869 0.00404723 0.0335537 0.00724633 0.999402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 962 1013 -0.886309 11.9848 -6.14811 0.0279811 0.038855 0.0644003 0.996775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 963 1012 -0.901917 -11.9747 -5.89434 -0.0138364 0.0267704 -0.0718612 0.996959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 963 1013 -0.207364 -0.013425 -6.27619 -0.00774889 0.0347111 -0.00607853 0.999349 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 963 1014 -0.906525 11.9816 -6.13461 0.0153463 0.0291013 0.0537262 0.998014 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 964 1013 -0.903733 -11.9995 -5.88448 -0.0198256 0.0371546 -0.0540733 0.997649 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 964 1014 -0.201272 -0.000678338 -6.28324 0.0072595 0.0298842 -0.00295716 0.999523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 964 1015 -0.930842 12.0108 -6.14171 0.023032 0.0357398 0.0517101 0.997757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 965 1014 -0.895769 -11.9841 -5.87413 -0.0213172 0.0320219 -0.0603672 0.997435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 965 1015 -0.20909 0.00394325 -6.283 0.0149002 0.0335693 -0.00513991 0.999312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 965 1016 -0.91335 12.0129 -6.13067 0.0229705 0.0345369 0.055423 0.997601 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 966 1015 -0.903742 -11.9888 -5.89875 -0.0280025 0.0286214 -0.0576681 0.997532 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 966 1016 -0.193049 -0.00704695 -6.29502 0.00359459 0.0284167 0.00974624 0.999542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 966 1017 -0.904095 11.9979 -6.14951 0.0133935 0.0397339 0.059952 0.99732 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 967 1016 -0.886648 -12.0037 -5.87902 -0.0184479 0.0275737 -0.0551855 0.997925 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 967 1017 -0.194175 0.000592487 -6.27037 0.00600167 0.0290974 -0.00359271 0.999552 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 967 1018 -0.930425 12.0282 -6.13324 0.0193577 0.0450181 0.0614098 0.996909 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 968 1017 -0.912833 -12.0135 -5.90296 -0.00921174 0.0259607 -0.052766 0.998227 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 968 1018 -0.203402 -0.0233705 -6.26362 0.0048704 0.0258154 0.00168925 0.999653 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 968 1019 -0.901601 12.0046 -6.14556 0.0244287 0.0324996 0.054948 0.997661 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 969 1018 -0.914198 -12.0212 -5.89445 -0.0221815 0.0306964 -0.0482099 0.998119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 969 1019 -0.189523 0.019981 -6.28413 -0.00798877 0.0437242 -0.00357846 0.999005 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 969 1020 -0.92007 12.0312 -6.14401 0.0228721 0.0268213 0.0600819 0.997571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 970 1019 -0.90637 -12.0248 -5.89531 -0.0247074 0.0253735 -0.0569803 0.997747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 970 1020 -0.205256 -0.00219624 -6.28389 -0.000467093 0.0262859 -0.00085311 0.999654 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 970 1021 -0.924545 11.9966 -6.14304 0.0192705 0.0338193 0.0599352 0.997443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 971 1020 -0.894976 -12.0098 -5.89158 -0.0217782 0.0290264 -0.0550394 0.997825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 971 1021 -0.190237 0.00862082 -6.30134 0.00143025 0.0270847 -0.0051586 0.999619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 971 1022 -0.922341 12.0349 -6.16048 0.0236447 0.036565 0.0531391 0.997637 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 972 1021 -0.894149 -12.0131 -5.89004 -0.0210229 0.0268258 -0.0614455 0.997528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 972 1022 -0.202485 0.0092219 -6.28332 0.00257756 0.0283702 -0.00132507 0.999593 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 972 1023 -0.910931 12.0262 -6.12635 0.0210552 0.0247626 0.0620054 0.997546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 973 1022 -0.902492 -12.0303 -5.89258 -0.0189323 0.0364713 -0.0630649 0.997163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 973 1023 -0.1939 0.00262454 -6.2806 -0.00673519 0.0298601 -0.00756902 0.999503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 973 1024 -0.919331 12.0347 -6.12651 0.0254241 0.0257988 0.0583149 0.997641 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 974 1023 -0.896171 -12.0184 -5.89484 -0.0269839 0.0177614 -0.0585455 0.997762 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 974 1024 -0.18547 -0.00545205 -6.2779 0.00769356 0.0272031 -0.00328091 0.999595 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 974 1025 -0.915278 12.048 -6.13882 0.0224989 0.0358738 0.0639168 0.997056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 975 1024 -0.889432 -12.032 -5.88919 -0.0205701 0.0323472 -0.0556629 0.997713 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 975 1025 -0.206308 -0.0122597 -6.27865 0.00233787 0.0239578 0.00556049 0.999695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 975 1026 -0.924011 12.0381 -6.15955 0.0165416 0.022291 0.0579214 0.997935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 976 1025 -0.905278 -12.0266 -5.91225 -0.0193555 0.0309974 -0.0606168 0.997492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 976 1026 -0.192734 0.0127341 -6.28519 -0.000196454 0.0316786 -0.00107253 0.999498 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 976 1027 -0.900736 12.0634 -6.15335 0.0176855 0.0432314 0.0713608 0.996356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 977 1026 -0.891478 -12.0581 -5.89338 -0.0265164 0.0238726 -0.0579084 0.997684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 977 1027 -0.199307 -0.00615978 -6.28616 0.00542016 0.0284329 -0.00639731 0.999561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 977 1028 -0.927052 12.0451 -6.15926 0.0315467 0.0267713 0.0648072 0.99704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 978 1027 -0.913738 -12.0518 -5.89764 -0.0210729 0.0345664 -0.0610712 0.997312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 978 1028 -0.210199 -0.00462583 -6.27343 0.00959125 0.0420815 -0.0021922 0.999066 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 978 1029 -0.916187 12.0534 -6.15428 0.0257518 0.0326036 0.0524038 0.997761 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 979 1028 -0.92453 -12.0556 -5.90692 -0.0136675 0.0312089 -0.0509904 0.998118 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 979 1029 -0.207678 -0.0143782 -6.28709 0.00847196 0.0303785 -0.000634124 0.999502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 979 1030 -0.909543 12.0535 -6.13784 0.0257271 0.025458 0.0596886 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 980 1029 -0.901267 -12.0507 -5.90896 -0.0241832 0.0334049 -0.0649774 0.997034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 980 1030 -0.207378 -0.00510364 -6.28181 -0.00535241 0.0369283 0.0118633 0.999233 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 980 1031 -0.922795 12.055 -6.16174 0.0246367 0.034113 0.0688 0.996743 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 981 1030 -0.904781 -12.0682 -5.8927 -0.0138383 0.0348508 -0.0580319 0.99761 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 981 1031 -0.195379 -0.00785823 -6.2756 0.0042581 0.0368939 -0.0130425 0.999225 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 981 1032 -0.930329 12.0635 -6.16852 0.0128746 0.0419594 0.0658651 0.996863 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 982 1031 -0.891879 -12.0532 -5.90927 -0.0288016 0.0337394 -0.056898 0.997394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 982 1032 -0.203784 -0.00904796 -6.26623 0.00439579 0.0309759 0.00578435 0.999494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 982 1033 -0.917201 12.0867 -6.14041 0.0153185 0.0416106 0.0627456 0.997044 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 983 1032 -0.909169 -12.0804 -5.90457 -0.0226946 0.0291591 -0.0732626 0.996628 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 983 1033 -0.195396 -0.00325626 -6.29127 0.000896453 0.0327881 -0.00240677 0.999459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 983 1034 -0.940096 12.0671 -6.15227 0.0152898 0.0369367 0.0623548 0.997253 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 984 1033 -0.902819 -12.0552 -5.90042 -0.0158324 0.0233312 -0.062735 0.997632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 984 1034 -0.196076 -0.00996495 -6.28046 9.75039e-05 0.0386221 0.00688376 0.99923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 984 1035 -0.922282 12.072 -6.14977 0.0105311 0.0321468 0.0577563 0.997757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 985 1034 -0.909448 -12.0928 -5.89935 -0.0225688 0.0287287 -0.0589438 0.997593 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 985 1035 -0.203718 -0.00612244 -6.26936 -0.000123201 0.0358357 0.00394368 0.99935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 985 1036 -0.94499 12.0911 -6.16145 0.0185437 0.0282225 0.0594321 0.997661 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 986 1035 -0.906909 -12.0791 -5.8892 -0.0211666 0.0326658 -0.0624047 0.997292 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 986 1036 -0.201587 0.00277821 -6.28848 0.00110325 0.0324169 -0.00571175 0.999458 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 986 1037 -0.920916 12.0811 -6.15506 0.0161646 0.0378707 0.0548483 0.997645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 987 1036 -0.911401 -12.0919 -5.91511 -0.0202379 0.0390173 -0.0567245 0.997422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 987 1037 -0.199936 0.00589522 -6.27823 -0.000613775 0.0142775 0.00621613 0.999879 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 987 1038 -0.901546 12.0862 -6.15983 0.00901681 0.0273355 0.0582738 0.997886 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 988 1037 -0.926822 -12.0765 -5.91864 -0.0205262 0.0438729 -0.0601801 0.997012 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 988 1038 -0.187104 0.00947356 -6.27725 0.00229367 0.0432252 0.00578596 0.999046 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 988 1039 -0.924211 12.0841 -6.16325 0.0154366 0.0255199 0.0570015 0.997928 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 989 1038 -0.927918 -12.0804 -5.92159 -0.00907376 0.031646 -0.0579481 0.997777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 989 1039 -0.208599 -0.00441417 -6.28006 0.00280242 0.031108 -0.00703529 0.999487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 989 1040 -0.919719 12.0966 -6.16294 0.014325 0.0283867 0.0604542 0.997664 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 990 1039 -0.922346 -12.1045 -5.91446 -0.0163123 0.0297666 -0.0602462 0.997606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 990 1040 -0.219173 0.00145559 -6.28806 0.00373829 0.0326697 0.00477573 0.999448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 990 1041 -0.920918 12.1052 -6.15497 0.0177636 0.0287307 0.0612815 0.997549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 991 1040 -0.911534 -12.1157 -5.90503 -0.0144215 0.0303891 -0.0536045 0.997996 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 991 1041 -0.181949 0.00251487 -6.27223 0.00970241 0.0419761 -0.00388115 0.999064 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 991 1042 -0.908017 12.1145 -6.15589 0.0173384 0.0469135 0.0726035 0.996106 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 992 1041 -0.891657 -12.1067 -5.90353 -0.0183255 0.033232 -0.0618001 0.997367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 992 1042 -0.192893 -0.00890603 -6.28124 0.0047451 0.0342432 0.000101149 0.999402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 992 1043 -0.917477 12.1147 -6.1742 0.0226366 0.0287254 0.0571448 0.997696 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 993 1042 -0.930541 -12.1128 -5.92045 -0.0125092 0.0334526 -0.067759 0.997062 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 993 1043 -0.18624 0.00257368 -6.26959 -0.00321822 0.0314196 0.0060269 0.999483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 993 1044 -0.926043 12.1049 -6.15181 0.00726701 0.037023 0.0639443 0.99724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 994 1043 -0.913663 -12.1324 -5.91444 -0.0222858 0.0294652 -0.0633382 0.997308 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 994 1044 -0.190453 0.00669763 -6.26881 0.0093376 0.0236866 0.00852171 0.99964 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 994 1045 -0.923886 12.1307 -6.16414 0.0142099 0.0336759 0.0614733 0.997439 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 995 1044 -0.909414 -12.1305 -5.90878 -0.0138361 0.0263273 -0.0542721 0.998083 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 995 1045 -0.197984 0.00136674 -6.28763 -0.00217078 0.0244236 -0.00263292 0.999696 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 995 1046 -0.926592 12.1237 -6.17312 0.0213055 0.0221168 0.060385 0.997703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 996 1045 -0.925097 -12.1355 -5.91526 -0.0175537 0.0320818 -0.0633749 0.99732 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 996 1046 -0.195868 0.00722076 -6.28938 -0.00232601 0.0200325 0.00213506 0.999794 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 996 1047 -0.927372 12.0925 -6.17503 0.0211962 0.0277501 0.0633917 0.997378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 997 1046 -0.93263 -12.1288 -5.91268 -0.0188132 0.0271628 -0.0693249 0.997047 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 997 1047 -0.19273 -0.00681438 -6.28975 -0.00353406 0.0247704 -0.00839104 0.999652 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 997 1048 -0.934187 12.1358 -6.15886 0.0141896 0.0279639 0.0630838 0.997515 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 998 1047 -0.923951 -12.1487 -5.92787 -0.0128671 0.0383338 -0.0630831 0.997189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 998 1048 -0.2005 -0.00199924 -6.26362 -0.00141798 0.0271961 -0.00483465 0.999617 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 998 1049 -0.922537 12.1342 -6.176 0.0138526 0.0287596 0.0629948 0.997503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 999 1048 -0.918425 -12.1399 -5.92352 -0.0184979 0.0361803 -0.066008 0.996991 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 999 1049 -0.205706 0.0131647 -6.29667 0.00832904 0.0299333 -0.00717755 0.999491 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 999 1050 -0.919767 12.1433 -6.17617 0.0111896 0.0398178 0.0625719 0.997183 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1000 1049 -0.91683 -12.1336 -5.91668 -0.0138502 0.0373374 -0.0607587 0.997358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1000 1050 -0.2174 0.00859826 -6.28446 -0.00725287 0.0269489 -0.010736 0.999553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1000 1051 -0.920942 12.1502 -6.15839 0.0158408 0.0351956 0.0611421 0.997383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1001 1050 -0.897202 -12.1308 -5.91728 -0.0196039 0.0291538 -0.0634363 0.997367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1001 1051 -0.206379 -0.00665256 -6.28282 0.00432414 0.0325424 -0.0116741 0.999393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1001 1052 -0.945403 12.1365 -6.15994 0.0208308 0.0334704 0.0712566 0.996679 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1002 1051 -0.917908 -12.1618 -5.92015 -0.018824 0.0311519 -0.0617877 0.997425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1002 1052 -0.196378 0.00791912 -6.29183 0.00721654 0.0269173 0.00661937 0.99959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1002 1053 -0.930592 12.1383 -6.17173 0.0178716 0.0289863 0.0519365 0.99807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1003 1052 -0.933304 -12.1649 -5.89217 -0.0229025 0.032582 -0.0623196 0.997261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1003 1053 -0.197283 -0.00938949 -6.28583 -0.00339933 0.0273068 0.00207314 0.999619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1003 1054 -0.936432 12.1488 -6.16293 0.0265144 0.0329569 0.0591282 0.997354 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1004 1053 -0.910026 -12.1566 -5.91911 -0.0103205 0.0309383 -0.0579153 0.997789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1004 1054 -0.207737 0.00461023 -6.28626 -0.00125858 0.0273874 0.000905136 0.999624 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1004 1055 -0.940034 12.1665 -6.1692 0.0126738 0.0305546 0.0634944 0.997434 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1005 1054 -0.905973 -12.1675 -5.91017 -0.022389 0.0367338 -0.0617418 0.997165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1005 1055 -0.198497 0.0021995 -6.27611 -0.00300937 0.0381026 0.0113632 0.999205 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1005 1056 -0.950185 12.1722 -6.16492 0.0247788 0.028196 0.0656461 0.997137 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1006 1055 -0.941425 -12.1732 -5.92493 -0.0288288 0.0292247 -0.0595527 0.997381 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1006 1056 -0.189719 0.00796831 -6.28888 0.00618245 0.0288786 -0.00498113 0.999551 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1006 1057 -0.945651 12.1494 -6.17555 0.0227161 0.0301794 0.0523798 0.997913 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1007 1056 -0.92069 -12.1684 -5.9191 -0.0191921 0.0349137 -0.0566599 0.997598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1007 1057 -0.205272 0.00539356 -6.26617 0.00249433 0.0284756 -0.00202621 0.999589 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1007 1058 -0.946895 12.187 -6.18771 0.02513 0.0381918 0.0514517 0.997628 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1008 1057 -0.932753 -12.1863 -5.9197 -0.0131963 0.0312474 -0.0612588 0.997545 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1008 1058 -0.20775 -0.000247614 -6.29455 0.000737746 0.0303215 -0.00541218 0.999525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1008 1059 -0.926641 12.1831 -6.17709 0.0157557 0.0222892 0.0562609 0.998043 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1009 1058 -0.923072 -12.1743 -5.93692 -0.00460796 0.0348054 -0.060308 0.997562 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1009 1059 -0.195699 0.0020579 -6.26548 -0.00769966 0.0318716 0.00807698 0.99943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1009 1060 -0.945592 12.1657 -6.18211 0.0147903 0.0276072 0.0643186 0.997438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1010 1059 -0.920277 -12.1896 -5.91647 -0.0199375 0.0372599 -0.0663364 0.996902 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1010 1060 -0.186315 -0.011784 -6.28269 0.00347795 0.0377418 -0.00455478 0.999271 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1010 1061 -0.934158 12.2061 -6.17281 0.0113018 0.0303766 0.0645474 0.997388 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1011 1060 -0.916261 -12.1985 -5.92274 -0.0139078 0.0297748 -0.0670183 0.99721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1011 1061 -0.210268 -0.0144806 -6.27047 0.00202845 0.0288617 0.00140196 0.99958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1011 1062 -0.930643 12.1861 -6.18895 0.0201261 0.0267438 0.0607348 0.997593 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1012 1061 -0.91615 -12.1718 -5.93431 -0.0136994 0.0270267 -0.0610823 0.997673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1012 1062 -0.189876 0.00281946 -6.28584 0.00128443 0.0423986 0.00504234 0.999087 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1012 1063 -0.924198 12.2089 -6.18605 0.0229219 0.0276517 0.0662324 0.997158 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1013 1062 -0.94273 -12.1879 -5.92686 -0.0240923 0.0305219 -0.0583379 0.997539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1013 1063 -0.205868 -0.0131633 -6.29057 0.00953341 0.02876 -0.00228283 0.999538 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1013 1064 -0.932523 12.195 -6.17224 0.0217007 0.02687 0.0653169 0.997267 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1014 1063 -0.931624 -12.1854 -5.92007 -0.0160958 0.0329973 -0.0576155 0.997664 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1014 1064 -0.194427 0.0159135 -6.26912 -0.00203714 0.0229944 -0.00310767 0.999729 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1014 1065 -0.926712 12.1816 -6.18888 0.0135947 0.0298971 0.0603033 0.99764 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1015 1064 -0.936852 -12.2146 -5.9258 -0.0118105 0.029268 -0.0555835 0.997955 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1015 1065 -0.195584 -0.0111724 -6.29247 -0.00911412 0.0271322 0.00341174 0.999584 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1015 1066 -0.931366 12.2041 -6.18845 0.0172212 0.0328543 0.0556456 0.997761 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1016 1065 -0.939357 -12.2007 -5.93208 -0.0218677 0.0387327 -0.0564361 0.997415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1016 1066 -0.185179 -0.000324465 -6.27703 0.00279351 0.0298754 0.00857199 0.999513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1016 1067 -0.946461 12.2104 -6.19927 0.00926824 0.0236063 0.0542946 0.998203 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1017 1066 -0.918659 -12.1963 -5.91967 -0.00797664 0.0339726 -0.0616475 0.997488 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1017 1067 -0.211605 0.000853392 -6.2839 0.00289513 0.0399495 0.00594919 0.99918 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1017 1068 -0.951733 12.2161 -6.18181 0.0150764 0.0401435 0.0666521 0.996854 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1018 1067 -0.91842 -12.2142 -5.93741 -0.0219375 0.0279728 -0.0565694 0.997766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1018 1068 -0.197881 -0.0125358 -6.28457 0.00192275 0.0259737 0.000251471 0.999661 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1018 1069 -0.945062 12.2301 -6.18489 0.0218565 0.0249888 0.0561958 0.997868 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1019 1068 -0.93694 -12.2132 -5.94367 -0.018985 0.0339555 -0.0617363 0.997334 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1019 1069 -0.178317 -0.0100035 -6.27728 -0.0084708 0.0290046 0.00281139 0.999539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1019 1070 -0.926719 12.2272 -6.17647 0.0142565 0.0393417 0.0620853 0.997193 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1020 1069 -0.913921 -12.1985 -5.9469 -0.0123933 0.0243737 -0.052685 0.998237 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1020 1070 -0.216366 0.013834 -6.29304 0.00181796 0.0291631 0.00368722 0.999566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1020 1071 -0.943428 12.2125 -6.17657 0.016811 0.0322732 0.0641435 0.997277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1021 1070 -0.934365 -12.2 -5.9306 -0.0138833 0.0344505 -0.0520929 0.997951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1021 1071 -0.199955 -0.0128185 -6.28028 0.0010637 0.034409 0.00476805 0.999396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1021 1072 -0.939489 12.2356 -6.17081 0.013875 0.0306912 0.0571961 0.997795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1022 1071 -0.916373 -12.2247 -5.93286 -0.0217558 0.0298548 -0.0639315 0.99727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1022 1072 -0.196 -0.00507843 -6.30372 0.00523787 0.0245543 -0.00480983 0.999673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1022 1073 -0.943369 12.2146 -6.19406 0.0113911 0.0383911 0.0569949 0.997571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1023 1072 -0.936856 -12.2352 -5.94589 -0.0175929 0.0263611 -0.0630741 0.997506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1023 1073 -0.210417 -0.0264525 -6.26699 0.00152814 0.0294188 -0.00164148 0.999565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1023 1074 -0.947722 12.2209 -6.20513 0.00760703 0.0329524 0.0652681 0.997295 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1024 1073 -0.929608 -12.2164 -5.94032 -0.0188242 0.0266687 -0.064705 0.99737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1024 1074 -0.15949 -0.00366316 -6.26284 0.00415465 0.0332527 -8.12535e-05 0.999438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1024 1075 -0.935072 12.2317 -6.20472 0.0120385 0.0363468 0.0583592 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1025 1074 -0.932313 -12.226 -5.93322 -0.0157029 0.0210466 -0.0719324 0.997064 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1025 1075 -0.214287 -0.00113079 -6.28974 -0.00170432 0.0296117 -0.00602211 0.999542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1025 1076 -0.962077 12.2297 -6.1942 0.029318 0.0318225 0.0673549 0.99679 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1026 1075 -0.930434 -12.2315 -5.93169 -0.0184989 0.027108 -0.0677873 0.99716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1026 1076 -0.2087 -0.00133028 -6.27765 0.0049972 0.0368584 0.00197824 0.999306 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1026 1077 -0.946527 12.2383 -6.18902 0.0209558 0.042319 0.064905 0.996773 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1027 1076 -0.944172 -12.2424 -5.9398 -0.017255 0.0333704 -0.0682997 0.996957 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1027 1077 -0.196384 0.0236204 -6.26454 -0.0049416 0.031931 0.00704324 0.999453 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1027 1078 -0.938408 12.2368 -6.1767 0.0113889 0.0346203 0.0579227 0.997656 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1028 1077 -0.941508 -12.2378 -5.92765 -0.0126186 0.0385729 -0.0523452 0.997804 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1028 1078 -0.173578 0.0038769 -6.26861 0.000875525 0.0273518 -0.00235527 0.999623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1028 1079 -0.940339 12.2323 -6.17896 0.0197631 0.03788 0.060107 0.997277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1029 1078 -0.921694 -12.2574 -5.94638 -0.0154597 0.0326432 -0.0660799 0.99716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1029 1079 -0.204126 0.0032567 -6.27727 0.00474845 0.0255141 -0.0120669 0.99959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1029 1080 -0.955856 12.261 -6.21072 0.0129799 0.0259947 0.0661336 0.997388 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1030 1079 -0.913418 -12.2607 -5.9484 -0.0196067 0.0309825 -0.0586651 0.997604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1030 1080 -0.190949 -0.00327571 -6.28131 -0.00197911 0.0369115 -0.00201847 0.999315 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1030 1081 -0.94575 12.2784 -6.18843 0.0151839 0.0261618 0.0696338 0.997114 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1031 1080 -0.941439 -12.2631 -5.94828 -0.010118 0.0192229 -0.0571735 0.998128 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1031 1081 -0.20252 -0.00364003 -6.256 -0.000418497 0.0247671 0.00135746 0.999692 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1031 1082 -0.940736 12.2582 -6.20233 0.00704579 0.0427366 0.0657986 0.996892 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1032 1081 -0.937442 -12.2733 -5.94877 -0.0166246 0.0276855 -0.06141 0.99759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1032 1082 -0.182343 -0.0023941 -6.30324 0.00289427 0.0336814 -0.0016186 0.999427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1032 1083 -0.936487 12.2456 -6.20922 0.0149347 0.0344735 0.0665189 0.997078 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1033 1082 -0.949133 -12.2635 -5.95102 -0.0188642 0.0323597 -0.0579289 0.997618 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1033 1083 -0.199026 0.00245516 -6.27894 0.00429767 0.0362496 -0.00266335 0.99933 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1033 1084 -0.947061 12.2551 -6.21008 0.0121969 0.0227952 0.0581631 0.997972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1034 1083 -0.950107 -12.2489 -5.94765 -0.0185866 0.0277329 -0.066752 0.997211 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1034 1084 -0.211481 -0.00201668 -6.28629 -0.00831373 0.0305148 -4.95706e-05 0.9995 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1034 1085 -0.962067 12.2654 -6.20263 0.0217838 0.0303122 0.0761296 0.996399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1035 1084 -0.924104 -12.281 -5.94131 0.000652406 0.0239292 -0.0616589 0.99781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1035 1085 -0.206358 -0.0137222 -6.27566 0.00144101 0.0245521 -0.00365912 0.999691 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1035 1086 -0.949134 12.2714 -6.18015 0.0136945 0.0326518 0.0648341 0.997268 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1036 1085 -0.937676 -12.2682 -5.94532 -0.0154093 0.0271735 -0.0587601 0.997783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1036 1086 -0.193371 0.00618146 -6.28207 0.000547043 0.0301396 0.00154029 0.999544 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1036 1087 -0.940263 12.2842 -6.19669 0.0210432 0.040443 0.0583761 0.997253 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1037 1086 -0.940137 -12.2783 -5.94774 -0.0180175 0.03034 -0.0710998 0.996845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1037 1087 -0.19164 0.0208675 -6.26394 -0.0168881 0.0384347 0.00702872 0.999094 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1037 1088 -0.953313 12.2745 -6.21069 0.00579028 0.0344302 0.0619157 0.997471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1038 1087 -0.927604 -12.2871 -5.94679 -0.0128298 0.0261992 -0.0593837 0.997809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1038 1088 -0.212914 -0.00118788 -6.27192 0.00515656 0.0277856 0.00834253 0.999566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1038 1089 -0.967709 12.2836 -6.21324 0.00187624 0.0270182 0.0541029 0.998168 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1039 1088 -0.951038 -12.2886 -5.94692 -0.0256697 0.0337615 -0.0627681 0.997127 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1039 1089 -0.194904 0.0054702 -6.26857 0.00410001 0.0203066 0.00389828 0.999778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1039 1090 -0.93559 12.3 -6.20163 0.0144577 0.034693 0.0697504 0.996856 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1040 1089 -0.946792 -12.2777 -5.95373 -0.0143786 0.0273193 -0.0573521 0.997877 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1040 1090 -0.197906 0.00788934 -6.29297 -0.00603034 0.0371188 -0.00262787 0.999289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1040 1091 -0.952776 12.2747 -6.19291 0.00934481 0.0341492 0.0647408 0.997274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1041 1090 -0.935025 -12.2766 -5.96452 -0.0118085 0.0279884 -0.0700397 0.997082 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1041 1091 -0.194355 -0.00977939 -6.26912 -0.00095311 0.0314734 -0.00172377 0.999503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1041 1092 -0.960832 12.3035 -6.21436 0.00628981 0.0440207 0.0579511 0.997329 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1042 1091 -0.950546 -12.2778 -5.94811 -0.0158413 0.0378137 -0.0658616 0.996986 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1042 1092 -0.186465 0.00507896 -6.27755 -0.00726135 0.0315904 0.00305222 0.99947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1042 1093 -0.943622 12.2923 -6.20644 0.0101969 0.0302128 0.0536916 0.998048 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1043 1092 -0.928421 -12.2909 -5.95792 -0.0113929 0.0301019 -0.0625996 0.99752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1043 1093 -0.203171 0.00678288 -6.27816 0.00298981 0.0302715 -0.00157567 0.999536 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1043 1094 -0.952981 12.2825 -6.19951 0.0109356 0.0311769 0.0711107 0.996921 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1044 1093 -0.927867 -12.3101 -5.94956 -0.0171012 0.0371353 -0.0600689 0.997357 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1044 1094 -0.191525 0.00451711 -6.25699 0.00214193 0.0316715 -0.00847397 0.99946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1044 1095 -0.957579 12.3106 -6.21342 0.0131544 0.0318085 0.0633804 0.997396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1045 1094 -0.930952 -12.2921 -5.94773 -0.0114233 0.0342571 -0.0520108 0.997993 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1045 1095 -0.221653 -0.0100293 -6.2884 -0.00275103 0.0322067 -0.00288723 0.999473 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1045 1096 -0.94206 12.3174 -6.1951 0.00107423 0.0384403 0.0602063 0.997445 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1046 1095 -0.939129 -12.3029 -5.95066 -0.0156519 0.026935 -0.0687713 0.997146 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1046 1096 -0.199256 -0.0155088 -6.2798 -0.010753 0.0281025 -0.00538571 0.999533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1046 1097 -0.950263 12.3144 -6.2031 0.0161808 0.0308713 0.0649217 0.997281 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1047 1096 -0.9473 -12.306 -5.96462 -0.0203388 0.0299457 -0.055056 0.997827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1047 1097 -0.213672 0.00165227 -6.2793 0.00447776 0.0276555 -0.000301615 0.999607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1047 1098 -0.962017 12.3233 -6.20481 0.0127012 0.0317285 0.066378 0.997209 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1048 1097 -0.912924 -12.2882 -5.97136 -0.0133884 0.0401974 -0.0666326 0.996878 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1048 1098 -0.199675 -0.00589048 -6.27289 -0.00395256 0.0248853 -0.00175676 0.999681 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1048 1099 -0.957666 12.3157 -6.21932 0.0226653 0.0400642 0.0589603 0.997198 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1049 1098 -0.951749 -12.291 -5.95353 -0.0217356 0.030176 -0.0558093 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1049 1099 -0.197536 -0.00916186 -6.28481 0.00377901 0.0339194 -0.0162777 0.999285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1049 1100 -0.953344 12.3037 -6.21934 0.0181553 0.0374193 0.0528123 0.997738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1050 1099 -0.945095 -12.2977 -5.96702 -0.0140694 0.0305929 -0.0591566 0.997681 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1050 1100 -0.197025 0.000108511 -6.28872 0.00462282 0.0271474 0.00905369 0.99958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1050 1101 -0.957028 12.3207 -6.21764 0.0138742 0.0378391 0.0630874 0.997194 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1051 1100 -0.931221 -12.3039 -5.96554 -0.0151358 0.026172 -0.0576598 0.997878 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1051 1101 -0.197118 0.0112348 -6.27675 0.00143712 0.030564 -0.0118498 0.999462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1051 1102 -0.95834 12.3194 -6.21205 0.0161251 0.0315796 0.0637553 0.997335 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1052 1101 -0.932315 -12.3272 -5.95642 -0.0212051 0.0208806 -0.0690275 0.997171 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1052 1102 -0.188379 -0.0145909 -6.28367 0.00103441 0.0397567 -0.00140021 0.999208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1052 1103 -0.943215 12.3045 -6.22118 0.00676117 0.0224003 0.0648145 0.997623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1053 1102 -0.934097 -12.3152 -5.97139 -0.00763441 0.0233227 -0.0586091 0.997979 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1053 1103 -0.215442 -0.00834366 -6.27731 -0.000202273 0.0304383 -0.0056703 0.999521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1053 1104 -0.968811 12.3157 -6.21132 0.0201945 0.032154 0.0582037 0.997582 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1054 1103 -0.943034 -12.3113 -5.96037 -0.0146667 0.0201027 -0.0583591 0.997985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1054 1104 -0.198636 -0.00321829 -6.26597 -0.0118927 0.0353257 -0.00309524 0.9993 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1054 1105 -0.971721 12.3286 -6.21408 0.0110599 0.0297209 0.0631885 0.997498 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1055 1104 -0.948396 -12.3413 -5.9521 -0.00851057 0.0258456 -0.0579491 0.997949 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1055 1105 -0.194971 0.0100062 -6.26375 0.00333051 0.028714 -0.0117365 0.999513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1055 1106 -0.96806 12.3319 -6.20683 0.014689 0.0215834 0.0633039 0.997653 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1056 1105 -0.935655 -12.343 -5.96034 -0.0101548 0.0340202 -0.0564915 0.997772 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1056 1106 -0.204579 0.000286498 -6.28062 0.00383472 0.0276148 -0.012034 0.999539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1056 1107 -0.954194 12.3346 -6.21775 0.00880441 0.0277335 0.0659988 0.997395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1057 1106 -0.941654 -12.3314 -5.97517 -0.00191272 0.0239072 -0.0643746 0.997638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1057 1107 -0.202273 -5.19646e-05 -6.28121 0.0047202 0.0268929 -0.000599832 0.999627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1057 1108 -0.952841 12.3442 -6.22781 0.0138791 0.02658 0.0646076 0.99746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1058 1107 -0.959976 -12.347 -5.97058 -0.00845206 0.0283422 -0.0672263 0.997299 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1058 1108 -0.199582 -0.000246185 -6.27826 -0.000784948 0.0347004 0.00319409 0.999392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1058 1109 -0.948158 12.3382 -6.23199 0.00174724 0.0407199 0.0642735 0.9971 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1059 1108 -0.941443 -12.3462 -5.96969 -0.0083116 0.0220977 -0.0629113 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1059 1109 -0.221037 0.00465255 -6.29026 0.000606916 0.0309485 0.00701034 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1059 1110 -0.956443 12.3525 -6.21438 0.00779743 0.0292242 0.0625689 0.997582 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1060 1109 -0.943064 -12.3432 -5.98365 -0.0202553 0.0352115 -0.0567841 0.99756 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1060 1110 -0.193978 -0.00290204 -6.28248 -0.00137193 0.0323317 0.0100894 0.999425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1060 1111 -0.971164 12.3412 -6.20343 0.01298 0.0311893 0.0610803 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1061 1110 -0.95627 -12.329 -5.98067 -0.0141045 0.0357064 -0.0542709 0.997788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1061 1111 -0.191988 0.00597634 -6.25964 0.000330907 0.0327944 -0.00486855 0.99945 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1061 1112 -0.957089 12.3533 -6.218 0.0155669 0.0388746 0.0606877 0.997278 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1062 1111 -0.95234 -12.341 -5.97939 -0.0171144 0.0378443 -0.0620872 0.997206 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1062 1112 -0.193317 0.000335273 -6.27924 -0.00676055 0.0317062 0.000207341 0.999474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1062 1113 -0.968191 12.3466 -6.2418 0.00780284 0.022958 0.0691643 0.997311 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1063 1112 -0.943746 -12.3424 -5.99207 -0.0155295 0.0348124 -0.0572621 0.997631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1063 1113 -0.21532 -0.00759511 -6.29294 0.00598972 0.0348274 0.00497529 0.999363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1063 1114 -0.964512 12.3397 -6.21001 0.0135589 0.0281173 0.0623918 0.997563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1064 1113 -0.954448 -12.3568 -5.97311 -0.0137257 0.0346046 -0.0587983 0.997576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1064 1114 -0.208634 -0.00694675 -6.27586 -0.00246201 0.0343548 -0.00357249 0.9994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1064 1115 -0.956036 12.3628 -6.19979 0.0075494 0.0293948 0.0579607 0.997857 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1065 1114 -0.941345 -12.3491 -6.00859 -0.0129637 0.0247084 -0.0685134 0.99726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1065 1115 -0.191997 -0.00829474 -6.27536 -0.00682536 0.0329071 -0.000841884 0.999435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1065 1116 -0.958174 12.3574 -6.20813 0.0140868 0.0342683 0.0672279 0.997049 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1066 1115 -0.94466 -12.3436 -5.97875 -0.0104722 0.0367745 -0.065302 0.997133 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1066 1116 -0.188601 0.000333413 -6.26233 0.00765148 0.0323397 0.00187513 0.999446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1066 1117 -0.963334 12.3495 -6.22323 0.00851652 0.0263672 0.0630566 0.997625 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1067 1116 -0.937947 -12.3524 -5.96962 -0.00866301 0.0342595 -0.0517145 0.998036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1067 1117 -0.196016 0.0191615 -6.27339 0.00170133 0.0322512 0.00163575 0.999477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1067 1118 -0.959056 12.3616 -6.23036 0.0101427 0.0324383 0.0605464 0.997587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1068 1117 -0.951987 -12.356 -5.96964 -0.0125095 0.0312828 -0.0573445 0.997786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1068 1118 -0.203245 0.00375541 -6.27891 -0.000311599 0.0401679 -0.00803464 0.999161 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1068 1119 -0.949472 12.3598 -6.22769 0.0257001 0.040655 0.0633703 0.99683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1069 1118 -0.950092 -12.3509 -5.98321 -0.0183336 0.0328062 -0.0574583 0.99764 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1069 1119 -0.196673 0.0148762 -6.28283 0.00158486 0.0370217 0.000322114 0.999313 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1069 1120 -0.974378 12.3728 -6.2334 0.0124361 0.0244624 0.0594262 0.997855 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1070 1119 -0.933461 -12.3669 -5.96417 -0.00650109 0.0318256 -0.0606569 0.99763 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1070 1120 -0.1914 -0.00470795 -6.28507 -0.00381556 0.0346933 0.000338143 0.999391 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1070 1121 -0.979187 12.3766 -6.24987 0.0236841 0.0286531 0.0636113 0.997282 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1071 1120 -0.949043 -12.3656 -5.97793 -0.00537999 0.032516 -0.0541451 0.997989 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1071 1121 -0.18246 0.00206586 -6.2812 -0.00703136 0.0262329 -0.00207035 0.999629 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1071 1122 -0.957108 12.3853 -6.23515 0.0175334 0.0282451 0.0590339 0.997702 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1072 1121 -0.941029 -12.3834 -5.97972 -0.0138424 0.0314399 -0.0678937 0.997101 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1072 1122 -0.189534 0.0235229 -6.27414 0.00225038 0.029458 0.00209481 0.999561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1072 1123 -0.968537 12.3704 -6.22148 0.0180077 0.0280067 0.0668401 0.997208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1073 1122 -0.955325 -12.3759 -5.96741 0.00024235 0.0263091 -0.0636484 0.997626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1073 1123 -0.185559 -0.0161769 -6.2847 -0.00688416 0.0299527 0.00217056 0.999525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1073 1124 -0.954097 12.3816 -6.22929 0.0171208 0.0381843 0.0645966 0.997034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1074 1123 -0.955191 -12.3841 -5.97469 -0.0107363 0.0332816 -0.0644959 0.997305 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1074 1124 -0.208256 -0.00177364 -6.27859 0.000919703 0.0361368 -0.00280555 0.999342 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1074 1125 -0.976624 12.3818 -6.24259 0.0115969 0.0319619 0.0626425 0.997457 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1075 1124 -0.962757 -12.376 -6.00012 -0.0186635 0.0349763 -0.0615212 0.997318 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1075 1125 -0.19786 0.00275417 -6.28257 -0.00251589 0.0341425 0.00279729 0.99941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1075 1126 -0.955776 12.389 -6.23131 0.00738781 0.0352838 0.0604528 0.99752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1076 1125 -0.973245 -12.3798 -5.97884 -0.0109885 0.040817 -0.0713323 0.996557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1076 1126 -0.198076 0.0067121 -6.27187 -0.00185631 0.020243 0.00325615 0.999788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1076 1127 -0.98775 12.3854 -6.2405 0.00463066 0.03507 0.0673383 0.997103 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1077 1126 -0.950368 -12.3967 -5.96956 -0.00688919 0.030343 -0.061723 0.997608 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1077 1127 -0.194832 -0.00063255 -6.29183 -0.00461519 0.0330492 -0.0035705 0.999437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1077 1128 -0.960638 12.3861 -6.24158 0.0152351 0.0271489 0.0631984 0.997515 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1078 1127 -0.964102 -12.383 -5.98615 0.000465199 0.0303886 -0.0641021 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1078 1128 -0.213427 0.00765399 -6.30203 0.00559535 0.0460369 -0.00176422 0.998923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1078 1129 -0.990547 12.3965 -6.25411 0.0153525 0.0339035 0.0646278 0.997215 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1079 1128 -0.946418 -12.392 -5.98409 -0.00832574 0.0285593 -0.0525463 0.998175 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1079 1129 -0.200437 0.00390255 -6.26521 -0.00439178 0.03362 0.00270225 0.999421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1079 1130 -0.983222 12.409 -6.24101 0.0132066 0.0262426 0.0597444 0.997781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1080 1129 -0.960608 -12.3972 -5.98248 -0.0190691 0.0277202 -0.0554221 0.997896 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1080 1130 -0.201149 -0.00767652 -6.28476 0.00264604 0.0355372 -0.00342947 0.999359 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1080 1131 -0.957897 12.3944 -6.24118 0.0189055 0.0322588 0.059788 0.997511 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1081 1130 -0.947991 -12.4047 -6.00199 -0.0103 0.0255491 -0.0670703 0.997368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1081 1131 -0.188475 0.01372 -6.27563 -0.00539297 0.0377789 0.000869684 0.999271 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1081 1132 -0.971737 12.4028 -6.24654 0.012934 0.0312534 0.0617205 0.99752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1082 1131 -0.962585 -12.3995 -5.99289 -0.00668243 0.0285062 -0.054962 0.998059 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1082 1132 -0.178809 -0.00287887 -6.28229 0.00347818 0.0254863 0.00688657 0.999645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1082 1133 -0.946964 12.3968 -6.24798 0.00773046 0.0211 0.0650044 0.997632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1083 1132 -0.950961 -12.3811 -5.98121 -0.00149067 0.0317489 -0.0647315 0.997396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1083 1133 -0.208068 -0.0109059 -6.29077 0.00383936 0.035828 -0.00941992 0.999306 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1083 1134 -0.960816 12.4062 -6.23877 0.0141592 0.0419142 0.0509801 0.997719 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1084 1133 -0.956807 -12.3888 -5.99506 -0.00740921 0.0307069 -0.0615671 0.997603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1084 1134 -0.210651 -0.0134939 -6.28153 0.00101827 0.0298992 0.00564684 0.999536 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1084 1135 -0.968503 12.4276 -6.25607 0.014991 0.0261727 0.0638851 0.997501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1085 1134 -0.927979 -12.3979 -5.96887 -0.0123416 0.0254143 -0.0595914 0.997823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1085 1135 -0.184352 -0.0118089 -6.28579 -0.00295334 0.0381492 -0.00148096 0.999267 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1085 1136 -0.961495 12.4465 -6.25068 0.00841482 0.0249723 0.0632338 0.997651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1086 1135 -0.9735 -12.3973 -6.00331 -0.0142577 0.0390478 -0.0620676 0.997206 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1086 1136 -0.199298 4.4774e-05 -6.2902 -0.00685145 0.0392251 0.00738619 0.99918 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1086 1137 -0.95119 12.3903 -6.24428 0.0161802 0.0297792 0.0653314 0.997288 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1087 1136 -0.958433 -12.4077 -5.99731 -0.015852 0.0283728 -0.0646823 0.997377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1087 1137 -0.178496 0.00317767 -6.27866 -0.000182273 0.0380272 -0.0022105 0.999274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1087 1138 -0.970317 12.3994 -6.23103 0.00213245 0.0359391 0.0605349 0.997517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1088 1137 -0.946428 -12.4115 -5.99813 -0.0195371 0.0233617 -0.06461 0.997446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1088 1138 -0.19331 -0.000608305 -6.27348 0.00311017 0.0309705 0.0089292 0.999476 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1088 1139 -0.946758 12.4116 -6.24926 0.00710818 0.0338955 0.0653717 0.99726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1089 1138 -0.95844 -12.4328 -5.98267 -0.00620145 0.0338765 -0.0612432 0.997529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1089 1139 -0.200155 -0.00449371 -6.27226 -0.00453335 0.0402909 -0.00276704 0.999174 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1089 1140 -0.98049 12.4113 -6.24792 0.00586189 0.0237719 0.0494847 0.998475 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1090 1139 -0.961556 -12.4044 -5.98037 -0.00257799 0.0339186 -0.062578 0.99746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1090 1140 -0.177516 0.0109915 -6.28443 -0.0037167 0.0285712 0.00400372 0.999577 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1090 1141 -0.966149 12.4248 -6.25651 0.0234992 0.0351627 0.0627546 0.997133 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1091 1140 -0.952773 -12.4336 -5.97977 -0.0083389 0.0240551 -0.066024 0.997493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1091 1141 -0.194783 -0.0199807 -6.27921 -0.00591424 0.0162624 -0.00293644 0.999846 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1091 1142 -0.964568 12.4189 -6.24347 0.00663856 0.0334689 0.062396 0.997468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1092 1141 -0.96133 -12.4035 -5.99806 -0.0126013 0.0296982 -0.0582482 0.997781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1092 1142 -0.181262 0.00935326 -6.27982 0.000374751 0.0325878 0.00726189 0.999442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1092 1143 -0.972279 12.4213 -6.24481 0.0153642 0.0332346 0.0627422 0.997358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1093 1142 -0.951833 -12.4157 -6.00712 -0.00878675 0.0323354 -0.0634638 0.997421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1093 1143 -0.186538 -0.00266026 -6.28257 -0.0038235 0.0243858 0.00141389 0.999694 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1093 1144 -0.975251 12.4412 -6.25084 0.0127695 0.0307516 0.0610125 0.997581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1094 1143 -0.95207 -12.4229 -5.99608 -0.00919536 0.031781 -0.0599802 0.997651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1094 1144 -0.203342 0.0119124 -6.29192 -0.0026281 0.0297043 0.000725064 0.999555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1094 1145 -0.982413 12.425 -6.24879 0.010621 0.0358956 0.0623784 0.99735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1095 1144 -0.952518 -12.4148 -6.00942 -0.00399335 0.0285591 -0.0688457 0.99721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1095 1145 -0.20538 -0.00742615 -6.29268 -0.00501236 0.0377411 -0.00457183 0.999265 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1095 1146 -0.954689 12.4165 -6.24385 0.00879932 0.034967 0.0551426 0.997827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1096 1145 -0.947295 -12.4189 -5.99675 -0.0133307 0.0402764 -0.0607684 0.99725 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1096 1146 -0.193672 -0.00709851 -6.27901 0.00158995 0.0284977 0.00234321 0.99959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1096 1147 -0.979212 12.4143 -6.25307 0.0249048 0.0421919 0.0614999 0.996904 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1097 1146 -0.965628 -12.4261 -6.01651 -0.00471618 0.0281598 -0.0653047 0.997457 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1097 1147 -0.209146 -0.00305555 -6.29053 -6.53834e-05 0.0302254 -0.00185556 0.999541 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1097 1148 -0.993499 12.4312 -6.26182 0.0148587 0.0318602 0.0631981 0.997382 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1098 1147 -0.970474 -12.4183 -6.00397 -0.0202063 0.0320223 -0.0686106 0.996925 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1098 1148 -0.205548 0.00865169 -6.28225 0.00283876 0.0316233 -0.00709817 0.999471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1098 1149 -0.964954 12.4649 -6.24586 0.0167213 0.0265514 0.0640061 0.997456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1099 1148 -0.965534 -12.4511 -5.99231 -0.0153158 0.0292923 -0.0529544 0.99805 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1099 1149 -0.217871 -0.000231651 -6.27754 0.00056838 0.0277679 -0.00246304 0.999611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1099 1150 -0.991912 12.4195 -6.26001 0.0059342 0.0284726 0.0615136 0.997682 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1100 1149 -0.964675 -12.4344 -6.01541 -0.00285795 0.0312797 -0.0743505 0.996737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1100 1150 -0.197608 0.0049919 -6.27402 0.0085442 0.0339626 -0.00192658 0.999385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1100 1151 -0.985795 12.4537 -6.27138 0.00386448 0.0296061 0.0552596 0.998026 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1101 1150 -0.95351 -12.4371 -6.01661 -0.00976935 0.0351269 -0.0690084 0.99695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1101 1151 -0.195889 -0.00119773 -6.27633 -0.0125971 0.0237587 -0.00479359 0.999627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1101 1152 -0.990368 12.4295 -6.25489 0.0120256 0.0252317 0.0598305 0.997817 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1102 1151 -0.954416 -12.4598 -5.99767 -0.00838577 0.0350427 -0.0569205 0.997728 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1102 1152 -0.193483 -0.00784091 -6.27102 -0.00449002 0.0340999 0.00756966 0.99938 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1102 1153 -0.970658 12.438 -6.27237 0.0139521 0.0296089 0.0741056 0.996713 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1103 1152 -0.9727 -12.4524 -6.00441 -0.0121611 0.0285018 -0.0605747 0.997683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1103 1153 -0.206111 -0.0117977 -6.2773 0.000620091 0.0167471 0.00535075 0.999845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1103 1154 -0.98135 12.432 -6.26603 0.00133547 0.0331982 0.0651855 0.99732 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1104 1153 -0.969079 -12.4355 -6.01314 -0.0101104 0.0249066 -0.0530058 0.998232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1104 1154 -0.2158 0.0116207 -6.27385 0.000418679 0.0323014 0.000721024 0.999478 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1104 1155 -0.972009 12.4539 -6.25679 0.0174738 0.0375065 0.0610003 0.99728 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1105 1154 -0.940117 -12.428 -6.01991 -0.00861506 0.0257735 -0.0670857 0.997377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1105 1155 -0.204396 -0.0120384 -6.25662 -0.00191744 0.029987 -0.00613876 0.99953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1105 1156 -0.977223 12.4322 -6.24333 0.00481557 0.0294821 0.0588645 0.997819 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1106 1155 -0.965779 -12.4529 -6.00424 -0.0149103 0.0289775 -0.0641689 0.997407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1106 1156 -0.211434 -0.00135821 -6.28267 -0.00163228 0.0389793 -0.00339194 0.999233 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1106 1157 -0.972346 12.4597 -6.26748 0.010786 0.0452397 0.0629434 0.996933 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1107 1156 -0.963615 -12.4364 -6.01839 -0.010815 0.0218463 -0.0621976 0.997766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1107 1157 -0.193537 0.00621737 -6.27218 0.00211234 0.0352666 -0.000723478 0.999375 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1107 1158 -0.985149 12.445 -6.26858 0.00727009 0.040552 0.0690957 0.996759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1108 1157 -0.954836 -12.4454 -5.99913 -0.00810233 0.0318152 -0.0671164 0.997205 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1108 1158 -0.206619 0.00797232 -6.26742 0.0091376 0.0306049 -0.00420793 0.999481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1108 1159 -0.961353 12.4425 -6.28531 0.0139332 0.0286669 0.0612745 0.997612 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1109 1158 -0.961703 -12.4477 -6.01951 -0.00994497 0.0337037 -0.0597262 0.997596 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1109 1159 -0.19308 -0.00664696 -6.26912 0.0013668 0.0272379 -0.00469969 0.999617 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1109 1160 -0.947135 12.4492 -6.25846 0.00695295 0.0301711 0.0480535 0.998365 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1110 1159 -0.955668 -12.4543 -6.0081 -0.0099589 0.0329309 -0.0545235 0.99792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1110 1160 -0.201444 0.0129105 -6.27329 -0.000922903 0.0312642 0.00129975 0.99951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1110 1161 -0.983364 12.4348 -6.26547 0.0149914 0.0311047 0.0620473 0.997476 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1111 1160 -0.960262 -12.4624 -6.02956 -0.0026569 0.0308142 -0.0613252 0.997639 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1111 1161 -0.184854 0.00137544 -6.26435 0.00081788 0.0356027 0.00293665 0.999361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1111 1162 -0.991448 12.4557 -6.26257 0.00836923 0.0226801 0.0650932 0.997586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1112 1161 -0.956318 -12.4585 -6.01895 -0.0164448 0.0344075 -0.0645022 0.997189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1112 1162 -0.192667 -0.00127866 -6.28232 -0.00599165 0.0285528 0.00595621 0.999557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1112 1163 -0.973368 12.4663 -6.28257 0.00638438 0.0310363 0.0555413 0.997953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1113 1162 -0.972048 -12.4571 -6.01195 0.000118645 0.0273325 -0.0644026 0.99755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1113 1163 -0.200102 0.0152748 -6.28302 0.0023912 0.0303801 0.000281828 0.999536 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1113 1164 -0.985301 12.4652 -6.26241 0.0182543 0.0300538 0.0668838 0.997141 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1114 1163 -0.953798 -12.4484 -6.02101 -0.0178463 0.0317162 -0.0555882 0.99779 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1114 1164 -0.192853 0.00337245 -6.2746 -0.00572745 0.031981 -0.00140659 0.999471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1114 1165 -0.96823 12.4424 -6.26411 0.00594997 0.0345642 0.062418 0.997434 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1115 1164 -0.955949 -12.4625 -6.03149 -0.00779977 0.0195412 -0.060077 0.997972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1115 1165 -0.196223 -1.15508e-05 -6.27179 0.00234633 0.0312379 -0.00333476 0.999504 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1115 1166 -0.965273 12.4637 -6.26525 0.00551552 0.023411 0.0636866 0.99768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1116 1165 -0.952025 -12.4716 -6.00212 -0.00564488 0.030015 -0.0676185 0.997244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1116 1166 -0.202238 0.00287891 -6.30548 0.000859044 0.0431803 0.00183206 0.999065 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1116 1167 -0.970466 12.4824 -6.28203 0.0163403 0.0337843 0.0683065 0.996958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1117 1166 -0.960494 -12.4632 -6.04406 -0.0112529 0.0264745 -0.0630833 0.997594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1117 1167 -0.196973 -0.0126032 -6.27644 0.00213452 0.0328187 0.00109829 0.999458 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1117 1168 -0.977664 12.4726 -6.29166 0.00431691 0.025468 0.0651167 0.997543 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1118 1167 -0.979361 -12.4584 -6.02657 -0.00672032 0.0326781 -0.0635847 0.997419 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1118 1168 -0.170739 -0.000504982 -6.27554 -1.03054e-05 0.0293484 0.00180964 0.999568 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1118 1169 -0.985013 12.4851 -6.26098 0.00110468 0.0195035 0.0651544 0.997684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1119 1168 -0.955805 -12.4468 -6.03218 -0.00647519 0.0292524 -0.059633 0.997771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1119 1169 -0.198027 -0.00709609 -6.30011 0.00043601 0.0324188 -0.00530257 0.99946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1119 1170 -0.980961 12.4735 -6.26719 0.0108925 0.041177 0.0622164 0.997153 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1120 1169 -0.969079 -12.4613 -6.04199 -0.00909851 0.0337039 -0.0531011 0.997979 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1120 1170 -0.209628 0.00409669 -6.29777 -0.00017955 0.0342608 -0.0103414 0.999359 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1120 1171 -0.98454 12.4745 -6.28799 0.0101219 0.0302217 0.0679995 0.997176 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1121 1170 -0.956115 -12.4694 -6.03671 -0.0104374 0.0397383 -0.0622128 0.997217 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1121 1171 -0.211666 0.0129898 -6.26581 0.00310323 0.0278835 0.00179179 0.999605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1121 1172 -0.970379 12.4688 -6.27022 -0.00240129 0.0298845 0.0576097 0.997889 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1122 1171 -0.97331 -12.4651 -6.03609 -0.00352747 0.0281888 -0.0652213 0.997466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1122 1172 -0.199174 -0.000505765 -6.27802 -0.00433039 0.0346026 -0.00630271 0.999372 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1122 1173 -0.997162 12.4764 -6.27275 0.00155671 0.0401323 0.0610496 0.997326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1123 1172 -0.963267 -12.4504 -6.02341 -0.000198195 0.0229524 -0.0624654 0.997783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1123 1173 -0.185169 0.0150799 -6.30457 0.00780296 0.0190812 0.00255426 0.999784 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1123 1174 -0.979646 12.4659 -6.29484 0.00600437 0.0404288 0.0694437 0.996748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1124 1173 -0.973599 -12.4781 -6.02946 0.000120889 0.0385442 -0.0621218 0.997324 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1124 1174 -0.198501 -0.0044095 -6.28388 8.74659e-05 0.0341193 0.00910071 0.999376 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1124 1175 -0.985268 12.4778 -6.28792 0.0051282 0.0283551 0.0618016 0.997672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1125 1174 -0.97402 -12.4842 -6.02992 -0.0118113 0.0203516 -0.0542455 0.99825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1125 1175 -0.180938 -0.013476 -6.26144 -0.00626608 0.0354379 0.00288645 0.999348 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1125 1176 -0.988238 12.4734 -6.297 0.0162338 0.0304636 0.0650076 0.997288 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1126 1175 -0.958894 -12.4686 -6.05255 -0.00405602 0.0289855 -0.065977 0.997392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1126 1176 -0.186939 -0.0142281 -6.27711 0.00559825 0.0308915 -0.0039203 0.999499 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1126 1177 -0.98141 12.4831 -6.27512 0.0120647 0.0273898 0.0613829 0.997665 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1127 1176 -0.981678 -12.4866 -6.03839 -0.0144214 0.0398566 -0.0629361 0.997117 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1127 1177 -0.194203 -0.0112916 -6.29344 -0.0114468 0.0304617 0.00185172 0.999469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1127 1178 -0.994621 12.4907 -6.28369 0.00865171 0.036395 0.0593849 0.997534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1128 1177 -0.948951 -12.4962 -6.03932 -0.00165767 0.0253639 -0.06101 0.997813 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1128 1178 -0.195987 0.00528804 -6.27895 -0.00473541 0.0293927 -0.00723377 0.999531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1128 1179 -0.971753 12.4797 -6.28304 0.0164347 0.0185375 0.0632994 0.997687 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1129 1178 -0.955305 -12.4857 -6.04519 -0.0120364 0.0269421 -0.0612919 0.997684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1129 1179 -0.178933 -0.000840982 -6.28409 -0.000109961 0.0329661 0.00479752 0.999445 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1129 1180 -0.987127 12.469 -6.28548 0.00250162 0.0354845 0.0617488 0.997458 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1130 1179 -0.961891 -12.4798 -6.04853 -0.00870932 0.0367406 -0.0732478 0.996599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1130 1180 -0.18757 -0.0166142 -6.29439 -0.0060395 0.0321316 0.000943698 0.999465 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1130 1181 -0.986663 12.4822 -6.30385 0.00912346 0.0259329 0.0661823 0.997429 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1131 1180 -0.973145 -12.5145 -6.04233 -0.00970415 0.0372419 -0.058126 0.997567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1131 1181 -0.200951 -0.0016958 -6.28728 -0.000105569 0.0294949 0.00566419 0.999549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1131 1182 -0.980129 12.4726 -6.28307 -0.00721041 0.0235184 0.0591455 0.997946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1132 1181 -0.977361 -12.4915 -6.03752 -0.0116916 0.029766 -0.0574124 0.997838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1132 1182 -0.201535 0.00766203 -6.26166 -0.00549536 0.0303338 0.00389399 0.999517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1132 1183 -0.97575 12.4905 -6.28317 0.00961706 0.0390035 0.0590649 0.997446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1133 1182 -0.976456 -12.4509 -6.02911 -0.00605594 0.0362219 -0.0577734 0.997654 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1133 1183 -0.212324 0.0200472 -6.26977 -0.0010941 0.0343566 -0.00262633 0.999406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1133 1184 -0.967033 12.4809 -6.29086 0.00409154 0.028392 0.0673676 0.997316 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1134 1183 -0.96352 -12.4965 -6.04137 -0.00300656 0.0294725 -0.0609456 0.997701 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1134 1184 -0.19738 0.00845394 -6.29193 0.00459226 0.0427396 -0.00250721 0.999073 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1134 1185 -0.975393 12.4878 -6.28567 0.0065487 0.0218515 0.0553071 0.998209 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1135 1184 -0.967683 -12.5034 -6.05397 -0.00655312 0.026514 -0.0635141 0.997607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1135 1185 -0.176201 -0.0012323 -6.28747 -0.00176631 0.0331666 -0.000743147 0.999448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1135 1186 -0.994113 12.4982 -6.29211 0.0115588 0.0266289 0.0755664 0.996718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1136 1185 -0.956525 -12.4956 -6.04305 -0.0132815 0.0268042 -0.0704735 0.997065 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1136 1186 -0.196516 0.014942 -6.28214 -0.00502829 0.0321832 0.010552 0.999414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1136 1187 -0.979689 12.4931 -6.29177 0.00725758 0.0380647 0.0613526 0.997364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1137 1186 -0.967689 -12.4799 -6.06232 -0.00526025 0.0307307 -0.0584563 0.997803 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1137 1187 -0.183641 0.00176993 -6.28841 -0.0025823 0.0306768 -0.00405738 0.999518 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1137 1188 -0.977404 12.5008 -6.29064 0.00920387 0.0250076 0.0646296 0.997553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1138 1187 -0.957704 -12.4955 -6.04981 -0.00243621 0.0324467 -0.0708785 0.996954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1138 1188 -0.202977 -0.00968767 -6.28283 0.00572044 0.0357672 -0.0139325 0.999247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1138 1189 -0.979487 12.4899 -6.28737 0.0188228 0.037109 0.0721603 0.996525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1139 1188 -0.978072 -12.4945 -6.03948 -0.00932957 0.0336618 -0.0624969 0.997434 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1139 1189 -0.219708 -0.0120453 -6.30491 9.50284e-06 0.0314791 -0.00489613 0.999492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1139 1190 -0.98917 12.5099 -6.29451 0.00110615 0.0275954 0.0686069 0.997261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1140 1189 -0.978195 -12.4914 -6.03888 -0.00816152 0.034716 -0.0610971 0.997495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1140 1190 -0.184885 -0.00357039 -6.28051 0.00811563 0.0379332 -0.00303783 0.999243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1140 1191 -0.988196 12.4993 -6.30308 0.000376831 0.032146 0.057791 0.997811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1141 1190 -0.962055 -12.5019 -6.06391 -0.0124634 0.0217243 -0.0635293 0.997666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1141 1191 -0.199082 -0.000685482 -6.28438 0.001177 0.0198126 0.0111568 0.999741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1141 1192 -0.974134 12.5196 -6.29281 0.00502913 0.0315734 0.0743485 0.99672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1142 1191 -0.964336 -12.5157 -6.04261 -0.000941021 0.0304032 -0.0667106 0.997309 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1142 1192 -0.200709 -0.00260439 -6.28477 0.00484339 0.0385532 0.00456652 0.999234 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1142 1193 -0.978401 12.5124 -6.29945 0.00754265 0.0345585 0.0591298 0.997623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1143 1192 -0.981198 -12.5122 -6.03961 -0.00289043 0.0269227 -0.0666006 0.997412 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1143 1193 -0.185196 0.00112418 -6.29229 0.00616171 0.0310286 -0.00061981 0.999499 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1143 1194 -0.980664 12.5146 -6.31412 0.0071325 0.0341671 0.0669335 0.997147 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1144 1193 -0.959607 -12.5083 -6.05099 -0.00664753 0.0307796 -0.0592952 0.997744 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1144 1194 -0.205674 -0.0135753 -6.29522 0.00411003 0.0203162 -0.000167122 0.999785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1144 1195 -0.97703 12.5099 -6.29459 0.00948352 0.0349938 0.0665038 0.997127 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1145 1194 -0.968301 -12.4884 -6.06337 -0.0217341 0.0386496 -0.0593953 0.997249 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1145 1195 -0.200762 -0.00654618 -6.27604 0.0087814 0.037458 8.018e-06 0.99926 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1145 1196 -0.989207 12.5041 -6.2887 0.0094031 0.0250656 0.0554573 0.998102 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1146 1195 -0.960477 -12.5173 -6.05708 -0.00852223 0.0328988 -0.0664123 0.997213 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1146 1196 -0.18232 -0.0060765 -6.29437 -0.00179586 0.0197154 -0.00734242 0.999777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1146 1197 -0.993082 12.5123 -6.31292 0.00465163 0.0302633 0.0663594 0.997326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1147 1196 -0.970886 -12.4985 -6.05568 -0.00148745 0.0333397 -0.0656131 0.997287 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1147 1197 -0.18012 -0.00321684 -6.30531 -0.00874489 0.033591 0.00250431 0.999394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1147 1198 -0.994279 12.4944 -6.2902 0.0097652 0.0306724 0.060978 0.99762 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1148 1197 -0.974804 -12.5144 -6.05155 0.00885493 0.0345954 -0.0579042 0.997683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1148 1198 -0.204112 -0.00482848 -6.26784 -0.00625087 0.0285119 -0.00200364 0.999572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1148 1199 -0.985363 12.5011 -6.3141 0.0108087 0.0277311 0.0565539 0.997956 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1149 1198 -0.96856 -12.4955 -6.0536 -0.00903986 0.0311759 -0.062146 0.997539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1149 1199 -0.200197 -0.000910983 -6.26201 0.00102025 0.0251636 0.00271841 0.999679 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1149 1200 -0.985169 12.5157 -6.30654 0.0113204 0.0333585 0.0667067 0.997151 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1150 1199 -0.984491 -12.5137 -6.05165 -0.00332327 0.0366961 -0.0534687 0.99789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1150 1200 -0.21451 0.0123871 -6.27545 -0.00456182 0.0310348 -0.00839374 0.999473 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1150 1201 -0.995008 12.5058 -6.31303 0.00194675 0.0331692 0.0594297 0.997679 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1151 1200 -0.987169 -12.5017 -6.05568 -0.0136877 0.0316639 -0.06197 0.997482 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1151 1201 -0.204944 0.000682138 -6.27869 -0.00194489 0.033633 0.00314909 0.999427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1151 1202 -0.982198 12.5192 -6.30928 0.0120472 0.0291213 0.0608557 0.997649 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1152 1201 -0.964474 -12.5089 -6.05215 0.0047762 0.0244702 -0.0667823 0.997456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1152 1202 -0.182863 -0.00705271 -6.26676 0.00516329 0.0366758 -0.000810799 0.999314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1152 1203 -0.994295 12.5265 -6.31665 0.00643937 0.0337408 0.0619825 0.997486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1153 1202 -0.984349 -12.5142 -6.04764 -0.0059518 0.0306989 -0.0633846 0.997499 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1153 1203 -0.208755 -0.00134818 -6.27677 0.003071 0.0396578 0.00104263 0.999208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1153 1204 -0.978645 12.5033 -6.29593 0.00479534 0.0340972 0.0546448 0.997912 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1154 1203 -0.966035 -12.5092 -6.05036 -0.00753529 0.0410059 -0.0641176 0.997071 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1154 1204 -0.212475 0.00279479 -6.29422 0.00238072 0.0301709 0.00430545 0.999533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1154 1205 -1.00242 12.5141 -6.32143 -0.00251913 0.032192 0.0720862 0.996876 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1155 1204 -0.983706 -12.5105 -6.05672 -0.00660526 0.0282493 -0.0628994 0.997598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1155 1205 -0.181334 -0.0060296 -6.26552 0.00140286 0.0224003 -0.00385331 0.999741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1155 1206 -0.992644 12.5057 -6.3086 0.00487522 0.0380391 0.0590165 0.99752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1156 1205 -0.951405 -12.4974 -6.06908 -0.00731797 0.0288643 -0.0641572 0.997495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1156 1206 -0.202694 0.00224533 -6.27368 -0.00433092 0.0411419 0.00820198 0.99911 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1156 1207 -0.99184 12.516 -6.30183 0.00514071 0.0262816 0.0663317 0.997438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1157 1206 -0.960935 -12.5217 -6.05046 -0.000603451 0.0319929 -0.0626777 0.997521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1157 1207 -0.198674 0.00407763 -6.27105 0.00268363 0.0316465 -0.0042068 0.999487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1157 1208 -0.996295 12.5177 -6.30551 0.00945901 0.0357285 0.0596802 0.997533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1158 1207 -0.968408 -12.5312 -6.08557 -0.00669509 0.0360973 -0.0650187 0.997208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1158 1208 -0.218939 0.0136165 -6.29236 0.00534631 0.0339955 -0.00937131 0.999364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1158 1209 -0.993698 12.5218 -6.31387 0.00294279 0.0392714 0.0629988 0.997236 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1159 1208 -0.981265 -12.5139 -6.07896 0.00242756 0.0223781 -0.0636436 0.997719 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1159 1209 -0.20062 -0.0133246 -6.26905 -0.00532624 0.0325481 -0.000252807 0.999456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1159 1210 -1.00811 12.5075 -6.29128 0.00668918 0.0266219 0.0604512 0.997794 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1160 1209 -0.972308 -12.5074 -6.08592 -0.00184377 0.0287057 -0.0658417 0.997415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1160 1210 -0.186278 -0.0185149 -6.29484 -0.00802164 0.0383141 0.00906729 0.999192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1160 1211 -0.985601 12.5097 -6.31563 0.00400142 0.034763 0.0712376 0.996845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1161 1210 -0.980635 -12.5204 -6.06124 -0.00717774 0.0314709 -0.0523062 0.998109 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1161 1211 -0.209008 -0.00548709 -6.27625 -0.000851158 0.033395 0.000505263 0.999442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1161 1212 -0.98509 12.5188 -6.3215 0.00229384 0.0292593 0.0639436 0.997522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1162 1211 -0.96513 -12.5169 -6.07103 -0.00758778 0.0279672 -0.0640232 0.997528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1162 1212 -0.199721 -0.00282738 -6.27571 0.00749491 0.0267574 0.0026763 0.99961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1162 1213 -0.988976 12.5098 -6.30757 0.00433898 0.0386343 0.0646471 0.997151 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1163 1212 -0.988959 -12.5318 -6.07651 -0.00715462 0.0353454 -0.0661649 0.997157 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1163 1213 -0.206879 0.00248905 -6.29426 0.0129215 0.0364829 0.00157807 0.999249 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1163 1214 -0.97417 12.5173 -6.32469 0.0148739 0.0315767 0.0619981 0.997466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1164 1213 -0.984819 -12.5149 -6.07907 -0.00745683 0.0293045 -0.0563471 0.997953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1164 1214 -0.190661 -0.0126789 -6.27425 -0.000915456 0.0321575 0.00636633 0.999462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1164 1215 -0.998528 12.5347 -6.31001 -0.00941986 0.0331388 0.0618849 0.997489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1165 1214 -0.984852 -12.5088 -6.07637 -0.0058297 0.0304288 -0.0644215 0.997442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1165 1215 -0.198413 0.00933924 -6.28329 0.00952005 0.0358304 -0.00793886 0.999281 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1165 1216 -0.976119 12.5272 -6.32104 0.00161773 0.026939 0.0634752 0.997618 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1166 1215 -0.967644 -12.5199 -6.08963 0.00491365 0.035497 -0.0637437 0.997323 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1166 1216 -0.200503 -0.00156162 -6.27945 0.00359869 0.0324154 -0.000231015 0.999468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1166 1217 -0.983811 12.5166 -6.32824 0.00242736 0.027029 0.0650116 0.997515 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1167 1216 -0.975699 -12.5246 -6.08258 -0.00491472 0.0310031 -0.059186 0.997753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1167 1217 -0.193382 0.0131678 -6.27731 -0.000871547 0.0360484 -0.00473664 0.999338 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1167 1218 -0.981317 12.5206 -6.32353 0.0108945 0.0250289 0.0571314 0.997993 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1168 1217 -0.962392 -12.5338 -6.0691 0.00786952 0.0319269 -0.0553209 0.997927 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1168 1218 -0.198106 -0.0123142 -6.27827 8.2898e-05 0.0271565 0.00830683 0.999597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1168 1219 -0.993305 12.5303 -6.31811 0.0100913 0.0330673 0.0710632 0.996872 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1169 1218 -0.983261 -12.5192 -6.07946 -0.00175606 0.0291278 -0.0753706 0.996729 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1169 1219 -0.199696 -0.0110438 -6.28767 -0.00116119 0.0242046 0.0126631 0.999626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1169 1220 -0.996231 12.525 -6.31625 0.00609739 0.0299141 0.0671248 0.997277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1170 1219 -0.9888 -12.5013 -6.09195 -0.00425741 0.0424642 -0.0558206 0.997528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1170 1220 -0.193483 -0.00255298 -6.28166 0.00290416 0.0334075 0.00692469 0.999414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1170 1221 -0.972024 12.5163 -6.32597 -0.00596249 0.0326974 0.0631375 0.997451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1171 1220 -0.986388 -12.522 -6.08506 0.00146591 0.0321768 -0.0662647 0.997282 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1171 1221 -0.197026 0.00121202 -6.28183 0.00797117 0.0297445 -0.00300674 0.999521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1171 1222 -1.00304 12.5261 -6.32015 0.00981622 0.0286166 0.0613355 0.997659 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1172 1221 -0.973905 -12.5185 -6.08087 -0.0116073 0.03555 -0.0625663 0.99734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1172 1222 -0.193114 -0.00708889 -6.28085 0.0078351 0.0258337 -0.00357669 0.999629 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1172 1223 -0.993132 12.5325 -6.32805 0.000393282 0.0310069 0.0597502 0.997732 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1173 1222 -0.981443 -12.5341 -6.09269 -0.00695832 0.0368117 -0.0639822 0.997248 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1173 1223 -0.18576 -0.00458109 -6.26449 0.000604442 0.0318139 -0.00731724 0.999467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1173 1224 -1.00172 12.5247 -6.34556 0.00486134 0.036617 0.0581413 0.997625 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1174 1223 -0.961017 -12.527 -6.09528 0.00475064 0.031316 -0.0669663 0.997252 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1174 1224 -0.188864 0.0076623 -6.28767 0.00166664 0.0325011 -0.00613616 0.999451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1174 1225 -0.989909 12.5381 -6.33143 0.00525406 0.0242819 0.0610423 0.997826 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1175 1224 -0.989213 -12.5296 -6.08222 -0.00906195 0.0318412 -0.0631977 0.997452 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1175 1225 -0.184266 0.00362301 -6.29171 0.00695182 0.0285764 0.00660089 0.999546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1175 1226 -0.984727 12.5384 -6.32897 0.00116759 0.0330156 0.0679248 0.997143 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1176 1225 -0.961353 -12.5244 -6.08835 -0.0052612 0.0321249 -0.0714677 0.996912 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1176 1226 -0.195049 0.0146562 -6.27464 -0.00121951 0.033379 0.000219428 0.999442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1176 1227 -0.992651 12.5352 -6.33751 0.0133433 0.0338471 0.0543085 0.997861 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1177 1226 -0.967915 -12.5246 -6.09388 -0.00240618 0.0335799 -0.0589183 0.997695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1177 1227 -0.210744 0.0161781 -6.27912 -0.00671104 0.0289197 0.000164387 0.999559 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1177 1228 -0.975985 12.5259 -6.3274 0.0057038 0.0287763 0.0707441 0.997063 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1178 1227 -0.970456 -12.5249 -6.08594 0.00401843 0.0294015 -0.0585395 0.997844 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1178 1228 -0.197158 0.00722988 -6.26792 0.00037986 0.0262189 0.00396281 0.999648 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1178 1229 -1.01832 12.5363 -6.33342 0.0014865 0.0305938 0.0667379 0.9973 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1179 1228 -0.967646 -12.5164 -6.075 -0.000717919 0.0336638 -0.0617095 0.997526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1179 1229 -0.197736 -0.00464026 -6.27341 -0.00967751 0.0289992 -0.00779186 0.999502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1179 1230 -0.986084 12.5287 -6.33975 0.010432 0.027098 0.0606381 0.997737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1180 1229 -0.985059 -12.5272 -6.08989 -0.00428907 0.0382935 -0.0609755 0.997395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1180 1230 -0.203815 0.0105774 -6.26698 -0.0022473 0.030713 0.00824009 0.999492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1180 1231 -1.00568 12.5325 -6.32379 0.00850771 0.0279757 0.0616429 0.99767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1181 1230 -0.977473 -12.5063 -6.0953 -0.00391453 0.0344722 -0.0602649 0.997579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1181 1231 -0.202398 0.00497655 -6.27891 0.00256178 0.0411703 -0.005404 0.999134 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1181 1232 -0.993448 12.5322 -6.32177 0.00246756 0.0346749 0.067446 0.997117 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1182 1231 -0.974359 -12.53 -6.06705 -0.00487904 0.0237909 -0.0638418 0.997664 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1182 1232 -0.198255 -0.00058247 -6.28184 0.00280615 0.0284739 6.79528e-05 0.999591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1182 1233 -0.985978 12.5324 -6.34665 0.00348002 0.032638 0.0677634 0.997161 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1183 1232 -0.976625 -12.5291 -6.08185 0.0049138 0.0287344 -0.0602432 0.997758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1183 1233 -0.194887 -0.00788222 -6.27737 -0.00581038 0.0381175 -6.35367e-05 0.999256 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1183 1234 -0.991175 12.5407 -6.34409 -0.00596955 0.0317879 0.0605818 0.997639 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1184 1233 -0.949789 -12.5343 -6.08753 -0.00316375 0.0295536 -0.0655629 0.997406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1184 1234 -0.183135 0.00670776 -6.28409 0.00260201 0.0372446 0.00667566 0.99928 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1184 1235 -1.01227 12.5229 -6.31958 0.00431366 0.0334107 0.066883 0.997192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1185 1234 -0.989211 -12.5226 -6.08512 -0.00431382 0.0306725 -0.0682284 0.997189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1185 1235 -0.192196 -0.00693324 -6.2724 -0.00442064 0.0284322 -0.0125791 0.999507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1185 1236 -0.988577 12.5197 -6.33858 0.00246192 0.0309833 0.0624747 0.997562 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1186 1235 -0.98779 -12.5021 -6.0894 0.00309479 0.0281358 -0.0547186 0.998101 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1186 1236 -0.196536 -0.0102024 -6.28127 -0.000112864 0.0264526 -0.00638691 0.99963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1186 1237 -0.993518 12.536 -6.3428 0.00715083 0.0442337 0.0671401 0.996737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1187 1236 -0.9808 -12.5198 -6.09346 -0.00494412 0.0236566 -0.0593301 0.997946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1187 1237 -0.18946 -0.0034517 -6.28224 -0.00247609 0.0302395 -0.00317666 0.999535 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1187 1238 -0.98573 12.5199 -6.32692 0.00205936 0.0332347 0.0594891 0.997673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1188 1237 -0.967224 -12.5318 -6.09713 0.000479115 0.0287545 -0.0625946 0.997625 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1188 1238 -0.195313 0.00999856 -6.28653 0.00207719 0.0371332 0.00114105 0.999308 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1188 1239 -0.971857 12.5261 -6.34628 0.00850247 0.0306902 0.0553383 0.99796 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1189 1238 -0.983924 -12.5379 -6.08813 -0.00306748 0.029531 -0.0652764 0.997425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1189 1239 -0.176488 -0.0122237 -6.26898 -0.00813626 0.0307679 -0.000473127 0.999493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1189 1240 -0.993829 12.5381 -6.33501 0.00447625 0.0292711 0.0767857 0.996608 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1190 1239 -0.992918 -12.5384 -6.0917 0.00247367 0.0283815 -0.0592228 0.997838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1190 1240 -0.205839 0.00958334 -6.28766 0.000672952 0.0304334 0.00643502 0.999516 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1190 1241 -0.984914 12.5122 -6.36121 -0.00204555 0.0180814 0.0581744 0.998141 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1191 1240 -0.976191 -12.5325 -6.09184 0.00341145 0.0364697 -0.0607507 0.997481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1191 1241 -0.209592 -0.0166732 -6.26141 -0.0109893 0.0349955 0.00552261 0.999312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1191 1242 -0.972478 12.5492 -6.33189 0.00996231 0.0338401 0.0688342 0.997004 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1192 1241 -0.978663 -12.5503 -6.08839 0.0012454 0.0271191 -0.062731 0.997661 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1192 1242 -0.193895 0.00157719 -6.27407 0.0105802 0.0336951 -0.00251769 0.999373 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1192 1243 -0.978005 12.52 -6.34399 -0.00181404 0.0319122 0.062448 0.997536 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1193 1242 -0.986184 -12.5389 -6.08743 -0.00216757 0.0338425 -0.0717203 0.996848 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1193 1243 -0.206433 0.00207059 -6.28208 -0.0107771 0.0291217 0.00163479 0.999516 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1193 1244 -0.971762 12.5418 -6.35362 0.00579089 0.0305009 0.0526359 0.998131 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1194 1243 -0.977419 -12.5246 -6.09536 -0.000887559 0.0344939 -0.0656764 0.997244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1194 1244 -0.199258 0.00650516 -6.26801 -0.00408867 0.0301285 0.000251653 0.999538 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1194 1245 -0.999952 12.5382 -6.35952 -0.00136783 0.0365423 0.0580759 0.997642 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1195 1244 -0.950758 -12.5353 -6.11558 -0.00760932 0.0329283 -0.0586417 0.997707 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1195 1245 -0.200824 0.00378393 -6.29606 -0.00902329 0.0387234 0.00221177 0.999207 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1195 1246 -1.0083 12.5253 -6.33768 0.00187918 0.0355488 0.0681069 0.997043 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1196 1245 -0.981105 -12.5409 -6.10249 0.0018185 0.0354543 -0.0589357 0.99763 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1196 1246 -0.196078 0.0249564 -6.26954 -0.00368888 0.0315045 0.000751049 0.999497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1196 1247 -0.988549 12.5301 -6.36793 0.00382145 0.0282873 0.0657518 0.997428 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1197 1246 -0.97613 -12.522 -6.10133 -0.000658751 0.0347378 -0.0548532 0.99789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1197 1247 -0.200758 -0.00378988 -6.29479 0.00859384 0.0297997 0.00403394 0.999511 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1197 1248 -0.980603 12.5276 -6.35065 -0.00176389 0.0229932 0.0670322 0.997484 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1198 1247 -0.974378 -12.5375 -6.10075 -0.00633261 0.0296607 -0.0617352 0.997632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1198 1248 -0.206058 -0.0103855 -6.26701 0.0037407 0.0375533 0.00346929 0.999282 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1198 1249 -0.995179 12.5504 -6.35192 0.00134711 0.0361535 0.0667507 0.997114 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1199 1248 -0.978541 -12.5476 -6.10551 -0.00946831 0.0307494 -0.057212 0.997843 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1199 1249 -0.196244 0.001388 -6.28622 0.00342223 0.0367232 0.00624321 0.9993 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1199 1250 -1.00881 12.5387 -6.3507 -0.000525903 0.0172646 0.0614795 0.997959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1200 1249 -0.969646 -12.5384 -6.10223 0.000748955 0.0274217 -0.0607018 0.997779 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1200 1250 -0.187463 -0.00289363 -6.28974 -0.00171086 0.0289721 -0.00153638 0.999578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1200 1251 -0.985863 12.5423 -6.37368 0.000963525 0.0253371 0.0691946 0.997281 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1201 1250 -0.979715 -12.533 -6.11155 -0.00444806 0.0318915 -0.0521916 0.998118 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1201 1251 -0.184447 -0.0163159 -6.27575 0.00516309 0.0290848 -0.00470591 0.999553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1201 1252 -1.00293 12.5494 -6.33888 0.00536022 0.0286816 0.0674982 0.997293 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1202 1251 -0.976353 -12.5417 -6.1024 -0.0090308 0.0318719 -0.0673748 0.997178 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1202 1252 -0.191099 0.00895891 -6.28859 -0.0020504 0.0304107 -0.00426993 0.999526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1202 1253 -0.983154 12.5353 -6.36401 0.00413922 0.0347098 0.0598264 0.997597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1203 1252 -0.97904 -12.5186 -6.10622 -0.00351059 0.0348482 -0.0566945 0.997777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1203 1253 -0.198231 -0.015095 -6.26817 0.0080821 0.0347232 -0.0029935 0.99936 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1203 1254 -0.979196 12.5276 -6.36133 0.00280325 0.0263143 0.0658701 0.997477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1204 1253 -0.967887 -12.5448 -6.1097 0.00239885 0.0336787 -0.0678996 0.997121 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1204 1254 -0.191958 0.0139612 -6.29049 -0.00327693 0.0276138 0.00655456 0.999592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1204 1255 -0.999852 12.5394 -6.35161 0.00498965 0.0282476 0.0615773 0.99769 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1205 1254 -0.975566 -12.546 -6.13122 -0.00827151 0.0354969 -0.0646167 0.997244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1205 1255 -0.209462 0.0164407 -6.28458 -0.00544234 0.0351094 0.00646998 0.999348 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1205 1256 -1.00383 12.5324 -6.3585 0.00240286 0.0284833 0.0602245 0.997775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1206 1255 -0.970773 -12.539 -6.11665 0.0012527 0.0269588 -0.0675441 0.997351 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1206 1256 -0.191105 0.00296998 -6.27374 -0.00205709 0.0354055 -0.00543307 0.999356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1206 1257 -0.973179 12.5221 -6.36184 0.00237136 0.0330126 0.0536186 0.998013 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1207 1256 -0.963191 -12.5228 -6.09326 -0.00348876 0.0321225 -0.0636344 0.99745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1207 1257 -0.198333 0.005055 -6.28441 0.0128734 0.0277163 -0.00143347 0.999532 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1207 1258 -0.996606 12.5537 -6.36833 0.00287836 0.0287129 0.060274 0.997765 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1208 1257 -0.971965 -12.5411 -6.11999 -0.00316915 0.0297224 -0.067521 0.99727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1208 1258 -0.212973 -0.00226729 -6.28688 0.00203082 0.0256137 0.00534196 0.999656 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1208 1259 -0.990457 12.5298 -6.35729 -0.0038031 0.0289961 0.0618816 0.997655 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1209 1258 -0.961822 -12.5387 -6.12032 0.0100652 0.0328408 -0.0571871 0.997772 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1209 1259 -0.182258 -0.0138746 -6.28077 0.00058746 0.0308964 -0.00108404 0.999522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1209 1260 -1.00421 12.5457 -6.36318 0.00671306 0.0305595 0.0617479 0.997601 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1210 1259 -0.978752 -12.5344 -6.10879 -0.00239803 0.0341156 -0.0582979 0.997713 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1210 1260 -0.199029 0.0121353 -6.28502 0.00359265 0.028971 0.000554525 0.999574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1210 1261 -0.997763 12.5172 -6.36382 0.0103641 0.028181 0.0596625 0.997767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1211 1260 -0.977991 -12.5311 -6.13782 -0.00679816 0.0259684 -0.0650703 0.99752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1211 1261 -0.204835 -0.000956627 -6.27594 -0.00612056 0.0262071 -0.00122564 0.999637 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1211 1262 -0.992225 12.5389 -6.3653 0.0049395 0.0310627 0.0712914 0.996959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1212 1261 -0.974113 -12.5418 -6.10889 -0.00340439 0.0311527 -0.0553982 0.997972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1212 1262 -0.197931 -0.00281171 -6.28584 -0.00405699 0.0332057 -0.00024567 0.99944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1212 1263 -0.999142 12.5429 -6.3835 -0.00208543 0.0287963 0.0632336 0.997581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1213 1262 -0.975018 -12.5341 -6.11499 -0.00123681 0.0311409 -0.0686333 0.997155 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1213 1263 -0.195667 0.000806156 -6.25009 0.000498418 0.0226987 0.00134881 0.999741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1213 1264 -0.9982 12.5268 -6.37385 0.00389576 0.0398246 0.0602016 0.997384 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1214 1263 -0.969822 -12.5402 -6.10966 0.000875259 0.0318335 -0.0605099 0.997659 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1214 1264 -0.187764 0.00531858 -6.27508 -0.00484595 0.0306273 0.0047148 0.999508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1214 1265 -0.995525 12.5305 -6.34865 0.00920104 0.0393742 0.0636625 0.997152 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1215 1264 -0.973219 -12.5401 -6.11275 -0.0075151 0.030286 -0.0576018 0.997852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1215 1265 -0.209263 0.00393453 -6.28908 -0.00548442 0.0296328 0.00302188 0.999541 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1215 1266 -1.00117 12.534 -6.39344 0.00727723 0.0408872 0.0625548 0.997177 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1216 1265 -0.974208 -12.5274 -6.12486 0.00385097 0.0308425 -0.0603579 0.997693 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1216 1266 -0.188251 0.0138575 -6.26794 0.00173107 0.0389388 0.00174146 0.999239 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1216 1267 -0.98939 12.513 -6.36537 0.00610895 0.0337181 0.0643522 0.997339 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1217 1266 -0.963645 -12.5208 -6.10767 -0.00342235 0.0281127 -0.0666066 0.997377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1217 1267 -0.191471 0.00113731 -6.2717 -0.00452149 0.0374712 -0.0125791 0.999208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1217 1268 -0.999099 12.5244 -6.3649 -0.00392423 0.0313597 0.0596459 0.997719 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1218 1267 -0.968084 -12.5299 -6.12846 0.00509543 0.0316083 -0.0665636 0.997268 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1218 1268 -0.196839 -0.00323378 -6.2822 0.00168162 0.0286918 0.00444772 0.999577 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1218 1269 -1.00034 12.5238 -6.37674 -0.00406693 0.0328425 0.0563378 0.997863 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1219 1268 -0.990911 -12.5258 -6.11463 -0.00724781 0.0273809 -0.0573142 0.997954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1219 1269 -0.197681 0.0155159 -6.27102 -0.00504742 0.0304632 0.000214094 0.999523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1219 1270 -1.00028 12.5339 -6.38805 7.70424e-05 0.0318563 0.0605801 0.997655 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1220 1269 -0.96848 -12.538 -6.11833 -0.00324661 0.025616 -0.0681188 0.997343 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1220 1270 -0.187591 -0.00514638 -6.28309 -0.00243265 0.0219584 0.00104101 0.999755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1220 1271 -0.991735 12.5305 -6.36817 0.00599138 0.0323349 0.0531023 0.998047 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1221 1270 -0.968375 -12.5201 -6.1437 -0.00279711 0.0278898 -0.0696937 0.997175 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1221 1271 -0.213277 -0.0049204 -6.26105 -0.00657843 0.0225194 0.000995943 0.999724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1221 1272 -0.996201 12.5379 -6.37155 -0.0066707 0.0326534 0.0578915 0.997766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1222 1271 -0.974719 -12.5166 -6.11796 -0.0008025 0.0272552 -0.0702074 0.99716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1222 1272 -0.204126 -0.00896923 -6.28091 0.00246854 0.0308476 0.000684894 0.999521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1222 1273 -0.982701 12.5298 -6.37476 0.00335329 0.0325657 0.0584713 0.997752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1223 1272 -0.983486 -12.5356 -6.13334 0.00232908 0.0332775 -0.0589661 0.997702 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1223 1273 -0.205082 -0.00375845 -6.2716 -0.00399873 0.0302823 -0.00536131 0.999519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1223 1274 -0.970936 12.5165 -6.36987 0.00639397 0.0310999 0.0652182 0.997366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1224 1273 -0.971001 -12.5201 -6.11697 0.00514974 0.0255992 -0.0682063 0.997329 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1224 1274 -0.197536 0.00281473 -6.276 -0.00902471 0.0267188 -0.00731931 0.999575 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1224 1275 -0.982386 12.5172 -6.37951 -0.001908 0.0370604 0.0614703 0.997419 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1225 1274 -0.978845 -12.5332 -6.1311 -0.011377 0.0338548 -0.0623422 0.997416 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1225 1275 -0.205732 -0.00949596 -6.27661 -0.00135227 0.033526 0.00046112 0.999437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1225 1276 -0.993126 12.5212 -6.37385 -0.000626615 0.0292578 0.0727447 0.996921 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1226 1275 -0.970773 -12.5358 -6.12718 -0.000851739 0.0324236 -0.0532031 0.998057 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1226 1276 -0.192957 0.0143809 -6.27602 0.0107814 0.0342296 0.00274613 0.999352 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1226 1277 -1.00162 12.525 -6.3829 0.00316903 0.0311999 0.0677337 0.99721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1227 1276 -0.976335 -12.5306 -6.11929 0.00624686 0.0342748 -0.0545994 0.9979 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1227 1277 -0.185353 0.00304724 -6.26809 -0.000818674 0.0277829 -0.000234427 0.999614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1227 1278 -1.00707 12.5144 -6.38966 -0.00085987 0.0366965 0.0656268 0.997169 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1228 1277 -0.967276 -12.5283 -6.1322 -0.000128342 0.0373668 -0.0699812 0.996848 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1228 1278 -0.208845 0.00870261 -6.28161 -9.566e-05 0.0332644 -0.0101086 0.999395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1228 1279 -0.987502 12.5363 -6.38796 -0.0152051 0.0298053 0.0690985 0.997049 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1229 1278 -0.976186 -12.5286 -6.13684 -0.00152142 0.0267294 -0.0676261 0.997351 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1229 1279 -0.19193 -0.00301001 -6.28395 0.00348943 0.0301112 -0.000594623 0.99954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1229 1280 -0.97637 12.5196 -6.38911 -0.00689859 0.036332 0.0638144 0.997276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1230 1279 -0.979438 -12.5302 -6.11942 -0.00742695 0.0265869 -0.0689012 0.997241 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1230 1280 -0.197232 0.00449264 -6.28661 -0.00399293 0.0356334 -0.0019368 0.999355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1230 1281 -0.991317 12.5361 -6.38375 0.00799526 0.0396897 0.0659251 0.997003 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1231 1280 -0.983716 -12.5117 -6.13068 -0.0106564 0.0354232 -0.0522247 0.99795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1231 1281 -0.192736 -0.00550553 -6.26991 -0.00374278 0.0330662 0.00314647 0.999441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1231 1282 -0.999509 12.5302 -6.37528 -0.00823147 0.0430867 0.0609385 0.997177 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1232 1281 -0.976209 -12.5313 -6.12494 -0.000520536 0.02318 -0.0633191 0.997724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1232 1282 -0.185479 -0.00729924 -6.27184 0.00109134 0.0314281 -0.00406912 0.999497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1232 1283 -0.999162 12.515 -6.3688 -0.00225998 0.0326816 0.0672044 0.997201 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1233 1282 -0.984957 -12.5227 -6.13346 -0.00259967 0.028092 -0.0655186 0.997452 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1233 1283 -0.181783 -0.0212954 -6.27466 0.0044142 0.0294345 0.00212643 0.999555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1233 1284 -0.996351 12.5348 -6.4021 -0.00221279 0.0317842 0.0614503 0.997601 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1234 1283 -0.963218 -12.5251 -6.14939 0.00979171 0.0327134 -0.0575761 0.997757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1234 1284 -0.209021 0.00331944 -6.2638 0.00349543 0.0283573 -0.00166823 0.99959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1234 1285 -1.00323 12.52 -6.39 -0.000299292 0.0422009 0.06732 0.996839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1235 1284 -0.971495 -12.514 -6.12726 0.0019535 0.0275704 -0.0637877 0.997581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1235 1285 -0.187755 -0.0056304 -6.28263 -0.000439946 0.0349583 0.000561554 0.999389 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1235 1286 -0.97319 12.5226 -6.40288 0.00584738 0.0312388 0.0617601 0.997585 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1236 1285 -0.972547 -12.5195 -6.1314 -0.00674501 0.040575 -0.056228 0.99757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1236 1286 -0.202107 0.00397657 -6.2642 -0.00243487 0.0382508 -0.00411349 0.999257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1236 1287 -0.992109 12.5212 -6.39345 -0.00391453 0.0290997 0.057965 0.997887 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1237 1286 -0.976332 -12.5407 -6.13831 0.00108989 0.0202818 -0.0596361 0.998014 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1237 1287 -0.208916 -0.0111505 -6.26495 -0.00237738 0.0408813 0.00220197 0.999159 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1237 1288 -0.987534 12.5284 -6.39672 -0.00486162 0.0289621 0.0692359 0.997168 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1238 1287 -0.965252 -12.5229 -6.14407 0.00317315 0.0314985 -0.0547177 0.998 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1238 1288 -0.197888 -0.00281258 -6.2727 0.00586291 0.0311363 -0.00868832 0.99946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1238 1289 -0.990469 12.5065 -6.38747 -0.00415227 0.0351629 0.0647878 0.997271 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1239 1288 -0.961982 -12.5094 -6.1542 0.00162164 0.0300176 -0.0666146 0.997326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1239 1289 -0.183388 0.00585352 -6.26779 0.00165062 0.036278 -0.00187924 0.999339 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1239 1290 -0.989426 12.5158 -6.3738 -0.00267479 0.0302225 0.0685028 0.997189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1240 1289 -0.993028 -12.5083 -6.15366 -0.000698234 0.0337464 -0.0701835 0.996963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1240 1290 -0.197712 -0.00152998 -6.2789 0.000454197 0.0345832 -0.000380958 0.999402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1240 1291 -1.00325 12.5187 -6.3999 0.0060493 0.026252 0.0630509 0.997647 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1241 1290 -0.983763 -12.5111 -6.15084 0.0135543 0.0308435 -0.0598186 0.997641 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1241 1291 -0.19553 0.00551129 -6.29845 0.00269599 0.0313607 0.0054837 0.999489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1241 1292 -0.999908 12.5248 -6.40127 -0.00304463 0.0330279 0.0614103 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1242 1291 -0.962814 -12.5209 -6.15554 0.00129714 0.0291291 -0.0475588 0.998443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1242 1292 -0.197086 0.00761789 -6.27644 -0.00333978 0.032085 -0.00488696 0.999468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1242 1293 -1.00588 12.519 -6.40807 -0.00149477 0.027782 0.0573037 0.997969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1243 1292 -0.984009 -12.5204 -6.13602 0.00963406 0.0329706 -0.0565535 0.997809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1243 1293 -0.184827 0.00104182 -6.27767 -0.0016934 0.0359657 -0.00426003 0.999343 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1243 1294 -1.00367 12.5241 -6.40353 -0.0117278 0.0308213 0.0632223 0.997454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1244 1293 -0.978762 -12.5239 -6.153 0.00472315 0.029294 -0.0701246 0.997097 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1244 1294 -0.195633 0.00456262 -6.27182 0.00501456 0.0320763 -0.00251506 0.99947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1244 1295 -0.969676 12.523 -6.40699 -0.00103967 0.0384333 0.0667171 0.997031 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1245 1294 -0.972149 -12.4976 -6.15793 0.00175666 0.0375156 -0.0626048 0.997332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1245 1295 -0.197659 0.00264836 -6.29193 -0.00185304 0.032506 -0.00893701 0.99943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1245 1296 -0.997927 12.5217 -6.3898 0.000522202 0.0260109 0.0710374 0.997134 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1246 1295 -0.990036 -12.4965 -6.16253 -0.00139604 0.0301314 -0.0648975 0.997436 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1246 1296 -0.204782 0.00243844 -6.29345 0.00518034 0.0257989 -0.000727703 0.999653 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1246 1297 -0.986202 12.5202 -6.38434 -0.0125204 0.0397547 0.0585454 0.997414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1247 1296 -0.960214 -12.4977 -6.15392 -0.00565209 0.0282463 -0.0621942 0.997648 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1247 1297 -0.221758 -0.00867021 -6.2877 0.00755755 0.0309164 0.00156648 0.999492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1247 1298 -0.978797 12.518 -6.40503 -0.00334563 0.0278492 0.0653063 0.997471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1248 1297 -0.975587 -12.51 -6.1585 -0.00458521 0.0280135 -0.064845 0.997492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1248 1298 -0.200989 -0.0124718 -6.27829 -0.00578333 0.0320554 -0.00549718 0.999454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1248 1299 -0.986216 12.52 -6.39579 -0.00384338 0.0298289 0.0590121 0.997804 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1249 1298 -0.965586 -12.5157 -6.15426 0.00074251 0.0223704 -0.0579976 0.998066 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1249 1299 -0.191573 0.0123728 -6.28527 -0.0107499 0.02815 0.00565763 0.99953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1249 1300 -0.975834 12.497 -6.40994 -0.00137399 0.029619 0.05723 0.997921 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1250 1299 -0.975304 -12.512 -6.13629 0.00599518 0.0311892 -0.0580132 0.99781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1250 1300 -0.196974 -0.00266037 -6.27854 0.000904353 0.0421799 0.00403044 0.999101 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1250 1301 -0.986733 12.5228 -6.39509 -0.00135292 0.0333684 0.0646912 0.997346 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1251 1300 -0.974401 -12.513 -6.1614 0.0025367 0.0289628 -0.0596313 0.997797 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1251 1301 -0.193284 0.00890719 -6.29466 0.0014914 0.0401588 0.00404749 0.999184 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1251 1302 -1.00839 12.5024 -6.41461 0.00524972 0.0334726 0.0746014 0.996638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1252 1301 -0.993885 -12.5056 -6.15619 0.00297185 0.0215539 -0.0640592 0.997709 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1252 1302 -0.202279 -0.0216333 -6.27915 -0.00241837 0.0303859 0.00339788 0.99953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1252 1303 -0.9897 12.4959 -6.42258 -0.00874973 0.0279696 0.0609763 0.997709 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1253 1302 -0.968911 -12.4953 -6.1681 0.00250074 0.0328927 -0.0635912 0.997431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1253 1303 -0.197802 -0.00644992 -6.28683 0.00355209 0.0288038 -0.00318056 0.999574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1253 1304 -0.983225 12.5022 -6.41838 -0.00287705 0.0283165 0.0578047 0.997922 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1254 1303 -0.996406 -12.506 -6.16562 0.00852772 0.0250145 -0.0658566 0.997479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1254 1304 -0.204282 0.00479195 -6.28782 0.00648654 0.025 -0.00764934 0.999637 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1254 1305 -0.988954 12.4899 -6.41592 -0.0067545 0.0425259 0.0646885 0.996976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1255 1304 -0.972454 -12.5046 -6.16431 -0.00431725 0.0257801 -0.0568204 0.998042 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1255 1305 -0.196391 0.00564551 -6.27941 -0.0035091 0.0269354 -0.0046752 0.99962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1255 1306 -0.984684 12.4956 -6.40696 0.00553825 0.0333127 0.0667454 0.997198 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1256 1305 -0.974208 -12.4944 -6.17651 0.0042933 0.0298856 -0.0529842 0.998139 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1256 1306 -0.203915 0.00450336 -6.28536 0.00533073 0.0428594 0.000367134 0.999067 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1256 1307 -0.990008 12.4987 -6.39987 0.000415719 0.0393517 0.0694123 0.996812 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1257 1306 -0.98157 -12.5158 -6.1625 -0.00164544 0.0335526 -0.0662486 0.997238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1257 1307 -0.193603 -0.00148175 -6.29519 0.00111472 0.025488 0.00239198 0.999672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1257 1308 -0.994679 12.4898 -6.41893 -0.00289263 0.0303684 0.0681425 0.997209 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1258 1307 -0.962391 -12.488 -6.16741 0.0118599 0.0260059 -0.0619637 0.997669 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1258 1308 -0.192076 0.0134895 -6.28152 -0.00429272 0.0328343 -0.000143756 0.999452 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1258 1309 -0.981074 12.481 -6.41076 0.00825289 0.0413687 0.0617526 0.9972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1259 1308 -0.985189 -12.4879 -6.16411 0.00782156 0.0304898 -0.0646171 0.997414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1259 1309 -0.21679 0.0051107 -6.27885 -0.00504459 0.038392 0.00390709 0.999242 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1259 1310 -0.96835 12.5139 -6.40019 -0.00820755 0.0359156 0.0595243 0.997547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1260 1309 -0.975147 -12.5225 -6.16821 0.00695869 0.0259319 -0.0685063 0.997289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1260 1310 -0.175674 0.00530578 -6.26098 -0.00715781 0.0343455 -0.00478237 0.999373 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1260 1311 -0.989303 12.4805 -6.42535 -0.00723162 0.0308288 0.0633355 0.99749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1261 1310 -0.958351 -12.4716 -6.16547 0.00978068 0.0436506 -0.0619497 0.997076 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1261 1311 -0.196718 -0.0104803 -6.26881 0.00950541 0.0402734 0.00171561 0.999142 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1261 1312 -0.992597 12.5022 -6.4179 -0.00689747 0.021128 0.0554163 0.998216 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1262 1311 -0.980485 -12.4861 -6.17744 0.00174921 0.0301117 -0.0599295 0.997747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1262 1312 -0.208629 -0.0133822 -6.27037 -0.00301322 0.0328334 -0.00569299 0.99944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1262 1313 -0.977282 12.4893 -6.41324 -0.00475314 0.0371748 0.0592396 0.99754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1263 1312 -0.974404 -12.4807 -6.17049 0.00704242 0.031463 -0.0566914 0.997871 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1263 1313 -0.187843 0.00156625 -6.29035 0.00260329 0.0316637 -0.000780379 0.999495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1263 1314 -0.994477 12.4905 -6.43607 -0.00217494 0.0296385 0.0606987 0.997714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1264 1313 -0.972744 -12.4845 -6.17833 0.00549018 0.0312226 -0.06959 0.997072 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1264 1314 -0.181281 0.0038705 -6.29507 0.00560621 0.0303041 -0.00091388 0.999525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1264 1315 -0.976465 12.5038 -6.42518 -0.00317256 0.0360711 0.0643959 0.997267 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1265 1314 -0.973056 -12.4693 -6.16223 0.014718 0.023181 -0.0621136 0.997691 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1265 1315 -0.199858 -0.00834163 -6.27282 0.00759011 0.0408419 0.00660737 0.999115 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1265 1316 -0.992963 12.4865 -6.40727 -0.00951971 0.0304637 0.0755436 0.996632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1266 1315 -0.978335 -12.4853 -6.18807 0.00402761 0.0304981 -0.0495149 0.9983 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1266 1316 -0.197993 -0.0132768 -6.28707 0.00407853 0.0325827 0.00333194 0.999455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1266 1317 -0.973568 12.4742 -6.4272 0.00768258 0.0292431 0.0653922 0.997401 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1267 1316 -0.958179 -12.4989 -6.17676 0.00145017 0.0254896 -0.0686094 0.997317 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1267 1317 -0.211403 -0.0053859 -6.2772 0.0108562 0.0312297 -0.00543804 0.999438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1267 1318 -0.975142 12.4892 -6.42938 -0.00946158 0.0274053 0.0686647 0.997218 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1268 1317 -0.972972 -12.49 -6.1677 -0.000745167 0.031637 -0.0638483 0.997458 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1268 1318 -0.202487 -0.0031674 -6.27156 0.00251514 0.0270372 0.00211321 0.999629 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1268 1319 -0.980221 12.492 -6.40391 -0.00189125 0.0290799 0.0672688 0.997309 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1269 1318 -0.998824 -12.4898 -6.18592 0.00138722 0.0295107 -0.0552286 0.998037 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1269 1319 -0.188145 0.007 -6.28168 0.0107838 0.0373655 0.00160493 0.999242 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1269 1320 -0.992214 12.488 -6.42727 -0.00272917 0.0300941 0.0551743 0.998019 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1270 1319 -0.982469 -12.4727 -6.17851 0.0071426 0.0275084 -0.0579247 0.997916 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1270 1320 -0.199861 -0.00142882 -6.28025 -0.00523326 0.028797 0.00368538 0.999565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1270 1321 -0.98503 12.4745 -6.44003 -0.00741147 0.0315151 0.0633335 0.997467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1271 1320 -0.971759 -12.4807 -6.17566 -0.0019305 0.0341914 -0.061465 0.997522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1271 1321 -0.192005 -0.00748355 -6.26907 -0.00654625 0.0409452 -0.00465621 0.999129 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1271 1322 -0.986022 12.4921 -6.42328 -0.00369016 0.0280549 0.0593118 0.997838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1272 1321 -0.995464 -12.4772 -6.17334 0.0157755 0.0282576 -0.0586353 0.997755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1272 1322 -0.204965 0.000843451 -6.28486 -0.00375507 0.0309156 0.00185699 0.999513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1272 1323 -0.997231 12.4771 -6.42481 0.00655795 0.0394463 0.0653804 0.997059 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1273 1322 -0.991773 -12.4698 -6.17438 0.00711256 0.0330247 -0.0595406 0.997654 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1273 1323 -0.214608 -0.00702405 -6.27022 0.00309102 0.0268989 -0.00567257 0.999617 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1273 1324 -0.969686 12.4667 -6.4292 0.00278024 0.0288848 0.0691826 0.997182 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1274 1323 -0.965756 -12.4797 -6.17432 0.00681087 0.0313592 -0.0578345 0.99781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1274 1324 -0.185607 0.00316157 -6.27711 -0.0102142 0.0314463 -0.00194433 0.999451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1274 1325 -0.991624 12.4666 -6.4386 -0.00987782 0.0411243 0.0547364 0.997605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1275 1324 -0.9762 -12.4731 -6.15118 0.004326 0.0344589 -0.0650385 0.997278 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1275 1325 -0.202268 0.00424657 -6.27973 0.000629023 0.035847 -0.00244328 0.999354 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1275 1326 -0.995037 12.4565 -6.4354 -0.0103448 0.0398943 0.0528533 0.997751 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1276 1325 -0.988167 -12.4704 -6.16195 -0.00378779 0.0277387 -0.0644443 0.997529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1276 1326 -0.208638 -0.015764 -6.28365 0.00140489 0.0388727 0.00114184 0.999243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1276 1327 -0.986068 12.4674 -6.42023 -0.00911587 0.031659 0.0617836 0.997546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1277 1326 -0.971674 -12.4777 -6.17824 0.00763306 0.0321647 -0.0619363 0.997532 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1277 1327 -0.203858 0.00288295 -6.29744 -0.00766885 0.0281916 -0.00905191 0.999532 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1277 1328 -1.00042 12.4755 -6.41741 -0.000817949 0.0357048 0.052066 0.998005 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1278 1327 -0.978271 -12.4803 -6.17805 0.00793335 0.0320289 -0.0665049 0.99724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1278 1328 -0.198224 -0.00524035 -6.27277 0.00967758 0.0335396 0.00137876 0.99939 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1278 1329 -0.999936 12.4708 -6.42535 -0.00487495 0.0257492 0.0704115 0.997174 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1279 1328 -0.958104 -12.4743 -6.17267 0.000433507 0.0339094 -0.0641509 0.997364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1279 1329 -0.202852 0.0059279 -6.27334 0.00258524 0.0413626 0.0132383 0.999053 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1279 1330 -0.99673 12.4741 -6.41452 -0.00404608 0.0308202 0.055499 0.997975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1280 1329 -0.977869 -12.4573 -6.18864 0.000848913 0.036215 -0.0566743 0.997735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1280 1330 -0.192669 0.00131213 -6.27184 0.00107536 0.0353461 -0.00133141 0.999374 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1280 1331 -0.97607 12.4796 -6.43314 -0.013368 0.0324635 0.0707549 0.996876 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1281 1330 -0.957803 -12.4902 -6.18706 0.0105682 0.0270254 -0.0661245 0.997389 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1281 1331 -0.183842 -0.0111203 -6.27929 0.00480951 0.0322748 0.00779018 0.999437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1281 1332 -0.982871 12.4725 -6.43897 -0.00364077 0.0212459 0.0642829 0.997699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1282 1331 -0.971854 -12.4583 -6.18529 0.00689056 0.0330268 -0.0551787 0.997906 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1282 1332 -0.203011 -0.0177663 -6.30029 0.0064115 0.0368455 0.00428554 0.999291 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1282 1333 -0.977286 12.4497 -6.44392 -0.00596861 0.0201409 0.0622125 0.997842 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1283 1332 -0.96452 -12.4606 -6.18715 0.00867893 0.0315431 -0.0647133 0.997367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1283 1333 -0.197802 -0.0121082 -6.2578 0.00364562 0.0355417 0.00911098 0.99932 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1283 1334 -0.99034 12.4647 -6.44898 -0.00594511 0.0380319 0.0566608 0.997651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1284 1333 -0.982841 -12.4663 -6.18329 0.015025 0.0255416 -0.0647612 0.997461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1284 1334 -0.180712 0.00185238 -6.29421 -0.00149223 0.0262942 0.00708627 0.999628 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1284 1335 -0.986983 12.4467 -6.44107 -0.00616544 0.0253297 0.0611841 0.997786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1285 1334 -0.977144 -12.4747 -6.20002 0.00510435 0.0283757 -0.0682985 0.997248 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1285 1335 -0.199206 0.00985924 -6.28239 -0.00366912 0.0412713 0.00385056 0.999134 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1285 1336 -0.985279 12.4576 -6.43475 -0.00257377 0.0348007 0.0585101 0.997677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1286 1335 -0.960848 -12.467 -6.20026 0.00507695 0.0347631 -0.0623679 0.997435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1286 1336 -0.183678 0.00682439 -6.29942 -0.00237161 0.0363727 -0.000216257 0.999335 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1286 1337 -0.989295 12.4483 -6.4313 0.0043543 0.0354077 0.0641766 0.997301 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1287 1336 -0.965254 -12.4684 -6.20302 0.00963203 0.0146688 -0.0522284 0.998481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1287 1337 -0.188723 0.00862083 -6.27912 -0.00604146 0.024573 0.00192812 0.999678 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1287 1338 -0.985551 12.4619 -6.43757 0.00169098 0.0276138 0.0603525 0.997794 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1288 1337 -0.965007 -12.4578 -6.20851 0.00866494 0.0249242 -0.0686256 0.997293 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1288 1338 -0.2073 -0.0130792 -6.28022 0.00591475 0.0294503 0.00361177 0.999542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1288 1339 -0.991303 12.4528 -6.43305 -0.00970538 0.0284735 0.0578759 0.99787 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1289 1338 -0.989771 -12.4793 -6.19728 0.00442573 0.0338501 -0.0500423 0.998163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1289 1339 -0.202218 -0.0204127 -6.27372 0.00377886 0.0246229 -0.00617232 0.999671 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1289 1340 -0.998899 12.4682 -6.43942 -0.00979198 0.0412888 0.0679332 0.996787 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1290 1339 -0.978789 -12.4647 -6.19792 0.00404883 0.027967 -0.0694865 0.997183 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1290 1340 -0.194093 -0.01023 -6.26435 -0.00175962 0.0279714 1.47092e-05 0.999607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1290 1341 -0.999199 12.446 -6.44315 -0.000205181 0.0308159 0.0617431 0.997616 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1291 1340 -0.964268 -12.4549 -6.20329 0.0101071 0.0331748 -0.0638345 0.997358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1291 1341 -0.201879 0.00287873 -6.29215 -0.012471 0.0222274 -0.000921001 0.999675 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1291 1342 -0.993665 12.4494 -6.44923 -0.0163959 0.033432 0.066559 0.997087 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1292 1341 -0.964647 -12.4353 -6.21353 0.00769125 0.0279308 -0.0577681 0.99791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1292 1342 -0.220045 0.00900387 -6.28727 9.1384e-05 0.0308228 0.00568046 0.999509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1292 1343 -0.979448 12.4547 -6.45695 -0.0101903 0.0352449 0.052439 0.99795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1293 1342 -0.988943 -12.4605 -6.18836 0.00411802 0.0278833 -0.0694333 0.997188 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1293 1343 -0.201061 -0.00102918 -6.28021 0.00872698 0.0270163 -0.00299509 0.999592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1293 1344 -0.995253 12.4488 -6.44949 -0.00668763 0.0220279 0.0697818 0.997297 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1294 1343 -0.979415 -12.4524 -6.19114 0.00101943 0.0383871 -0.0587192 0.997536 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1294 1344 -0.195684 -0.0166126 -6.27165 -0.00353984 0.0306917 -0.00206616 0.99952 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1294 1345 -1.00245 12.4501 -6.44215 -0.00827975 0.0405618 0.0629769 0.997156 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1295 1344 -0.981569 -12.4506 -6.19753 0.00298977 0.0398097 -0.0632347 0.9972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1295 1345 -0.20087 -0.00112789 -6.29681 0.0043167 0.0362283 -0.00518531 0.999321 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1295 1346 -1.0001 12.4504 -6.44788 -0.00730537 0.0283934 0.0589264 0.997832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1296 1345 -0.970978 -12.4264 -6.19184 0.0073705 0.0297144 -0.0618432 0.997616 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1296 1346 -0.200383 -0.00173165 -6.27397 0.000664478 0.0312069 -0.00398479 0.999505 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1296 1347 -0.978674 12.4441 -6.44491 -0.00873759 0.0339691 0.0553622 0.99785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1297 1346 -0.976954 -12.4547 -6.19239 0.0174601 0.0372255 -0.0627799 0.99718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1297 1347 -0.187623 -0.000878947 -6.28748 -0.00727126 0.0345746 0.00450946 0.999365 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1297 1348 -0.972168 12.4235 -6.43308 -0.00706807 0.032068 0.0572923 0.997817 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1298 1347 -0.971417 -12.4432 -6.20027 0.00814086 0.0394427 -0.0557868 0.99763 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1298 1348 -0.20489 0.0154313 -6.26729 0.00459827 0.0315589 0.00249274 0.999488 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1298 1349 -0.986494 12.4421 -6.44273 -0.00309536 0.033194 0.0590366 0.997699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1299 1348 -0.993202 -12.4163 -6.21968 0.00198435 0.0361802 -0.0688235 0.996971 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1299 1349 -0.195221 0.010164 -6.28264 -6.97559e-05 0.0328576 -0.00500842 0.999447 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1299 1350 -0.984244 12.4225 -6.46176 -0.00867638 0.025059 0.0658567 0.997477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1300 1349 -0.977957 -12.4377 -6.20864 0.00524084 0.0325538 -0.0678378 0.997151 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1300 1350 -0.202001 -0.021799 -6.30246 0.0036071 0.0289748 0.00635889 0.999553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1300 1351 -0.989886 12.4335 -6.44999 -0.0113857 0.0341709 0.0676304 0.99706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1301 1350 -0.96815 -12.4367 -6.18585 -0.0028746 0.031977 -0.0686771 0.997122 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1301 1351 -0.207597 -0.0177873 -6.25585 0.00252701 0.035783 0.00245736 0.999353 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1301 1352 -0.973719 12.446 -6.46226 -0.00742811 0.034774 0.0600902 0.997559 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1302 1351 -0.982305 -12.423 -6.20356 0.00434934 0.0348304 -0.0668462 0.997146 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1302 1352 -0.200871 0.00539717 -6.28408 0.00294309 0.0387787 -0.00404612 0.999235 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1302 1353 -0.984565 12.4438 -6.46742 -0.00275219 0.0316535 0.0609314 0.997636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1303 1352 -0.98095 -12.4176 -6.19576 0.00492743 0.0366136 -0.0545631 0.997827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1303 1353 -0.2048 -0.0291763 -6.28595 -0.00815239 0.0396183 -0.00138674 0.999181 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1303 1354 -1.00306 12.4364 -6.46261 -0.00517333 0.0334899 0.0618122 0.997512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1304 1353 -0.958941 -12.44 -6.21021 0.00785193 0.0337029 -0.066774 0.997168 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1304 1354 -0.191257 -0.010418 -6.28819 -0.00299303 0.0159771 0.00372386 0.999861 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1304 1355 -0.97287 12.4111 -6.45263 -0.0141601 0.0308718 0.058382 0.997716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1305 1354 -0.959775 -12.4265 -6.20307 0.00431867 0.0406968 -0.0582352 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1305 1355 -0.213564 -0.00613343 -6.28198 -0.00195635 0.0279669 -0.0178683 0.999447 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1305 1356 -0.970709 12.4363 -6.46012 0.000362375 0.0305239 0.0731677 0.996852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1306 1355 -0.966955 -12.4292 -6.20951 0.00885535 0.0260813 -0.0577705 0.99795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1306 1356 -0.209354 -0.00844872 -6.26537 0.00350071 0.0441356 -0.00201266 0.999017 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1306 1357 -0.987437 12.4194 -6.4623 -0.0104427 0.0245837 0.0669161 0.997401 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1307 1356 -0.975439 -12.4045 -6.22192 0.0131931 0.0319976 -0.0664454 0.99719 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1307 1357 -0.19607 0.00303485 -6.28319 2.94823e-05 0.0294116 -0.0026222 0.999564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1307 1358 -0.976615 12.43 -6.46723 -0.00518988 0.0286051 0.0611885 0.997703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1308 1357 -0.981082 -12.423 -6.2127 0.0116534 0.024614 -0.057186 0.997992 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1308 1358 -0.199931 -0.00483569 -6.27876 0.00408646 0.0280629 -0.00690482 0.999574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1308 1359 -0.978705 12.4021 -6.45674 -0.00656711 0.0288301 0.0716144 0.996994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1309 1358 -0.963403 -12.4037 -6.21833 0.00643815 0.0379959 -0.064277 0.997188 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1309 1359 -0.192523 0.0088217 -6.27277 0.00391157 0.0284627 0.00743275 0.99956 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1309 1360 -0.989954 12.4011 -6.46169 -0.0156146 0.0342099 0.0607688 0.997443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1310 1359 -0.965483 -12.4132 -6.21263 0.0136893 0.0385432 -0.0661836 0.996969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1310 1360 -0.201507 0.00132149 -6.27269 0.000783501 0.0238675 -0.00392927 0.999707 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1310 1361 -0.980858 12.4168 -6.45839 -0.00545235 0.036182 0.0632305 0.997328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1311 1360 -0.97108 -12.4295 -6.20377 0.0214655 0.0268055 -0.0625724 0.997449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1311 1361 -0.181671 0.00644034 -6.28234 0.00783012 0.031528 0.00682231 0.999449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1311 1362 -0.972049 12.4181 -6.46146 -0.00924171 0.0261034 0.0525357 0.998235 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1312 1361 -0.960555 -12.3987 -6.22881 0.0160208 0.0302228 -0.0641834 0.997352 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1312 1362 -0.208451 -0.00830143 -6.26128 0.0103141 0.0226835 0.00215173 0.999687 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1312 1363 -0.985489 12.3939 -6.46523 -0.00779137 0.028423 0.0600133 0.997762 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1313 1362 -0.973068 -12.4013 -6.20671 0.00251487 0.0366907 -0.0636671 0.997293 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1313 1363 -0.204761 0.0139731 -6.28543 0.00785627 0.0242872 -0.00268003 0.999671 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1313 1364 -0.978619 12.3886 -6.46006 -0.0149581 0.0373365 0.0609724 0.997329 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1314 1363 -0.957252 -12.4097 -6.23097 0.00412058 0.024027 -0.0699604 0.997252 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1314 1364 -0.184218 0.00861403 -6.27733 0.00366286 0.0290571 0.00543944 0.999556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1314 1365 -0.97949 12.4149 -6.45568 -0.00799628 0.0429918 0.0605208 0.997209 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1315 1364 -0.967327 -12.4043 -6.22511 0.0137345 0.0231777 -0.058547 0.997921 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1315 1365 -0.221498 0.000829115 -6.2885 -0.000132255 0.0271877 0.00785262 0.999599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1315 1366 -0.987101 12.3992 -6.45874 -0.00317265 0.0254877 0.0569771 0.998045 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1316 1365 -0.974382 -12.3998 -6.21614 0.0154036 0.0348946 -0.0664172 0.997063 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1316 1366 -0.207646 0.0100328 -6.2828 -0.00215654 0.0369008 0.00429746 0.999307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1316 1367 -0.99131 12.3949 -6.47916 -0.0064175 0.0379062 0.0654264 0.997117 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1317 1366 -0.965037 -12.3898 -6.2227 0.0104738 0.0266778 -0.0640364 0.997536 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1317 1367 -0.186876 -0.000704321 -6.27221 -0.0047757 0.0274013 -0.00133614 0.999612 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1317 1368 -0.979201 12.3793 -6.46084 -0.00118836 0.0255091 0.0662332 0.997477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1318 1367 -0.978791 -12.3962 -6.22924 0.0112928 0.035779 -0.0579703 0.997613 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1318 1368 -0.205395 -0.00146132 -6.27974 0.00516092 0.0406554 0.00664449 0.999138 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1318 1369 -0.991143 12.4061 -6.46991 -0.00188467 0.026114 0.0515916 0.998325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1319 1368 -0.979948 -12.3926 -6.22045 0.00610903 0.044885 -0.0743497 0.996203 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1319 1369 -0.201484 0.0072034 -6.26496 0.00774695 0.0285788 0.00391607 0.999554 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1319 1370 -0.957228 12.4015 -6.47194 -0.0135933 0.0334224 0.0640621 0.997293 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1320 1369 -0.980375 -12.3898 -6.22235 0.00969815 0.0319573 -0.0590438 0.997697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1320 1370 -0.190415 0.00561998 -6.28359 0.000759473 0.035611 -0.00806325 0.999333 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1320 1371 -0.979467 12.3841 -6.45189 -0.0112615 0.0360195 0.0567804 0.997673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1321 1370 -0.943113 -12.3905 -6.21899 0.0064565 0.0359552 -0.0642825 0.997263 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1321 1371 -0.198159 -0.00650769 -6.27139 -9.22659e-05 0.0298116 -0.00352135 0.999549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1321 1372 -0.977379 12.3814 -6.48498 -0.0130754 0.0374277 0.0640817 0.997157 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1322 1371 -0.959167 -12.3735 -6.23185 0.00919349 0.0313635 -0.0696851 0.997033 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1322 1372 -0.19793 -0.00659503 -6.27834 -0.00866038 0.0215455 -0.00600271 0.999712 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1322 1373 -0.978006 12.3991 -6.50006 -0.0152835 0.0382327 0.0638592 0.997109 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1323 1372 -0.979074 -12.3785 -6.22319 0.00705302 0.0380355 -0.0626104 0.997288 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1323 1373 -0.184595 -0.00666094 -6.28657 0.00165402 0.0368086 0.000917731 0.999321 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1323 1374 -0.991392 12.3743 -6.47444 -0.0126308 0.0291793 0.0707319 0.996988 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1324 1373 -0.972689 -12.3857 -6.22813 0.00880285 0.0340792 -0.06042 0.997552 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1324 1374 -0.181689 -0.0198158 -6.27667 0.00133389 0.0295383 -0.0018703 0.999561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1324 1375 -0.974609 12.3795 -6.45931 -0.00335677 0.0418763 0.0590934 0.997368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1325 1374 -0.953904 -12.3788 -6.22134 0.0104467 0.0344669 -0.0627565 0.997379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1325 1375 -0.196524 -0.017529 -6.27546 0.00222135 0.0255766 -0.00320397 0.999665 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1325 1376 -0.987249 12.3813 -6.47853 -0.0091293 0.0324174 0.0558161 0.997873 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1326 1375 -0.960625 -12.3873 -6.22247 0.00184635 0.0291463 -0.0624286 0.997622 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1326 1376 -0.200494 -0.000139244 -6.26096 0.00132731 0.0363603 -0.000717219 0.999338 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1326 1377 -0.979412 12.3497 -6.47854 -0.0078344 0.0253144 0.0576936 0.997983 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1327 1376 -0.956483 -12.3655 -6.2147 0.00685374 0.0293848 -0.0677749 0.997244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1327 1377 -0.200072 -0.0160745 -6.27525 -0.00725334 0.0363513 -0.00333912 0.999307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1327 1378 -0.974838 12.3831 -6.46343 -0.000709686 0.0321981 0.0621057 0.99755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1328 1377 -0.966605 -12.3674 -6.23861 0.0129374 0.0281151 -0.0529489 0.998118 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1328 1378 -0.202578 0.00176577 -6.28425 -0.00293539 0.031286 -0.00948302 0.999461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1328 1379 -0.99121 12.3644 -6.47266 -0.00822421 0.0353596 0.0654289 0.997197 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1329 1378 -0.956379 -12.3691 -6.24088 0.00486531 0.0267867 -0.0634438 0.997614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1329 1379 -0.198 0.0119112 -6.27083 -0.00491434 0.0380728 0.00677825 0.99924 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1329 1380 -0.986468 12.3533 -6.47034 -0.00744792 0.034892 0.0586014 0.997644 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1330 1379 -0.952213 -12.3285 -6.22845 0.00903074 0.0260898 -0.0663599 0.997414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1330 1380 -0.205836 -0.011817 -6.28885 0.00412325 0.0300785 0.00319115 0.999534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1330 1381 -0.989026 12.3753 -6.47134 -0.00486572 0.0272908 0.0643669 0.997541 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1331 1380 -0.958881 -12.3626 -6.22654 0.010791 0.0367913 -0.058842 0.997531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1331 1381 -0.214581 0.00216026 -6.26689 0.000428423 0.0308737 -0.0110551 0.999462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1331 1382 -0.970627 12.3601 -6.48931 -0.0135459 0.0304176 0.0552263 0.997918 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1332 1381 -0.939366 -12.3691 -6.23058 0.0122845 0.0265341 -0.0647893 0.99747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1332 1382 -0.201082 -0.000533206 -6.27404 -0.00684195 0.030556 0.00383159 0.999502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1332 1383 -0.98021 12.3534 -6.47707 -0.0112861 0.0290914 0.0619734 0.99759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1333 1382 -0.974113 -12.3564 -6.23162 0.0096484 0.0378015 -0.0582933 0.997537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1333 1383 -0.20821 0.00339211 -6.26225 -0.00531943 0.0298757 0.00565029 0.999523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1333 1384 -0.977048 12.3686 -6.4832 -0.0123811 0.0387414 0.0609439 0.997312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1334 1383 -0.954333 -12.3386 -6.24536 0.0106423 0.0329802 -0.0535881 0.997962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1334 1384 -0.202468 -0.00323724 -6.27509 -0.0084688 0.026784 -0.000813313 0.999605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1334 1385 -0.961447 12.3357 -6.48152 -0.0067771 0.0404311 0.066325 0.996956 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1335 1384 -0.959128 -12.3351 -6.22368 0.0113588 0.0307 -0.0563935 0.997872 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1335 1385 -0.200464 -0.00313086 -6.28723 -0.00176839 0.0290408 -6.56698e-05 0.999577 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1335 1386 -0.969897 12.3445 -6.48348 -0.00534553 0.0362937 0.0643385 0.997254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1336 1385 -0.976403 -12.3546 -6.24204 0.00496276 0.0324595 -0.0691201 0.997068 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1336 1386 -0.202218 0.00158063 -6.27806 0.00020888 0.0354592 0.00413314 0.999363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1336 1387 -0.964999 12.3431 -6.50053 -0.0080334 0.0277275 0.0628558 0.997605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1337 1386 -0.962687 -12.3505 -6.22887 0.0108194 0.03121 -0.0612411 0.997576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1337 1387 -0.20293 -0.00592108 -6.2886 -0.00655107 0.0306219 0.00610232 0.999491 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1337 1388 -0.954838 12.3475 -6.49018 -0.0151227 0.035101 0.0675918 0.996981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1338 1387 -0.965777 -12.359 -6.24741 0.0151319 0.0383583 -0.0676907 0.996854 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1338 1388 -0.20767 -0.00374522 -6.28684 -0.00667569 0.0359394 -0.00619849 0.999312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1338 1389 -0.977395 12.3309 -6.49133 -0.00813 0.0281967 0.0638412 0.997529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1339 1388 -0.967308 -12.3369 -6.26891 0.0105184 0.0219957 -0.0698261 0.997261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1339 1389 -0.206353 -0.00127296 -6.27843 -0.000435994 0.0282247 -0.00236051 0.999599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1339 1390 -0.974649 12.3297 -6.49506 -0.00278793 0.0291866 0.0613633 0.997685 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1340 1389 -0.974045 -12.3249 -6.22906 0.0140663 0.0387624 -0.0632133 0.997148 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1340 1390 -0.203163 -0.0167058 -6.2723 0.00212067 0.0361433 -0.00592804 0.999327 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1340 1391 -0.975084 12.3307 -6.50186 -0.00200456 0.0381502 0.0642304 0.997204 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1341 1390 -0.977678 -12.3237 -6.25955 0.00898567 0.0348815 -0.060075 0.997544 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1341 1391 -0.195464 0.001164 -6.28404 0.00571533 0.0343808 -0.00521351 0.999379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1341 1392 -0.978598 12.3382 -6.49428 -0.00719534 0.0297773 0.0677026 0.997235 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1342 1391 -0.957097 -12.3518 -6.23852 0.00832468 0.027629 -0.0532428 0.998165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1342 1392 -0.194837 -0.00134068 -6.27996 0.00311367 0.0251147 -0.00190869 0.999678 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1342 1393 -0.959118 12.3342 -6.49272 -0.00426577 0.0410385 0.0663228 0.996945 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1343 1392 -0.947874 -12.3306 -6.26452 0.00697672 0.0393593 -0.0571737 0.997564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1343 1393 -0.193417 0.0169375 -6.27592 -0.00523749 0.0293187 0.000158372 0.999556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1343 1394 -0.984236 12.3274 -6.48864 -0.00900915 0.0380401 0.0631077 0.997241 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1344 1393 -0.956554 -12.3351 -6.26867 0.00834214 0.0300902 -0.066005 0.997331 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1344 1394 -0.191646 0.00236725 -6.27307 0.00164927 0.0229348 -0.00506167 0.999723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1344 1395 -0.979107 12.3281 -6.49834 -0.00691405 0.0312183 0.0641034 0.997431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1345 1394 -0.975811 -12.3517 -6.23538 0.0065913 0.0325083 -0.0622445 0.99751 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1345 1395 -0.18321 -0.0115203 -6.28182 -0.00855968 0.039894 0.000492871 0.999167 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1345 1396 -0.969342 12.3295 -6.48601 -0.0102254 0.0313952 0.0722397 0.996841 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1346 1395 -0.96253 -12.3027 -6.23739 0.0150415 0.0297348 -0.0689957 0.99706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1346 1396 -0.197387 0.011568 -6.2688 -0.00843323 0.0212203 0.00758186 0.999711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1346 1397 -0.985386 12.3247 -6.48438 -0.00872681 0.0339421 0.0729807 0.996717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1347 1396 -0.965616 -12.3238 -6.25018 0.0109466 0.0276707 -0.0525868 0.998173 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1347 1397 -0.180902 0.00362677 -6.25958 -0.00437012 0.0267536 0.00404017 0.999624 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1347 1398 -0.980716 12.2929 -6.51641 -0.00783566 0.0338343 0.0584346 0.997687 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1348 1397 -0.957995 -12.3328 -6.23984 0.00610778 0.0370483 -0.0647909 0.997192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1348 1398 -0.194543 -0.000642571 -6.28567 -0.00686087 0.0248405 -0.000334042 0.999668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1348 1399 -0.980554 12.3128 -6.4911 -0.00894148 0.0346524 0.066514 0.997143 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1349 1398 -0.953984 -12.3223 -6.25667 0.0087863 0.0250727 -0.060884 0.997791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1349 1399 -0.213224 0.00694331 -6.25527 -0.00410414 0.0252101 -0.00449333 0.999664 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1349 1400 -0.975876 12.3008 -6.49372 -0.00463143 0.0341419 0.0643379 0.997333 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1350 1399 -0.960121 -12.3188 -6.25751 0.00777287 0.0308228 -0.0642621 0.997427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1350 1400 -0.200448 -0.0129768 -6.29141 -0.00162171 0.0316416 -0.00609637 0.999479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1350 1401 -0.976128 12.3102 -6.50767 -0.0162393 0.0303674 0.068351 0.997067 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1351 1400 -0.961644 -12.3031 -6.2491 0.00229879 0.0314359 -0.0684592 0.997156 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1351 1401 -0.189204 0.00642122 -6.27737 0.00107364 0.0207624 -0.00111376 0.999783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1351 1402 -0.986962 12.2987 -6.49343 -0.0137994 0.0331816 0.0628792 0.997374 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1352 1401 -0.96845 -12.2876 -6.26202 0.010439 0.0368984 -0.0605642 0.997427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1352 1402 -0.206361 -9.75451e-05 -6.27924 -0.00297757 0.03263 -0.00235366 0.99946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1352 1403 -0.963293 12.3039 -6.50496 -0.0104674 0.02301 0.0620872 0.997751 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1353 1402 -0.983601 -12.2914 -6.2424 0.0130074 0.0220678 -0.0588989 0.997935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1353 1403 -0.195896 0.00279747 -6.27011 -0.00468305 0.0418238 -0.00077421 0.999114 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1353 1404 -0.969033 12.2942 -6.50571 0.00351079 0.0306157 0.0620878 0.997595 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1354 1403 -0.967777 -12.2836 -6.25109 0.00474145 0.0391886 -0.0637464 0.997185 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1354 1404 -0.195879 -0.0101216 -6.27583 -0.0106676 0.03242 0.00977486 0.99937 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1354 1405 -0.95861 12.2953 -6.50689 -0.0101202 0.0304168 0.0567964 0.997871 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1355 1404 -0.950813 -12.306 -6.24245 0.0126341 0.0316738 -0.0628986 0.997437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1355 1405 -0.190682 0.0243005 -6.27782 0.00348723 0.0351108 -0.00534452 0.999363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1355 1406 -0.977704 12.2847 -6.49363 -0.00492179 0.0299967 0.0713713 0.996987 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1356 1405 -0.952206 -12.2948 -6.22748 0.0105569 0.0354981 -0.0669687 0.997068 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1356 1406 -0.208528 0.00591355 -6.26953 -0.00499139 0.0280269 -0.00517798 0.999581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1356 1407 -0.9689 12.285 -6.50026 -0.0109996 0.0258084 0.0633938 0.997594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1357 1406 -0.949655 -12.299 -6.25042 0.00895066 0.0315613 -0.0576415 0.997798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1357 1407 -0.196938 -0.00772015 -6.27662 0.00962902 0.0357474 0.00212544 0.999312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1357 1408 -0.976401 12.2792 -6.50274 -0.0166779 0.034669 0.0610629 0.997392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1358 1407 -0.962609 -12.3007 -6.22889 0.00872707 0.0314808 -0.0616152 0.997565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1358 1408 -0.205456 -0.00988664 -6.26161 -0.00175043 0.0308052 0.0077829 0.999494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1358 1409 -0.975848 12.2824 -6.51976 -0.0107587 0.0289044 0.0681131 0.997201 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1359 1408 -0.970803 -12.2742 -6.26617 0.0226059 0.0236935 -0.0721609 0.996855 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1359 1409 -0.215295 -0.000278999 -6.28234 -0.00295629 0.033567 0.000783322 0.999432 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1359 1410 -0.953424 12.2711 -6.51384 -0.0079387 0.0245676 0.0660365 0.997483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1360 1409 -0.965399 -12.2607 -6.27361 0.0134573 0.0202214 -0.0604952 0.997873 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1360 1410 -0.1986 -0.0103598 -6.26297 -0.00954089 0.0267679 0.00454056 0.999586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1360 1411 -0.995245 12.2739 -6.52177 -0.00950414 0.0455009 0.0608233 0.997066 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1361 1410 -0.954006 -12.2813 -6.26411 0.00976311 0.02673 -0.0607128 0.99775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1361 1411 -0.19157 0.00822433 -6.26508 -0.00130029 0.0284611 -0.0059322 0.999576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1361 1412 -0.971574 12.2742 -6.50787 -0.0146593 0.0383919 0.0663366 0.996951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1362 1411 -0.951099 -12.2786 -6.2637 0.00781171 0.0310948 -0.0637096 0.997453 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1362 1412 -0.210894 0.00913618 -6.28703 0.0050698 0.0354898 0.000451019 0.999357 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1362 1413 -0.974832 12.2593 -6.52298 -0.0120402 0.0402872 0.0635796 0.997091 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1363 1412 -0.948829 -12.2772 -6.2821 0.0102415 0.0218344 -0.0709722 0.997187 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1363 1413 -0.18602 0.015035 -6.28925 0.0106385 0.0403772 -0.00790376 0.999097 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1363 1414 -0.977381 12.2649 -6.49155 -0.00856272 0.0163188 0.0546057 0.998338 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1364 1413 -0.957522 -12.2711 -6.27326 0.0071352 0.0287414 -0.0558204 0.998002 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1364 1414 -0.197183 0.00859571 -6.27629 -0.00186547 0.028167 0.00197229 0.9996 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1364 1415 -0.966857 12.2713 -6.51922 -0.0225723 0.0354932 0.0621872 0.997178 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1365 1414 -0.933224 -12.2682 -6.2616 0.0158464 0.0301802 -0.0604247 0.997591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1365 1415 -0.191348 0.0140291 -6.28583 0.00296554 0.0387837 -0.00537978 0.999229 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1365 1416 -0.976887 12.2632 -6.52848 -0.00237427 0.0289433 0.0699848 0.997125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1366 1415 -0.944673 -12.2633 -6.25333 0.0114569 0.02871 -0.0660026 0.997341 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1366 1416 -0.206021 -0.00317685 -6.28156 0.000553659 0.0328375 -0.00774053 0.999431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1366 1417 -0.975018 12.2537 -6.52351 -0.012343 0.0284999 0.0659318 0.997341 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1367 1416 -0.945103 -12.2628 -6.26728 0.0117291 0.0271265 -0.0572604 0.997922 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1367 1417 -0.196985 0.0123717 -6.28258 0.00269035 0.0352764 0.00182747 0.999372 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1367 1418 -0.968889 12.2489 -6.53487 -0.011599 0.0442477 0.0616468 0.997049 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1368 1417 -0.969792 -12.2479 -6.28089 0.00863067 0.0286408 -0.0630718 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1368 1418 -0.202509 0.0160375 -6.28393 0.002937 0.0238146 -0.00340755 0.999706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1368 1419 -0.972237 12.2597 -6.51414 -0.0135333 0.0373154 0.063093 0.997218 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1369 1418 -0.940825 -12.2456 -6.27988 0.00987189 0.0340706 -0.0545138 0.997883 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1369 1419 -0.202128 0.00977662 -6.2766 0.00173483 0.027814 0.00394429 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1369 1420 -0.960001 12.2325 -6.50815 -0.00831965 0.0311826 0.0559188 0.997914 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1370 1419 -0.948652 -12.2442 -6.28723 0.0140638 0.0348385 -0.0620192 0.997368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1370 1420 -0.197546 -0.00424862 -6.28221 0.00521583 0.0263212 -0.00843283 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1370 1421 -0.95272 12.2366 -6.51467 -0.01196 0.030563 0.0583879 0.997754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1371 1420 -0.940211 -12.2225 -6.26935 0.00769819 0.034291 -0.0644548 0.997302 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1371 1421 -0.198365 -0.0120822 -6.27831 0.0100347 0.0344475 0.00086705 0.999356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1371 1422 -0.975537 12.2353 -6.53278 -0.01165 0.033862 0.0598002 0.997568 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1372 1421 -0.950519 -12.2512 -6.26847 0.0131347 0.0211452 -0.0678748 0.997383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1372 1422 -0.183491 0.000312484 -6.28017 0.000748445 0.0301712 -0.00420407 0.999536 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1372 1423 -0.975702 12.2297 -6.52477 -0.0112621 0.0317812 0.059764 0.997643 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1373 1422 -0.952323 -12.2279 -6.27005 0.00725766 0.0381291 -0.0617268 0.997338 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1373 1423 -0.20928 -0.00408226 -6.28507 -0.00414443 0.0200389 -1.74296e-05 0.999791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1373 1424 -0.964841 12.2165 -6.52423 -0.0031667 0.0399956 0.0626873 0.997226 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1374 1423 -0.95407 -12.2161 -6.28136 0.0091205 0.0286526 -0.0682937 0.997212 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1374 1424 -0.202 0.000245171 -6.27739 0.00843982 0.0374234 0.00990431 0.999215 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1374 1425 -0.962146 12.2294 -6.51937 -0.00971552 0.0291135 0.0657632 0.997363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1375 1424 -0.952142 -12.2381 -6.25631 0.0175413 0.02514 -0.0597612 0.997742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1375 1425 -0.214843 0.0213355 -6.29456 -0.00498716 0.0259115 -0.00773584 0.999622 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1375 1426 -0.959128 12.2228 -6.51496 -0.00812678 0.0343005 0.0643179 0.997307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1376 1425 -0.946114 -12.2351 -6.262 0.0136138 0.0258266 -0.0586795 0.99785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1376 1426 -0.189269 0.00297023 -6.26954 -0.000795278 0.0337574 -0.000347103 0.99943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1376 1427 -0.961767 12.2213 -6.53658 -0.0126003 0.0350101 0.0625752 0.997346 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1377 1426 -0.957142 -12.218 -6.27254 0.0124555 0.0330901 -0.0579168 0.997695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1377 1427 -0.201632 0.012854 -6.29306 -1.36842e-05 0.0266839 0.00444352 0.999634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1377 1428 -0.969793 12.2306 -6.5151 -0.0103948 0.0202241 0.0606127 0.997902 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1378 1427 -0.937261 -12.2105 -6.2741 0.0114035 0.0350315 -0.0589224 0.997583 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1378 1428 -0.214866 0.00903446 -6.28228 -0.00473198 0.0290217 -0.004824 0.999556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1378 1429 -0.970112 12.2247 -6.52325 -0.0186162 0.0336225 0.0652632 0.997128 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1379 1428 -0.958906 -12.2143 -6.26282 0.0134102 0.0278676 -0.0572005 0.997884 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1379 1429 -0.198474 0.0126578 -6.27956 -0.0100616 0.0327725 -0.00197008 0.99941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1379 1430 -0.955682 12.2014 -6.53391 -0.0197343 0.0323926 0.0611303 0.997409 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1380 1429 -0.946253 -12.2104 -6.28444 0.00857533 0.0277526 -0.0550115 0.998063 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1380 1430 -0.212232 -0.0100471 -6.28174 0.00275437 0.0442306 0.0075439 0.998989 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1380 1431 -0.974412 12.1946 -6.52644 -0.0104722 0.0347476 0.0531486 0.997927 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1381 1430 -0.951969 -12.208 -6.2805 0.0207053 0.0286187 -0.0547872 0.997873 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1381 1431 -0.183604 -0.0038377 -6.28522 0.00553397 0.0214082 -0.00805611 0.999723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1381 1432 -0.960038 12.2177 -6.52529 -0.00856006 0.0286592 0.0683994 0.99721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1382 1431 -0.949491 -12.2201 -6.29275 0.0170692 0.0238706 -0.0708437 0.997056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1382 1432 -0.189464 -0.00835282 -6.26376 0.00217855 0.0374507 -0.000171788 0.999296 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1382 1433 -0.978044 12.1846 -6.52462 -0.0087631 0.0349509 0.0687465 0.996983 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1383 1432 -0.936697 -12.2186 -6.28336 0.0263881 0.0359335 -0.0573157 0.99736 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1383 1433 -0.192595 -0.000402554 -6.28622 -0.00359311 0.0333708 0.00822716 0.999403 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1383 1434 -0.960815 12.2186 -6.53068 -0.0186813 0.0298066 0.0510095 0.998078 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1384 1433 -0.939499 -12.2006 -6.26935 0.000985283 0.0300002 -0.0621458 0.997616 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1384 1434 -0.205923 0.00124865 -6.27358 0.000481602 0.032516 0.00204142 0.999469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1384 1435 -0.954901 12.1668 -6.54092 -0.0119671 0.0225888 0.0510481 0.998369 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1385 1434 -0.960788 -12.2144 -6.28376 0.0132225 0.0309062 -0.0652068 0.997305 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1385 1435 -0.179214 0.0076494 -6.27655 -0.00446592 0.0284445 0.00215904 0.999583 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1385 1436 -0.954286 12.1686 -6.55739 -0.00904431 0.0357803 0.0578909 0.997641 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1386 1435 -0.941093 -12.2168 -6.27886 0.0095669 0.0322875 -0.0552932 0.997902 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1386 1436 -0.202897 -0.0160692 -6.2686 -0.00638162 0.0319572 0.00793114 0.999437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1386 1437 -0.955204 12.183 -6.53691 -0.0106723 0.0445186 0.0590112 0.997207 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1387 1436 -0.958647 -12.1952 -6.28512 0.00793213 0.0276184 -0.0586734 0.997864 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1387 1437 -0.192087 0.00415429 -6.27055 0.00217174 0.0393508 -0.00500319 0.999211 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1387 1438 -0.96258 12.1935 -6.53944 -0.0176062 0.0267304 0.065086 0.997366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1388 1437 -0.96357 -12.2017 -6.29001 0.000579496 0.0363381 -0.0608628 0.997484 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1388 1438 -0.198167 -5.78031e-05 -6.26863 0.000757424 0.0285686 0.0161394 0.999461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1388 1439 -0.963622 12.1767 -6.54787 -0.0214234 0.0317504 0.0641057 0.997208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1389 1438 -0.942888 -12.1776 -6.27922 0.0167462 0.0339402 -0.0608809 0.997427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1389 1439 -0.184372 -0.0204044 -6.29351 -0.00753912 0.0258867 0.0148577 0.999526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1389 1440 -0.976003 12.1842 -6.53797 -0.00108082 0.0332037 0.0635697 0.997424 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1390 1439 -0.942511 -12.1837 -6.29171 0.0164447 0.0239261 -0.0532444 0.998159 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1390 1440 -0.191946 -0.0142256 -6.28551 -0.00538303 0.030109 0.00520765 0.999519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1390 1441 -0.963666 12.1802 -6.54346 -0.0136247 0.0303467 0.0617017 0.99754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1391 1440 -0.946804 -12.1711 -6.28795 0.0186575 0.0307883 -0.0611311 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1391 1441 -0.201416 0.0100203 -6.29862 -0.00501283 0.0267313 0.000778807 0.99963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1391 1442 -0.958712 12.1757 -6.54593 -0.0116131 0.0402584 0.0592113 0.997366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1392 1441 -0.947179 -12.1855 -6.2905 0.00226581 0.0303767 -0.0512605 0.998221 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1392 1442 -0.188706 -0.00723031 -6.27806 -0.000261887 0.0276035 0.00434093 0.999609 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1392 1443 -0.937683 12.1429 -6.54458 -0.0130455 0.0340538 0.0609587 0.997474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1393 1442 -0.912881 -12.1704 -6.30328 0.00504626 0.025078 -0.0656606 0.997514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1393 1443 -0.200555 -0.024766 -6.27519 0.00305221 0.0341718 0.0131115 0.999325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1393 1444 -0.953283 12.1708 -6.53536 -0.0106792 0.0326831 0.0556048 0.997861 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1394 1443 -0.924992 -12.1488 -6.29256 0.009106 0.0316987 -0.0564316 0.997862 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1394 1444 -0.192452 -0.00451062 -6.28228 -0.000769314 0.0333618 -0.00129444 0.999442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1394 1445 -0.965724 12.1683 -6.54508 -0.0198964 0.0245571 0.0683364 0.997162 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1395 1444 -0.9494 -12.1672 -6.28091 0.0159726 0.0288436 -0.0668666 0.997217 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1395 1445 -0.182866 0.00771449 -6.28134 0.0004824 0.0248282 0.0100972 0.999641 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1395 1446 -0.967467 12.1483 -6.53609 -0.00889414 0.0276263 0.0568595 0.99796 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1396 1445 -0.935418 -12.1574 -6.29354 0.0124886 0.032399 -0.0631298 0.997401 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1396 1446 -0.195436 0.0064318 -6.2852 -0.000416989 0.0333444 -0.00401047 0.999436 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1396 1447 -0.946093 12.1543 -6.54677 -0.0123794 0.0338962 0.0617002 0.997442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1397 1446 -0.944646 -12.1539 -6.26241 0.0163146 0.0352263 -0.055703 0.997692 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1397 1447 -0.195027 0.00566008 -6.26853 -0.000190756 0.0373669 -0.00108601 0.999301 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1397 1448 -0.933382 12.1085 -6.53918 -0.0197944 0.0330969 0.0659468 0.997078 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1398 1447 -0.935698 -12.1592 -6.30518 0.00791005 0.0329316 -0.061066 0.997559 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1398 1448 -0.198806 0.00244182 -6.2886 0.00588505 0.0258396 -0.00936903 0.999605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1398 1449 -0.953465 12.1415 -6.56079 -0.0196709 0.0266289 0.0619904 0.997528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1399 1448 -0.937 -12.1307 -6.30728 0.0141089 0.037976 -0.0692259 0.996778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1399 1449 -0.20878 -0.00682713 -6.2636 0.00430088 0.0258749 -0.00648278 0.999635 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1399 1450 -0.946122 12.1316 -6.55399 -0.0242041 0.0305297 0.064411 0.997163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1400 1449 -0.932224 -12.1431 -6.3005 0.0252696 0.0282808 -0.0595843 0.997503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1400 1450 -0.197773 0.015443 -6.2912 0.00502362 0.0326275 0.000791429 0.999455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1400 1451 -0.94597 12.1342 -6.54137 -0.0115988 0.0315512 0.0638652 0.997392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1401 1450 -0.94484 -12.1379 -6.28942 0.0183909 0.0324282 -0.0632297 0.997302 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1401 1451 -0.185063 -0.00252781 -6.28628 0.006474 0.0323801 -0.00294969 0.99945 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1401 1452 -0.950922 12.1353 -6.55411 -0.0234898 0.0285842 0.0618609 0.997399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1402 1451 -0.933279 -12.1372 -6.29743 0.0196568 0.0355158 -0.0734627 0.996472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1402 1452 -0.18546 0.000217209 -6.27006 0.00321774 0.0312844 0.00248786 0.999502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1402 1453 -0.970808 12.1352 -6.54292 -0.00794107 0.0294196 0.0520874 0.998178 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1403 1452 -0.92722 -12.1199 -6.31264 0.0164233 0.0312798 -0.0600306 0.997571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1403 1453 -0.194261 0.0183749 -6.29383 -0.00509697 0.0254989 0.000303045 0.999662 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1403 1454 -0.958547 12.1166 -6.57302 -0.018478 0.0453021 0.0517029 0.997463 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1404 1453 -0.926726 -12.1295 -6.29821 0.0165797 0.0324275 -0.0478119 0.998192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1404 1454 -0.195332 -0.00779983 -6.25938 -0.00182036 0.0358017 -0.00581741 0.99934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1404 1455 -0.955394 12.1032 -6.54443 -0.0169199 0.0408984 0.0591691 0.997266 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1405 1454 -0.933438 -12.1209 -6.29433 0.0152133 0.0250871 -0.0593876 0.997804 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1405 1455 -0.188633 -0.0017876 -6.28855 0.00106802 0.038227 -0.00286042 0.999264 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1405 1456 -0.944247 12.1352 -6.54174 -0.0178708 0.0289895 0.0602845 0.9976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1406 1455 -0.928928 -12.102 -6.29469 0.013384 0.0422085 -0.0604278 0.99719 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1406 1456 -0.187328 0.0248112 -6.27398 -0.0047674 0.0356804 -0.000911047 0.999351 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1406 1457 -0.970048 12.1021 -6.57314 -0.0092331 0.0326713 0.0573597 0.997776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1407 1456 -0.938444 -12.0978 -6.30666 0.0100125 0.0332879 -0.0610479 0.997529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1407 1457 -0.201956 0.000692823 -6.28234 0.00142605 0.0309883 -0.0057369 0.999502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1407 1458 -0.951558 12.1059 -6.55999 -0.0110808 0.029373 0.0555701 0.997961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1408 1457 -0.95553 -12.115 -6.30195 0.0143971 0.0280298 -0.0596228 0.997723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1408 1458 -0.194893 0.00761952 -6.28176 -0.0012473 0.0283041 -0.00119347 0.999598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1408 1459 -0.934125 12.0968 -6.57411 -0.0223844 0.0328847 0.057352 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1409 1458 -0.922614 -12.0951 -6.32096 0.0197705 0.0251326 -0.054149 0.998021 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1409 1459 -0.192563 0.00479762 -6.27451 -0.00187258 0.0370178 -0.00752676 0.999285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1409 1460 -0.958278 12.115 -6.56981 -0.0090452 0.0306471 0.0567784 0.997875 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1410 1459 -0.93618 -12.0978 -6.32031 0.014226 0.0298643 -0.0628187 0.997477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1410 1460 -0.213863 -0.000761984 -6.2785 0.00162922 0.0333371 0.000293684 0.999443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1410 1461 -0.937232 12.1035 -6.54402 -0.012437 0.036727 0.0680057 0.996931 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1411 1460 -0.942886 -12.0908 -6.327 0.0288044 0.0300623 -0.0617587 0.997222 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1411 1461 -0.195376 -0.0183987 -6.28081 0.00620487 0.0274826 -0.00881121 0.999564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1411 1462 -0.933546 12.1074 -6.5461 -0.022656 0.0300205 0.069968 0.99684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1412 1461 -0.920903 -12.0972 -6.30407 0.00585519 0.0276352 -0.0731251 0.996923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1412 1462 -0.19742 0.0121909 -6.28123 -0.00442178 0.0235147 -0.0057053 0.999697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1412 1463 -0.961973 12.0775 -6.56884 -0.00624698 0.0388279 0.060382 0.9974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1413 1462 -0.91908 -12.096 -6.28556 0.0202167 0.0296943 -0.0609163 0.997496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1413 1463 -0.2049 -0.000329041 -6.282 -0.00575659 0.022274 0.00106509 0.999735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1413 1464 -0.952299 12.0867 -6.56217 -0.0102737 0.0275519 0.0607948 0.997717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1414 1463 -0.920109 -12.0745 -6.30122 0.0196823 0.0301709 -0.0611209 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1414 1464 -0.207232 0.00835685 -6.26248 0.00105287 0.029524 0.00386253 0.999556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1414 1465 -0.949848 12.0683 -6.57527 -0.013581 0.0327251 0.0675167 0.997089 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1415 1464 -0.936616 -12.0715 -6.33009 0.0176183 0.0230263 -0.0608767 0.997724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1415 1465 -0.216099 -0.0186117 -6.2835 -0.00290958 0.0311429 0.00608533 0.999492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1415 1466 -0.955673 12.0861 -6.5543 -0.0203906 0.0301799 0.0657442 0.997172 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1416 1465 -0.941036 -12.0538 -6.31521 0.018239 0.031148 -0.0590316 0.997603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1416 1466 -0.20241 0.0158093 -6.28574 0.000452476 0.0385954 0.00416328 0.999246 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1416 1467 -0.960817 12.0437 -6.56107 -0.0202847 0.0291059 0.0587015 0.997645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1417 1466 -0.944374 -12.0843 -6.3227 0.0128247 0.0297848 -0.0622923 0.997531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1417 1467 -0.196187 -0.0180209 -6.28552 0.00218462 0.0325029 0.0155978 0.999348 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1417 1468 -0.939576 12.0553 -6.57736 -0.024378 0.034617 0.0584026 0.997395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1418 1467 -0.944642 -12.0561 -6.32077 0.017928 0.0305826 -0.071131 0.996837 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1418 1468 -0.184248 0.00554263 -6.28886 -0.00127787 0.0353324 0.00648497 0.999354 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1418 1469 -0.942801 12.0619 -6.56902 -0.0238208 0.0325658 0.0697483 0.996748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1419 1468 -0.931003 -12.0455 -6.31188 0.0211768 0.0281728 -0.0584628 0.997667 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1419 1469 -0.18547 0.00167832 -6.27743 0.00355048 0.0320366 -0.00413378 0.999472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1419 1470 -0.945483 12.0237 -6.55001 -0.0167507 0.0362938 0.0615432 0.997304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1420 1469 -0.93371 -12.0546 -6.30816 0.0192178 0.0306089 -0.0594652 0.997576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1420 1470 -0.184824 0.023191 -6.2832 0.000942034 0.0250972 0.00266535 0.999681 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1420 1471 -0.935222 12.0386 -6.5717 -0.0225638 0.0312388 0.0673679 0.996984 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1421 1470 -0.903402 -12.0498 -6.31295 0.0178924 0.0227627 -0.0637626 0.997545 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1421 1471 -0.183011 0.00425092 -6.28977 0.00721918 0.0298935 -0.00774161 0.999497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1421 1472 -0.948618 12.0341 -6.5555 -0.013035 0.0373176 0.057355 0.997571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1422 1471 -0.922143 -12.0344 -6.34409 0.00947156 0.0333553 -0.061881 0.997481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1422 1472 -0.199686 0.00595727 -6.26773 -0.00165876 0.0258155 -0.0010699 0.999665 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1422 1473 -0.947426 12.0424 -6.56491 -0.0107123 0.0239446 0.0566519 0.998049 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1423 1472 -0.937265 -12.0499 -6.32763 0.00904189 0.0275173 -0.0634071 0.997567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1423 1473 -0.20584 0.00419891 -6.28467 -0.00201799 0.0318651 -0.00307425 0.999485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1423 1474 -0.941569 12.0219 -6.57689 -0.0184462 0.0360459 0.0583797 0.997473 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1424 1473 -0.93216 -12.0447 -6.29139 0.0171415 0.0352155 -0.0685691 0.996877 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1424 1474 -0.22442 -0.0108827 -6.27731 -0.00413907 0.0270173 -0.00327058 0.999621 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1424 1475 -0.936703 12.0339 -6.58339 -0.0134914 0.0274722 0.0604759 0.9977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1425 1474 -0.927707 -12.0323 -6.30959 0.0186898 0.0307844 -0.0596091 0.997572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1425 1475 -0.205358 0.000912328 -6.27519 0.00439032 0.0327242 -0.00449948 0.999445 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1425 1476 -0.923284 12.0425 -6.57404 -0.00656513 0.027478 0.0558122 0.998042 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1426 1475 -0.933608 -12.0288 -6.33058 0.0154946 0.0334969 -0.0721993 0.996707 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1426 1476 -0.195092 0.0104654 -6.27812 -0.00809421 0.0333863 -0.010242 0.999357 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1426 1477 -0.9324 12.0414 -6.56393 -0.0163759 0.0270984 0.0620721 0.997569 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1427 1476 -0.930668 -12.007 -6.30635 0.00934004 0.0260013 -0.0617548 0.997709 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1427 1477 -0.187415 -0.00539506 -6.28212 0.00346947 0.036435 -0.00316148 0.999325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1427 1478 -0.950871 12.0067 -6.569 -0.0153975 0.0318959 0.0608283 0.99752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1428 1477 -0.935112 -12.0184 -6.31863 0.0184131 0.0336132 -0.0615388 0.997369 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1428 1478 -0.197472 0.000890624 -6.28494 -0.00182398 0.0224372 -0.000458264 0.999746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1428 1479 -0.948391 12.0055 -6.57549 -0.0165102 0.0316604 0.0514535 0.998037 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1429 1478 -0.927438 -12.0179 -6.31882 0.0217417 0.0344743 -0.0576133 0.997507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1429 1479 -0.197855 0.00461695 -6.27331 0.00681213 0.0259713 0.0013892 0.999639 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1429 1480 -0.929153 12.0028 -6.57172 -0.0130116 0.0297363 0.058706 0.997747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1430 1479 -0.931405 -12.0147 -6.32378 0.0187022 0.0368701 -0.0630756 0.997152 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1430 1480 -0.198104 -0.00153987 -6.28171 -0.00232152 0.0345406 -0.00715793 0.999375 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1430 1481 -0.934898 12.0086 -6.57967 -0.0135592 0.0341402 0.0627224 0.997355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1431 1480 -0.924254 -12.0053 -6.32856 0.00987557 0.0335039 -0.0635059 0.99737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1431 1481 -0.224539 -0.0014872 -6.27617 0.00906584 0.0341623 0.00276713 0.999371 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1431 1482 -0.922545 11.9869 -6.57342 -0.0108705 0.0385439 0.058815 0.997465 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1432 1481 -0.935756 -11.9951 -6.33499 0.00564295 0.0286974 -0.060989 0.99771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1432 1482 -0.198666 -0.0020222 -6.25316 0.00274793 0.0191456 -0.0038379 0.999806 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1432 1483 -0.927002 11.9934 -6.56137 -0.0164084 0.0293933 0.0650576 0.997314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1433 1482 -0.93861 -12.0048 -6.32751 0.0111704 0.0283573 -0.0657209 0.997372 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1433 1483 -0.165056 -0.00410439 -6.2906 -0.000671105 0.026054 0.00230416 0.999658 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1433 1484 -0.942389 11.9989 -6.57424 -0.00664094 0.038281 0.0611134 0.997374 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1434 1483 -0.931345 -11.9973 -6.33653 0.0248123 0.0353085 -0.0673952 0.996793 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1434 1484 -0.20123 -0.000872149 -6.27074 -0.00240913 0.0265239 -0.0106417 0.999589 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1434 1485 -0.94445 11.9817 -6.59157 -0.0220374 0.0271415 0.0669349 0.997145 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1435 1484 -0.922455 -11.9811 -6.32614 0.0127549 0.0268822 -0.0667278 0.997327 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1435 1485 -0.203505 0.00177823 -6.2718 -0.00138418 0.0239178 -0.00209697 0.999711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1435 1486 -0.919408 11.9808 -6.58741 -0.0154895 0.0313154 0.0560171 0.997818 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1436 1485 -0.924296 -11.98 -6.34653 0.0106387 0.0289581 -0.0670282 0.997274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1436 1486 -0.194834 0.00329269 -6.27319 -0.00296728 0.0273683 0.00387163 0.999614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1436 1487 -0.937102 11.9677 -6.57678 -0.0163846 0.0331809 0.0597335 0.997528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1437 1486 -0.941789 -11.9961 -6.33314 0.00552587 0.0311139 -0.0602254 0.997684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1437 1487 -0.196919 0.00177987 -6.2811 0.00338302 0.0276937 0.00592791 0.999593 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1437 1488 -0.934237 11.9599 -6.57432 -0.0139225 0.0253428 0.0540204 0.998121 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1438 1487 -0.909233 -11.98 -6.315 0.0175347 0.0209147 -0.062183 0.997692 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1438 1488 -0.204535 -0.0105782 -6.27645 -0.00104242 0.0324913 0.00283469 0.999467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1438 1489 -0.93809 11.975 -6.56337 -0.0198756 0.0275684 0.0651903 0.997294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1439 1488 -0.900546 -11.9669 -6.34011 0.00342509 0.0407622 -0.0618193 0.997249 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1439 1489 -0.190694 -0.0178708 -6.26713 0.004301 0.0333694 0.00105161 0.999433 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1439 1490 -0.922174 11.9478 -6.58339 -0.0247352 0.0239997 0.0564869 0.997808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1440 1489 -0.930366 -11.9638 -6.33413 0.0209405 0.0293949 -0.060282 0.997529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1440 1490 -0.188603 -0.0096684 -6.27485 0.00741024 0.0290803 0.0103083 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1440 1491 -0.944963 11.9573 -6.57248 -0.0172232 0.0287472 0.052605 0.998053 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1441 1490 -0.915173 -11.9488 -6.33961 0.0173025 0.032726 -0.0568005 0.997699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1441 1491 -0.2001 -0.00903333 -6.27033 -0.00343352 0.035589 0.00693273 0.999337 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1441 1492 -0.926559 11.961 -6.60817 -0.0142573 0.0338327 0.0618653 0.997409 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1442 1491 -0.898262 -11.9624 -6.31794 0.0171371 0.0242268 -0.0639522 0.997512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1442 1492 -0.192929 0.00597901 -6.29524 0.00106554 0.0416516 0.00825037 0.999098 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1442 1493 -0.912966 11.9472 -6.58486 -0.018297 0.028235 0.0596707 0.997651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1443 1492 -0.930077 -11.9621 -6.32478 0.0180006 0.0285359 -0.0628612 0.997452 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1443 1493 -0.186402 0.000928611 -6.26403 -0.00993955 0.0274429 -0.00366916 0.999567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1443 1494 -0.935125 11.9457 -6.60355 -0.0141473 0.0298499 0.0543979 0.997973 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1444 1493 -0.918049 -11.9557 -6.34963 0.0146451 0.0273297 -0.0581326 0.997827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1444 1494 -0.189968 0.00035199 -6.30056 0.00169683 0.0294343 -0.00130313 0.999564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1444 1495 -0.943446 11.944 -6.58169 -0.00814164 0.0263775 0.0578717 0.997942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1445 1494 -0.934419 -11.9269 -6.35713 0.0261229 0.0252732 -0.0638495 0.997297 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1445 1495 -0.18921 0.00166837 -6.29505 0.000152612 0.0268736 -0.00632511 0.999619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1445 1496 -0.933466 11.9248 -6.58928 -0.0208924 0.036591 0.0661234 0.996921 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1446 1495 -0.911322 -11.9442 -6.33104 0.0202352 0.0319104 -0.0541341 0.997819 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1446 1496 -0.19051 -0.00655636 -6.28137 -0.000494556 0.0249443 -0.0037981 0.999682 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1446 1497 -0.922676 11.9432 -6.58749 -0.022946 0.040739 0.0590399 0.99716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1447 1496 -0.934154 -11.9296 -6.31679 0.0211468 0.0345079 -0.054221 0.997708 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1447 1497 -0.203088 0.000774209 -6.29772 -0.00674207 0.0276576 0.00403529 0.999587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1447 1498 -0.928378 11.9178 -6.59535 -0.020868 0.0261139 0.0579443 0.99776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1448 1497 -0.92082 -11.929 -6.34944 0.0226209 0.0385124 -0.0625689 0.997041 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1448 1498 -0.191195 -0.00410734 -6.29241 0.00496439 0.0355928 0.00162124 0.999353 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1448 1499 -0.943395 11.9218 -6.59299 -0.0253979 0.0399492 0.0650729 0.996757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1449 1498 -0.904935 -11.9456 -6.32291 0.0173269 0.0420319 -0.0461195 0.997901 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1449 1499 -0.205158 0.00341561 -6.28413 -0.00180357 0.033969 0.00649174 0.9994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1449 1500 -0.955933 11.9089 -6.60284 -0.00846589 0.0321465 0.0661708 0.997254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1450 1499 -0.922096 -11.9215 -6.33581 0.016485 0.0200591 -0.052212 0.998298 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1450 1500 -0.167561 0.00566735 -6.28357 0.00200134 0.0263529 -0.00576673 0.999634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1450 1501 -0.944689 11.9005 -6.58845 -0.0150998 0.0337333 0.0553507 0.997783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1451 1500 -0.914795 -11.9214 -6.33855 0.0143289 0.0308877 -0.0563125 0.997832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1451 1501 -0.204239 -0.00925824 -6.27416 0.00634829 0.0403329 0.00760724 0.999137 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1451 1502 -0.931804 11.9322 -6.59689 -0.0203442 0.031774 0.0558484 0.997726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1452 1501 -0.913902 -11.9081 -6.34568 0.0164477 0.0274062 -0.0474699 0.998361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1452 1502 -0.211812 0.00765993 -6.26642 0.00389182 0.0296915 -0.0072048 0.999526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1452 1503 -0.926655 11.8917 -6.60475 -0.0151806 0.0235118 0.0549923 0.998094 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1453 1502 -0.920655 -11.8988 -6.33445 0.0190313 0.030545 -0.0534247 0.997923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1453 1503 -0.204586 0.0112002 -6.27722 -0.00295622 0.040187 -0.00244124 0.999185 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1453 1504 -0.928819 11.8819 -6.58918 -0.0166903 0.0320855 0.0643504 0.997272 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1454 1503 -0.906982 -11.896 -6.33614 0.00886635 0.0346907 -0.0597642 0.99757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1454 1504 -0.205913 -0.00424323 -6.26168 0.00194942 0.0285955 0.00344957 0.999583 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1454 1505 -0.91926 11.8954 -6.58522 -0.0160355 0.0199167 0.0609048 0.997816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1455 1504 -0.90052 -11.8895 -6.34765 0.0228571 0.0349121 -0.0600023 0.997326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1455 1505 -0.193047 -0.00920357 -6.29065 0.00193764 0.0373852 -0.00640078 0.999279 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1455 1506 -0.925975 11.8876 -6.59493 -0.0268332 0.0328726 0.0594707 0.997328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1456 1505 -0.90132 -11.8886 -6.34977 0.01793 0.0219345 -0.0582103 0.997902 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1456 1506 -0.194099 0.00212714 -6.28354 0.00222447 0.0377583 0.00652747 0.999263 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1456 1507 -0.928455 11.8782 -6.59049 -0.0196139 0.0340702 0.0586273 0.997506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1457 1506 -0.934183 -11.8823 -6.35478 0.0149964 0.0327558 -0.0516827 0.998014 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1457 1507 -0.201542 0.00366646 -6.26458 0.00493276 0.0282243 0.000221337 0.999589 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1457 1508 -0.939529 11.8788 -6.60451 -0.014048 0.0312178 0.0602132 0.997598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1458 1507 -0.90904 -11.886 -6.3593 0.020391 0.0257095 -0.0597223 0.997676 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1458 1508 -0.1906 -0.0187204 -6.2843 -0.00735192 0.0330049 0.00218859 0.999426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1458 1509 -0.932184 11.8667 -6.593 -0.0236603 0.0331919 0.0645381 0.997082 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1459 1508 -0.906818 -11.8851 -6.33357 0.0139684 0.02909 -0.0676287 0.997189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1459 1509 -0.192679 0.00597146 -6.2845 -0.0057731 0.0257198 -0.00637258 0.999632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1459 1510 -0.931844 11.8643 -6.59485 -0.0227697 0.0271615 0.0644885 0.997289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1460 1509 -0.896882 -11.8625 -6.34469 0.0199335 0.0268066 -0.0671099 0.997186 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1460 1510 -0.208442 -0.0110364 -6.27819 -0.00493657 0.0221986 0.00185735 0.99974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1460 1511 -0.920366 11.8492 -6.59371 -0.0224062 0.0265812 0.0621816 0.997459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1461 1510 -0.901112 -11.8745 -6.33502 0.0150078 0.0334318 -0.0708099 0.996816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1461 1511 -0.211107 0.00844842 -6.27759 -0.00340348 0.0285173 0.0160234 0.999459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1461 1512 -0.912011 11.875 -6.60267 -0.0126469 0.0352253 0.0564759 0.997702 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1462 1511 -0.91017 -11.8673 -6.34532 0.0207566 0.0293871 -0.0598576 0.997558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1462 1512 -0.18737 -0.00363899 -6.27587 0.00192928 0.0360456 -0.00578934 0.999332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1462 1513 -0.927472 11.8462 -6.61402 -0.0212122 0.0447298 0.0669574 0.996527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1463 1512 -0.910546 -11.8495 -6.34336 0.0148813 0.0367464 -0.0610256 0.997349 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1463 1513 -0.207383 -0.0123435 -6.28174 -0.00381856 0.0382955 0.00619171 0.99924 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1463 1514 -0.923275 11.86 -6.58979 -0.0193223 0.0329679 0.0679784 0.996955 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1464 1513 -0.908189 -11.8719 -6.35631 0.0136573 0.0301213 -0.0594084 0.997686 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1464 1514 -0.1891 0.0164517 -6.29186 -0.00589125 0.0344907 0.00944817 0.999343 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1464 1515 -0.92264 11.8294 -6.59861 -0.0148208 0.0246772 0.0588454 0.997852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1465 1514 -0.902577 -11.8455 -6.36184 0.0170441 0.0381823 -0.0660324 0.996941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1465 1515 -0.209344 -0.00139154 -6.2758 0.0035284 0.0299013 -0.00144639 0.999546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1465 1516 -0.923334 11.823 -6.59105 -0.0137933 0.0307249 0.0651008 0.99731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1466 1515 -0.913218 -11.8285 -6.35498 0.0173776 0.03286 -0.0640689 0.997253 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1466 1516 -0.21048 -0.00156685 -6.2937 -0.00427009 0.0184991 0.00648635 0.999799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1466 1517 -0.922466 11.8341 -6.59163 -0.0158266 0.040805 0.0621108 0.997109 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1467 1516 -0.90583 -11.8262 -6.36871 0.0149022 0.0410462 -0.0650378 0.996927 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1467 1517 -0.202457 0.00256537 -6.27918 -0.00217012 0.0271181 -0.000633863 0.99963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1467 1518 -0.925583 11.8215 -6.60067 -0.0174372 0.0345951 0.0596356 0.997468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1468 1517 -0.895154 -11.8318 -6.35603 0.0167266 0.0243772 -0.0552529 0.998035 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1468 1518 -0.207165 0.00199647 -6.27284 0.00652329 0.0372603 0.00377636 0.999277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1468 1519 -0.929173 11.838 -6.59375 -0.0196739 0.0291193 0.0608243 0.99753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1469 1518 -0.916986 -11.8295 -6.35632 0.0104506 0.0288058 -0.0528956 0.99813 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1469 1519 -0.199484 -0.0061021 -6.29258 0.00890886 0.0315859 -0.00520993 0.999448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1469 1520 -0.921909 11.8117 -6.61985 -0.0214395 0.0287238 0.0627026 0.997388 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1470 1519 -0.893753 -11.827 -6.35804 0.0268566 0.0351285 -0.0569671 0.997396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1470 1520 -0.202821 0.00842745 -6.28212 -0.00571149 0.0202908 -0.0083346 0.999743 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1470 1521 -0.911722 11.8221 -6.59833 -0.0173472 0.0289408 0.0564041 0.997838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1471 1520 -0.905437 -11.8089 -6.35393 0.0215107 0.0251251 -0.0626287 0.997489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1471 1521 -0.192839 0.00122015 -6.28951 -0.000443466 0.0290342 0.000875316 0.999578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1471 1522 -0.914486 11.82 -6.62907 -0.0169355 0.0305414 0.0553049 0.997859 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1472 1521 -0.894178 -11.8241 -6.36555 0.0257233 0.0295322 -0.054425 0.99775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1472 1522 -0.203788 -0.00937305 -6.28794 0.000526087 0.0365246 0.0115459 0.999266 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1472 1523 -0.926476 11.7918 -6.62282 -0.0256164 0.0319629 0.0586166 0.99744 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1473 1522 -0.894929 -11.8257 -6.36321 0.0209092 0.0248178 -0.0605474 0.997638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1473 1523 -0.175161 -0.0040005 -6.27809 -0.00212544 0.0340837 0.00337259 0.999411 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1473 1524 -0.928099 11.7883 -6.62907 -0.0217366 0.0331923 0.06204 0.997285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1474 1523 -0.908374 -11.8012 -6.35876 0.0191653 0.0274655 -0.0684083 0.997095 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1474 1524 -0.207396 0.0112387 -6.27474 0.00152097 0.0352852 -0.00452109 0.999366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1474 1525 -0.911077 11.7745 -6.61136 -0.0263698 0.0304523 0.0586118 0.997468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1475 1524 -0.896209 -11.782 -6.35964 0.0181839 0.0308803 -0.0616605 0.997454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1475 1525 -0.211409 -0.0225507 -6.29411 -0.00523181 0.036364 -0.00342895 0.999319 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1475 1526 -0.916424 11.7768 -6.62906 -0.0265733 0.0365029 0.0539336 0.997523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1476 1525 -0.916223 -11.7846 -6.39018 0.0156217 0.0342507 -0.0618683 0.997374 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1476 1526 -0.205772 -0.00617951 -6.27687 0.000861822 0.0340653 -0.00320642 0.999414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1476 1527 -0.929705 11.7762 -6.61375 -0.029083 0.0251251 0.060274 0.997442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1477 1526 -0.911107 -11.7882 -6.34514 0.0148611 0.0327417 -0.0639961 0.997302 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1477 1527 -0.221896 -0.0123571 -6.28454 -0.0061514 0.0262839 0.00145752 0.999635 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1477 1528 -0.928797 11.7638 -6.59019 -0.02536 0.0288809 0.0489434 0.998062 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1478 1527 -0.914981 -11.7607 -6.36554 0.0181005 0.0256181 -0.0662034 0.997313 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1478 1528 -0.190846 -0.00548588 -6.29813 -0.00638465 0.0329454 -0.00661127 0.999415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1478 1529 -0.922177 11.7598 -6.62013 -0.022133 0.0342552 0.0636993 0.997135 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1479 1528 -0.890346 -11.7649 -6.35781 0.0197122 0.0338357 -0.0570215 0.997605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1479 1529 -0.184974 -0.000883613 -6.26059 -0.00218324 0.0248706 -0.0112095 0.999625 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1479 1530 -0.924108 11.758 -6.61077 -0.0201105 0.0263361 0.0595221 0.997677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1480 1529 -0.905205 -11.7621 -6.3705 0.0120823 0.0287715 -0.0584928 0.9978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1480 1530 -0.193374 -0.0101754 -6.27348 -0.000631086 0.032605 0.0109012 0.999409 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1480 1531 -0.899107 11.7687 -6.62171 -0.0242456 0.0301793 0.0576226 0.997588 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1481 1530 -0.908107 -11.7587 -6.38398 0.0224961 0.0311946 -0.0562706 0.997675 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1481 1531 -0.18963 0.00260268 -6.2764 -0.000955483 0.0378244 -0.00685148 0.99926 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1481 1532 -0.910783 11.7697 -6.61536 -0.0276269 0.0392839 0.0646765 0.99675 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1482 1531 -0.909403 -11.7738 -6.36103 0.017132 0.0273078 -0.0583342 0.997776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1482 1532 -0.202044 0.000993596 -6.28922 0.00379517 0.0237376 0.00933494 0.999667 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1482 1533 -0.894329 11.7544 -6.61422 -0.0159083 0.0345887 0.0685692 0.99692 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1483 1532 -0.884045 -11.7401 -6.37827 0.0278092 0.0335621 -0.0533956 0.997622 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1483 1533 -0.203376 0.00268305 -6.27934 0.00602081 0.0289675 -0.00329585 0.999557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1483 1534 -0.90567 11.7229 -6.61247 -0.0200048 0.0269887 0.0623605 0.997488 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1484 1533 -0.893979 -11.7384 -6.36808 0.0226547 0.0238009 -0.0656854 0.997299 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1484 1534 -0.20234 0.0101634 -6.27393 -0.00164584 0.0320689 0.00374935 0.999477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1484 1535 -0.913492 11.727 -6.62206 -0.0232668 0.0284189 0.0586233 0.997604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1485 1534 -0.914465 -11.7352 -6.36425 0.0267529 0.0405753 -0.053467 0.997386 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1485 1535 -0.201302 0.0169858 -6.26835 -0.000269334 0.0288225 -0.00223219 0.999582 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1485 1536 -0.909741 11.708 -6.60878 -0.027076 0.0360003 0.0564603 0.997388 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1486 1535 -0.91357 -11.7335 -6.36317 0.0172687 0.0304585 -0.0665341 0.99717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1486 1536 -0.209972 -0.0077861 -6.26792 0.00414869 0.0336248 -0.00450624 0.999416 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1486 1537 -0.910118 11.7336 -6.59992 -0.028154 0.0390564 0.057953 0.997158 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1487 1536 -0.888305 -11.7121 -6.37854 0.0232065 0.041013 -0.0529655 0.997484 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1487 1537 -0.193148 -0.00301021 -6.27403 0.00217398 0.031919 0.00649915 0.999467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1487 1538 -0.901392 11.7372 -6.62763 -0.0169407 0.0432164 0.0530903 0.99751 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1488 1537 -0.903586 -11.7153 -6.36993 0.023983 0.0340268 -0.0481803 0.997971 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1488 1538 -0.200506 0.00933451 -6.29328 0.00441066 0.0359407 0.00483561 0.999332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1488 1539 -0.916103 11.6944 -6.6152 -0.00843766 0.0326722 0.0654673 0.997284 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1489 1538 -0.896837 -11.7251 -6.37569 0.0143641 0.0336698 -0.0624957 0.997374 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1489 1539 -0.208402 -0.00327997 -6.26976 -0.000316589 0.0278071 0.0045402 0.999603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1489 1540 -0.928224 11.7236 -6.62133 -0.0235193 0.0212951 0.0632472 0.997493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1490 1539 -0.902741 -11.7066 -6.37685 0.020971 0.032637 -0.0555057 0.997704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1490 1540 -0.189711 -0.0254891 -6.27634 -0.00405243 0.0215049 0.00590404 0.999743 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1490 1541 -0.890764 11.7099 -6.6144 -0.0261706 0.0418417 0.0631339 0.996784 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1491 1540 -0.896311 -11.695 -6.389 0.0203551 0.0186666 -0.0532293 0.9982 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1491 1541 -0.198602 -0.00228627 -6.28527 0.00618183 0.0228178 0.00283408 0.999717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1491 1542 -0.912093 11.6745 -6.62493 -0.0294119 0.0366936 0.0601091 0.997083 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1492 1541 -0.897783 -11.6946 -6.36362 0.0162957 0.0246259 -0.053059 0.998155 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1492 1542 -0.199764 0.00851316 -6.28506 -0.000804932 0.0246218 -0.00196491 0.999695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1492 1543 -0.893491 11.6837 -6.61939 -0.0163721 0.0276067 0.0613578 0.9976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1493 1542 -0.884033 -11.6976 -6.38751 0.0244775 0.0306225 -0.0665821 0.99701 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1493 1543 -0.198605 0.00267055 -6.27839 0.00697717 0.0274999 -0.00798952 0.999566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1493 1544 -0.912925 11.6941 -6.62374 -0.00828939 0.033316 0.054648 0.997915 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1494 1543 -0.895838 -11.6921 -6.38708 0.0192815 0.0339276 -0.0534929 0.997805 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1494 1544 -0.195441 0.00649597 -6.25726 -0.000811814 0.0265953 -0.0141111 0.999546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1494 1545 -0.904507 11.6777 -6.62548 -0.0192967 0.033692 0.0533287 0.997822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1495 1544 -0.899375 -11.6993 -6.38653 0.0171648 0.0315651 -0.0596852 0.99757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1495 1545 -0.20165 -0.0156189 -6.28728 -0.00457297 0.0262542 0.00240314 0.999642 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1495 1546 -0.897307 11.6802 -6.63311 -0.0217653 0.0261175 0.0603418 0.997599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1496 1545 -0.887919 -11.6832 -6.37557 0.0169016 0.0357368 -0.0519539 0.997867 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1496 1546 -0.187639 -0.0114494 -6.27794 -0.00209563 0.0277128 -0.00460692 0.999603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1496 1547 -0.897291 11.6583 -6.62847 -0.0202852 0.0315222 0.0571338 0.997663 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1497 1546 -0.909333 -11.6671 -6.38383 0.0249563 0.0317746 -0.0637889 0.997145 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1497 1547 -0.181432 -0.00284372 -6.28966 0.0016256 0.0288403 0.00798906 0.999551 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1497 1548 -0.889115 11.6548 -6.61557 -0.0148952 0.0267319 0.0499257 0.998284 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1498 1547 -0.890464 -11.6485 -6.37324 0.0183681 0.03561 -0.0568183 0.99758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1498 1548 -0.194259 0.0111682 -6.26843 0.00305277 0.0296062 0.0033139 0.999551 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1498 1549 -0.891839 11.648 -6.62573 -0.0171668 0.0370664 0.0581837 0.99747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1499 1548 -0.888653 -11.6557 -6.38208 0.0139328 0.028789 -0.0649146 0.997378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1499 1549 -0.184367 -0.00692722 -6.27316 0.000734764 0.0340684 -0.00102428 0.999419 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1499 1550 -0.896974 11.6473 -6.63253 -0.0295657 0.030573 0.0605028 0.997262 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1500 1549 -0.877473 -11.6594 -6.37617 0.0259497 0.0287583 -0.0654081 0.997106 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1500 1550 -0.182572 -0.0096184 -6.28151 -0.00973875 0.0242037 -0.00115725 0.999659 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1500 1551 -0.900955 11.6533 -6.63677 -0.0231916 0.0377885 0.056053 0.997443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1501 1550 -0.899387 -11.6365 -6.38306 0.0306123 0.0278709 -0.063551 0.99712 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1501 1551 -0.185359 0.00811291 -6.29669 0.00209841 0.0372498 -0.000788529 0.999303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1501 1552 -0.888144 11.624 -6.62522 -0.0190111 0.0381476 0.0620611 0.997162 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1502 1551 -0.894113 -11.6398 -6.38177 0.0286126 0.0267054 -0.0566659 0.997626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1502 1552 -0.206334 0.00256244 -6.28321 -0.00485573 0.0321707 0.00470219 0.99946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1502 1553 -0.910516 11.6375 -6.63213 -0.0229315 0.0341123 0.0609622 0.997293 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1503 1552 -0.898641 -11.6451 -6.36528 0.0180527 0.0321715 -0.0623365 0.997373 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1503 1553 -0.204622 -0.0149645 -6.2769 0.00112706 0.0355364 0.00175177 0.999366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1503 1554 -0.915784 11.6275 -6.63499 -0.0278861 0.0255764 0.0565255 0.997684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1504 1553 -0.8683 -11.6366 -6.4006 0.0201983 0.0279827 -0.060803 0.997553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1504 1554 -0.188528 -0.0088706 -6.27369 0.000916377 0.0333715 -0.00340046 0.999437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1504 1555 -0.904121 11.6359 -6.60861 -0.0159613 0.025881 0.0630494 0.997547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1505 1554 -0.882634 -11.6175 -6.3869 0.0179057 0.0187073 -0.0536199 0.998226 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1505 1555 -0.205101 -0.00402259 -6.27154 0.00658312 0.0356237 -0.00071858 0.999343 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1505 1556 -0.903655 11.6143 -6.64444 -0.0261851 0.039326 0.0560505 0.997309 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1506 1555 -0.879182 -11.6182 -6.36555 0.0151278 0.0307795 -0.0606045 0.997572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1506 1556 -0.184678 0.00329589 -6.28303 0.00440539 0.0265756 0.00913069 0.999595 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1506 1557 -0.895546 11.604 -6.63931 -0.0294029 0.0250982 0.0637991 0.997214 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1507 1556 -0.869824 -11.6207 -6.401 0.0184139 0.0315128 -0.05098 0.998033 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1507 1557 -0.188956 0.0182493 -6.28796 -0.00488966 0.0340665 -0.00500536 0.999395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1507 1558 -0.901475 11.6122 -6.64059 -0.0286395 0.0271184 0.0586431 0.9975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1508 1557 -0.896359 -11.5982 -6.41008 0.0305549 0.0316073 -0.0590813 0.997285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1508 1558 -0.196086 -0.020974 -6.28925 0.0123419 0.0277462 0.00543632 0.999524 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1508 1559 -0.89786 11.6026 -6.63689 -0.0268573 0.029942 0.0613912 0.997303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1509 1558 -0.882902 -11.6089 -6.39524 0.0280983 0.0254616 -0.0547282 0.997781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1509 1559 -0.208848 0.00278322 -6.27367 -0.00102921 0.0403759 0.0107903 0.999126 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1509 1560 -0.890054 11.5866 -6.64724 -0.0238152 0.0369443 0.0529223 0.997631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1510 1559 -0.881461 -11.6038 -6.37798 0.0153073 0.0371189 -0.065092 0.997071 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1510 1560 -0.20303 0.0082995 -6.28456 0.00783096 0.0324889 0.00213484 0.999439 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1510 1561 -0.900302 11.5718 -6.62906 -0.0289936 0.0353187 0.0605425 0.997119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1511 1560 -0.880369 -11.5794 -6.40922 0.021446 0.0276502 -0.0588711 0.997652 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1511 1561 -0.193847 -0.00495501 -6.27911 -0.00586031 0.044189 0.002105 0.999004 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1511 1562 -0.890825 11.5743 -6.65605 -0.0225317 0.0284813 0.0555073 0.997798 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1512 1561 -0.885975 -11.5857 -6.39001 0.0200106 0.0303228 -0.0689846 0.996956 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1512 1562 -0.196339 -0.00690282 -6.25593 -0.00682193 0.0240792 0.00176915 0.999685 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1512 1563 -0.882343 11.5682 -6.63503 -0.0340601 0.0239886 0.0656653 0.996972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1513 1562 -0.878209 -11.572 -6.39467 0.0264293 0.0366072 -0.0710461 0.996451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1513 1563 -0.194266 -0.00831866 -6.28469 -0.000889118 0.0429405 -0.00619433 0.999058 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1513 1564 -0.892044 11.5531 -6.6421 -0.0183137 0.0290936 0.0607969 0.997558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1514 1563 -0.879026 -11.5604 -6.38022 0.0206316 0.0410904 -0.0717451 0.996363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1514 1564 -0.187643 -0.00219875 -6.28378 -0.00121645 0.0335819 -0.000183964 0.999435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1514 1565 -0.885661 11.5506 -6.67096 -0.0323275 0.0270716 0.0549164 0.9976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1515 1564 -0.865076 -11.5675 -6.38817 0.0143175 0.0305826 -0.0564405 0.997835 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1515 1565 -0.196412 0.00211949 -6.29042 0.00152662 0.0333294 0.000548029 0.999443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1515 1566 -0.884461 11.5376 -6.63071 -0.0294331 0.0355999 0.0596581 0.99715 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1516 1565 -0.884701 -11.5487 -6.39226 0.016348 0.0266075 -0.0637206 0.997479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1516 1566 -0.183533 0.00649034 -6.27631 0.00172556 0.0343061 0.001846 0.999408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1516 1567 -0.895157 11.5403 -6.65027 -0.019366 0.0309774 0.0584056 0.997624 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1517 1566 -0.865223 -11.5653 -6.3998 0.0150688 0.0231082 -0.0473893 0.998495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1517 1567 -0.19289 3.65723e-05 -6.28127 0.00201494 0.0331045 0.00435453 0.99944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1517 1568 -0.872603 11.5416 -6.64757 -0.0159945 0.0241202 0.0597798 0.997792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1518 1567 -0.876747 -11.5295 -6.40963 0.0219263 0.0230791 -0.0613485 0.997609 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1518 1568 -0.189926 -0.00106208 -6.26488 0.0023539 0.0342854 0.0044917 0.999399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1518 1569 -0.879963 11.5429 -6.64964 -0.0201262 0.0231296 0.0604006 0.997703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1519 1568 -0.872098 -11.5405 -6.38126 0.0214976 0.0288005 -0.0684934 0.997004 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1519 1569 -0.198237 0.00351524 -6.28124 0.0107405 0.0370658 -0.00905455 0.999214 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1519 1570 -0.877317 11.5203 -6.63554 -0.0218326 0.0259052 0.0490183 0.998223 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1520 1569 -0.871826 -11.5342 -6.4034 0.0141809 0.0278267 -0.0612395 0.997634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1520 1570 -0.206933 -0.0201323 -6.28759 -0.00384896 0.0314625 -0.00277174 0.999494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1520 1571 -0.906581 11.5078 -6.6562 -0.0264038 0.0295211 0.0505278 0.997937 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1521 1570 -0.881176 -11.5193 -6.40595 0.0239889 0.0285444 -0.056545 0.997704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1521 1571 -0.195257 -0.0102583 -6.27642 0.00266854 0.0363309 -0.00614809 0.999317 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1521 1572 -0.894767 11.5209 -6.6363 -0.0246496 0.034066 0.0543701 0.997635 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1522 1571 -0.857768 -11.5168 -6.39947 0.0158759 0.0289489 -0.0648044 0.997352 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1522 1572 -0.199595 -0.00394425 -6.2898 0.00151073 0.0325191 -0.00394512 0.999462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1522 1573 -0.903023 11.5346 -6.64079 -0.0319282 0.0430883 0.0647886 0.996457 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1523 1572 -0.856106 -11.5188 -6.39173 0.0195699 0.0322915 -0.0514394 0.997962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1523 1573 -0.189451 0.00833646 -6.29071 0.00484994 0.0347902 0.00239538 0.99938 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1523 1574 -0.891038 11.5042 -6.65808 -0.0253158 0.0260099 0.0672223 0.997078 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1524 1573 -0.867094 -11.5196 -6.39003 0.0220422 0.0304694 -0.0493207 0.998075 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1524 1574 -0.210399 -0.0101193 -6.28806 -0.00122939 0.0375067 -2.85291e-05 0.999296 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1524 1575 -0.871504 11.4925 -6.6683 -0.0306502 0.0327196 0.0534669 0.997563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1525 1574 -0.867829 -11.4989 -6.40699 0.0215807 0.0331077 -0.0550291 0.997702 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1525 1575 -0.187826 0.00454403 -6.2758 0.00262039 0.0402009 -0.000806949 0.999188 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1525 1576 -0.884982 11.5019 -6.6416 -0.0179542 0.0345996 0.0596343 0.997459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1526 1575 -0.858787 -11.4853 -6.39191 0.0196389 0.0288596 -0.0601983 0.997576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1526 1576 -0.201685 0.00908533 -6.29042 0.00601363 0.0272742 0.00258367 0.999607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1526 1577 -0.892418 11.4916 -6.64969 -0.0290305 0.0405425 0.052747 0.997362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1527 1576 -0.874365 -11.4889 -6.39247 0.0211013 0.0286108 -0.0558531 0.997806 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1527 1577 -0.200809 0.00588209 -6.27779 0.00513593 0.0314778 0.00915058 0.999449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1527 1578 -0.864934 11.4807 -6.63206 -0.022136 0.037122 0.0652462 0.996933 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1528 1577 -0.847258 -11.4772 -6.39897 0.0242033 0.025047 -0.0577476 0.997723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1528 1578 -0.208477 -0.00121273 -6.2661 -0.0047137 0.025184 0.00877186 0.999633 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1528 1579 -0.89443 11.4764 -6.65386 -0.0121523 0.026326 0.0585712 0.997862 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1529 1578 -0.881601 -11.4903 -6.39368 0.0266227 0.0240649 -0.053686 0.997913 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1529 1579 -0.185399 0.0179363 -6.29502 0.00655002 0.0341079 0.00231523 0.999394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1529 1580 -0.891276 11.4725 -6.66542 -0.021449 0.0331939 0.0512073 0.997906 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1530 1579 -0.858854 -11.4772 -6.40822 0.0104573 0.0330935 -0.0574103 0.997747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1530 1580 -0.201209 -0.00444792 -6.28657 -0.00527648 0.0319268 0.00813014 0.999443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1530 1581 -0.877097 11.4677 -6.63914 -0.0278853 0.0381452 0.0578185 0.997208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1531 1580 -0.876124 -11.4519 -6.42541 0.0301987 0.0215457 -0.0649637 0.997198 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1531 1581 -0.195365 -0.017505 -6.30488 -0.00122615 0.0358589 -3.57096e-05 0.999356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1531 1582 -0.876314 11.467 -6.66525 -0.0277379 0.02466 0.0589675 0.99757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1532 1581 -0.849069 -11.4496 -6.4059 0.0242108 0.0391476 -0.0568436 0.997321 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1532 1582 -0.189934 0.000174177 -6.26975 -0.00568506 0.0363412 -0.00287847 0.999319 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1532 1583 -0.868181 11.4349 -6.6515 -0.026723 0.0343904 0.057269 0.997408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1533 1582 -0.861733 -11.4552 -6.412 0.0186698 0.0329814 -0.0539272 0.997825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1533 1583 -0.204694 0.00129222 -6.28956 0.000895898 0.0290602 -0.00773251 0.999547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1533 1584 -0.886049 11.4464 -6.65087 -0.0190099 0.028674 0.0596043 0.997629 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1534 1583 -0.861653 -11.4328 -6.41372 0.0129947 0.0327258 -0.0621693 0.997444 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1534 1584 -0.187424 -0.00670555 -6.27086 -0.00537606 0.0313532 0.000232002 0.999494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1534 1585 -0.881157 11.431 -6.66091 -0.0351048 0.0313556 0.0615983 0.996991 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1535 1584 -0.857041 -11.4345 -6.4188 0.0260688 0.0319186 -0.0585807 0.997432 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1535 1585 -0.18939 -0.0170482 -6.28685 -0.00500671 0.0322501 0.00172311 0.999466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1535 1586 -0.886617 11.4125 -6.65252 -0.0238286 0.033483 0.0647707 0.997054 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1536 1585 -0.868541 -11.4125 -6.39148 0.0204565 0.0306433 -0.0592331 0.997564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1536 1586 -0.20152 0.00197139 -6.28751 -0.00367464 0.037689 -0.00060465 0.999283 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1536 1587 -0.884686 11.4275 -6.65216 -0.0265336 0.0371753 0.0596252 0.997175 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1537 1586 -0.878818 -11.437 -6.39991 0.0171446 0.0348804 -0.0585961 0.997525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1537 1587 -0.214631 -0.00410853 -6.29196 0.00653729 0.0258108 -0.00020131 0.999645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1537 1588 -0.869861 11.4155 -6.6735 -0.0279385 0.0379455 0.0593531 0.997124 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1538 1587 -0.859383 -11.4227 -6.3986 0.0253916 0.0309908 -0.0565196 0.997597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1538 1588 -0.220721 -0.00201524 -6.27626 0.000242567 0.0331704 -0.00112074 0.999449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1538 1589 -0.85907 11.4071 -6.64759 -0.0262321 0.040372 0.0524263 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1539 1588 -0.84679 -11.413 -6.3969 0.0232505 0.0300523 -0.0606221 0.997437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1539 1589 -0.19902 -0.00271367 -6.27501 -0.0041861 0.0280836 -0.00361065 0.99959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1539 1590 -0.870065 11.4098 -6.65478 -0.0222709 0.0418747 0.0613332 0.99699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1540 1589 -0.864771 -11.3987 -6.4196 0.0201393 0.0262188 -0.0578233 0.997779 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1540 1590 -0.202282 -0.00280992 -6.27331 0.00374257 0.0315366 -0.00416279 0.999487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1540 1591 -0.871816 11.3864 -6.63899 -0.0193782 0.0322273 0.0582373 0.997594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1541 1590 -0.853558 -11.4176 -6.39642 0.0271196 0.0304618 -0.0707201 0.996662 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1541 1591 -0.195363 -0.0050492 -6.27261 -0.00451207 0.0309052 0.00305623 0.999507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1541 1592 -0.886829 11.382 -6.65808 -0.0374353 0.0437852 0.0518031 0.996994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1542 1591 -0.847134 -11.3979 -6.41924 0.0140199 0.0280009 -0.0548283 0.998005 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1542 1592 -0.191965 0.00999207 -6.2766 0.00410163 0.027358 0.00583739 0.9996 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1542 1593 -0.871675 11.3773 -6.65432 -0.0267685 0.0358923 0.0556435 0.997446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1543 1592 -0.856264 -11.4078 -6.40221 0.0188246 0.0279222 -0.0602587 0.997615 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1543 1593 -0.223896 -0.00353711 -6.27362 0.00585555 0.0329693 0.00197631 0.999437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1543 1594 -0.861711 11.3891 -6.65729 -0.0332978 0.0242618 0.0562881 0.997564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1544 1593 -0.845555 -11.3678 -6.42047 0.0256161 0.0389234 -0.0595619 0.997136 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1544 1594 -0.210275 0.00348013 -6.26781 -0.00758074 0.025339 0.00262886 0.999647 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1544 1595 -0.870625 11.3897 -6.65272 -0.0317059 0.0328347 0.0467923 0.997861 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1545 1594 -0.859783 -11.3688 -6.43093 0.0242518 0.0272046 -0.0560587 0.997762 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1545 1595 -0.197274 0.00417328 -6.27054 0.00181269 0.0352266 0.00142634 0.999377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1545 1596 -0.900309 11.358 -6.66722 -0.0116499 0.026811 0.0584477 0.997862 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1546 1595 -0.85653 -11.375 -6.42064 0.0240201 0.0308025 -0.0636038 0.997211 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1546 1596 -0.210171 0.0197693 -6.28064 0.00123326 0.0315065 0.00356885 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1546 1597 -0.891846 11.3543 -6.67373 -0.0265439 0.0305475 0.0560461 0.997608 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1547 1596 -0.866614 -11.361 -6.42395 0.0285791 0.0306577 -0.0519973 0.997767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1547 1597 -0.195575 -0.0144159 -6.28675 0.00161781 0.0368086 -0.0126023 0.999242 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1547 1598 -0.86966 11.3485 -6.67238 -0.0251295 0.0325113 0.0607054 0.99731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1548 1597 -0.854312 -11.3592 -6.41584 0.0270708 0.0245047 -0.0507315 0.998045 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1548 1598 -0.174674 0.00850862 -6.26389 -0.00114185 0.0351806 -0.000336638 0.99938 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1548 1599 -0.867756 11.3426 -6.66134 -0.0215716 0.0407487 0.0524163 0.99756 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1549 1598 -0.863293 -11.3558 -6.4176 0.0273889 0.0325876 -0.0629118 0.997111 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1549 1599 -0.198101 -0.00321546 -6.27616 0.00135425 0.032604 0.00146718 0.999466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1549 1600 -0.893437 11.3393 -6.67731 -0.0237081 0.0304706 0.058334 0.99755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1550 1599 -0.871191 -11.3349 -6.43174 0.0244621 0.0252414 -0.053726 0.997937 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1550 1600 -0.182282 -0.00443285 -6.27306 0.000647281 0.0272594 -0.000922586 0.999628 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1550 1601 -0.860167 11.3242 -6.64813 -0.0243528 0.0339544 0.0592434 0.997369 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1551 1600 -0.859293 -11.3283 -6.42754 0.0162801 0.029134 -0.0631388 0.997447 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1551 1601 -0.190893 0.0120293 -6.27267 -0.0046321 0.0332843 -0.00287106 0.999431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1551 1602 -0.87099 11.3275 -6.67872 -0.0259555 0.0270343 0.0577664 0.997626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1552 1601 -0.854852 -11.3297 -6.41704 0.0181383 0.0302051 -0.0570415 0.99775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1552 1602 -0.191891 -0.000187752 -6.27985 -0.00385233 0.0318145 0.000352455 0.999486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1552 1603 -0.866454 11.3005 -6.65903 -0.0238815 0.0326173 0.0544465 0.997698 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1553 1602 -0.87018 -11.3114 -6.44778 0.0278902 0.0183285 -0.0616958 0.997537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1553 1603 -0.186439 -0.000332299 -6.27711 -0.00323234 0.0251974 -0.0020343 0.999675 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1553 1604 -0.873346 11.291 -6.68631 -0.017404 0.0247965 0.0563884 0.997949 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1554 1603 -0.867039 -11.2969 -6.41361 0.0252602 0.0307346 -0.0566461 0.997601 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1554 1604 -0.206189 -0.00265389 -6.27934 0.00484261 0.0277425 0.00199229 0.999601 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1554 1605 -0.867073 11.2967 -6.66925 -0.0203522 0.0281721 0.0618604 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1555 1604 -0.858626 -11.3084 -6.4174 0.0249402 0.023974 -0.0557596 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1555 1605 -0.20207 0.0060878 -6.28489 0.0086474 0.0316395 0.00308274 0.999457 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1555 1606 -0.847206 11.3094 -6.67661 -0.0382034 0.0424743 0.0567782 0.996751 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1556 1605 -0.856212 -11.2866 -6.41416 0.0303971 0.0293537 -0.0628678 0.997127 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1556 1606 -0.202227 -0.00102723 -6.26847 -0.0046418 0.0320382 -0.00354739 0.99947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1556 1607 -0.865403 11.2871 -6.65723 -0.0268974 0.0341804 0.0667425 0.996822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1557 1606 -0.840655 -11.2999 -6.406 0.0232707 0.0310813 -0.0568514 0.997627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1557 1607 -0.197709 -0.0133847 -6.28033 -0.0101372 0.0332257 -0.00210307 0.999394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1557 1608 -0.85343 11.2689 -6.67548 -0.0279033 0.0321593 0.0504613 0.997818 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1558 1607 -0.827738 -11.2901 -6.43624 0.0264609 0.0336956 -0.0658843 0.996907 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1558 1608 -0.203397 -0.00351922 -6.27097 -0.00532344 0.0334078 0.00137052 0.999427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1558 1609 -0.877721 11.2505 -6.67889 -0.0228388 0.0313742 0.0518658 0.9979 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1559 1608 -0.847222 -11.2714 -6.41968 0.0301018 0.0293629 -0.0584684 0.997403 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1559 1609 -0.193477 0.00728404 -6.28114 0.000531414 0.0277405 -0.00496659 0.999603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1559 1610 -0.866074 11.277 -6.67195 -0.03867 0.0317449 0.0615075 0.996852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1560 1609 -0.847317 -11.2797 -6.43625 0.0303798 0.0295058 -0.0558419 0.997541 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1560 1610 -0.218641 0.000512664 -6.27498 0.00615883 0.0274966 -0.000536447 0.999603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1560 1611 -0.851622 11.2778 -6.67387 -0.0354283 0.0262996 0.0620469 0.997097 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1561 1610 -0.838758 -11.2722 -6.40198 0.0223987 0.0352465 -0.0539696 0.997669 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1561 1611 -0.206185 -0.0143542 -6.27669 -0.00969884 0.0290417 -0.00605305 0.999513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1561 1612 -0.853173 11.2582 -6.67595 -0.0235509 0.0327976 0.0523961 0.99781 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1562 1611 -0.83198 -11.2645 -6.43179 0.0304465 0.0260567 -0.0566342 0.99759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1562 1612 -0.19412 0.000973467 -6.2868 0.00348143 0.0309209 0.00921076 0.999473 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1562 1613 -0.871024 11.2538 -6.67619 -0.0271068 0.031153 0.0523915 0.997772 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1563 1612 -0.859281 -11.2544 -6.42439 0.0309516 0.0303147 -0.0602911 0.99724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1563 1613 -0.18637 -0.0056143 -6.28764 0.000795181 0.0339749 -0.00373751 0.999415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1563 1614 -0.843354 11.2233 -6.68353 -0.0192908 0.0295058 0.0600482 0.997573 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1564 1613 -0.857799 -11.2501 -6.43442 0.0226945 0.024178 -0.061421 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1564 1614 -0.200748 0.000455268 -6.27561 0.00381161 0.0289146 0.00298971 0.99957 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1564 1615 -0.848688 11.2376 -6.66615 -0.0205123 0.0452559 0.0527644 0.99737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1565 1614 -0.84498 -11.2365 -6.41947 0.029024 0.0309274 -0.0588707 0.997364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1565 1615 -0.185542 0.000119454 -6.26611 0.000367036 0.0327123 -0.00287563 0.999461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1565 1616 -0.855117 11.2339 -6.6852 -0.02811 0.0345424 0.0582224 0.99731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1566 1615 -0.831865 -11.2346 -6.43008 0.0215722 0.0387391 -0.0588135 0.997284 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1566 1616 -0.202998 -0.0103019 -6.26793 0.00756801 0.0244507 -0.00200707 0.99967 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1566 1617 -0.855049 11.2201 -6.67751 -0.0334668 0.0387614 0.0602426 0.996869 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1567 1616 -0.836103 -11.2413 -6.44454 0.0272232 0.0315498 -0.0598407 0.997338 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1567 1617 -0.200638 -0.000580443 -6.27168 0.00375342 0.0351754 -6.12096e-05 0.999374 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1567 1618 -0.858665 11.231 -6.6764 -0.0268473 0.0411542 0.0564 0.997198 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1568 1617 -0.834994 -11.2224 -6.41989 0.0235264 0.0302191 -0.0547037 0.997768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1568 1618 -0.222075 -0.00445489 -6.2807 0.00930627 0.0387289 0.00740858 0.999179 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1568 1619 -0.830311 11.2008 -6.67448 -0.027131 0.0273803 0.0589691 0.997515 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1569 1618 -0.846234 -11.2152 -6.44275 0.0248665 0.0410157 -0.0620643 0.996919 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1569 1619 -0.187217 -0.00441495 -6.2758 0.0103027 0.029877 0.00166387 0.999499 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1569 1620 -0.860153 11.2106 -6.6831 -0.0230615 0.0365151 0.0562164 0.997484 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1570 1619 -0.831827 -11.2118 -6.4337 0.0286898 0.0354872 -0.0542368 0.997485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1570 1620 -0.186638 0.0201199 -6.27199 -0.0112673 0.0333227 -0.00258585 0.999378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1570 1621 -0.858176 11.193 -6.70665 -0.0335689 0.0294779 0.0482437 0.997836 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1571 1620 -0.826526 -11.1975 -6.42744 0.0237712 0.0365125 -0.0536849 0.997607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1571 1621 -0.197003 0.0196625 -6.29584 0.00762453 0.0302868 0.00186534 0.99951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1571 1622 -0.849395 11.1564 -6.66917 -0.0345606 0.0208509 0.0545159 0.997697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1572 1621 -0.834488 -11.179 -6.43475 0.035906 0.02853 -0.0504525 0.997673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1572 1622 -0.208335 0.00657033 -6.27811 -0.00343567 0.0292371 0.000108647 0.999567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1572 1623 -0.855423 11.1877 -6.66372 -0.0327917 0.0376025 0.0617852 0.996842 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1573 1622 -0.83507 -11.1858 -6.43978 0.0303911 0.0269016 -0.0512725 0.99786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1573 1623 -0.206012 -0.00035115 -6.28801 0.00904201 0.0325268 -0.012851 0.999347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1573 1624 -0.841044 11.1784 -6.68827 -0.0170068 0.0209693 0.0593933 0.997869 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1574 1623 -0.83241 -11.1745 -6.44577 0.0318492 0.0327501 -0.0508554 0.997661 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1574 1624 -0.197873 -0.00825531 -6.28787 -0.00289993 0.0322544 0.00276404 0.999472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1574 1625 -0.852625 11.1651 -6.68766 -0.0267124 0.0425584 0.0609766 0.996874 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1575 1624 -0.84054 -11.1803 -6.42822 0.0265243 0.0373829 -0.0680911 0.996626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1575 1625 -0.199834 0.0227922 -6.28972 -0.00856027 0.0252956 0.00299624 0.999639 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1575 1626 -0.853345 11.1592 -6.67843 -0.0200673 0.0268256 0.0626606 0.997472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1576 1625 -0.84115 -11.1692 -6.44213 0.0310925 0.0323156 -0.0438197 0.998032 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1576 1626 -0.202221 0.00647902 -6.27525 0.00554401 0.0299538 -0.00383089 0.999529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1576 1627 -0.860102 11.132 -6.67309 -0.0248014 0.0397631 0.0577524 0.99723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1577 1626 -0.840239 -11.1657 -6.44465 0.0299364 0.022276 -0.0540754 0.997839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1577 1627 -0.206147 -0.000683512 -6.28207 -0.000784855 0.0270969 0.000793937 0.999632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1577 1628 -0.859425 11.1324 -6.6797 -0.013734 0.0338746 0.0566091 0.997727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1578 1627 -0.833765 -11.1334 -6.43469 0.0347416 0.0245314 -0.0543811 0.997614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1578 1628 -0.184653 -0.00101689 -6.28795 0.0066728 0.0314685 0.00563734 0.999467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1578 1629 -0.849218 11.1388 -6.69208 -0.0296879 0.0394733 0.0614344 0.996888 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1579 1628 -0.824761 -11.1497 -6.42795 0.0259539 0.0438632 -0.0625643 0.996739 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1579 1629 -0.202913 -0.0053557 -6.29382 -0.00628821 0.030434 -0.000856748 0.999517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1579 1630 -0.855667 11.114 -6.69198 -0.0168867 0.0325242 0.0596052 0.997549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1580 1629 -0.851235 -11.1395 -6.42932 0.025358 0.0286269 -0.0536367 0.997828 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1580 1630 -0.202849 -0.00881109 -6.27873 -0.00285167 0.0325381 -0.00276339 0.999463 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1580 1631 -0.8451 11.1124 -6.68199 -0.0265137 0.030745 0.0585018 0.997461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1581 1630 -0.834885 -11.1084 -6.43839 0.0267979 0.0256896 -0.0537287 0.997865 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1581 1631 -0.208635 0.00224601 -6.25384 -0.00710847 0.0251988 -0.00347731 0.999651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1581 1632 -0.835191 11.1096 -6.70525 -0.018702 0.0405144 0.0587992 0.997272 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1582 1631 -0.83479 -11.1231 -6.43846 0.032161 0.0281069 -0.0575914 0.997426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1582 1632 -0.192899 -0.00605207 -6.27352 0.00152818 0.0303536 0.000140543 0.999538 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1582 1633 -0.850203 11.1088 -6.69199 -0.0268203 0.030761 0.0538152 0.997717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1583 1632 -0.835135 -11.1083 -6.43268 0.0328929 0.0315311 -0.0519465 0.99761 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1583 1633 -0.210988 0.0188318 -6.28159 -0.000977369 0.0284322 0.00195536 0.999593 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1583 1634 -0.846532 11.096 -6.68248 -0.013392 0.0338333 0.0548712 0.99783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1584 1633 -0.820996 -11.0974 -6.42132 0.0264667 0.0228139 -0.0490506 0.998185 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1584 1634 -0.18517 -0.00619158 -6.29001 -0.00161701 0.029598 -0.00326156 0.999555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1584 1635 -0.845165 11.0818 -6.70568 -0.0246873 0.0386473 0.0567225 0.997336 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1585 1634 -0.839588 -11.0926 -6.42797 0.0225861 0.0338496 -0.056535 0.997571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1585 1635 -0.181758 0.000454386 -6.27291 -0.00698727 0.0273911 0.00655754 0.999579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1585 1636 -0.860254 11.0804 -6.69652 -0.0308099 0.0242892 0.056797 0.997615 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1586 1635 -0.832611 -11.0924 -6.46637 0.026911 0.0290987 -0.0529906 0.997808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1586 1636 -0.185109 0.00264885 -6.27842 -0.00380483 0.03085 -0.00595288 0.999499 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1586 1637 -0.860351 11.0753 -6.68432 -0.0285669 0.0331731 0.0548619 0.997534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1587 1636 -0.802016 -11.0878 -6.44186 0.0264839 0.0263646 -0.0566179 0.997696 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1587 1637 -0.187701 0.0106982 -6.27579 0.00226096 0.0327251 0.00365531 0.999455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1587 1638 -0.847278 11.0581 -6.69982 -0.0195549 0.0217128 0.0590146 0.997829 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1588 1637 -0.822696 -11.0758 -6.43195 0.0380815 0.0290181 -0.0517188 0.997513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1588 1638 -0.191198 -0.00656964 -6.28977 -0.00550294 0.0371903 -0.00293852 0.999289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1588 1639 -0.852619 11.0597 -6.69154 -0.0184872 0.0423757 0.055064 0.997412 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1589 1638 -0.820243 -11.0634 -6.43765 0.0304822 0.0271323 -0.0518431 0.997821 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1589 1639 -0.197886 0.0137464 -6.26853 0.00538564 0.0297165 -0.0107219 0.999486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1589 1640 -0.828405 11.052 -6.69122 -0.0277678 0.031303 0.0528957 0.997723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1590 1639 -0.825961 -11.045 -6.44597 0.032636 0.0203238 -0.055411 0.997723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1590 1640 -0.197825 0.00208512 -6.29082 0.00190173 0.0299253 -0.00299589 0.999546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1590 1641 -0.841927 11.0645 -6.70075 -0.0331772 0.0307065 0.0436553 0.998023 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1591 1640 -0.828644 -11.0637 -6.43582 0.0264071 0.037897 -0.0504421 0.997658 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1591 1641 -0.207399 -0.00328304 -6.2733 -0.00209935 0.0290838 -0.00206426 0.999573 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1591 1642 -0.839617 11.0446 -6.69687 -0.027623 0.0321233 0.0520345 0.997746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1592 1641 -0.81029 -11.0467 -6.4398 0.0331619 0.0258124 -0.0611026 0.997246 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1592 1642 -0.183876 0.00817243 -6.29379 0.00362858 0.0344577 -0.000342341 0.9994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1592 1643 -0.830498 11.0216 -6.68684 -0.0312122 0.0293864 0.0468407 0.997982 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1593 1642 -0.83308 -11.0317 -6.4395 0.0328991 0.0207364 -0.0578518 0.997567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1593 1643 -0.212105 -0.00387866 -6.26016 0.00217955 0.0310384 -0.00713047 0.99949 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1593 1644 -0.831534 11.0263 -6.68866 -0.0271141 0.032956 0.0594616 0.997318 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1594 1643 -0.817195 -11.0494 -6.4326 0.0289389 0.0334224 -0.0591532 0.997269 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1594 1644 -0.195287 0.00789767 -6.28905 -0.00275026 0.039721 -0.00841072 0.999172 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1594 1645 -0.83993 11.0254 -6.71091 -0.0367953 0.0330609 0.0542313 0.997302 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1595 1644 -0.821746 -11.0055 -6.45727 0.0281211 0.0216198 -0.0570306 0.997742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1595 1645 -0.202735 -0.00288729 -6.27783 -0.00345718 0.0326144 0.00754932 0.999434 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1595 1646 -0.814857 10.9833 -6.70242 -0.0341972 0.0305542 0.0465174 0.997864 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1596 1645 -0.809735 -11.0016 -6.44806 0.0190004 0.0332254 -0.0586106 0.997547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1596 1646 -0.191251 -0.0217593 -6.28662 -0.00243988 0.0345136 0.00151508 0.9994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1596 1647 -0.828114 11.0015 -6.7115 -0.0343919 0.0394945 0.0597982 0.996836 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1597 1646 -0.818536 -11.0097 -6.44016 0.0191008 0.0342651 -0.0548946 0.997721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1597 1647 -0.204836 -0.000615918 -6.26985 0.00356496 0.0304287 -0.000355551 0.999531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1597 1648 -0.8388 11.0021 -6.69231 -0.032748 0.0245984 0.0625994 0.997198 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1598 1647 -0.824495 -10.9961 -6.44317 0.0244706 0.0291572 -0.0548684 0.997768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1598 1648 -0.197755 0.000225046 -6.27277 -0.00231726 0.0391687 -0.00981357 0.999182 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1598 1649 -0.827082 10.9795 -6.68912 -0.0334111 0.0416259 0.0629584 0.996588 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1599 1648 -0.813446 -11.0012 -6.46123 0.0195421 0.0272153 -0.0585276 0.997723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1599 1649 -0.181124 0.00414459 -6.27001 0.00853829 0.0264984 1.83065e-06 0.999612 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1599 1650 -0.823341 10.9836 -6.69854 -0.0276576 0.0389457 0.0594206 0.99709 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1600 1649 -0.813493 -10.9935 -6.4647 0.0321261 0.0259164 -0.0559924 0.997578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1600 1650 -0.183852 0.018417 -6.27415 0.00185175 0.0281024 -0.00113739 0.999603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1600 1651 -0.820582 10.9759 -6.68988 -0.0177227 0.0261867 0.0626569 0.997534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1601 1650 -0.814713 -10.9723 -6.46164 0.0294463 0.0250975 -0.0597528 0.997463 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1601 1651 -0.190247 -0.00440646 -6.27097 0.00142608 0.0254758 0.00505577 0.999662 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1601 1652 -0.827922 10.9628 -6.70767 -0.0292108 0.0362473 0.0566192 0.99731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1602 1651 -0.81724 -10.9566 -6.43431 0.0349122 0.0376286 -0.0655497 0.996528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1602 1652 -0.202945 -0.0146471 -6.28427 -0.000319284 0.0279236 -0.000885039 0.99961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1602 1653 -0.836208 10.9411 -6.69829 -0.0235891 0.0253192 0.0634406 0.997385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1603 1652 -0.828649 -10.9739 -6.45446 0.0236173 0.0230263 -0.0549605 0.997944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1603 1653 -0.205576 0.010688 -6.27774 -0.00143573 0.0274972 0.00480258 0.999609 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1603 1654 -0.833781 10.9639 -6.6922 -0.0234581 0.0279372 0.0599497 0.997535 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1604 1653 -0.815905 -10.9616 -6.45003 0.0388602 0.0233043 -0.0655076 0.996823 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1604 1654 -0.202685 -0.00799155 -6.27198 0.00546523 0.0292113 4.50325e-05 0.999558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1604 1655 -0.826325 10.9335 -6.69903 -0.0240351 0.0391201 0.0566756 0.997336 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1605 1654 -0.8079 -10.9488 -6.47515 0.0285808 0.0303895 -0.0600682 0.997322 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1605 1655 -0.181041 -0.00889052 -6.2798 0.0037035 0.035147 0.00535674 0.999361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1605 1656 -0.810391 10.942 -6.69559 -0.0230338 0.0279821 0.0618117 0.99743 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1606 1655 -0.815507 -10.9445 -6.44513 0.0293963 0.0250903 -0.0654918 0.997104 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1606 1656 -0.199261 0.00998264 -6.29877 -0.00128162 0.0324807 0.00172356 0.99947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1606 1657 -0.837301 10.9345 -6.72449 -0.0243574 0.0355139 0.0576628 0.997407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1607 1656 -0.80233 -10.9351 -6.45871 0.0248656 0.0267059 -0.0585295 0.997619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1607 1657 -0.209376 -0.00417163 -6.28378 0.00412516 0.0260309 0.0142385 0.999551 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1607 1658 -0.815977 10.9237 -6.70349 -0.0309731 0.0346071 0.0550077 0.997405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1608 1657 -0.812617 -10.9284 -6.46303 0.0267845 0.0275453 -0.0580653 0.997573 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1608 1658 -0.191918 -0.0104329 -6.2819 -0.00436331 0.0259327 0.00125657 0.999653 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1608 1659 -0.84249 10.918 -6.69837 -0.033827 0.037369 0.0563519 0.997138 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1609 1658 -0.80848 -10.8944 -6.44845 0.0263953 0.0290794 -0.0478644 0.998081 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1609 1659 -0.212381 -0.00130996 -6.27513 -0.00717959 0.0331879 0.00239578 0.99942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1609 1660 -0.827351 10.9043 -6.70986 -0.0235038 0.0345887 0.0567551 0.997512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1610 1659 -0.793838 -10.895 -6.45705 0.0316272 0.0268132 -0.0586687 0.997416 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1610 1660 -0.19379 -0.00106685 -6.27869 0.00607274 0.0230889 -0.000520876 0.999715 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1610 1661 -0.808171 10.8835 -6.72036 -0.033 0.0401216 0.0528496 0.99725 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1611 1660 -0.791795 -10.8911 -6.45809 0.0314293 0.0196991 -0.0556897 0.997759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1611 1661 -0.18322 -0.0131107 -6.29531 0.00206425 0.0313883 -0.0045131 0.999495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1611 1662 -0.819713 10.8911 -6.70556 -0.0318521 0.0255725 0.049473 0.99794 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1612 1661 -0.793866 -10.8885 -6.45267 0.0321497 0.0240066 -0.058785 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1612 1662 -0.188786 0.0120264 -6.27961 -0.00127679 0.0265149 0.00175059 0.999646 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1612 1663 -0.810535 10.8808 -6.7102 -0.0277022 0.0338094 0.055639 0.997494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1613 1662 -0.804657 -10.8943 -6.44814 0.0330946 0.0435409 -0.0535371 0.997067 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1613 1663 -0.202056 -0.00378213 -6.28788 0.00292198 0.0321885 -0.00257124 0.999474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1613 1664 -0.811941 10.8608 -6.70304 -0.0314668 0.0311449 0.0464071 0.997941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1614 1663 -0.803618 -10.8767 -6.45679 0.0328572 0.0278106 -0.0583633 0.997367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1614 1664 -0.202962 -0.0151273 -6.26993 0.00215794 0.0329647 0.00819991 0.999421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1614 1665 -0.820364 10.8491 -6.70947 -0.0295774 0.0383495 0.0486946 0.997639 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1615 1664 -0.800247 -10.8863 -6.45025 0.0237541 0.03102 -0.0496589 0.998002 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1615 1665 -0.207409 0.00983061 -6.27635 0.00137576 0.0316984 0.00277921 0.999493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1615 1666 -0.808512 10.8424 -6.70254 -0.0280306 0.0288176 0.0449144 0.998182 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1616 1665 -0.804382 -10.8596 -6.45714 0.0329633 0.0253654 -0.0574839 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1616 1666 -0.175935 -0.0191346 -6.25571 0.0105027 0.0240529 0.00396949 0.999648 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1616 1667 -0.813563 10.8638 -6.70977 -0.0273262 0.0305438 0.0643826 0.997083 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1617 1666 -0.802556 -10.8439 -6.46374 0.0293516 0.0309127 -0.0590839 0.997342 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1617 1667 -0.194462 -0.0182 -6.27012 0.000240645 0.0311474 -0.003205 0.99951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1617 1668 -0.804461 10.8148 -6.70304 -0.0381065 0.0259592 0.0538302 0.997485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1618 1667 -0.81196 -10.8135 -6.46853 0.030248 0.0193166 -0.054649 0.99786 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1618 1668 -0.206183 0.011447 -6.27805 0.0072745 0.0305063 0.00343415 0.999502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1618 1669 -0.824483 10.8199 -6.68829 -0.0339277 0.0344787 0.0534364 0.997399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1619 1668 -0.793042 -10.8299 -6.45334 0.030164 0.0375123 -0.0584647 0.997128 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1619 1669 -0.192452 0.0145922 -6.28235 -0.00582667 0.0248626 -0.000527676 0.999674 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1619 1670 -0.812209 10.8248 -6.69089 -0.027219 0.0347069 0.0644274 0.996947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1620 1669 -0.807265 -10.8359 -6.46615 0.0358946 0.0319731 -0.0553872 0.997307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1620 1670 -0.206394 -0.0175603 -6.27783 0.00242104 0.027801 -0.00172471 0.999609 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1620 1671 -0.823909 10.8003 -6.70001 -0.0316234 0.0218166 0.0516253 0.997927 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1621 1670 -0.78508 -10.8182 -6.45556 0.0321145 0.0241983 -0.0650845 0.997069 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1621 1671 -0.202447 -0.00592189 -6.26892 -0.00837071 0.0275372 -0.00432558 0.999576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1621 1672 -0.807392 10.8086 -6.70138 -0.0286054 0.0376246 0.0575101 0.997226 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1622 1671 -0.80956 -10.8174 -6.46891 0.028158 0.0307143 -0.051107 0.997824 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1622 1672 -0.193409 -0.0153298 -6.28033 0.00244512 0.0370266 0.00466464 0.9993 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1622 1673 -0.802512 10.8063 -6.70713 -0.0310001 0.024977 0.0582943 0.997505 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1623 1672 -0.782768 -10.8214 -6.45879 0.0274224 0.0173228 -0.0563672 0.997883 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1623 1673 -0.215124 0.0125413 -6.29079 -0.00529817 0.030361 0.00189819 0.999523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1623 1674 -0.799853 10.7736 -6.72553 -0.0315575 0.0299551 0.0579772 0.997369 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1624 1673 -0.793621 -10.8113 -6.46759 0.0322219 0.0327692 -0.0416976 0.998073 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1624 1674 -0.214508 -0.0170906 -6.27959 -0.010328 0.0262851 0.00178008 0.9996 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1624 1675 -0.791738 10.7789 -6.71091 -0.03743 0.0216692 0.0635517 0.997041 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1625 1674 -0.79574 -10.7886 -6.46823 0.0263284 0.0296062 -0.0528993 0.997814 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1625 1675 -0.193612 -0.0018598 -6.28612 -0.00285091 0.0364244 -0.00415351 0.999324 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1625 1676 -0.820798 10.7761 -6.70895 -0.037148 0.0374481 0.0527814 0.997212 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1626 1675 -0.782105 -10.786 -6.46632 0.0296781 0.0227819 -0.0580017 0.997615 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1626 1676 -0.205918 -0.00649027 -6.28157 0.00155375 0.0261587 -0.0087073 0.999619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1626 1677 -0.813017 10.7485 -6.71356 -0.0216987 0.0268764 0.0555508 0.997858 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1627 1676 -0.807595 -10.7642 -6.44729 0.0274413 0.0311363 -0.0582784 0.997437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1627 1677 -0.196156 0.0101364 -6.26105 -0.00333546 0.0305641 -0.00361601 0.999521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1627 1678 -0.807471 10.7486 -6.72417 -0.0352026 0.031265 0.055525 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1628 1677 -0.785698 -10.7825 -6.45926 0.0292716 0.0239477 -0.0534974 0.997852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1628 1678 -0.186287 -0.0111294 -6.27523 0.000894544 0.030456 -0.00535694 0.999521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1628 1679 -0.818925 10.7627 -6.73026 -0.0304491 0.0336819 0.0528451 0.99757 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1629 1678 -0.786617 -10.758 -6.46076 0.0256853 0.0202741 -0.0579653 0.997782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1629 1679 -0.201706 0.000400422 -6.28724 0.00241686 0.0356609 0.00249097 0.999358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1629 1680 -0.77799 10.7355 -6.70846 -0.0221258 0.0308798 0.063232 0.997276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1630 1679 -0.795307 -10.748 -6.47534 0.0348399 0.0257723 -0.0586906 0.997335 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1630 1680 -0.190178 0.00754465 -6.26946 0.00520155 0.0272953 0.0052797 0.9996 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1630 1681 -0.792555 10.7365 -6.72155 -0.0357844 0.030456 0.053615 0.997455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1631 1680 -0.801075 -10.7483 -6.47407 0.0273158 0.0299205 -0.0599511 0.997379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1631 1681 -0.200177 -0.00123772 -6.26925 0.00314044 0.0403877 0.00540691 0.999165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1631 1682 -0.799986 10.7291 -6.72536 -0.0304631 0.0324492 0.0559048 0.997444 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1632 1681 -0.800566 -10.7389 -6.48168 0.0339744 0.0215202 -0.0627946 0.997216 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1632 1682 -0.204398 -0.0186572 -6.27873 -0.00122328 0.0257686 -0.000924281 0.999667 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1632 1683 -0.814125 10.7182 -6.73295 -0.0352567 0.0240115 0.0580104 0.997404 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1633 1682 -0.782199 -10.727 -6.46722 0.0392196 0.0228412 -0.0485666 0.997788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1633 1683 -0.20947 -0.0143436 -6.28583 0.00466873 0.0369709 -0.00101696 0.999305 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1633 1684 -0.788152 10.6822 -6.71593 -0.0270211 0.0354254 0.0657704 0.99684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1634 1683 -0.786499 -10.7122 -6.46577 0.0319528 0.0293988 -0.062553 0.997097 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1634 1684 -0.201279 0.00758901 -6.28078 -0.00201272 0.0284884 0.00702981 0.999567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1634 1685 -0.79 10.6931 -6.71764 -0.0426369 0.0350144 0.0463748 0.997399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1635 1684 -0.779222 -10.7109 -6.49182 0.032873 0.0277191 -0.0635757 0.99705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1635 1685 -0.2047 0.00203775 -6.27419 0.00367923 0.0293228 0.00398732 0.999555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1635 1686 -0.803882 10.6973 -6.72294 -0.0315757 0.0276602 0.0627965 0.997143 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1636 1685 -0.792383 -10.6923 -6.46349 0.0277953 0.0340607 -0.0585544 0.997316 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1636 1686 -0.201212 -0.00525129 -6.25297 0.00317148 0.0332395 -0.00170226 0.999441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1636 1687 -0.808396 10.6776 -6.71238 -0.0285047 0.0161715 0.0603861 0.997637 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1637 1686 -0.782653 -10.6825 -6.48425 0.0288101 0.0367869 -0.0569361 0.997284 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1637 1687 -0.187525 -0.0260499 -6.27242 0.00152768 0.0293832 0.00407481 0.999559 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1637 1688 -0.819417 10.6797 -6.72907 -0.0247961 0.0354198 0.0508871 0.997768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1638 1687 -0.7807 -10.6804 -6.46692 0.0354475 0.0271811 -0.0587825 0.997271 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1638 1688 -0.198562 -0.00844793 -6.28344 -0.00569248 0.0323147 -0.00265356 0.999458 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1638 1689 -0.805668 10.6469 -6.73309 -0.0367208 0.0200297 0.0617261 0.997216 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1639 1688 -0.784563 -10.6745 -6.47384 0.0303461 0.026577 -0.0626045 0.997223 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1639 1689 -0.188549 -0.00820787 -6.28599 0.00393442 0.0392813 0.00512498 0.999207 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1639 1690 -0.796998 10.6578 -6.71051 -0.0246777 0.0302872 0.0536148 0.997797 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1640 1689 -0.781483 -10.6552 -6.48492 0.0376415 0.0362524 -0.0532239 0.997214 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1640 1690 -0.194623 -0.0122494 -6.26872 0.00458815 0.0260994 -0.0023725 0.999646 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1640 1691 -0.809867 10.6519 -6.71456 -0.0316278 0.0387304 0.0475625 0.997616 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1641 1690 -0.787396 -10.6506 -6.47579 0.0324235 0.0234071 -0.0529918 0.997794 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1641 1691 -0.193658 0.000732528 -6.27711 -0.00737365 0.0415103 0.00124188 0.99911 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1641 1692 -0.79186 10.6528 -6.72172 -0.0305544 0.0220547 0.058842 0.997556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1642 1691 -0.788101 -10.6577 -6.4803 0.0336366 0.0200182 -0.0543177 0.997756 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1642 1692 -0.203088 0.00348288 -6.28162 0.0040618 0.0333225 0.00480659 0.999425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1642 1693 -0.780656 10.6394 -6.72408 -0.0248806 0.0329984 0.0512264 0.997832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1643 1692 -0.784176 -10.6371 -6.47684 0.0266647 0.0239326 -0.0446123 0.998362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1643 1693 -0.191635 0.00283453 -6.27134 0.00213753 0.0305676 0.00212369 0.999528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1643 1694 -0.811645 10.6299 -6.72147 -0.0317941 0.0378604 0.045769 0.997728 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1644 1693 -0.76883 -10.6366 -6.47178 0.0300545 0.0306598 -0.0563498 0.997488 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1644 1694 -0.189619 -0.00853477 -6.2775 0.00220292 0.0313243 0.00830831 0.999472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1644 1695 -0.787907 10.6088 -6.72527 -0.0377453 0.0242709 0.0563881 0.9974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1645 1694 -0.781493 -10.6107 -6.48274 0.0281931 0.0261147 -0.0586392 0.997539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1645 1695 -0.218021 0.00694612 -6.28567 0.00317189 0.0232604 0.00752522 0.999696 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1645 1696 -0.784378 10.6098 -6.7257 -0.0301299 0.0311546 0.0564494 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1646 1695 -0.767297 -10.6014 -6.4643 0.0443688 0.0335634 -0.0531391 0.997036 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1646 1696 -0.177489 0.00439232 -6.28152 -0.00881851 0.027714 0.00621164 0.999558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1646 1697 -0.776501 10.5956 -6.71492 -0.0333123 0.0350518 0.056474 0.997232 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1647 1696 -0.794596 -10.593 -6.49168 0.0364119 0.0276434 -0.0519421 0.997603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1647 1697 -0.192545 0.000517265 -6.28801 -0.013825 0.0391887 0.0040759 0.999128 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1647 1698 -0.793807 10.5855 -6.72079 -0.0277516 0.0266958 0.0629706 0.997272 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1648 1697 -0.784123 -10.6009 -6.46542 0.0319137 0.0288383 -0.050774 0.997783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1648 1698 -0.204132 -0.00233124 -6.28072 0.00403292 0.0304841 0.00032604 0.999527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1648 1699 -0.799311 10.596 -6.72257 -0.0268648 0.0333617 0.0622054 0.997144 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1649 1698 -0.771485 -10.5829 -6.47548 0.033738 0.0317872 -0.0576822 0.997258 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1649 1699 -0.182378 0.000373246 -6.27842 -0.00318074 0.0320951 0.00625408 0.99946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1649 1700 -0.789766 10.555 -6.73513 -0.0281211 0.0274733 0.0560833 0.997652 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1650 1699 -0.774007 -10.5804 -6.48299 0.0344681 0.0380672 -0.0613977 0.996791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1650 1700 -0.205003 0.00234018 -6.28933 -0.00477069 0.0352078 -0.0022199 0.999366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1650 1701 -0.778768 10.5523 -6.7138 -0.0381255 0.0315286 0.0560189 0.997203 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1651 1700 -0.776322 -10.5791 -6.46671 0.0399858 0.0389528 -0.0530107 0.997032 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1651 1701 -0.204267 0.0160586 -6.28933 -0.00477471 0.0332241 -0.000310877 0.999436 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1651 1702 -0.786416 10.574 -6.72191 -0.0237077 0.0322663 0.0547004 0.9977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1652 1701 -0.769827 -10.5707 -6.47587 0.0322899 0.0291654 -0.0552377 0.997525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1652 1702 -0.196425 0.00717365 -6.27069 -0.00609533 0.0373802 0.00652662 0.999261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1652 1703 -0.785249 10.5292 -6.74211 -0.0260345 0.0276893 0.0537602 0.99783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1653 1702 -0.753711 -10.5565 -6.47178 0.0302705 0.0288932 -0.0616167 0.997222 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1653 1703 -0.184729 -0.000637539 -6.27447 0.00176726 0.028553 -0.00439673 0.999581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1653 1704 -0.799107 10.5363 -6.71102 -0.0350972 0.039013 0.0619739 0.996697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1654 1703 -0.761986 -10.53 -6.48152 0.0374428 0.0376197 -0.0522812 0.997221 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1654 1704 -0.177746 0.0108253 -6.26326 0.000707212 0.0341299 0.00434717 0.999408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1654 1705 -0.792461 10.5288 -6.73299 -0.0401905 0.0315768 0.0521381 0.997331 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1655 1704 -0.764351 -10.5274 -6.48403 0.0305881 0.0289762 -0.0568046 0.997496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1655 1705 -0.204458 0.00917101 -6.2857 -0.00890361 0.0307037 -0.00337818 0.999483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1655 1706 -0.777374 10.52 -6.72413 -0.0387591 0.0362633 0.0560269 0.997017 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1656 1705 -0.766262 -10.537 -6.46879 0.0212305 0.0326933 -0.0560607 0.997666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1656 1706 -0.200113 -0.0100623 -6.26427 0.00417464 0.0239681 0.00114668 0.999703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1656 1707 -0.799379 10.5171 -6.7302 -0.038054 0.0285542 0.0495945 0.997636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1657 1706 -0.763203 -10.5244 -6.48634 0.0319385 0.0285354 -0.0554288 0.997544 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1657 1707 -0.201155 0.009488 -6.27934 0.00257652 0.0215298 -0.00346143 0.999759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1657 1708 -0.795481 10.4986 -6.72137 -0.0330765 0.0314964 0.0479853 0.997803 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1658 1707 -0.771264 -10.5272 -6.48469 0.0386015 0.03871 -0.0516121 0.99717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1658 1708 -0.194325 -0.0056672 -6.28363 0.00194767 0.0227295 -0.00418182 0.999731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1658 1709 -0.772463 10.5109 -6.74591 -0.0406031 0.0267746 0.0536461 0.997375 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1659 1708 -0.74837 -10.5043 -6.48579 0.0355364 0.0252304 -0.0588761 0.997313 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1659 1709 -0.19397 -0.00515849 -6.2805 0.00408252 0.035209 -0.00343165 0.999366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1659 1710 -0.766013 10.4831 -6.74271 -0.0385034 0.0303051 0.0513099 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1660 1709 -0.772173 -10.495 -6.49393 0.033207 0.034247 -0.0520241 0.997506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1660 1710 -0.187132 0.0083495 -6.28619 -0.00184018 0.0237247 -0.00601956 0.999699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1660 1711 -0.773435 10.4891 -6.74429 -0.0382577 0.0250421 0.0567896 0.997339 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1661 1710 -0.7592 -10.5014 -6.46879 0.0307888 0.0275507 -0.0436977 0.99819 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1661 1711 -0.188539 0.012819 -6.28555 -0.00179463 0.032202 -0.0077965 0.999449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1661 1712 -0.764455 10.4765 -6.71984 -0.0384799 0.0305338 0.0571738 0.997155 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1662 1711 -0.77561 -10.4964 -6.49338 0.0352365 0.0307697 -0.0579171 0.997225 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1662 1712 -0.181147 -0.00493774 -6.27994 -0.00490785 0.0348781 0.00202684 0.999377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1662 1713 -0.781883 10.4636 -6.73734 -0.0295301 0.0354338 0.0497451 0.997696 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1663 1712 -0.767006 -10.488 -6.4855 0.0346222 0.0353029 -0.0455655 0.997737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1663 1713 -0.191746 -0.000539088 -6.27267 0.00590025 0.0314647 -0.0114756 0.999422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1663 1714 -0.791157 10.4439 -6.74319 -0.0401314 0.0201417 0.0509769 0.99769 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1664 1713 -0.776517 -10.4712 -6.4739 0.0231749 0.0239605 -0.0562705 0.997859 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1664 1714 -0.200617 0.0067542 -6.28436 0.00168356 0.0283095 -0.000311306 0.999598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1664 1715 -0.772735 10.4458 -6.74833 -0.0305466 0.0377719 0.043827 0.997857 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1665 1714 -0.744429 -10.4417 -6.46753 0.0394476 0.0317741 -0.0498398 0.997472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1665 1715 -0.207364 -0.000676288 -6.28568 -0.00159732 0.0213234 0.00362217 0.999765 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1665 1716 -0.786545 10.4448 -6.72459 -0.0283183 0.0261126 0.0479861 0.998105 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1666 1715 -0.771746 -10.437 -6.50829 0.0385138 0.0230397 -0.0476602 0.997855 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1666 1716 -0.189705 0.00209058 -6.26391 -0.000329814 0.034132 0.00511709 0.999404 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1666 1717 -0.781448 10.4337 -6.74341 -0.0244318 0.0339134 0.0488507 0.997931 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1667 1716 -0.757412 -10.435 -6.4817 0.0334574 0.0346736 -0.0565525 0.997236 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1667 1717 -0.205444 0.00764143 -6.27337 -0.00928672 0.0376712 0.00646186 0.999226 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1667 1718 -0.781695 10.4063 -6.72482 -0.0281582 0.0299563 0.0519977 0.997801 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1668 1717 -0.752393 -10.4092 -6.50081 0.0350601 0.0251041 -0.0496522 0.997835 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1668 1718 -0.197841 -0.00801973 -6.27723 -0.00187891 0.0290831 -0.00507644 0.999562 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1668 1719 -0.772739 10.3993 -6.74491 -0.0259483 0.0248595 0.049755 0.998115 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1669 1718 -0.747361 -10.4089 -6.49861 0.0327749 0.0321857 -0.0374849 0.998241 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1669 1719 -0.179794 -0.00590959 -6.28101 -0.000877569 0.0268101 0.0058624 0.999623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1669 1720 -0.771645 10.4015 -6.73501 -0.0316821 0.0330924 0.0503517 0.99768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1670 1719 -0.757839 -10.4164 -6.46802 0.0277233 0.0288866 -0.0598397 0.997405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1670 1720 -0.198361 -0.000691397 -6.26765 0.00624587 0.0213651 -0.00352421 0.999746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1670 1721 -0.764087 10.3686 -6.74038 -0.0295784 0.0290128 0.0617604 0.997231 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1671 1720 -0.750382 -10.4101 -6.49944 0.0350407 0.0329303 -0.0520374 0.997487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1671 1721 -0.203385 0.00706508 -6.2725 -0.0050333 0.0310174 -0.0029316 0.999502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1671 1722 -0.760032 10.3733 -6.74562 -0.0371588 0.0348143 0.0570062 0.997074 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1672 1721 -0.771694 -10.3946 -6.48617 0.0363299 0.0201271 -0.05727 0.997494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1672 1722 -0.212235 0.00756579 -6.27675 -0.0130053 0.0277726 -0.00613686 0.999511 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1672 1723 -0.76764 10.3693 -6.74924 -0.0333808 0.0427883 0.0586885 0.9968 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1673 1722 -0.751889 -10.3766 -6.49849 0.0204923 0.0323743 -0.0593765 0.9975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1673 1723 -0.204085 0.0037261 -6.2659 -0.00607665 0.0248027 -0.00326553 0.999669 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1673 1724 -0.77288 10.378 -6.74508 -0.042211 0.0279686 0.0534579 0.997285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1674 1723 -0.751499 -10.3607 -6.47452 0.0233654 0.0199216 -0.0593255 0.997766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1674 1724 -0.199803 -0.00738644 -6.28193 0.00557225 0.0459281 -0.00326302 0.998924 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1674 1725 -0.766135 10.3662 -6.73351 -0.0321863 0.0328012 0.0535532 0.997507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1675 1724 -0.74906 -10.3691 -6.49832 0.035543 0.0291493 -0.0460477 0.997881 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1675 1725 -0.189244 0.00420651 -6.27378 0.00192475 0.0195667 0.00529034 0.999793 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1675 1726 -0.762745 10.3406 -6.73035 -0.0284868 0.0300528 0.0551353 0.99762 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1676 1725 -0.733312 -10.3607 -6.49753 0.0259113 0.0293976 -0.0539574 0.997774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1676 1726 -0.215044 0.0103751 -6.27828 -0.00303883 0.0379283 -0.00724859 0.99925 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1676 1727 -0.757661 10.3425 -6.75234 -0.0355582 0.0404075 0.0551277 0.997027 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1677 1726 -0.742485 -10.3425 -6.49075 0.0338076 0.0332176 -0.0522585 0.997508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1677 1727 -0.192711 0.0109226 -6.2882 -0.00335251 0.0325739 0.0058435 0.999447 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1677 1728 -0.767134 10.3169 -6.74957 -0.031573 0.0289685 0.045297 0.998054 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1678 1727 -0.737249 -10.3334 -6.49418 0.030269 0.0248517 -0.0598469 0.997439 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1678 1728 -0.206174 0.0222133 -6.27478 0.00840008 0.0383248 -0.00390673 0.999222 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1678 1729 -0.760932 10.3129 -6.74089 -0.0295392 0.0292104 0.0542366 0.997664 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1679 1728 -0.750383 -10.3388 -6.47829 0.0347634 0.0340441 -0.0532972 0.997393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1679 1729 -0.195413 0.0129399 -6.28328 -0.00228859 0.0355694 0.00133081 0.999364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1679 1730 -0.767361 10.3185 -6.74405 -0.0397001 0.0392248 0.0472662 0.997322 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1680 1729 -0.73725 -10.3302 -6.48413 0.0313109 0.0361108 -0.055926 0.99729 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1680 1730 -0.182452 -0.0203743 -6.27684 0.00486788 0.0245681 0.00574279 0.99967 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1680 1731 -0.759171 10.3055 -6.74994 -0.038025 0.035048 0.0444418 0.997673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1681 1730 -0.746558 -10.2951 -6.47206 0.0351341 0.0243307 -0.0609273 0.997227 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1681 1731 -0.201869 -0.00131493 -6.28892 -0.000493481 0.0310454 0.00149038 0.999517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1681 1732 -0.765279 10.2923 -6.7333 -0.0293351 0.0358889 0.0524819 0.997546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1682 1731 -0.756282 -10.3087 -6.48535 0.0271284 0.0263611 -0.0478463 0.998138 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1682 1732 -0.199737 -0.0132603 -6.29336 -0.00119139 0.0256484 0.00505483 0.999658 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1682 1733 -0.755337 10.279 -6.73651 -0.0385913 0.0342427 0.0506269 0.997384 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1683 1732 -0.753367 -10.3002 -6.49619 0.0356778 0.0333697 -0.0531193 0.997393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1683 1733 -0.192499 0.0127597 -6.27974 0.0032738 0.0328498 0.0026394 0.999451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1683 1734 -0.752765 10.2965 -6.7336 -0.0322107 0.0334645 0.0564176 0.997326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1684 1733 -0.732187 -10.2792 -6.48466 0.0404718 0.0306534 -0.0584913 0.996996 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1684 1734 -0.195587 -0.00751446 -6.27403 0.00126419 0.0274227 -0.0138048 0.999528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1684 1735 -0.742125 10.2807 -6.73608 -0.0300732 0.0182236 0.0452841 0.998355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1685 1734 -0.727653 -10.2719 -6.49775 0.0347796 0.0378099 -0.057073 0.997047 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1685 1735 -0.190499 0.0147273 -6.29997 -0.0030572 0.032818 -0.000691257 0.999456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1685 1736 -0.767591 10.2736 -6.74931 -0.0313572 0.0363745 0.0523134 0.997475 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1686 1735 -0.738245 -10.2717 -6.48175 0.0363942 0.0336836 -0.0523062 0.997399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1686 1736 -0.19816 0.0148799 -6.28604 -0.00236216 0.0227985 0.00186697 0.999736 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1686 1737 -0.749503 10.2456 -6.7236 -0.0337978 0.0271789 0.0493704 0.997838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1687 1736 -0.734569 -10.2434 -6.51483 0.0360518 0.0317052 -0.0499118 0.997599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1687 1737 -0.19183 -0.0104685 -6.2755 -0.00139378 0.0312159 -0.00970918 0.999465 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1687 1738 -0.73379 10.2542 -6.73987 -0.0370654 0.0294391 0.0525945 0.997494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1688 1737 -0.746915 -10.2453 -6.51029 0.031626 0.0345007 -0.057354 0.997256 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1688 1738 -0.197883 0.0132997 -6.29976 -0.00119829 0.0329099 0.00421588 0.999449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1688 1739 -0.765118 10.2259 -6.74883 -0.0294539 0.0230418 0.0526597 0.997912 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1689 1738 -0.731432 -10.2301 -6.49241 0.0411161 0.028165 -0.0511351 0.997447 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1689 1739 -0.198192 -0.0098317 -6.28231 0.00484128 0.0281339 -0.000206344 0.999592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1689 1740 -0.745013 10.2235 -6.74483 -0.0223989 0.0335338 0.0493235 0.997968 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1690 1739 -0.735646 -10.2376 -6.49105 0.0355131 0.0243887 -0.0560526 0.997498 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1690 1740 -0.201346 0.00905808 -6.27427 -0.00568228 0.0475991 0.000683903 0.99885 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1690 1741 -0.731078 10.2206 -6.74703 -0.0260178 0.028232 0.0523519 0.99789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1691 1740 -0.713802 -10.2345 -6.50326 0.0382166 0.0376557 -0.0511277 0.99725 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1691 1741 -0.20529 0.00669635 -6.29363 0.00110025 0.0310075 0.0010392 0.999518 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1691 1742 -0.74335 10.2049 -6.75111 -0.0300164 0.032158 0.03961 0.998246 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1692 1741 -0.724653 -10.1934 -6.4928 0.0291264 0.040514 -0.0500602 0.997499 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1692 1742 -0.191751 0.00992174 -6.29016 0.00651957 0.0263888 -0.00134498 0.99963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1692 1743 -0.754294 10.1911 -6.74445 -0.0285265 0.0253763 0.0519371 0.99792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1693 1742 -0.735447 -10.1998 -6.47286 0.0377325 0.0332018 -0.0528921 0.997335 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1693 1743 -0.204748 0.0028352 -6.28188 0.00248725 0.0300605 -0.00656342 0.999523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1693 1744 -0.752423 10.2031 -6.7546 -0.0409408 0.029061 0.0436594 0.997784 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1694 1743 -0.72913 -10.1989 -6.47575 0.0278971 0.0268034 -0.0595095 0.997478 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1694 1744 -0.199583 0.0018441 -6.28414 0.0016702 0.0388698 0.00337077 0.999237 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1694 1745 -0.746379 10.1847 -6.74369 -0.0349859 0.0200223 0.053281 0.997766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1695 1744 -0.723108 -10.2007 -6.49724 0.0346656 0.0316125 -0.0539021 0.997443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1695 1745 -0.194495 -0.00413098 -6.2793 -0.00386343 0.0265607 -0.00368185 0.999633 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1695 1746 -0.750984 10.1695 -6.73946 -0.0289065 0.0328571 0.0558659 0.997479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1696 1745 -0.738576 -10.1856 -6.48693 0.0383911 0.0261239 -0.0476786 0.997783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1696 1746 -0.201233 0.0184458 -6.27672 -0.0037899 0.0278703 0.000889219 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1696 1747 -0.749487 10.1634 -6.7326 -0.0300658 0.0344771 0.0577712 0.997281 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1697 1746 -0.725614 -10.1586 -6.49098 0.0324167 0.0294784 -0.0525449 0.997657 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1697 1747 -0.174947 -0.00734288 -6.28451 -0.000532676 0.0267353 -0.00217828 0.99964 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1697 1748 -0.750115 10.1414 -6.73222 -0.0334768 0.0331987 0.0567147 0.997277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1698 1747 -0.726908 -10.1572 -6.47789 0.0386288 0.0278096 -0.0461055 0.997802 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1698 1748 -0.191024 -0.00461966 -6.27391 -0.00543562 0.0308089 -0.0012973 0.99951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1698 1749 -0.744095 10.1432 -6.73904 -0.0347179 0.0312127 0.0615949 0.997009 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1699 1748 -0.699626 -10.1661 -6.48686 0.0426736 0.0304245 -0.0522909 0.997256 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1699 1749 -0.192901 0.00328568 -6.28575 -0.00226352 0.0220095 0.00388351 0.999748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1699 1750 -0.743984 10.1291 -6.74612 -0.0484741 0.0376089 0.0461289 0.99705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1700 1749 -0.712153 -10.1421 -6.49877 0.0281371 0.0354487 -0.0458224 0.997924 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1700 1750 -0.187857 -0.0162766 -6.28717 -0.00225169 0.0358781 -0.00314886 0.999349 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1700 1751 -0.732694 10.1109 -6.75899 -0.045317 0.0329406 0.0564564 0.996832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1701 1750 -0.727011 -10.142 -6.48308 0.0362849 0.0327516 -0.0481099 0.997645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1701 1751 -0.18246 0.0104605 -6.27653 -0.00496671 0.0315705 -0.00212577 0.999487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1701 1752 -0.732436 10.1241 -6.75068 -0.0314246 0.0408183 0.0527958 0.997276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1702 1751 -0.72637 -10.1166 -6.47979 0.0305371 0.0323375 -0.0475005 0.99788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1702 1752 -0.203418 0.0113572 -6.27572 0.000367056 0.0237216 0.00622337 0.999699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1702 1753 -0.745877 10.1128 -6.74446 -0.0299861 0.0345691 0.046872 0.997852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1703 1752 -0.724891 -10.1145 -6.48966 0.0360614 0.0286321 -0.0457061 0.997893 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1703 1753 -0.189842 -0.00935592 -6.28134 -0.00178359 0.025727 -0.002485 0.999664 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1703 1754 -0.741794 10.0867 -6.73924 -0.0415803 0.0262991 0.0512036 0.997476 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1704 1753 -0.723126 -10.0923 -6.49637 0.0337182 0.0339702 -0.0557791 0.997295 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1704 1754 -0.195578 -0.0060436 -6.27086 -0.00195103 0.0323882 -0.00618013 0.999454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1704 1755 -0.729731 10.0849 -6.74642 -0.0259155 0.0314991 0.0437987 0.998207 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1705 1754 -0.718053 -10.0749 -6.5006 0.0305071 0.0305458 -0.0576083 0.997405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1705 1755 -0.19186 0.0185513 -6.27445 0.00511539 0.0235951 0.00253069 0.999705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1705 1756 -0.744882 10.0741 -6.75342 -0.0329941 0.0352409 0.0487229 0.997645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1706 1755 -0.706109 -10.0814 -6.5051 0.0372366 0.035442 -0.046608 0.99759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1706 1756 -0.210747 -0.00555359 -6.28059 0.00544061 0.0354432 -0.00512712 0.999344 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1706 1757 -0.740388 10.0815 -6.76748 -0.0235108 0.0374499 0.0488919 0.997825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1707 1756 -0.73649 -10.0798 -6.51899 0.0451135 0.0208209 -0.0511021 0.997457 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1707 1757 -0.197526 -0.0084022 -6.2688 0.000886284 0.0310449 0.00280151 0.999514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1707 1758 -0.756737 10.0542 -6.74612 -0.0306857 0.0346877 0.0514177 0.997603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1708 1757 -0.724063 -10.0693 -6.50959 0.0342799 0.0238702 -0.0593315 0.997364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1708 1758 -0.198857 -0.000699516 -6.26734 -4.25227e-05 0.0268373 0.000995201 0.999639 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1708 1759 -0.715215 10.0404 -6.74113 -0.0283624 0.0316938 0.0501884 0.997834 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1709 1758 -0.721393 -10.0535 -6.50084 0.0444528 0.0245937 -0.0466806 0.997617 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1709 1759 -0.187241 0.0150769 -6.29392 0.00349495 0.0322208 -0.00742152 0.999447 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1709 1760 -0.72845 10.025 -6.72634 -0.0341521 0.0347775 0.056043 0.997238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1710 1759 -0.738183 -10.0159 -6.50454 0.0334787 0.0290073 -0.0504834 0.997742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1710 1760 -0.190784 -0.0368937 -6.28692 -0.00261913 0.029112 -0.00252332 0.99957 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1710 1761 -0.723448 10.0424 -6.75324 -0.0365318 0.031234 0.0516198 0.99751 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1711 1760 -0.713626 -10.0378 -6.49397 0.0405736 0.0302059 -0.0605006 0.996886 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1711 1761 -0.184132 -0.00909009 -6.25354 0.00183102 0.0285008 0.00183773 0.99959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1711 1762 -0.723183 10.0135 -6.76069 -0.0384039 0.0341411 0.0488826 0.997482 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1712 1761 -0.714523 -10.0487 -6.4982 0.0339382 0.0291824 -0.0431317 0.998066 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1712 1762 -0.184375 -0.00737149 -6.27061 0.00443582 0.0324097 0.00207489 0.999463 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1712 1763 -0.717645 10.0147 -6.74423 -0.0267576 0.0360115 0.0454681 0.997958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1713 1762 -0.706954 -10.0152 -6.51225 0.036367 0.0331028 -0.0491182 0.997582 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1713 1763 -0.194567 -0.000554837 -6.28222 0.00222914 0.0333335 0.0103743 0.999388 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1713 1764 -0.736024 9.98794 -6.74388 -0.0341661 0.0277276 0.0528237 0.997634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1714 1763 -0.725924 -9.99824 -6.50365 0.0384072 0.0274162 -0.0520603 0.997528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1714 1764 -0.20672 -0.00839366 -6.28244 0.00282862 0.0346339 -0.00751612 0.999368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1714 1765 -0.728202 9.9715 -6.75604 -0.037197 0.0337569 0.0507458 0.997448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1715 1764 -0.711714 -10.0132 -6.49493 0.0429388 0.0311787 -0.0500849 0.997334 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1715 1765 -0.191038 -0.00551404 -6.27221 -0.00425952 0.0408082 -0.00168384 0.999157 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1715 1766 -0.734086 9.9898 -6.75215 -0.0361375 0.0393133 0.0457957 0.997523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1716 1765 -0.715062 -9.99868 -6.49019 0.0347053 0.0388935 -0.0425491 0.997734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1716 1766 -0.193346 0.00253227 -6.28378 0.00306394 0.0327748 0.00791819 0.999427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1716 1767 -0.729085 9.9583 -6.7388 -0.0404938 0.0357065 0.0508952 0.997244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1717 1766 -0.727144 -9.98057 -6.49644 0.0420284 0.0325381 -0.0558598 0.997023 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1717 1767 -0.194617 -0.000780307 -6.28455 -0.00239866 0.0317371 0.00340571 0.999488 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1717 1768 -0.724471 9.97001 -6.73213 -0.0394261 0.0343627 0.0544516 0.997146 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1718 1767 -0.713961 -9.95594 -6.50988 0.0391677 0.0367788 -0.0472169 0.997439 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1718 1768 -0.206807 0.00521478 -6.29333 -0.00133125 0.0445722 0.00102752 0.999005 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1718 1769 -0.719147 9.95528 -6.75679 -0.0369875 0.0276582 0.0519951 0.997579 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1719 1768 -0.700749 -9.96299 -6.49355 0.0447818 0.0312899 -0.0416411 0.997638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1719 1769 -0.197761 -0.0219521 -6.27512 0.00284673 0.0307694 0.0065814 0.999501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1719 1770 -0.722437 9.93631 -6.74801 -0.0404955 0.0332045 0.0558108 0.997067 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1720 1769 -0.719036 -9.97081 -6.5146 0.0358258 0.0370255 -0.0594463 0.996901 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1720 1770 -0.21011 -0.0106823 -6.27858 0.00396502 0.0247997 -0.00187304 0.999683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1720 1771 -0.734017 9.95643 -6.75737 -0.0382856 0.0354563 0.0442944 0.997655 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1721 1770 -0.732776 -9.9407 -6.50954 0.0385976 0.0354759 -0.0503771 0.997353 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1721 1771 -0.188025 -0.00250777 -6.28304 -0.00803715 0.0273283 0.00105232 0.999594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1721 1772 -0.735292 9.91699 -6.76174 -0.0236133 0.0316202 0.0534448 0.997791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1722 1771 -0.700288 -9.94209 -6.46574 0.0345491 0.0404825 -0.0479504 0.997431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1722 1772 -0.189192 -0.00219527 -6.28097 0.000888142 0.027567 -0.00169869 0.999618 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1722 1773 -0.730861 9.92498 -6.75436 -0.0354643 0.0256918 0.0530617 0.997631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1723 1772 -0.710516 -9.92344 -6.49233 0.0343809 0.0344603 -0.0526465 0.997426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1723 1773 -0.185448 -0.00371442 -6.28399 0.00908934 0.0254704 0.00258478 0.999631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1723 1774 -0.710466 9.89753 -6.74177 -0.0383931 0.031507 0.0524738 0.997386 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1724 1773 -0.686327 -9.92109 -6.48957 0.036706 0.0274272 -0.0424129 0.998049 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1724 1774 -0.19258 0.0137428 -6.27462 -0.00782837 0.0378913 0.00234128 0.999248 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1724 1775 -0.712346 9.90174 -6.77135 -0.0321003 0.0267842 0.0526482 0.997738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1725 1774 -0.694103 -9.90509 -6.50097 0.0466094 0.0288346 -0.0554417 0.996957 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1725 1775 -0.202141 -0.000395851 -6.2807 -0.00409254 0.0380028 0.00673751 0.999247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1725 1776 -0.725215 9.88267 -6.73222 -0.0370268 0.0364995 0.0456979 0.997601 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1726 1775 -0.701612 -9.89527 -6.48748 0.0393873 0.034233 -0.0488403 0.997442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1726 1776 -0.20164 0.0213665 -6.28372 -0.00234111 0.0307535 0.00322726 0.999519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1726 1777 -0.721042 9.87587 -6.7356 -0.0436718 0.0330913 0.0533919 0.997069 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1727 1776 -0.706045 -9.87379 -6.49801 0.036102 0.0349193 -0.0495101 0.99751 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1727 1777 -0.197239 -0.00856764 -6.28073 0.000918701 0.0379838 -0.00114385 0.999277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1727 1778 -0.718572 9.85037 -6.73806 -0.0301414 0.0413907 0.054832 0.997182 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1728 1777 -0.703421 -9.86762 -6.50606 0.0348052 0.0359885 -0.0524124 0.99737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1728 1778 -0.214105 -0.00945076 -6.27673 -0.00417039 0.0400007 -0.0065264 0.99917 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1728 1779 -0.70413 9.86057 -6.76129 -0.0378958 0.0364005 0.052145 0.997256 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1729 1778 -0.707875 -9.86201 -6.49313 0.0414148 0.027353 -0.0505346 0.997488 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1729 1779 -0.190676 -0.0119508 -6.2885 -0.00259327 0.0331239 0.00298502 0.999443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1729 1780 -0.723438 9.85091 -6.76051 -0.0357714 0.0295498 0.0447358 0.997921 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1730 1779 -0.705989 -9.84216 -6.50371 0.0385182 0.0270802 -0.0667629 0.996657 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1730 1780 -0.193298 -0.0122444 -6.27655 -0.00536551 0.0355845 -0.00440352 0.999343 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1730 1781 -0.709059 9.85672 -6.75925 -0.030711 0.0245599 0.0556848 0.997674 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1731 1780 -0.703863 -9.8534 -6.52117 0.0337712 0.0261825 -0.0552287 0.997559 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1731 1781 -0.197107 -0.000139108 -6.2715 0.00162674 0.0292392 9.19221e-05 0.999571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1731 1782 -0.732258 9.83376 -6.75607 -0.0368261 0.0314921 0.044384 0.997839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1732 1781 -0.698378 -9.84387 -6.51682 0.0341189 0.0270158 -0.0470096 0.997946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1732 1782 -0.190313 -1.40102e-06 -6.28365 0.00403899 0.0331937 0.00241527 0.999438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1732 1783 -0.702639 9.81453 -6.76619 -0.0360016 0.0230701 0.0499463 0.997836 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1733 1782 -0.687805 -9.83799 -6.51068 0.0331588 0.0447151 -0.0511988 0.997136 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1733 1783 -0.210353 -0.00902814 -6.27938 -0.00138765 0.0323876 -0.0070551 0.99945 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1733 1784 -0.728139 9.79695 -6.76367 -0.0360947 0.0375217 0.0430676 0.997715 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1734 1783 -0.697901 -9.82469 -6.51592 0.0462231 0.0304906 -0.0466088 0.997377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1734 1784 -0.19818 -0.00969744 -6.27415 0.00747611 0.0356484 -0.00124106 0.999336 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1734 1785 -0.712911 9.8073 -6.75844 -0.0489304 0.031238 0.0586558 0.996589 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1735 1784 -0.700697 -9.80375 -6.50072 0.0384747 0.0347888 -0.0543028 0.997176 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1735 1785 -0.198802 0.0197012 -6.29808 -0.00618948 0.026328 4.45574e-05 0.999634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1735 1786 -0.699994 9.79895 -6.76664 -0.0425533 0.0313662 0.0552099 0.997074 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1736 1785 -0.694331 -9.80318 -6.51529 0.0347883 0.032416 -0.0571978 0.99723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1736 1786 -0.190118 0.0105489 -6.28239 0.00555419 0.0373175 0.000176655 0.999288 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1736 1787 -0.703529 9.78368 -6.75428 -0.0360557 0.0340282 0.0468399 0.997671 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1737 1786 -0.692517 -9.81161 -6.52872 0.042527 0.0252123 -0.0546517 0.997281 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1737 1787 -0.199922 -0.00546933 -6.27537 0.000440578 0.0326489 0.00305457 0.999462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1737 1788 -0.709673 9.77133 -6.76344 -0.0518182 0.0391953 0.0462441 0.996815 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1738 1787 -0.698032 -9.78121 -6.51834 0.0424778 0.0200095 -0.061378 0.99701 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1738 1788 -0.213173 -0.00715375 -6.27043 0.00241083 0.0298831 -0.00179776 0.999549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1738 1789 -0.728922 9.74787 -6.74783 -0.0329869 0.0311721 0.0510476 0.997664 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1739 1788 -0.692788 -9.76362 -6.51508 0.0273778 0.046042 -0.0536445 0.997122 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1739 1789 -0.209348 -0.0126975 -6.28824 0.00332928 0.0265086 -0.00154818 0.999642 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1739 1790 -0.696411 9.75364 -6.75374 -0.0438748 0.0346861 0.0426515 0.997523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1740 1789 -0.681921 -9.7783 -6.5192 0.0449475 0.0340609 -0.0531085 0.996995 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1740 1790 -0.196427 0.00973866 -6.27051 -0.00189012 0.0374063 -0.00426398 0.999289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1740 1791 -0.708135 9.76328 -6.77067 -0.0354381 0.0411041 0.0501003 0.997269 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1741 1790 -0.686355 -9.75554 -6.51265 0.0375309 0.0338911 -0.0533167 0.997296 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1741 1791 -0.167213 -0.00331831 -6.28321 -0.0055003 0.0309894 -0.00790209 0.999473 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1741 1792 -0.706223 9.7196 -6.74504 -0.0408462 0.0362045 0.0499738 0.997258 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1742 1791 -0.676517 -9.72833 -6.51192 0.0329303 0.0303582 -0.0506782 0.99771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1742 1792 -0.206405 -0.00833131 -6.27339 0.00523988 0.0294885 0.00596671 0.999534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1742 1793 -0.706077 9.71203 -6.75287 -0.034516 0.0229125 0.0464984 0.998059 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1743 1792 -0.695213 -9.72395 -6.49792 0.0326872 0.0265045 -0.0467958 0.998018 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1743 1793 -0.199037 -0.0156117 -6.26723 -0.00779497 0.0271279 0.00217503 0.999599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1743 1794 -0.717908 9.70707 -6.7724 -0.0432771 0.0307387 0.0502339 0.997326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1744 1793 -0.670019 -9.72422 -6.52442 0.0370447 0.0256764 -0.0494483 0.997759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1744 1794 -0.180533 -0.012822 -6.30207 0.00287366 0.0325503 0.00278555 0.999462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1744 1795 -0.712941 9.6855 -6.77224 -0.0436976 0.030219 0.0403082 0.997774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1745 1794 -0.682028 -9.70089 -6.51291 0.0366114 0.0341537 -0.0498495 0.997501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1745 1795 -0.200652 0.00157492 -6.28037 0.00220742 0.0386608 0.00253843 0.999247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1745 1796 -0.673843 9.70395 -6.75143 -0.0347438 0.0404654 0.0553667 0.997041 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1746 1795 -0.682806 -9.70545 -6.52383 0.0400971 0.034363 -0.0529459 0.9972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1746 1796 -0.199959 0.0119881 -6.26607 0.00113545 0.0401095 -0.00116413 0.999194 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1746 1797 -0.699572 9.67637 -6.77968 -0.0414642 0.0349762 0.0569362 0.996903 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1747 1796 -0.682912 -9.69914 -6.507 0.0428841 0.0375212 -0.0472833 0.997255 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1747 1797 -0.215457 -0.00689765 -6.29234 -0.00472691 0.0264909 -0.00681186 0.999615 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1747 1798 -0.703294 9.67562 -6.77962 -0.0368073 0.034887 0.0597736 0.996923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1748 1797 -0.693172 -9.67556 -6.50369 0.040481 0.0333289 -0.0476411 0.997487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1748 1798 -0.197613 0.0100487 -6.30097 -0.00455022 0.033771 -0.00561342 0.999403 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1748 1799 -0.704561 9.67019 -6.76504 -0.03344 0.029859 0.0465528 0.997909 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1749 1798 -0.691834 -9.66529 -6.50429 0.0373866 0.0375376 -0.0552255 0.997067 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1749 1799 -0.18956 -5.03301e-05 -6.28427 -0.00537515 0.0373211 0.00748535 0.999261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1749 1800 -0.696771 9.64354 -6.75379 -0.0441619 0.0301703 0.0404488 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1750 1799 -0.684669 -9.64741 -6.52869 0.0449191 0.0273665 -0.0478376 0.997469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1750 1800 -0.212482 -0.00600172 -6.28658 0.00319611 0.0304603 0.00199369 0.999529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1750 1801 -0.689905 9.64746 -6.75638 -0.0441461 0.0242165 0.0468054 0.997634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1751 1800 -0.676724 -9.65326 -6.50648 0.0346349 0.0306995 -0.0597836 0.997138 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1751 1801 -0.187965 0.00921921 -6.26853 -0.00059416 0.0332686 -0.00785904 0.999415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1751 1802 -0.699064 9.63444 -6.76796 -0.0347294 0.0423314 0.046924 0.997397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1752 1801 -0.690909 -9.64637 -6.50355 0.0417696 0.0323193 -0.0470745 0.997494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1752 1802 -0.182034 -0.00551795 -6.2692 0.0117893 0.0425491 0.00559819 0.999009 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1752 1803 -0.694043 9.59975 -6.77447 -0.0390678 0.036239 0.0582231 0.99688 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1753 1802 -0.696387 -9.63354 -6.52126 0.038747 0.0284015 -0.0554752 0.997304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1753 1803 -0.199457 0.00510537 -6.28067 0.0010531 0.0297272 -0.00203483 0.999555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1753 1804 -0.690593 9.60333 -6.74721 -0.0361937 0.0233582 0.0469955 0.997966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1754 1803 -0.677146 -9.6099 -6.51853 0.0435653 0.028029 -0.0638961 0.996611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1754 1804 -0.200698 -0.00200243 -6.28129 0.00286669 0.032383 0.00119213 0.999471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1754 1805 -0.683051 9.59855 -6.74683 -0.0368011 0.0217228 0.0542261 0.997614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1755 1804 -0.674337 -9.59898 -6.51184 0.042275 0.0351436 -0.0479357 0.997336 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1755 1805 -0.222184 0.0159068 -6.28632 -0.0063102 0.0375041 0.00226824 0.999274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1755 1806 -0.702917 9.5784 -6.75392 -0.0385731 0.0426983 0.0485939 0.99716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1756 1805 -0.669931 -9.59799 -6.51189 0.0412031 0.0326544 -0.0607129 0.99677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1756 1806 -0.202991 0.00950157 -6.27635 -0.0017023 0.0283137 -0.000667301 0.999597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1756 1807 -0.686118 9.57769 -6.75619 -0.048216 0.0308437 0.0403994 0.997543 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1757 1806 -0.687697 -9.58785 -6.50438 0.0367946 0.0369248 -0.038716 0.99789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1757 1807 -0.198479 0.0140544 -6.27337 0.00296521 0.0313899 0.00211376 0.999501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1757 1808 -0.673516 9.553 -6.76303 -0.0358854 0.0366981 0.0363695 0.998019 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1758 1807 -0.675013 -9.56564 -6.51635 0.037486 0.0337681 -0.0465737 0.99764 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1758 1808 -0.195679 0.00231608 -6.28516 -0.0030623 0.0330684 0.00245535 0.999445 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1758 1809 -0.670097 9.56178 -6.74997 -0.0257166 0.034144 0.0534792 0.997654 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1759 1808 -0.666755 -9.56664 -6.51054 0.0420726 0.0313796 -0.0461095 0.997557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1759 1809 -0.203244 -0.00775372 -6.27382 -0.00441492 0.038737 0.000103478 0.99924 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1759 1810 -0.669979 9.5705 -6.7694 -0.044248 0.0326798 0.0473364 0.997363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1760 1809 -0.667012 -9.55594 -6.52153 0.03309 0.0338067 -0.0488329 0.997686 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1760 1810 -0.17504 -0.00977364 -6.30413 -0.00718864 0.0365975 -0.00271505 0.999301 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1760 1811 -0.684912 9.54281 -6.76062 -0.0381896 0.03802 0.04446 0.997557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1761 1810 -0.668974 -9.53443 -6.51194 0.0430749 0.0313606 -0.0407873 0.997746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1761 1811 -0.179533 -0.0192109 -6.29036 -0.00316625 0.0429483 -0.00434289 0.999063 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1761 1812 -0.696772 9.5374 -6.77266 -0.0437903 0.0273792 0.0605477 0.996828 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1762 1811 -0.676914 -9.55552 -6.52612 0.0419417 0.0268206 -0.049471 0.997534 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1762 1812 -0.210333 0.0182464 -6.28524 -0.00108647 0.0292958 -0.0037637 0.999563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1762 1813 -0.695051 9.53975 -6.76222 -0.0389408 0.0296718 0.0453378 0.997771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1763 1812 -0.664604 -9.53877 -6.50955 0.0441428 0.0207154 -0.0491994 0.997598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1763 1813 -0.190368 -0.00377562 -6.27328 0.00311516 0.0335113 0.000565162 0.999433 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1763 1814 -0.69055 9.5049 -6.77797 -0.0417695 0.036222 0.0468227 0.997372 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1764 1813 -0.679355 -9.51416 -6.5035 0.0444829 0.0296512 -0.0552656 0.99704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1764 1814 -0.224461 0.00542927 -6.28466 -0.00283119 0.0370893 0.00690771 0.999284 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1764 1815 -0.673317 9.50283 -6.76294 -0.0420375 0.0331991 0.0495891 0.997332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1765 1814 -0.657945 -9.48428 -6.53226 0.030678 0.0266445 -0.0434074 0.998231 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1765 1815 -0.202828 -0.00583202 -6.27031 0.00315788 0.0306444 0.00262423 0.999522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1765 1816 -0.684436 9.48862 -6.767 -0.0424012 0.0369476 0.0523757 0.997043 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1766 1815 -0.661941 -9.49382 -6.49502 0.0368697 0.0260121 -0.0513714 0.99766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1766 1816 -0.187046 0.00523153 -6.27134 -0.00421736 0.0271604 -0.00010002 0.999622 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1766 1817 -0.68641 9.47346 -6.77238 -0.0376018 0.035848 0.0497077 0.997412 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1767 1816 -0.665287 -9.48726 -6.49905 0.0410222 0.0398649 -0.0490602 0.997156 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1767 1817 -0.187165 -0.00825754 -6.296 -0.00532201 0.0361371 -0.00298972 0.999328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1767 1818 -0.692522 9.45225 -6.77233 -0.0389042 0.0383735 0.0501945 0.997243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1768 1817 -0.662836 -9.48082 -6.52075 0.0414195 0.0332948 -0.0477908 0.997443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1768 1818 -0.192959 -0.0150869 -6.2698 -0.000620757 0.0369354 0.00226484 0.999315 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1768 1819 -0.672215 9.43662 -6.7544 -0.0353852 0.0291028 0.0496319 0.997716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1769 1818 -0.653379 -9.47491 -6.51251 0.0410986 0.0292416 -0.0549233 0.997216 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1769 1819 -0.202249 0.0119854 -6.26047 -0.00360728 0.0342873 -0.00101405 0.999405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1769 1820 -0.671922 9.42934 -6.75873 -0.0362737 0.0382383 0.0518449 0.997263 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1770 1819 -0.675396 -9.4376 -6.49081 0.0437652 0.0278851 -0.0540221 0.99719 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1770 1820 -0.207568 0.0028841 -6.27166 -0.00423758 0.0315789 0.00642526 0.999472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1770 1821 -0.687557 9.43198 -6.7795 -0.029946 0.0351139 0.0443883 0.997948 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1771 1820 -0.65552 -9.43549 -6.52566 0.0395323 0.0280847 -0.0434559 0.997878 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1771 1821 -0.185942 -0.0150363 -6.26611 -0.00592116 0.0359307 -0.00172838 0.999335 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1771 1822 -0.672613 9.44592 -6.77673 -0.0396723 0.0392394 0.0436288 0.997488 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1772 1821 -0.670072 -9.42387 -6.50486 0.0496399 0.0221528 -0.0454579 0.997486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1772 1822 -0.217174 -0.00145258 -6.26602 -0.000326376 0.0297597 0.00361548 0.99955 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1772 1823 -0.679284 9.41183 -6.77502 -0.0411924 0.0345316 0.0513078 0.997235 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1773 1822 -0.655264 -9.42011 -6.51704 0.0387941 0.0283998 -0.0442632 0.997862 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1773 1823 -0.203618 -0.0108397 -6.26568 0.00167145 0.028844 -0.00409313 0.999574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1773 1824 -0.675688 9.41242 -6.75822 -0.042317 0.032557 0.0561695 0.996993 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1774 1823 -0.661464 -9.43074 -6.51635 0.0525589 0.0377965 -0.054195 0.99643 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1774 1824 -0.195313 -0.0044885 -6.2769 0.0053516 0.0403739 0.00502585 0.999158 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1774 1825 -0.668402 9.37895 -6.76155 -0.0343228 0.0319208 0.0553754 0.997365 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1775 1824 -0.667559 -9.38996 -6.5077 0.0331604 0.0332451 -0.0508173 0.997604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1775 1825 -0.194888 0.0048758 -6.28166 -0.000362996 0.0304618 0.000562492 0.999536 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1775 1826 -0.685132 9.38071 -6.77461 -0.0416783 0.0290789 0.0428035 0.99779 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1776 1825 -0.667067 -9.37764 -6.51736 0.042841 0.0313136 -0.0471706 0.997476 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1776 1826 -0.183016 0.000231383 -6.2682 0.00629486 0.0248185 0.00254624 0.999669 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1776 1827 -0.673484 9.36977 -6.77197 -0.037471 0.0305355 0.0547978 0.997327 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1777 1826 -0.673301 -9.39592 -6.53085 0.0370296 0.0271472 -0.0452849 0.997918 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1777 1827 -0.186435 0.011332 -6.25323 0.000785956 0.0450708 -0.00402236 0.998975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1777 1828 -0.676017 9.37871 -6.76657 -0.0360556 0.0398271 0.0453137 0.997527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1778 1827 -0.645973 -9.35216 -6.51148 0.0384634 0.0332201 -0.0423847 0.997808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1778 1828 -0.188722 -0.00404561 -6.28722 -0.000117395 0.0300081 0.00357745 0.999543 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1778 1829 -0.6801 9.34901 -6.76325 -0.0450383 0.0393919 0.0487658 0.997016 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1779 1828 -0.656295 -9.35837 -6.51368 0.0471738 0.0362833 -0.0514253 0.996902 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1779 1829 -0.191995 0.00125409 -6.25872 0.00024849 0.0242278 0.00475332 0.999695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1779 1830 -0.663916 9.36005 -6.78403 -0.0375745 0.0293193 0.051562 0.997532 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1780 1829 -0.664895 -9.34099 -6.52591 0.0421729 0.0363206 -0.0526711 0.99706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1780 1830 -0.20064 0.00856696 -6.29171 -0.00274568 0.0312135 0.00334664 0.999503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1780 1831 -0.683655 9.34006 -6.75787 -0.0441922 0.0254025 0.0436744 0.997745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1781 1830 -0.667585 -9.35454 -6.50797 0.0431051 0.0236022 -0.0488616 0.997596 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1781 1831 -0.19444 -0.00433594 -6.28174 0.00174466 0.0310847 0.0059549 0.999497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1781 1832 -0.673373 9.30714 -6.77418 -0.0401146 0.031485 0.0483006 0.99753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1782 1831 -0.640297 -9.31799 -6.51442 0.0438793 0.0322112 -0.0515503 0.997186 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1782 1832 -0.19672 0.0180837 -6.28413 0.00204345 0.0263444 0.00408641 0.999642 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1782 1833 -0.673575 9.30953 -6.75843 -0.0359531 0.0315666 0.0587013 0.997128 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1783 1832 -0.658282 -9.32142 -6.51524 0.0458765 0.0209543 -0.053769 0.997279 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1783 1833 -0.206412 0.00409411 -6.28456 -0.0141429 0.0351826 0.00949881 0.999236 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1783 1834 -0.663517 9.27953 -6.78805 -0.0416135 0.0352351 0.0497843 0.99727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1784 1833 -0.641509 -9.3209 -6.51571 0.0407557 0.0291802 -0.0480071 0.997588 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1784 1834 -0.201776 0.0118449 -6.2823 -0.0121141 0.0352393 0.001013 0.999305 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1784 1835 -0.667204 9.28556 -6.78361 -0.0421487 0.0374931 0.0422784 0.997512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1785 1834 -0.66225 -9.29594 -6.51751 0.0421345 0.0326978 -0.0489105 0.997378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1785 1835 -0.179815 -0.0144417 -6.28091 0.000831356 0.0365894 -0.00946351 0.999285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1785 1836 -0.671366 9.28977 -6.75644 -0.0427241 0.0310041 0.0419471 0.997724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1786 1835 -0.650096 -9.27253 -6.50798 0.0419441 0.0412228 -0.0406968 0.997439 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1786 1836 -0.210722 0.0136501 -6.27024 0.00493367 0.0231957 0.00288913 0.999715 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1786 1837 -0.66769 9.2744 -6.77697 -0.0446782 0.0377427 0.0430935 0.997358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1787 1836 -0.632567 -9.27443 -6.53563 0.0370343 0.0421727 -0.0389353 0.997664 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1787 1837 -0.197423 -0.00809825 -6.26109 0.000357042 0.0398129 -0.000549805 0.999207 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1787 1838 -0.667136 9.22915 -6.77407 -0.0359188 0.0295153 0.043932 0.997952 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1788 1837 -0.649521 -9.26973 -6.52654 0.0388222 0.0268027 -0.0444293 0.997898 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1788 1838 -0.20676 0.018434 -6.29215 -0.00352232 0.0259747 -0.00781068 0.999626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1788 1839 -0.663486 9.24644 -6.76533 -0.0383825 0.0422342 0.0404896 0.997549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1789 1838 -0.650933 -9.26144 -6.50955 0.0386086 0.0276922 -0.0563196 0.997282 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1789 1839 -0.199302 0.000789467 -6.28493 0.00285172 0.0351452 0.00393704 0.99937 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1789 1840 -0.680534 9.22858 -6.78997 -0.0446365 0.0282361 0.0485277 0.997424 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1790 1839 -0.649882 -9.22539 -6.52072 0.0405279 0.0288974 -0.045812 0.997709 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1790 1840 -0.191584 -0.00342909 -6.27932 -0.00270081 0.0376239 -0.00156722 0.999287 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1790 1841 -0.65851 9.23048 -6.78007 -0.0375633 0.0321613 0.0364552 0.998111 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1791 1840 -0.641507 -9.2393 -6.49884 0.0462534 0.0290133 -0.0479668 0.997356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1791 1841 -0.214285 0.00264275 -6.2703 0.00627676 0.0248386 0.00568138 0.999656 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1791 1842 -0.661071 9.20953 -6.77642 -0.0544892 0.0466179 0.0402464 0.996613 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1792 1841 -0.629371 -9.23643 -6.53309 0.041821 0.0398115 -0.0474126 0.997205 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1792 1842 -0.199448 -0.00944111 -6.29181 -0.0060689 0.0384076 -0.00411715 0.999235 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1792 1843 -0.659906 9.20498 -6.76875 -0.0374576 0.0424913 0.0504913 0.997117 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1793 1842 -0.641723 -9.21176 -6.5262 0.0452114 0.031789 -0.0440122 0.997501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1793 1843 -0.198434 0.000563723 -6.2847 -0.00365564 0.0279694 -0.000350228 0.999602 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1793 1844 -0.656393 9.17979 -6.77938 -0.0376605 0.0359673 0.0538653 0.997189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1794 1843 -0.621033 -9.19257 -6.5182 0.0342576 0.0268894 -0.052366 0.997678 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1794 1844 -0.20161 0.00639454 -6.27618 0.00418273 0.0380875 -0.000329124 0.999266 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1794 1845 -0.653496 9.18944 -6.771 -0.04271 0.0345146 0.0522881 0.997121 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1795 1844 -0.634752 -9.19056 -6.51955 0.0342721 0.0364037 -0.043718 0.997792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1795 1845 -0.188856 0.0044268 -6.25242 -0.00572277 0.0286096 -0.00303778 0.99957 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1795 1846 -0.648558 9.18937 -6.7775 -0.0434408 0.0344379 0.0446307 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1796 1845 -0.608508 -9.17076 -6.53155 0.0396734 0.0232245 -0.0461155 0.997878 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1796 1846 -0.196562 -0.00671461 -6.28125 0.00556465 0.0267917 -0.00469301 0.999615 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1796 1847 -0.657687 9.14871 -6.77152 -0.0463057 0.0372423 0.0414619 0.997371 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1797 1846 -0.642063 -9.1577 -6.53445 0.0382883 0.0268996 -0.0489683 0.997704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1797 1847 -0.206219 -0.00980995 -6.28939 0.0056233 0.0263017 -0.00568259 0.999622 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1797 1848 -0.657128 9.15404 -6.77616 -0.0429996 0.0354733 0.045672 0.9974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1798 1847 -0.640118 -9.16289 -6.53489 0.0434996 0.0316206 -0.038915 0.997794 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1798 1848 -0.209256 0.0224819 -6.2707 -0.00206118 0.0459432 -0.00222712 0.998939 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1798 1849 -0.653428 9.12279 -6.76878 -0.0482021 0.0358874 0.0494706 0.996966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1799 1848 -0.638541 -9.15236 -6.52904 0.0452762 0.0357697 -0.0462358 0.997263 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1799 1849 -0.200142 0.00853296 -6.27577 0.000644513 0.0307026 -0.00996124 0.999479 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1799 1850 -0.652378 9.12789 -6.76816 -0.0422972 0.029502 0.0491854 0.997457 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1800 1849 -0.632727 -9.13978 -6.52068 0.0418253 0.0241489 -0.0430167 0.997906 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1800 1850 -0.189538 -0.00612971 -6.29472 0.0055044 0.0305438 0.00226369 0.999516 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1800 1851 -0.642368 9.10458 -6.75994 -0.0329997 0.0390866 0.0550613 0.997172 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1801 1850 -0.632179 -9.12141 -6.51477 0.0433015 0.0232225 -0.0421611 0.997902 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1801 1851 -0.187501 0.0051544 -6.27537 -0.00430683 0.0366259 -0.00204289 0.999318 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1801 1852 -0.653222 9.11028 -6.77889 -0.041946 0.0277457 0.0503948 0.997462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1802 1851 -0.622061 -9.12731 -6.54234 0.0389468 0.0309461 -0.0555254 0.997217 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1802 1852 -0.199271 -0.00088894 -6.29535 -0.00902936 0.0311321 -0.00229583 0.999472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1802 1853 -0.636058 9.10277 -6.78251 -0.0412636 0.036233 0.0477978 0.997346 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1803 1852 -0.617867 -9.11869 -6.53787 0.0332482 0.0378358 -0.0594988 0.996957 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1803 1853 -0.177269 0.00549368 -6.27106 0.00616993 0.0380302 -0.000730161 0.999257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1803 1854 -0.641199 9.0854 -6.75513 -0.0380354 0.0313876 0.0454442 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1804 1853 -0.629971 -9.10834 -6.52317 0.0415074 0.0289305 -0.0382794 0.997985 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1804 1854 -0.195308 -0.00716891 -6.29618 -0.00882947 0.0332454 -0.00319765 0.999403 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1804 1855 -0.641643 9.0672 -6.78847 -0.0490766 0.0372977 0.0387462 0.997346 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1805 1854 -0.637058 -9.08769 -6.52383 0.0432048 0.0317591 -0.0516274 0.997226 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1805 1855 -0.190103 0.0156039 -6.29539 0.00176395 0.0295377 0.00511292 0.999549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1805 1856 -0.63969 9.06783 -6.75784 -0.0456876 0.0367839 0.03806 0.997553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1806 1855 -0.6172 -9.05887 -6.52022 0.0445323 0.0408859 -0.045295 0.997143 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1806 1856 -0.191638 -0.00345833 -6.29071 0.00545967 0.0336557 0.00183682 0.999417 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1806 1857 -0.630995 9.03742 -6.77999 -0.0386525 0.0300214 0.0393414 0.998027 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1807 1856 -0.610989 -9.05091 -6.50015 0.0391555 0.0277614 -0.0377387 0.998134 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1807 1857 -0.199727 0.0172586 -6.26838 0.00237392 0.0305968 0.0019413 0.999527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1807 1858 -0.629916 9.04483 -6.76809 -0.0339946 0.0247486 0.0484289 0.997941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1808 1857 -0.621622 -9.04813 -6.51256 0.0369047 0.0342704 -0.0449728 0.997718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1808 1858 -0.174712 -0.000404041 -6.27551 -0.000239896 0.0367257 0.00073322 0.999325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1808 1859 -0.650532 9.02056 -6.76461 -0.0388391 0.0364996 0.0528402 0.99718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1809 1858 -0.624418 -9.02583 -6.52823 0.0472267 0.0360178 -0.0506047 0.996951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1809 1859 -0.200513 0.0110808 -6.27913 -0.00160003 0.0335102 0.00559948 0.999421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1809 1860 -0.652212 9.00571 -6.77283 -0.044375 0.0282143 0.0422068 0.997724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1810 1859 -0.627265 -9.02875 -6.51852 0.0449002 0.0360038 -0.054091 0.996876 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1810 1860 -0.191153 -0.00293989 -6.28331 -0.00487343 0.0307797 0.000888069 0.999514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1810 1861 -0.609831 9.00383 -6.75579 -0.0477988 0.0343612 0.0440665 0.997293 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1811 1860 -0.606223 -9.0067 -6.54189 0.0476208 0.036234 -0.0422432 0.997314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1811 1861 -0.209389 -0.00137967 -6.28339 -0.00308289 0.0251563 0.00321091 0.999674 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1811 1862 -0.620854 9.00658 -6.76762 -0.0414146 0.0307633 0.0443836 0.997682 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1812 1861 -0.610715 -9.00578 -6.52092 0.03779 0.0293757 -0.0507671 0.997563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1812 1862 -0.20001 0.00878433 -6.28532 -0.000877818 0.0436752 0.00147414 0.999044 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1812 1863 -0.635567 8.99637 -6.78055 -0.0380594 0.0358168 0.0523237 0.997262 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1813 1862 -0.617446 -8.99237 -6.50648 0.0500256 0.0318575 -0.0496193 0.997006 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1813 1863 -0.211206 0.00106104 -6.26245 -0.00640399 0.0274633 -0.00733363 0.999575 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1813 1864 -0.630394 8.96089 -6.7624 -0.0366362 0.0345136 0.0443006 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1814 1863 -0.604405 -8.98878 -6.51884 0.0469074 0.0359589 -0.0432652 0.997314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1814 1864 -0.197646 -0.0126662 -6.29244 -0.00441103 0.0361501 0.00115476 0.999336 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1814 1865 -0.639893 8.96436 -6.75917 -0.0558719 0.0373445 0.0461183 0.996673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1815 1864 -0.621834 -8.98657 -6.53942 0.0394171 0.0356618 -0.0464416 0.997506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1815 1865 -0.202508 -0.000738443 -6.28589 0.00517277 0.0346803 0.00105035 0.999385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1815 1866 -0.632485 8.9566 -6.75843 -0.0477013 0.0382727 0.0504078 0.996854 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1816 1865 -0.619149 -8.96515 -6.51654 0.042812 0.0312691 -0.0572487 0.996951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1816 1866 -0.195804 -0.0332783 -6.29886 -0.0044519 0.0211146 0.00185559 0.999765 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1816 1867 -0.631355 8.9398 -6.77126 -0.0511861 0.0297954 0.0411297 0.997397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1817 1866 -0.61547 -8.96613 -6.51964 0.0443754 0.0363553 -0.0441387 0.997377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1817 1867 -0.193353 -0.013933 -6.28233 0.00308495 0.0327043 0.00435547 0.999451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1817 1868 -0.617544 8.93364 -6.77501 -0.0531071 0.0306722 0.0525185 0.996735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1818 1867 -0.620577 -8.94725 -6.53156 0.0503123 0.031171 -0.0552642 0.996716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1818 1868 -0.191676 0.00339845 -6.26897 -0.0039253 0.0290447 -0.00237875 0.999568 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1818 1869 -0.611604 8.91207 -6.77677 -0.0465443 0.0338092 0.0454554 0.997309 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1819 1868 -0.618844 -8.91699 -6.52674 0.0328281 0.0326077 -0.0531354 0.997515 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1819 1869 -0.182206 0.00172591 -6.29014 0.00305813 0.0183813 0.00661664 0.999804 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1819 1870 -0.628983 8.90216 -6.77098 -0.0415245 0.0322216 0.0408214 0.997783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1820 1869 -0.611204 -8.92181 -6.51913 0.0337626 0.0338274 -0.0397979 0.998064 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1820 1870 -0.208831 -0.0047979 -6.27363 0.00233154 0.03421 -0.0062658 0.999392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1820 1871 -0.618976 8.89271 -6.76858 -0.0391198 0.0349392 0.044774 0.997619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1821 1870 -0.622608 -8.9003 -6.52534 0.0415558 0.0285932 -0.0387206 0.997976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1821 1871 -0.183171 -0.00241999 -6.28545 0.00138154 0.0315189 -0.000172891 0.999502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1821 1872 -0.632033 8.88589 -6.78421 -0.0385985 0.0413677 0.0401493 0.997591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1822 1871 -0.599763 -8.91071 -6.54931 0.0419305 0.035034 -0.0534335 0.997075 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1822 1872 -0.199682 0.00177301 -6.26885 -0.00378208 0.029934 0.00482663 0.999533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1822 1873 -0.634422 8.86646 -6.77682 -0.0463031 0.0437118 0.0467106 0.996877 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1823 1872 -0.600425 -8.87454 -6.52443 0.0474749 0.0345062 -0.0533083 0.996852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1823 1873 -0.197666 0.013339 -6.29035 0.00673333 0.0314685 0.00858174 0.999445 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1823 1874 -0.634878 8.85621 -6.77203 -0.0374231 0.0220007 0.0421113 0.998169 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1824 1873 -0.618316 -8.8631 -6.53335 0.0428029 0.0346656 -0.0439686 0.997513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1824 1874 -0.193062 -0.00474194 -6.26755 0.00598631 0.0333472 -0.000616671 0.999426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1824 1875 -0.61714 8.84633 -6.76884 -0.0481853 0.033806 0.0529947 0.996859 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1825 1874 -0.605539 -8.86781 -6.52538 0.0407192 0.0294134 -0.0524045 0.997362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1825 1875 -0.177625 0.0130128 -6.25966 -0.00692785 0.0283151 -0.00437183 0.999565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1825 1876 -0.608464 8.84492 -6.76277 -0.0469567 0.0349786 0.0472749 0.997164 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1826 1875 -0.605566 -8.84186 -6.5104 0.0401618 0.0330227 -0.0478384 0.997501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1826 1876 -0.196743 -0.015054 -6.26581 -0.00166302 0.0250746 -0.0013366 0.999683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1826 1877 -0.617835 8.84291 -6.76873 -0.030834 0.0333115 0.0395743 0.998185 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1827 1876 -0.618846 -8.8255 -6.51964 0.0390938 0.0293848 -0.0451075 0.997784 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1827 1877 -0.199317 -0.00453242 -6.2826 0.00687809 0.0255515 0.00814253 0.999617 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1827 1878 -0.610074 8.8126 -6.76027 -0.0492131 0.026473 0.0440267 0.997466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1828 1877 -0.621055 -8.82749 -6.52196 0.0409282 0.0320027 -0.0430945 0.997719 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1828 1878 -0.191062 -0.00254888 -6.27552 0.000541943 0.0299817 0.00424881 0.999541 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1828 1879 -0.615392 8.81001 -6.7595 -0.0410658 0.0363811 0.0503485 0.997224 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1829 1878 -0.592432 -8.81193 -6.5302 0.041721 0.0294595 -0.0468826 0.997594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1829 1879 -0.205435 0.0114361 -6.28061 -0.000580655 0.0312442 0.01254 0.999433 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1829 1880 -0.610313 8.79781 -6.7645 -0.0476949 0.0327654 0.043788 0.997364 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1830 1879 -0.591173 -8.81219 -6.5234 0.0374031 0.0408697 -0.0457597 0.997415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1830 1880 -0.195307 0.0104969 -6.26329 0.00522604 0.0281983 0.00538691 0.999574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1830 1881 -0.629621 8.78655 -6.76618 -0.0458269 0.0350329 0.0462461 0.997263 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1831 1880 -0.606874 -8.80478 -6.51956 0.0437404 0.0331621 -0.044893 0.997483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1831 1881 -0.187062 0.00588027 -6.26961 0.00015545 0.0249284 -0.000112362 0.999689 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1831 1882 -0.629306 8.77716 -6.77611 -0.0504615 0.0319317 0.0423784 0.997315 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1832 1881 -0.573562 -8.80127 -6.51555 0.0378989 0.0250901 -0.0426789 0.998054 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1832 1882 -0.196035 0.0114833 -6.27192 -0.00355056 0.0192974 0.00420506 0.999799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1832 1883 -0.59387 8.76497 -6.77381 -0.038738 0.0367309 0.049264 0.997358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1833 1882 -0.607786 -8.76846 -6.51881 0.0397246 0.0201846 -0.0427688 0.998091 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1833 1883 -0.204792 -0.00628978 -6.27494 0.000958153 0.0311982 -0.00719917 0.999487 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1833 1884 -0.594261 8.75808 -6.74875 -0.0509958 0.0372543 0.0456101 0.996961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1834 1883 -0.595103 -8.75659 -6.5219 0.0432658 0.0296086 -0.0503819 0.997353 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1834 1884 -0.196065 0.0102981 -6.27447 0.00305056 0.0278614 -0.0041608 0.999598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1834 1885 -0.616474 8.74267 -6.76915 -0.0326757 0.042063 0.05138 0.997258 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1835 1884 -0.593827 -8.74537 -6.52793 0.0411302 0.0311401 -0.0445767 0.997673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1835 1885 -0.198419 0.00963221 -6.27598 0.00358499 0.0378164 -0.00544354 0.999263 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1835 1886 -0.599515 8.71309 -6.78298 -0.0463411 0.028852 0.0467345 0.997415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1836 1885 -0.599161 -8.73584 -6.50646 0.0467493 0.0300902 -0.0473896 0.997328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1836 1886 -0.181026 -0.00357243 -6.27631 0.00291397 0.0392109 -0.00805442 0.999194 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1836 1887 -0.625344 8.7317 -6.77182 -0.0400158 0.0308469 0.0503776 0.997451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1837 1886 -0.58536 -8.71078 -6.52211 0.0358315 0.0245346 -0.0334175 0.998498 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1837 1887 -0.193299 -0.0112802 -6.28438 -0.00352995 0.0406425 0.00850032 0.999131 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1837 1888 -0.611039 8.72869 -6.77266 -0.0473632 0.0293106 0.0487543 0.997257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1838 1887 -0.600014 -8.7143 -6.51341 0.0477851 0.0254128 -0.0454835 0.997498 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1838 1888 -0.18932 -0.00873888 -6.28251 0.00411909 0.0263934 -0.00675441 0.99962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1838 1889 -0.615863 8.6971 -6.76176 -0.0346478 0.0290042 0.042988 0.998053 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1839 1888 -0.589338 -8.69899 -6.51655 0.0383456 0.0270514 -0.0483119 0.997729 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1839 1889 -0.182679 0.00197742 -6.27099 0.00184644 0.0333222 0.0020988 0.999441 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1839 1890 -0.599642 8.70265 -6.75548 -0.0483903 0.0357896 0.0345516 0.997589 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1840 1889 -0.595685 -8.67898 -6.53534 0.0403886 0.026081 -0.0583934 0.997135 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1840 1890 -0.200658 0.00164758 -6.28587 -0.00142257 0.0288366 -0.00240361 0.99958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1840 1891 -0.599141 8.66865 -6.76785 -0.0390837 0.0313812 0.0448056 0.997738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1841 1890 -0.577325 -8.69986 -6.50728 0.0579942 0.0332403 -0.0465391 0.996677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1841 1891 -0.19124 -0.00726791 -6.28424 -0.00508725 0.0418377 0.00749754 0.999083 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1841 1892 -0.61231 8.65314 -6.77224 -0.0394402 0.0237714 0.0426293 0.998029 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1842 1891 -0.601112 -8.67358 -6.51848 0.0434801 0.028517 -0.0527343 0.997254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1842 1892 -0.21026 -0.0059269 -6.27925 -0.00291563 0.0226417 0.00349137 0.999733 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1842 1893 -0.605946 8.64632 -6.77766 -0.0469632 0.0358305 0.0367593 0.997577 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1843 1892 -0.60253 -8.65104 -6.5219 0.049414 0.0329945 -0.0440228 0.997262 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1843 1893 -0.184795 -0.000532165 -6.2887 0.00922043 0.0298399 0.00033405 0.999512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1843 1894 -0.594703 8.62956 -6.76814 -0.045088 0.0352728 0.0350612 0.997744 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1844 1893 -0.590706 -8.66057 -6.54016 0.0477926 0.0320933 -0.0484018 0.997168 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1844 1894 -0.180596 -0.00472051 -6.28588 -0.0122751 0.0352391 -0.00237679 0.999301 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1844 1895 -0.594628 8.63883 -6.79137 -0.0437816 0.0374797 0.047789 0.997193 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1845 1894 -0.579759 -8.65011 -6.50893 0.0466256 0.0364133 -0.0508124 0.996954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1845 1895 -0.182219 0.0158442 -6.27229 -0.000624816 0.0354446 0.00167036 0.99937 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1845 1896 -0.608119 8.60581 -6.77374 -0.0488531 0.0374832 0.0475571 0.996969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1846 1895 -0.592409 -8.62715 -6.50517 0.0543661 0.0263431 -0.0361111 0.99752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1846 1896 -0.195472 -0.000583136 -6.25803 -0.00729067 0.0393799 -0.00165052 0.999196 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1846 1897 -0.602327 8.60376 -6.78629 -0.0533754 0.0315448 0.0470715 0.996966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1847 1896 -0.578013 -8.61693 -6.53229 0.0433002 0.0362747 -0.0392322 0.997632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1847 1897 -0.188496 -0.00506465 -6.28474 -0.0131281 0.0332833 -0.00274009 0.999356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1847 1898 -0.605881 8.5922 -6.7767 -0.0544011 0.038499 0.0396369 0.996989 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1848 1897 -0.589338 -8.62085 -6.52228 0.0404609 0.0342022 -0.0445373 0.997602 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1848 1898 -0.183536 -0.00157375 -6.27006 0.00792135 0.0323593 0.00181027 0.999443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1848 1899 -0.594737 8.58859 -6.79435 -0.0396909 0.0419183 0.0391651 0.997564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1849 1898 -0.576613 -8.57106 -6.51726 0.0393757 0.026216 -0.0463587 0.997804 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1849 1899 -0.192574 -0.00705227 -6.27389 -0.00945256 0.0343545 0.00066008 0.999365 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1849 1900 -0.587853 8.55597 -6.77883 -0.0359155 0.0308766 0.0452539 0.997852 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1850 1899 -0.58178 -8.57435 -6.52372 0.0483588 0.037436 -0.0388527 0.997372 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1850 1900 -0.204277 -0.00857878 -6.28041 -0.00104967 0.0237844 -0.000216522 0.999717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1850 1901 -0.590115 8.55006 -6.76817 -0.0429206 0.0339494 0.0400162 0.997699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1851 1900 -0.587312 -8.56737 -6.53227 0.0425117 0.0376022 -0.04997 0.997137 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1851 1901 -0.216221 -0.00496975 -6.27742 -0.0113287 0.0299082 -0.000997267 0.999488 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1851 1902 -0.585498 8.55257 -6.79686 -0.0439733 0.0270662 0.0447176 0.997664 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1852 1901 -0.578065 -8.56741 -6.511 0.0390438 0.0264304 -0.049178 0.997677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1852 1902 -0.19632 -0.00266179 -6.28835 -0.0013436 0.0335416 -0.00117377 0.999436 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1852 1903 -0.588122 8.53963 -6.76508 -0.0357615 0.0262709 0.0546193 0.997521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1853 1902 -0.569719 -8.52399 -6.53235 0.0400709 0.0337396 -0.0421295 0.997738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1853 1903 -0.189188 0.0177483 -6.28123 0.00121617 0.0254388 -0.00299529 0.999671 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1853 1904 -0.574531 8.51793 -6.7793 -0.0384482 0.0263231 0.0440036 0.997944 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1854 1903 -0.587242 -8.542 -6.51449 0.0463871 0.0281835 -0.0379085 0.997806 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1854 1904 -0.193574 -0.0217285 -6.26854 -0.0173503 0.0337755 0.00569097 0.999263 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1854 1905 -0.604857 8.49701 -6.771 -0.0462777 0.0319356 0.0423494 0.997519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1855 1904 -0.578618 -8.52772 -6.52261 0.0500401 0.0250651 -0.0457679 0.997383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1855 1905 -0.204439 -0.00344765 -6.26505 0.000370104 0.0199455 -0.00214924 0.999799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1855 1906 -0.588183 8.49655 -6.76593 -0.0358663 0.0322373 0.0528808 0.997436 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1856 1905 -0.584184 -8.51085 -6.53378 0.0438225 0.0330811 -0.0401619 0.997683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1856 1906 -0.196492 0.000518194 -6.28807 0.00758565 0.0254738 0.00792838 0.999615 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1856 1907 -0.587867 8.48846 -6.77806 -0.0448044 0.0365656 0.0455174 0.997288 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1857 1906 -0.572896 -8.50612 -6.52471 0.0453273 0.0314529 -0.0458327 0.997424 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1857 1907 -0.201078 0.00969797 -6.27922 -0.00322499 0.0371506 -0.00639821 0.999284 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1857 1908 -0.586192 8.48062 -6.7703 -0.0394365 0.0332141 0.043208 0.997735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1858 1907 -0.580222 -8.48537 -6.52497 0.0400804 0.034521 -0.037548 0.997894 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1858 1908 -0.193403 0.00142933 -6.27788 0.00637278 0.0243821 0.00616635 0.999663 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1858 1909 -0.595855 8.46646 -6.75716 -0.0442732 0.0298521 0.0509657 0.997272 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1859 1908 -0.553417 -8.47434 -6.51657 0.0548797 0.0221818 -0.0477706 0.997103 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1859 1909 -0.196106 0.0180681 -6.25454 -0.00464592 0.0332157 -0.00433806 0.999428 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1859 1910 -0.586363 8.46598 -6.77306 -0.044394 0.0295507 0.0440047 0.997607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1860 1909 -0.575153 -8.44995 -6.51921 0.0510808 0.0401695 -0.0423482 0.996987 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1860 1910 -0.197532 0.013033 -6.28293 -0.00271323 0.0188169 -0.00242928 0.999816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1860 1911 -0.586128 8.4316 -6.7647 -0.0439604 0.0300162 0.0468985 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1861 1910 -0.577589 -8.42303 -6.51777 0.0472078 0.0311195 -0.0418238 0.997524 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1861 1911 -0.194661 0.0152815 -6.26955 -0.00226637 0.0278578 -0.00322457 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1861 1912 -0.586363 8.42821 -6.76873 -0.0471556 0.0327221 0.0437294 0.997393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1862 1911 -0.579068 -8.4399 -6.53285 0.0379022 0.0265927 -0.0419162 0.998048 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1862 1912 -0.201908 -0.00847456 -6.27553 -4.07412e-05 0.0350046 0.00488102 0.999375 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1862 1913 -0.585364 8.41658 -6.77126 -0.0294066 0.0175749 0.051603 0.99808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1863 1912 -0.576271 -8.43469 -6.54574 0.0500415 0.0226855 -0.0386922 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1863 1913 -0.182199 -0.0163908 -6.28028 -0.000375378 0.0259279 0.00370429 0.999657 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1863 1914 -0.569774 8.39621 -6.7802 -0.0471008 0.0327784 0.0391896 0.997583 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1864 1913 -0.569577 -8.41225 -6.53863 0.0469833 0.0301692 -0.0447865 0.997435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1864 1914 -0.180472 -0.00169375 -6.28912 -0.00312247 0.0212349 -0.00413525 0.999761 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1864 1915 -0.591858 8.3961 -6.76601 -0.0382978 0.0305064 0.0348531 0.998192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1865 1914 -0.550625 -8.41477 -6.52393 0.0480659 0.0316997 -0.0413065 0.997486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1865 1915 -0.199077 0.0246253 -6.28505 -0.00431681 0.0230979 -0.0130447 0.999639 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1865 1916 -0.56797 8.38348 -6.77686 -0.052475 0.0286454 0.0338623 0.997637 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1866 1915 -0.561631 -8.4133 -6.5182 0.0467359 0.0247086 -0.0477803 0.997458 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1866 1916 -0.200225 0.00328564 -6.28844 -0.00456499 0.0230887 -0.00407618 0.999715 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1866 1917 -0.584977 8.37467 -6.77426 -0.0562937 0.0351534 0.0448145 0.996788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1867 1916 -0.580541 -8.38235 -6.53071 0.0443473 0.0267468 -0.0361638 0.998003 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1867 1917 -0.182567 0.00815689 -6.2871 0.00282149 0.0377582 -0.00469879 0.999272 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1867 1918 -0.581032 8.35223 -6.75342 -0.048303 0.034728 0.0448705 0.99722 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1868 1917 -0.561359 -8.37062 -6.51184 0.0419071 0.0299467 -0.0412192 0.997822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1868 1918 -0.189851 0.00662619 -6.26287 0.000634305 0.027447 -0.00315925 0.999618 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1868 1919 -0.587219 8.33282 -6.76367 -0.0368488 0.0277848 0.0419706 0.998052 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1869 1918 -0.56185 -8.36221 -6.52492 0.0508966 0.0269923 -0.0483132 0.997169 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1869 1919 -0.213736 -0.00446465 -6.27842 0.00384311 0.0314959 -0.00459098 0.999486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1869 1920 -0.576348 8.33934 -6.77705 -0.047212 0.0379222 0.0395757 0.99738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1870 1919 -0.558032 -8.35037 -6.51243 0.0503463 0.028633 -0.0461968 0.997252 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1870 1920 -0.198121 -0.00322108 -6.27695 -0.000381124 0.030548 0.000454618 0.999533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1870 1921 -0.583281 8.33391 -6.7828 -0.0512361 0.0269123 0.0431175 0.997392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1871 1920 -0.579687 -8.3331 -6.52333 0.0470298 0.0263679 -0.0458979 0.99749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1871 1921 -0.189812 0.00640329 -6.28269 -0.00557523 0.0217305 -0.00923445 0.999706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1871 1922 -0.592408 8.31707 -6.76078 -0.0423564 0.0256585 0.0430854 0.997843 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1872 1921 -0.567311 -8.31682 -6.51406 0.051633 0.035198 -0.040326 0.997231 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1872 1922 -0.201544 -0.00914123 -6.27956 0.00389298 0.0225222 0.00779724 0.999708 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1872 1923 -0.587102 8.29055 -6.78147 -0.0475058 0.03494 0.0433824 0.997317 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1873 1922 -0.585433 -8.31265 -6.52186 0.0404684 0.0282771 -0.0548159 0.997275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1873 1923 -0.188498 0.000246528 -6.27218 0.0053024 0.0312931 0.00181414 0.999495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1873 1924 -0.575355 8.30253 -6.73869 -0.051492 0.0325078 0.0425403 0.997237 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1874 1923 -0.565089 -8.30062 -6.53535 0.0476384 0.0272708 -0.0505831 0.99721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1874 1924 -0.199418 -0.000700525 -6.28451 0.000845309 0.0318553 0.000786707 0.999492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1874 1925 -0.580695 8.27041 -6.74565 -0.0509034 0.0291611 0.0336016 0.997712 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1875 1924 -0.555414 -8.29426 -6.53216 0.0556689 0.034515 -0.0457684 0.996802 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1875 1925 -0.170719 -0.00845899 -6.27706 -0.00205559 0.0310012 -0.00694665 0.999493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1875 1926 -0.577736 8.26006 -6.77308 -0.0463956 0.0376364 0.04644 0.997133 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1876 1925 -0.553005 -8.28114 -6.50976 0.0502691 0.0268514 -0.0495069 0.997146 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1876 1926 -0.180643 0.000719595 -6.27341 -0.000557543 0.0327361 0.0034189 0.999458 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1876 1927 -0.591388 8.23467 -6.7646 -0.0431444 0.0308031 0.0432491 0.997657 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1877 1926 -0.579417 -8.24469 -6.5221 0.0453688 0.0198215 -0.0420836 0.997887 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1877 1927 -0.194511 -0.00587872 -6.27326 0.012535 0.0286983 -0.00270489 0.999506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1877 1928 -0.569064 8.23494 -6.78521 -0.0408882 0.0322769 0.04313 0.99771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1878 1927 -0.55778 -8.25458 -6.51297 0.0498737 0.03629 -0.0342246 0.997509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1878 1928 -0.204377 -0.00530664 -6.29299 0.0081509 0.0315843 -0.00396249 0.99946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1878 1929 -0.56605 8.21341 -6.77617 -0.0452847 0.0247506 0.0522522 0.9973 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1879 1928 -0.561532 -8.23477 -6.52166 0.0399351 0.0308396 -0.0407762 0.997893 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1879 1929 -0.178676 -0.00574 -6.28982 -0.00395799 0.033487 -0.00345802 0.999425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1879 1930 -0.570513 8.22692 -6.78734 -0.0453922 0.039547 0.0364266 0.997521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1880 1929 -0.563804 -8.22598 -6.52979 0.0504422 0.0211084 -0.038497 0.997761 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1880 1930 -0.221467 -0.00139555 -6.28046 -0.00744439 0.0359011 0.00689835 0.999304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1880 1931 -0.563962 8.2203 -6.78718 -0.0405448 0.0399701 0.0434693 0.997431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1881 1930 -0.556744 -8.21812 -6.52668 0.0495278 0.0290565 -0.0362308 0.997692 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1881 1931 -0.205276 -0.00121303 -6.26864 -0.00118526 0.0293187 0.0073652 0.999542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1881 1932 -0.583406 8.19728 -6.78635 -0.0575059 0.0295175 0.0439074 0.996942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1882 1931 -0.559618 -8.22125 -6.53219 0.0425648 0.0373673 -0.0593223 0.996631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1882 1932 -0.213402 0.0125312 -6.2902 -0.00140763 0.0351413 -0.00629686 0.999362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1882 1933 -0.547401 8.18604 -6.76937 -0.0495959 0.0251306 0.0440147 0.997483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1883 1932 -0.558294 -8.20133 -6.51926 0.0345364 0.0288912 -0.0389812 0.998225 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1883 1933 -0.201027 -0.0139687 -6.28217 -0.00129327 0.0362703 0.00756951 0.999313 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1883 1934 -0.577788 8.17064 -6.77916 -0.0400383 0.0289586 0.0338723 0.998204 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1884 1933 -0.562965 -8.17557 -6.52308 0.043252 0.0276585 -0.0399389 0.997882 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1884 1934 -0.195513 -0.0123019 -6.28692 -0.00252137 0.0359619 0.00670036 0.999328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1884 1935 -0.564234 8.14942 -6.78347 -0.0320295 0.028199 0.0316046 0.998589 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1885 1934 -0.559567 -8.16636 -6.52769 0.0504011 0.0284665 -0.0301339 0.997868 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1885 1935 -0.210868 0.00961339 -6.26815 -0.00311254 0.0353718 0.00376942 0.999362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1885 1936 -0.559573 8.14886 -6.77151 -0.0409578 0.0274426 0.0436126 0.997831 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1886 1935 -0.550849 -8.14585 -6.52594 0.0364969 0.0213449 -0.0472323 0.997989 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1886 1936 -0.187392 0.00985663 -6.27418 -0.00557737 0.0325515 -0.0064232 0.999434 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1886 1937 -0.573154 8.13 -6.7754 -0.0518303 0.0218989 0.0421209 0.997527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1887 1936 -0.551605 -8.14323 -6.53566 0.0441318 0.026544 -0.0411055 0.997827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1887 1937 -0.212054 0.0118277 -6.28711 -0.00525741 0.0354532 -0.000918207 0.999357 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1887 1938 -0.551162 8.11095 -6.76885 -0.0396215 0.0292964 0.0456808 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1888 1937 -0.542109 -8.12005 -6.50759 0.0457148 0.0303554 -0.0347944 0.997887 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1888 1938 -0.203923 0.00178793 -6.27974 -0.00657932 0.0345419 -0.00676364 0.999359 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1888 1939 -0.570871 8.10115 -6.77151 -0.047292 0.0344978 0.0443793 0.997298 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1889 1938 -0.551639 -8.12381 -6.49939 0.0432506 0.0287957 -0.0321329 0.998132 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1889 1939 -0.190196 0.00785006 -6.27106 -0.00473478 0.022784 0.000553233 0.999729 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1889 1940 -0.565032 8.10481 -6.7525 -0.0478883 0.0364862 0.0415588 0.997321 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1890 1939 -0.560862 -8.09916 -6.51132 0.0478072 0.0307925 -0.0473092 0.99726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1890 1940 -0.179821 -0.00630602 -6.27965 0.00866396 0.0369383 0.00141599 0.999279 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1890 1941 -0.544471 8.0722 -6.75821 -0.0466348 0.0338111 0.0442818 0.997357 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1891 1940 -0.548166 -8.09851 -6.52056 0.0491187 0.030607 -0.0417806 0.997449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1891 1941 -0.199749 0.002929 -6.2733 0.00152176 0.0291744 -0.00377748 0.999566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1891 1942 -0.569126 8.07976 -6.78988 -0.0410709 0.0271439 0.0386683 0.998039 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1892 1941 -0.557382 -8.08618 -6.51213 0.0418454 0.0290658 -0.0429662 0.997777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1892 1942 -0.191464 0.00307211 -6.2861 -0.00808412 0.0321914 0.00178386 0.999447 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1892 1943 -0.552755 8.04487 -6.76232 -0.0560265 0.0407372 0.0450404 0.996581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1893 1942 -0.525219 -8.0736 -6.52791 0.0458879 0.0308249 -0.0513741 0.997148 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1893 1943 -0.200248 -0.0113018 -6.28633 -0.00560993 0.025479 -0.00445752 0.99965 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1893 1944 -0.544664 8.04074 -6.77521 -0.0507902 0.017916 0.0472527 0.99743 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1894 1943 -0.52563 -8.03923 -6.53131 0.0405009 0.0371788 -0.0336611 0.99792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1894 1944 -0.186554 -0.0144038 -6.28948 -0.0025124 0.0273289 0.00433809 0.999614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1894 1945 -0.546034 8.03399 -6.78755 -0.0390759 0.0320681 0.0417476 0.997849 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1895 1944 -0.555456 -8.03979 -6.51675 0.0364203 0.0359455 -0.0362797 0.998031 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1895 1945 -0.202533 -0.00197378 -6.2701 -0.0073103 0.033582 0.00883568 0.99937 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1895 1946 -0.571302 8.01712 -6.77535 -0.0493375 0.0232704 0.0406342 0.997684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1896 1945 -0.53915 -8.03136 -6.52333 0.0400335 0.0292718 -0.0426334 0.997859 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1896 1946 -0.20745 0.0156922 -6.27559 0.00611817 0.0340276 -0.00477923 0.999391 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1896 1947 -0.550905 8.02266 -6.77673 -0.0436394 0.0239846 0.0408733 0.997923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1897 1946 -0.533249 -8.01846 -6.52818 0.0479137 0.0282758 -0.0427169 0.997537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1897 1947 -0.188852 -0.00121148 -6.27583 -0.00209367 0.0430108 -0.000183022 0.999072 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1897 1948 -0.549338 8.00326 -6.77006 -0.045838 0.032084 0.0390352 0.99767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1898 1947 -0.522951 -8.01773 -6.52294 0.047645 0.0368757 -0.0378623 0.997465 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1898 1948 -0.214492 0.00342101 -6.28175 -0.00269933 0.0270307 -0.000703578 0.999631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1898 1949 -0.548935 7.99154 -6.76792 -0.0467055 0.0244106 0.0365544 0.997941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1899 1948 -0.523819 -7.99527 -6.52192 0.0349623 0.0204194 -0.0426526 0.998269 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1899 1949 -0.200073 -0.00501345 -6.29519 0.000114653 0.0311953 -0.00819202 0.99948 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1899 1950 -0.525566 7.96108 -6.77511 -0.0507724 0.0241799 0.0342412 0.99783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1900 1949 -0.53946 -7.98695 -6.51752 0.0540555 0.0325311 -0.0402687 0.997195 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1900 1950 -0.189002 -0.00503112 -6.26335 -0.00477188 0.0478052 0.00695056 0.998821 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1900 1951 -0.555636 7.96937 -6.78233 -0.046439 0.0392457 0.0422009 0.997257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1901 1950 -0.534214 -7.9747 -6.51731 0.0489126 0.0295216 -0.0424105 0.997465 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1901 1951 -0.201151 0.015376 -6.27972 -0.00252135 0.0406549 -0.000429763 0.99917 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1901 1952 -0.554226 7.95082 -6.77859 -0.0502725 0.0308432 0.0396911 0.99747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1902 1951 -0.533962 -7.9553 -6.52742 0.0437949 0.0360936 -0.0380806 0.997662 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1902 1952 -0.207619 0.0117892 -6.2875 -0.00292726 0.0323502 -0.00236664 0.99947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1902 1953 -0.525204 7.94509 -6.76671 -0.0473442 0.0349038 0.0432366 0.997332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1903 1952 -0.546263 -7.95637 -6.52151 0.0444192 0.0308843 -0.0354441 0.997906 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1903 1953 -0.186481 0.00717822 -6.27305 -0.00162326 0.0361581 0.000733007 0.999344 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1903 1954 -0.552658 7.94332 -6.77437 -0.0506174 0.0294884 0.0440896 0.997309 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1904 1953 -0.510736 -7.94919 -6.51261 0.0508488 0.0266291 -0.0459371 0.997294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1904 1954 -0.191326 0.01665 -6.28649 -0.00217677 0.0353854 -0.00155224 0.99937 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1904 1955 -0.537212 7.89218 -6.77418 -0.0622486 0.0383571 0.0391785 0.996554 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1905 1954 -0.537511 -7.9446 -6.5251 0.0540236 0.029109 -0.0352511 0.997493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1905 1955 -0.211724 0.0228323 -6.27798 0.00482184 0.0191572 -0.00339698 0.999799 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1905 1956 -0.553781 7.89739 -6.76869 -0.0401841 0.041559 0.0309864 0.997847 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1906 1955 -0.527477 -7.92736 -6.53649 0.0468745 0.0347207 -0.0369421 0.997613 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1906 1956 -0.201663 -0.0168532 -6.28075 0.00516208 0.0299714 0.00410604 0.999529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1906 1957 -0.550472 7.88752 -6.76493 -0.0422111 0.0354264 0.0381435 0.997752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1907 1956 -0.51676 -7.9077 -6.51902 0.0479117 0.0328678 -0.0364652 0.997644 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1907 1957 -0.187495 -0.00560438 -6.27572 -0.00652703 0.0336476 -0.00283925 0.999408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1907 1958 -0.548301 7.8788 -6.77222 -0.0472154 0.0211946 0.0394774 0.997879 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1908 1957 -0.507161 -7.89582 -6.51651 0.0570022 0.0249714 -0.0447565 0.997058 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1908 1958 -0.198961 8.81215e-05 -6.28559 -0.00203287 0.0220358 0.00187272 0.999753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1908 1959 -0.535052 7.86351 -6.78343 -0.0538568 0.0358314 0.031278 0.997415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1909 1958 -0.519541 -7.88814 -6.51075 0.0463944 0.0271524 -0.0420066 0.99767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1909 1959 -0.193842 -0.0101634 -6.28165 -0.00296785 0.0271614 0.000864318 0.999626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1909 1960 -0.533905 7.87469 -6.77618 -0.0502234 0.0359279 0.0441428 0.997115 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1910 1959 -0.515212 -7.86022 -6.51331 0.0418075 0.0244814 -0.0444975 0.997834 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1910 1960 -0.196556 -0.0148382 -6.28161 -0.0089899 0.0287185 0.00452297 0.999537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1910 1961 -0.545425 7.84789 -6.76456 -0.0511641 0.0366275 0.0364064 0.997354 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1911 1960 -0.503329 -7.86588 -6.50786 0.0511885 0.0353817 -0.0319439 0.997551 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1911 1961 -0.221364 -0.0154081 -6.27772 0.0105679 0.0258308 0.000563634 0.99961 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1911 1962 -0.539797 7.83673 -6.76204 -0.0464295 0.0342388 0.0363122 0.997674 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1912 1961 -0.520461 -7.84812 -6.51262 0.0425466 0.0286503 -0.0407871 0.99785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1912 1962 -0.202723 -0.00176222 -6.28829 -0.000602414 0.0312726 0.00340348 0.999505 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1912 1963 -0.537238 7.81391 -6.76448 -0.0561031 0.0284601 0.0385729 0.997274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1913 1962 -0.521697 -7.8352 -6.52285 0.0470416 0.021336 -0.0433513 0.997724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1913 1963 -0.200318 -0.00111497 -6.27383 -0.000364983 0.0252246 -0.00199781 0.99968 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1913 1964 -0.547194 7.80472 -6.77772 -0.0561672 0.0302666 0.046643 0.996872 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1914 1963 -0.531631 -7.82854 -6.54955 0.0453296 0.0333635 -0.0492428 0.9972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1914 1964 -0.224459 0.00494854 -6.28954 0.00256105 0.0327177 0.00793172 0.99943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1914 1965 -0.548591 7.79289 -6.77917 -0.0483918 0.0357175 0.0396308 0.997403 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1915 1964 -0.505479 -7.81254 -6.53574 0.0543094 0.0330555 -0.0355516 0.997343 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1915 1965 -0.206951 0.0024052 -6.2846 -0.0114719 0.03063 0.00498779 0.999453 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1915 1966 -0.531869 7.77601 -6.76097 -0.0513159 0.0312325 0.044439 0.997204 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1916 1965 -0.52234 -7.7896 -6.50864 0.0480226 0.0236778 -0.0492363 0.997351 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1916 1966 -0.216071 -0.00050477 -6.26509 0.0038673 0.0303745 -0.000938736 0.999531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1916 1967 -0.542811 7.7552 -6.78262 -0.0450264 0.0269481 0.0393542 0.997847 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1917 1966 -0.516186 -7.76945 -6.51799 0.0487017 0.0296352 -0.0500271 0.997119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1917 1967 -0.197756 -0.0226273 -6.27278 0.00213432 0.0289227 -0.00868358 0.999542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1917 1968 -0.527314 7.77227 -6.77161 -0.0475077 0.0271111 0.0381171 0.997775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1918 1967 -0.513298 -7.78939 -6.53145 0.0490439 0.0357885 -0.0500465 0.9969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1918 1968 -0.213312 -0.00755798 -6.28301 0.00237415 0.0286486 0.000700255 0.999586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1918 1969 -0.543831 7.75736 -6.77838 -0.0423681 0.0328746 0.050127 0.997302 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1919 1968 -0.504471 -7.75983 -6.52105 0.0537603 0.0351629 -0.0370515 0.997247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1919 1969 -0.193666 0.000600495 -6.28934 -0.000558071 0.0402557 0.000423261 0.999189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1919 1970 -0.520774 7.73414 -6.77944 -0.0548684 0.0315969 0.0350652 0.997377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1920 1969 -0.508208 -7.74028 -6.5195 0.0520049 0.0351345 -0.0411062 0.997182 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1920 1970 -0.202135 0.00557892 -6.28177 -0.00644552 0.0344318 0.00142254 0.999385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1920 1971 -0.546656 7.71691 -6.76207 -0.0472896 0.0358077 0.04508 0.997221 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1921 1970 -0.512151 -7.72556 -6.51133 0.0478604 0.037581 -0.0418468 0.997269 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1921 1971 -0.183479 0.00112048 -6.26769 -0.0022449 0.0325545 0.00169275 0.999466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1921 1972 -0.537645 7.70562 -6.77861 -0.0495612 0.0371908 0.0424035 0.997177 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1922 1971 -0.502997 -7.70974 -6.5395 0.0508472 0.0407962 -0.0365255 0.997204 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1922 1972 -0.205464 0.00755757 -6.27308 0.00284231 0.0250658 0.00285452 0.999678 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1922 1973 -0.53436 7.70213 -6.77757 -0.046772 0.0393219 0.0354672 0.997501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1923 1972 -0.507683 -7.71309 -6.50551 0.0500999 0.0363282 -0.034775 0.997477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1923 1973 -0.195123 0.0104608 -6.27494 0.00362396 0.0339047 0.000578373 0.999418 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1923 1974 -0.524755 7.67795 -6.76344 -0.0406666 0.0369177 0.0336588 0.997923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1924 1973 -0.514689 -7.7033 -6.51957 0.0420804 0.0295715 -0.0351147 0.998059 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1924 1974 -0.208778 0.0137177 -6.2888 0.00613274 0.0325212 -0.00432308 0.999443 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1924 1975 -0.517466 7.65559 -6.76102 -0.0516502 0.0233942 0.0421083 0.997503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1925 1974 -0.506107 -7.68082 -6.52084 0.0528668 0.029046 -0.0301164 0.997725 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1925 1975 -0.202089 0.0116773 -6.25875 0.00196701 0.0351594 -0.000243763 0.99938 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1925 1976 -0.519025 7.65041 -6.76808 -0.0435607 0.0402107 0.044673 0.997241 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1926 1975 -0.506644 -7.66534 -6.51076 0.0499191 0.0310266 -0.0418027 0.997396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1926 1976 -0.199944 -0.0097086 -6.28983 0.00372508 0.0258844 -0.00364041 0.999651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1926 1977 -0.515688 7.65407 -6.75422 -0.0461743 0.0281533 0.0390216 0.997774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1927 1976 -0.510637 -7.64923 -6.52244 0.0521661 0.0275548 -0.0346056 0.997658 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1927 1977 -0.206679 -0.00728225 -6.29026 -0.00498177 0.035112 -0.000865543 0.999371 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1927 1978 -0.536256 7.63347 -6.76726 -0.0495566 0.035199 0.0289584 0.997731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1928 1977 -0.501398 -7.64007 -6.52399 0.0483684 0.0324 -0.0434929 0.997356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1928 1978 -0.208193 0.0151175 -6.27023 0.00174476 0.0330773 -0.00254749 0.999448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1928 1979 -0.54266 7.61866 -6.76005 -0.0598043 0.0344066 0.0416994 0.996745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1929 1978 -0.49797 -7.65 -6.52847 0.0504949 0.0217093 -0.0404885 0.997667 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1929 1979 -0.198545 0.0169499 -6.286 0.00132921 0.0341434 -0.00986574 0.999367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1929 1980 -0.514309 7.61352 -6.77445 -0.0536203 0.029201 0.0369513 0.99745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1930 1979 -0.51586 -7.6198 -6.53515 0.039362 0.0329282 -0.043372 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1930 1980 -0.213208 -0.00122641 -6.27428 0.00186342 0.0320605 -0.00235702 0.999481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1930 1981 -0.512083 7.58858 -6.77858 -0.0586861 0.0257487 0.0351633 0.997325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1931 1980 -0.517332 -7.60176 -6.50384 0.0434553 0.0319569 -0.0443863 0.997557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1931 1981 -0.203445 -0.000563217 -6.27894 -0.000111864 0.0354994 0.00379252 0.999362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1931 1982 -0.511594 7.5796 -6.75021 -0.0486153 0.0335937 0.0409349 0.997413 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1932 1981 -0.482688 -7.59514 -6.52332 0.0595173 0.0346432 -0.042711 0.996711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1932 1982 -0.187667 0.0054963 -6.2942 -0.00575378 0.0403915 0.000103372 0.999167 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1932 1983 -0.50756 7.56962 -6.76269 -0.0461664 0.0296657 0.0467272 0.997399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1933 1982 -0.515446 -7.58024 -6.51832 0.0496431 0.0337731 -0.0404464 0.997376 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1933 1983 -0.204609 -0.0107445 -6.27367 -0.000950866 0.0345111 0.00213269 0.999402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1933 1984 -0.507212 7.5803 -6.75953 -0.0474726 0.0359205 0.0381046 0.997499 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1934 1983 -0.484471 -7.55365 -6.5015 0.0481966 0.0328671 -0.0344637 0.997702 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1934 1984 -0.192894 0.00102631 -6.27846 0.00826879 0.0259168 -0.00372412 0.999623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1934 1985 -0.512763 7.55528 -6.76007 -0.0463025 0.0422887 0.049165 0.99682 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1935 1984 -0.504331 -7.56151 -6.51229 0.0470325 0.0317799 -0.0431389 0.997455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1935 1985 -0.203215 0.00571657 -6.26838 -0.00760426 0.0311075 0.00175674 0.999486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1935 1986 -0.511422 7.52034 -6.7711 -0.0508312 0.0269292 0.0363755 0.997681 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1936 1985 -0.513438 -7.56066 -6.52297 0.0433429 0.03324 -0.0334128 0.997948 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1936 1986 -0.207123 0.00790396 -6.28981 0.0020247 0.0352058 0.00672012 0.999355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1936 1987 -0.510673 7.50941 -6.76942 -0.0484973 0.0277778 0.0356673 0.9978 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1937 1986 -0.500343 -7.54824 -6.51604 0.0560564 0.0387553 -0.0375682 0.996968 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1937 1987 -0.201904 0.00011608 -6.28638 -0.00331265 0.0385192 -0.00335111 0.999247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1937 1988 -0.507365 7.5022 -6.77066 -0.0520773 0.0217995 0.0372515 0.99771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1938 1987 -0.490109 -7.52751 -6.51142 0.0527206 0.0259399 -0.0497382 0.997032 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1938 1988 -0.196354 -0.00446981 -6.27975 0.00311487 0.0321213 -0.0067283 0.999456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1938 1989 -0.530413 7.48823 -6.76161 -0.0527957 0.0250307 0.0462434 0.99722 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1939 1988 -0.504581 -7.51507 -6.49975 0.0473578 0.0257221 -0.0289736 0.998126 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1939 1989 -0.204 -0.0102575 -6.28397 -0.00156259 0.027168 0.000178765 0.99963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1939 1990 -0.511431 7.48567 -6.77625 -0.0401227 0.033423 0.0463984 0.997557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1940 1989 -0.485584 -7.48063 -6.51818 0.0407681 0.0254788 -0.0331852 0.998292 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1940 1990 -0.182911 0.00464926 -6.2745 5.42082e-05 0.0387034 -0.00695196 0.999227 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1940 1991 -0.491045 7.46152 -6.74385 -0.0448259 0.0368303 0.0377193 0.997603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1941 1990 -0.499886 -7.46998 -6.49617 0.0498644 0.0261636 -0.0407569 0.997581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1941 1991 -0.18447 -0.0198746 -6.26341 -0.00497903 0.0241001 0.0107893 0.999639 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1941 1992 -0.502598 7.45745 -6.75274 -0.0457408 0.0325119 0.0350747 0.997808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1942 1991 -0.49804 -7.46219 -6.49493 0.0498983 0.0195926 -0.0402136 0.997752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1942 1992 -0.187406 -0.00602774 -6.27527 0.00113926 0.0324545 0.00605614 0.999454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1942 1993 -0.496888 7.43551 -6.78066 -0.0496754 0.0269534 0.0445942 0.997405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1943 1992 -0.499758 -7.46452 -6.51595 0.0455291 0.0326599 -0.0342953 0.99784 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1943 1993 -0.208928 0.00263155 -6.28365 0.0035641 0.0226445 -0.00834437 0.999702 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1943 1994 -0.50649 7.43814 -6.75794 -0.0525064 0.0357138 0.0333666 0.997424 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1944 1993 -0.500975 -7.45988 -6.50607 0.0519662 0.0313492 -0.0357001 0.997518 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1944 1994 -0.181857 0.000416607 -6.28833 0.000616929 0.0282971 0.00838258 0.999564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1944 1995 -0.518046 7.41466 -6.76714 -0.0517392 0.0307871 0.0364178 0.997521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1945 1994 -0.501525 -7.43669 -6.51125 0.0523488 0.030908 -0.0360547 0.997499 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1945 1995 -0.215973 0.000362288 -6.28791 -0.00187149 0.0317973 0.00377764 0.999485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1945 1996 -0.515429 7.42171 -6.78079 -0.0508906 0.0445729 0.0329869 0.997164 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1946 1995 -0.495975 -7.42199 -6.50182 0.0494328 0.0358404 -0.0338251 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1946 1996 -0.195735 0.00238147 -6.26197 0.00204012 0.0285651 -0.000105729 0.99959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1946 1997 -0.50753 7.38979 -6.75664 -0.0437966 0.0351291 0.0320329 0.997909 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1947 1996 -0.496364 -7.40256 -6.51281 0.0469522 0.0316742 -0.0369666 0.99771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1947 1997 -0.181227 0.0068781 -6.27691 -0.00474372 0.0321949 0.00300927 0.999466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1947 1998 -0.487551 7.38492 -6.76367 -0.0576738 0.0302233 0.0362085 0.997221 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1948 1997 -0.502698 -7.38464 -6.51101 0.0430844 0.0301571 -0.0425746 0.997708 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1948 1998 -0.194501 0.000239033 -6.27485 -0.00344547 0.0242026 -0.00338686 0.999695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1948 1999 -0.506678 7.38103 -6.7676 -0.0496499 0.0331487 0.0310019 0.997735 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1949 1998 -0.503746 -7.38715 -6.51941 0.0426788 0.0277634 -0.0368334 0.998024 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1949 1999 -0.200755 -0.0226935 -6.27818 0.00115023 0.0280609 -0.00707755 0.99958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1949 2000 -0.506581 7.35061 -6.76675 -0.0637058 0.0297453 0.0384291 0.996785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1950 1999 -0.487299 -7.37127 -6.51153 0.0480331 0.0285654 -0.0292271 0.998009 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1950 2000 -0.214664 -0.0176211 -6.28366 0.000358598 0.0212246 0.00396091 0.999767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1950 2001 -0.492818 7.34451 -6.74134 -0.0530794 0.0321824 0.0304886 0.997606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1951 2000 -0.475637 -7.36401 -6.49973 0.0457651 0.0261213 -0.0389342 0.997851 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1951 2001 -0.210867 0.00258176 -6.26255 7.97995e-05 0.0269751 -0.00507494 0.999623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1951 2002 -0.501187 7.32573 -6.75605 -0.0441784 0.0264704 0.0472948 0.997552 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1952 2001 -0.481821 -7.33885 -6.49735 0.0560687 0.0266293 -0.0372475 0.997376 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1952 2002 -0.202842 -0.00745622 -6.26685 -0.00231726 0.0376194 -0.000118666 0.999289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1952 2003 -0.497383 7.30903 -6.75244 -0.0604282 0.0233074 0.0405659 0.997076 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1953 2002 -0.488951 -7.32661 -6.51708 0.0485029 0.0324482 -0.046226 0.997225 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1953 2003 -0.191791 -0.00812172 -6.28007 0.00016043 0.020551 0.00273777 0.999785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1953 2004 -0.490409 7.31256 -6.77608 -0.0570918 0.0306983 0.0328251 0.997357 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1954 2003 -0.467025 -7.31113 -6.50372 0.0520553 0.0213224 -0.0467763 0.99732 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1954 2004 -0.212462 0.00540178 -6.27839 0.00655115 0.0403029 -0.00369635 0.999159 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1954 2005 -0.48484 7.28996 -6.76311 -0.0461733 0.0342496 0.0452502 0.99732 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1955 2004 -0.47931 -7.30031 -6.50112 0.0571536 0.0253452 -0.0308559 0.997567 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1955 2005 -0.18278 -1.59908e-05 -6.28864 -0.00387047 0.0377142 -0.0033445 0.999275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1955 2006 -0.498727 7.28201 -6.75494 -0.0474943 0.0362895 0.0446128 0.997215 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1956 2005 -0.476274 -7.29587 -6.48872 0.0448064 0.0261248 -0.0332587 0.9981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1956 2006 -0.207508 0.0143185 -6.26546 0.00251887 0.0308679 0.007068 0.999495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1956 2007 -0.502522 7.25633 -6.75453 -0.0483123 0.0373896 0.0290752 0.997709 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1957 2006 -0.464422 -7.2753 -6.5097 0.0405481 0.0321365 -0.0492418 0.997446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1957 2007 -0.206813 0.0172582 -6.27583 0.00406245 0.0405536 -0.00657441 0.999147 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1957 2008 -0.491013 7.24926 -6.75267 -0.0453126 0.0289003 0.040301 0.997741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1958 2007 -0.490014 -7.26413 -6.51529 0.0478986 0.0233677 -0.0386517 0.997831 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1958 2008 -0.211551 0.007323 -6.26387 0.00247444 0.0319356 0.00218986 0.999484 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1958 2009 -0.485109 7.2449 -6.76378 -0.0589191 0.035215 0.0444503 0.996651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1959 2008 -0.465097 -7.26245 -6.4994 0.0482349 0.0369076 -0.0399358 0.997355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1959 2009 -0.193007 -0.007763 -6.26947 0.00217188 0.0193274 -0.000254958 0.999811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1959 2010 -0.48139 7.24465 -6.76498 -0.0536873 0.0365745 0.032236 0.997367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1960 2009 -0.468257 -7.23439 -6.50491 0.0546976 0.0240809 -0.0336859 0.997644 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1960 2010 -0.188819 0.0144027 -6.28753 -0.00250777 0.0290198 -0.00311898 0.999571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1960 2011 -0.488882 7.21005 -6.76671 -0.0379487 0.0349898 0.0410709 0.997822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1961 2010 -0.479573 -7.21785 -6.49966 0.0460244 0.0217233 -0.0354143 0.998076 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1961 2011 -0.206011 0.00176075 -6.26714 -0.000870303 0.0298207 -0.00845346 0.999519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1961 2012 -0.488948 7.21198 -6.75089 -0.0496632 0.0268619 0.0377191 0.997692 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1962 2011 -0.477542 -7.21915 -6.50897 0.0519494 0.0349314 -0.0350701 0.997422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1962 2012 -0.204542 0.0113304 -6.2764 -0.0120299 0.0292183 0.00605067 0.999482 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1962 2013 -0.493279 7.20927 -6.75799 -0.051753 0.0439906 0.0344428 0.997096 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1963 2012 -0.484315 -7.20312 -6.51515 0.045475 0.0323915 -0.0432568 0.997503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1963 2013 -0.196197 -0.00633883 -6.27447 0.00691389 0.0304415 -0.012921 0.999429 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1963 2014 -0.487644 7.16608 -6.74938 -0.0465806 0.0375462 0.0401309 0.997402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1964 2013 -0.470962 -7.18685 -6.50392 0.048277 0.0376961 -0.0413962 0.997264 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1964 2014 -0.204114 -0.0100959 -6.26361 0.00347269 0.0278368 0.000766929 0.999606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1964 2015 -0.478358 7.16188 -6.75628 -0.050262 0.0353468 0.0391388 0.997343 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1965 2014 -0.46571 -7.17931 -6.49507 0.0510962 0.0339589 -0.028711 0.997703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1965 2015 -0.196394 0.0183324 -6.27611 0.00510296 0.0381148 0.000497059 0.99926 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1965 2016 -0.466082 7.15392 -6.75568 -0.0521937 0.0358985 0.037912 0.997271 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1966 2015 -0.466816 -7.1547 -6.50833 0.0385077 0.0340771 -0.0381024 0.99795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1966 2016 -0.202184 -0.0034594 -6.28016 -0.00128375 0.0307668 0.00728113 0.999499 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1966 2017 -0.481016 7.13719 -6.77367 -0.0503296 0.0364405 0.0344432 0.997473 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1967 2016 -0.486906 -7.14512 -6.49952 0.0501605 0.0304262 -0.0427405 0.997362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1967 2017 -0.192509 4.28349e-05 -6.27863 0.000256839 0.0379023 0.0031755 0.999276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1967 2018 -0.489975 7.13024 -6.75597 -0.0512768 0.0246094 0.0397027 0.997591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1968 2017 -0.476931 -7.13422 -6.51489 0.055665 0.0279719 -0.0295931 0.997619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1968 2018 -0.198343 0.0225091 -6.28376 -0.0072884 0.0319449 0.00425456 0.999454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1968 2019 -0.48257 7.10268 -6.75336 -0.0510342 0.0348512 0.0336987 0.99752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1969 2018 -0.480547 -7.11398 -6.50801 0.0501046 0.0350199 -0.0317551 0.997625 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1969 2019 -0.197488 -0.00147942 -6.29503 0.000264693 0.0327674 0.00276844 0.999459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1969 2020 -0.484647 7.09119 -6.77462 -0.050695 0.0269183 0.0295198 0.997915 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1970 2019 -0.46229 -7.11215 -6.50383 0.0508343 0.0328264 -0.0392212 0.997397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1970 2020 -0.195952 0.00272195 -6.27252 -0.012761 0.0290308 0.00270476 0.999493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1970 2021 -0.492004 7.07902 -6.76037 -0.0618789 0.0304205 0.0378624 0.996901 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1971 2020 -0.456386 -7.08497 -6.49442 0.0513555 0.0286371 -0.0418324 0.997393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1971 2021 -0.206071 -0.00960493 -6.26419 -0.0038371 0.0384224 0.000854048 0.999254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1971 2022 -0.451495 7.08008 -6.77057 -0.0614568 0.0323517 0.0358087 0.996942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1972 2021 -0.446936 -7.07873 -6.51015 0.0655768 0.027458 -0.0352764 0.996846 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1972 2022 -0.192089 -0.000249505 -6.30035 0.0106829 0.0298211 -0.00252513 0.999495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1972 2023 -0.482677 7.0627 -6.74726 -0.0601606 0.0223951 0.0292843 0.997508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1973 2022 -0.469734 -7.06432 -6.50003 0.0563624 0.0324715 -0.0380871 0.997155 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1973 2023 -0.193502 -0.018148 -6.27282 0.00222121 0.0332122 -0.0005556 0.999446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1973 2024 -0.50096 7.04261 -6.74954 -0.0539358 0.0363935 0.0393086 0.997106 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1974 2023 -0.451725 -7.06411 -6.50061 0.0532647 0.029661 -0.0331018 0.997591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1974 2024 -0.204182 -0.00767541 -6.27663 0.00637833 0.039957 -0.000432895 0.999181 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1974 2025 -0.481873 7.01769 -6.75494 -0.0460881 0.0360237 0.0293728 0.997855 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1975 2024 -0.482687 -7.04195 -6.49423 0.0482084 0.0293058 -0.0358517 0.997763 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1975 2025 -0.190613 -0.00477962 -6.26966 0.00510294 0.0394339 0.00165676 0.999208 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1975 2026 -0.492817 7.02245 -6.74555 -0.0517854 0.0269544 0.0375243 0.997589 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1976 2025 -0.465796 -7.03554 -6.51086 0.0523587 0.0311762 -0.0297873 0.997697 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1976 2026 -0.199365 -0.0105263 -6.27856 -3.95138e-05 0.0386337 0.00895241 0.999213 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1976 2027 -0.47332 7.01554 -6.76432 -0.0492386 0.0277845 0.0434337 0.997455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1977 2026 -0.470118 -7.02323 -6.49497 0.0436756 0.0380285 -0.0379042 0.997602 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1977 2027 -0.188356 0.00746369 -6.28739 0.00286722 0.0239632 -0.00287978 0.999705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1977 2028 -0.484333 6.98032 -6.75184 -0.0507271 0.0347384 0.0391362 0.997341 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1978 2027 -0.456952 -6.99542 -6.51275 0.0446344 0.0389182 -0.0418067 0.997369 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1978 2028 -0.189968 0.0115331 -6.2765 0.00494944 0.0408876 -0.000226753 0.999151 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1978 2029 -0.481368 7.00179 -6.76938 -0.0451082 0.0326687 0.0329101 0.997905 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1979 2028 -0.468178 -6.98536 -6.49509 0.0531927 0.0375348 -0.0344657 0.997283 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1979 2029 -0.192492 0.0147091 -6.27683 0.00669162 0.027119 0.00484567 0.999598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1979 2030 -0.469405 6.97223 -6.74579 -0.0468316 0.031111 0.0436765 0.997462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1980 2029 -0.434994 -7.00471 -6.50603 0.0479837 0.0307866 -0.042018 0.997489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1980 2030 -0.213215 0.0175204 -6.27958 -0.00402956 0.0323459 0.00349217 0.999463 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1980 2031 -0.481269 6.9415 -6.75368 -0.0527019 0.0296393 0.0427242 0.997256 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1981 2030 -0.453981 -6.9609 -6.49731 0.0522095 0.0321953 -0.0446327 0.997119 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1981 2031 -0.209787 -0.0174822 -6.26522 -0.000193996 0.0258101 0.00176818 0.999665 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1981 2032 -0.465102 6.92784 -6.74573 -0.0477508 0.0250013 0.0395685 0.997762 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1982 2031 -0.454804 -6.95186 -6.52143 0.0480527 0.0386438 -0.0336229 0.99753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1982 2032 -0.204084 0.00162759 -6.27833 0.00562986 0.0286555 -0.00153991 0.999572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1982 2033 -0.469922 6.942 -6.74888 -0.0508815 0.0367957 0.0347215 0.997422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1983 2032 -0.462625 -6.9259 -6.48526 0.066093 0.0315317 -0.0382772 0.99658 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1983 2033 -0.194778 0.0101385 -6.29704 0.000528535 0.0365983 -0.00342191 0.999324 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1983 2034 -0.456837 6.90591 -6.7414 -0.0438309 0.0354926 0.0346318 0.997807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1984 2033 -0.454432 -6.9317 -6.49907 0.0464309 0.045615 -0.0362439 0.997221 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1984 2034 -0.184977 0.00280342 -6.2791 -0.00189775 0.0407012 -0.00541031 0.999155 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1984 2035 -0.47842 6.89626 -6.77575 -0.0486017 0.0385208 0.0303334 0.997614 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1985 2034 -0.449911 -6.91273 -6.51104 0.0529517 0.0303961 -0.0312193 0.997646 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1985 2035 -0.191111 0.00140475 -6.27778 0.00443748 0.0281272 -0.000239126 0.999594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1985 2036 -0.484418 6.86312 -6.73219 -0.0618566 0.0350277 0.0375071 0.996765 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1986 2035 -0.438149 -6.90993 -6.49567 0.0472808 0.0253111 -0.0384529 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1986 2036 -0.20074 -2.40569e-06 -6.27034 0.00494196 0.0363643 -0.000522431 0.999326 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1986 2037 -0.458327 6.86574 -6.74075 -0.054842 0.0277912 0.0428184 0.997189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1987 2036 -0.442892 -6.88778 -6.4971 0.0482583 0.0246417 -0.0336051 0.997965 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1987 2037 -0.209056 -0.00271317 -6.26345 0.00829244 0.0387141 0.00777514 0.999186 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1987 2038 -0.471378 6.86699 -6.74146 -0.051512 0.0310477 0.0409997 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1988 2037 -0.440637 -6.87727 -6.50197 0.0486301 0.0415135 -0.0402683 0.997141 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1988 2038 -0.188156 0.0207618 -6.28168 0.00830343 0.0296958 -0.00321935 0.999519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1988 2039 -0.467342 6.83548 -6.7433 -0.0495305 0.0297825 0.0385483 0.997584 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1989 2038 -0.4417 -6.85623 -6.50269 0.0543045 0.0305965 -0.0387033 0.997305 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1989 2039 -0.19333 0.00228617 -6.27758 0.00322457 0.0274695 -0.00513827 0.999604 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1989 2040 -0.45324 6.8294 -6.74977 -0.0591962 0.0307186 0.0284781 0.997367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1990 2039 -0.452813 -6.84851 -6.51943 0.0482459 0.0336072 -0.0347315 0.997666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1990 2040 -0.212715 0.00737722 -6.27461 0.00499895 0.0273382 0.00170861 0.999612 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1990 2041 -0.4551 6.82585 -6.74367 -0.0555599 0.0386748 0.0279826 0.997314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1991 2040 -0.43827 -6.80272 -6.50297 0.0415668 0.0262694 -0.0357787 0.998149 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1991 2041 -0.213241 -0.00487028 -6.27182 -0.00111608 0.0275729 0.00139575 0.999618 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1991 2042 -0.455844 6.78932 -6.73208 -0.049958 0.0301263 0.0365546 0.997627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1992 2041 -0.441924 -6.82303 -6.49736 0.0489115 0.0374313 -0.0290184 0.99768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1992 2042 -0.205714 0.00443359 -6.27331 0.00513472 0.037981 -0.00495345 0.999253 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1992 2043 -0.440185 6.78903 -6.76391 -0.0508366 0.0364578 0.0327289 0.997505 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1993 2042 -0.439492 -6.80411 -6.49613 0.0542171 0.0332134 -0.0311459 0.997491 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1993 2043 -0.201634 -2.42536e-05 -6.26163 0.00396745 0.0141644 2.1778e-05 0.999892 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1993 2044 -0.465467 6.79469 -6.74994 -0.0513501 0.0276323 0.0358153 0.997656 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1994 2043 -0.451116 -6.80086 -6.50282 0.0507068 0.0340194 -0.0432659 0.997196 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1994 2044 -0.19563 0.00385925 -6.26367 -0.00225559 0.037066 0.0108288 0.999252 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1994 2045 -0.458029 6.77539 -6.75156 -0.0635595 0.0333076 0.0350036 0.996808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1995 2044 -0.445387 -6.78548 -6.4865 0.0489045 0.0266841 -0.0317166 0.997943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1995 2045 -0.203882 0.0102863 -6.28973 0.00613063 0.0371074 -0.000252985 0.999292 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1995 2046 -0.449585 6.76091 -6.73308 -0.048808 0.0400925 0.0381611 0.997273 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1996 2045 -0.443772 -6.76299 -6.50122 0.0432773 0.0258086 -0.0398667 0.997934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1996 2046 -0.192735 0.00862841 -6.29579 0.00994249 0.0254803 0.00135298 0.999625 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1996 2047 -0.445834 6.72786 -6.74839 -0.0559832 0.0339279 0.0349577 0.997243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1997 2046 -0.439129 -6.7529 -6.49279 0.0584745 0.0288744 -0.0291693 0.997445 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1997 2047 -0.201098 0.00828748 -6.27997 -0.0005329 0.0237108 -0.000422467 0.999719 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1997 2048 -0.460386 6.72558 -6.74055 -0.043533 0.0303512 0.0281917 0.998193 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1998 2047 -0.44834 -6.73595 -6.48366 0.0382888 0.0265079 -0.0287388 0.998502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1998 2048 -0.21155 -0.0027266 -6.29835 -0.00909421 0.0308282 -0.00191403 0.999481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1998 2049 -0.451248 6.71465 -6.73686 -0.0509281 0.0275542 0.0348092 0.997715 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1999 2048 -0.446729 -6.74031 -6.49697 0.0419287 0.0310012 -0.0417457 0.997767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1999 2049 -0.201125 -0.0171317 -6.26895 -0.00161233 0.0271265 -0.00381789 0.999623 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 1999 2050 -0.45698 6.70814 -6.74952 -0.0608083 0.0355709 0.0443192 0.99653 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2000 2049 -0.446152 -6.70815 -6.50301 0.0627794 0.0250498 -0.0373635 0.997013 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2000 2050 -0.193828 0.00150283 -6.27912 0.00572838 0.0235736 -0.00096545 0.999705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2000 2051 -0.456733 6.69828 -6.75247 -0.0490354 0.0345193 0.0401891 0.997391 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2001 2050 -0.438702 -6.69697 -6.49395 0.0547646 0.0237254 -0.0407594 0.997385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2001 2051 -0.199314 0.000800346 -6.28162 -0.00638173 0.0371508 -0.0068245 0.999266 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2001 2052 -0.457763 6.6698 -6.75584 -0.0510481 0.0276834 0.0383182 0.997577 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2002 2051 -0.422227 -6.68511 -6.48806 0.0468265 0.0278953 -0.0318318 0.998006 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2002 2052 -0.190444 0.00444266 -6.28159 0.00207665 0.0278693 -0.00450155 0.999599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2002 2053 -0.468072 6.66407 -6.74504 -0.0621917 0.0395948 0.0333363 0.996721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2003 2052 -0.442752 -6.67981 -6.49285 0.0525389 0.0294109 -0.0401297 0.997379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2003 2053 -0.184238 0.0112134 -6.27627 0.00315764 0.0286882 -0.000926607 0.999583 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2003 2054 -0.452254 6.6645 -6.73329 -0.0496898 0.0330522 0.0294834 0.997782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2004 2053 -0.412449 -6.63697 -6.49744 0.0486992 0.0332522 -0.0423105 0.997363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2004 2054 -0.199576 -0.00484487 -6.2819 0.00857122 0.0336809 -0.00108983 0.999395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2004 2055 -0.463882 6.62401 -6.74189 -0.0569901 0.0382832 0.0427061 0.996726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2005 2054 -0.445183 -6.64159 -6.48659 0.0560081 0.0321041 -0.0498113 0.99667 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2005 2055 -0.193141 -0.011513 -6.27105 0.00306784 0.0329944 -0.00411577 0.999442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2005 2056 -0.425452 6.63997 -6.74208 -0.0509539 0.0327916 0.0343014 0.997573 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2006 2055 -0.456231 -6.63054 -6.48048 0.047176 0.0297673 -0.0325064 0.997914 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2006 2056 -0.1992 0.00951205 -6.28666 -0.00014263 0.0300691 0.0015568 0.999547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2006 2057 -0.444868 6.5982 -6.72944 -0.0515933 0.0396309 0.0299234 0.997433 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2007 2056 -0.422502 -6.62046 -6.49654 0.0578218 0.0340475 -0.0337861 0.997174 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2007 2057 -0.185717 -0.00744037 -6.27559 -0.00268104 0.0326727 0.00604215 0.999444 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2007 2058 -0.435553 6.59408 -6.7307 -0.051512 0.0218575 0.0279376 0.998042 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2008 2057 -0.422244 -6.61801 -6.49269 0.0516626 0.0294286 -0.0335974 0.997665 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2008 2058 -0.198433 -0.00644708 -6.2601 0.00149788 0.0309279 0.0014981 0.999519 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2008 2059 -0.451504 6.57153 -6.7212 -0.0502415 0.03193 0.032647 0.997693 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2009 2058 -0.416099 -6.5881 -6.47028 0.0537296 0.0331221 -0.0292208 0.997578 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2009 2059 -0.187478 0.00357354 -6.27615 -0.00234837 0.0318033 0.00417558 0.999483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2009 2060 -0.444814 6.56385 -6.7295 -0.0609237 0.0376333 0.0304736 0.996967 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2010 2059 -0.446242 -6.59264 -6.48618 0.0435577 0.0303689 -0.0375082 0.997885 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2010 2060 -0.194146 0.000634626 -6.2877 -0.00678843 0.0292939 -0.00628691 0.999528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2010 2061 -0.448774 6.57588 -6.74006 -0.0572074 0.0373824 0.0378651 0.996943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2011 2060 -0.419826 -6.55727 -6.48921 0.0519622 0.0312973 -0.0421453 0.997268 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2011 2061 -0.21273 0.0214975 -6.26648 -0.000732396 0.0353624 0.010672 0.999317 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2011 2062 -0.446392 6.52719 -6.739 -0.053368 0.0304538 0.0282428 0.997711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2012 2061 -0.420584 -6.54925 -6.48808 0.056396 0.0338673 -0.0295392 0.997397 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2012 2062 -0.185446 0.00200346 -6.26659 0.00281259 0.0278736 0.00236286 0.999605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2012 2063 -0.431189 6.52521 -6.73772 -0.0531799 0.0268451 0.0334833 0.997662 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2013 2062 -0.433837 -6.54989 -6.49533 0.0559491 0.0282313 -0.0303734 0.997572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2013 2063 -0.213574 0.019622 -6.29399 -0.00562864 0.0425292 0.00321204 0.999074 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2013 2064 -0.450678 6.52258 -6.75182 -0.0548648 0.0211419 0.0397565 0.997478 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2014 2063 -0.44025 -6.51353 -6.47029 0.0519678 0.0216483 -0.0280868 0.998019 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2014 2064 -0.199063 0.0222621 -6.28642 0.00329982 0.0248948 -0.00788486 0.999654 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2014 2065 -0.449371 6.50392 -6.74271 -0.045961 0.0258575 0.0275267 0.998229 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2015 2064 -0.419421 -6.51284 -6.47684 0.0498549 0.0212142 -0.0280486 0.998137 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2015 2065 -0.177303 0.0101032 -6.28352 -0.00483171 0.0231282 0.00162001 0.99972 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2015 2066 -0.445457 6.46424 -6.74697 -0.0504951 0.0228063 0.0418508 0.997586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2016 2065 -0.426449 -6.50782 -6.47633 0.0572691 0.022576 -0.0348504 0.997495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2016 2066 -0.19815 0.00418812 -6.26237 0.00292232 0.0314253 -0.00155449 0.999501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2016 2067 -0.447167 6.47603 -6.73176 -0.0513756 0.0352434 0.0357164 0.997418 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2017 2066 -0.419378 -6.50096 -6.48645 0.0473161 0.0265393 -0.0315559 0.998029 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2017 2067 -0.194284 -0.0143539 -6.27913 0.00442401 0.0311631 -0.00724232 0.999478 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2017 2068 -0.431863 6.45603 -6.75086 -0.0612731 0.0264859 0.0312681 0.99728 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2018 2067 -0.430264 -6.47063 -6.49819 0.0503726 0.0303154 -0.0310354 0.997788 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2018 2068 -0.201761 -0.0111837 -6.26104 -0.0125214 0.0347646 0.00531075 0.999303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2018 2069 -0.437296 6.4402 -6.73205 -0.0521795 0.0430443 0.0407883 0.996876 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2019 2068 -0.426743 -6.4648 -6.48176 0.0509325 0.0381024 -0.0399048 0.997177 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2019 2069 -0.201507 0.00016482 -6.2769 -0.000611139 0.0339466 0.00201774 0.999421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2019 2070 -0.431834 6.4335 -6.73376 -0.0556799 0.0233368 0.0357575 0.997535 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2020 2069 -0.412634 -6.43455 -6.48691 0.0498278 0.024566 -0.0330942 0.997907 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2020 2070 -0.194947 -0.00351317 -6.27822 -0.00155179 0.0275857 -0.00808467 0.999586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2020 2071 -0.435871 6.39955 -6.7325 -0.0504726 0.0346952 0.0319491 0.997611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2021 2070 -0.400163 -6.4403 -6.49318 0.0551747 0.0305453 -0.0322605 0.997488 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2021 2071 -0.192331 0.000995302 -6.26962 0.00262808 0.0336187 0.00284702 0.999427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2021 2072 -0.432229 6.41057 -6.72054 -0.0475791 0.0276647 0.0351544 0.997865 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2022 2071 -0.402572 -6.42038 -6.48441 0.054078 0.0328479 -0.0364882 0.997329 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2022 2072 -0.194189 -0.0111896 -6.28755 -0.00966533 0.0316046 0.0149252 0.999342 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2022 2073 -0.43497 6.39232 -6.72784 -0.0467115 0.0342931 0.0363149 0.997659 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2023 2072 -0.43027 -6.39373 -6.49484 0.0499571 0.0315991 -0.0355574 0.997618 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2023 2073 -0.19014 -0.00334681 -6.27984 -0.000775902 0.036947 -0.00418233 0.999308 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2023 2074 -0.43682 6.39017 -6.76168 -0.0557003 0.0352618 0.034276 0.997236 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2024 2073 -0.425396 -6.39404 -6.47802 0.0590762 0.0262179 -0.026319 0.997562 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2024 2074 -0.192783 0.0122477 -6.29426 -0.00422787 0.0405732 0.0032585 0.999162 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2024 2075 -0.447441 6.36138 -6.75149 -0.0572056 0.0293652 0.0285817 0.997521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2025 2074 -0.422166 -6.34964 -6.47675 0.0538583 0.0261449 -0.0260339 0.997867 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2025 2075 -0.191399 0.00144642 -6.2799 0.00603217 0.0309179 0.00210881 0.999501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2025 2076 -0.43717 6.35909 -6.74338 -0.0505335 0.0308401 0.0353078 0.997621 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2026 2075 -0.431416 -6.37414 -6.47477 0.048339 0.0297083 -0.0341921 0.997803 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2026 2076 -0.167525 0.00317721 -6.26929 -0.00149313 0.0349719 6.01947e-05 0.999387 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2026 2077 -0.432483 6.3281 -6.74404 -0.0619943 0.0313522 0.0288923 0.997165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2027 2076 -0.398597 -6.37106 -6.48249 0.0522061 0.0327607 -0.032631 0.997565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2027 2077 -0.194077 -0.000452261 -6.28592 0.000845502 0.0274472 0.00387083 0.999615 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2027 2078 -0.444032 6.33366 -6.73999 -0.054832 0.0297173 0.038703 0.997303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2028 2077 -0.416229 -6.3345 -6.48328 0.0496075 0.0389338 -0.0240764 0.997719 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2028 2078 -0.213231 0.0129909 -6.26769 -0.000720827 0.0368019 -0.00141354 0.999321 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2028 2079 -0.436417 6.31542 -6.73682 -0.0546181 0.0329358 0.0313452 0.997472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2029 2078 -0.407879 -6.34381 -6.48356 0.054633 0.0281285 -0.0365902 0.997439 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2029 2079 -0.198595 -0.000964019 -6.28135 0.000460799 0.0362798 0.00329012 0.999336 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2029 2080 -0.435157 6.28614 -6.74555 -0.0529079 0.0331227 0.0304623 0.997585 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2030 2079 -0.419698 -6.31329 -6.46515 0.0531653 0.0316445 -0.0366157 0.997412 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2030 2080 -0.18856 -0.00248505 -6.27724 -0.00454072 0.0319689 -0.000563339 0.999478 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2030 2081 -0.426235 6.30635 -6.72293 -0.0568785 0.0228565 0.0286741 0.997707 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2031 2080 -0.414904 -6.29335 -6.48423 0.0602176 0.0277253 -0.0435492 0.996849 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2031 2081 -0.18582 0.00455629 -6.2725 -0.00139873 0.0265949 -0.000903156 0.999645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2031 2082 -0.41846 6.26973 -6.73621 -0.0519052 0.0403566 0.034589 0.997237 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2032 2081 -0.422939 -6.27993 -6.49453 0.0592687 0.027917 -0.0404028 0.997033 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2032 2082 -0.19609 -0.00587746 -6.27535 0.00639428 0.0395838 0.000718887 0.999196 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2032 2083 -0.438095 6.23981 -6.74225 -0.0560662 0.0262893 0.0353542 0.997455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2033 2082 -0.412452 -6.25647 -6.48162 0.0518071 0.0332918 -0.0325375 0.997572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2033 2083 -0.170707 -0.00332382 -6.2725 0.00180285 0.0297368 0.000132793 0.999556 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2033 2084 -0.421553 6.22918 -6.72163 -0.0577571 0.028552 0.0317636 0.997417 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2034 2083 -0.391444 -6.25833 -6.4671 0.0607949 0.0279259 -0.03727 0.997063 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2034 2084 -0.206359 0.012532 -6.28393 -0.00350939 0.0353822 -0.0013424 0.999367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2034 2085 -0.425157 6.2419 -6.72582 -0.0474953 0.0419845 0.0336884 0.99742 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2035 2084 -0.388503 -6.24357 -6.49422 0.0516597 0.0341158 -0.0310527 0.997599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2035 2085 -0.18608 -0.00774151 -6.2819 -0.00569908 0.0221547 0.00206555 0.999736 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2035 2086 -0.422723 6.2153 -6.71968 -0.0549651 0.0399803 0.0418625 0.996809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2036 2085 -0.412005 -6.24518 -6.47359 0.050619 0.0286401 -0.0268777 0.997945 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2036 2086 -0.203858 -0.00755745 -6.27912 0.00211203 0.0272056 0.0088523 0.999588 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2036 2087 -0.410377 6.20454 -6.7233 -0.0590205 0.0356942 0.0307688 0.997144 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2037 2086 -0.421404 -6.20937 -6.47682 0.0521242 0.0308779 -0.0303091 0.997703 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2037 2087 -0.189154 0.00910167 -6.29037 0.000655311 0.0380587 0.00143646 0.999274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2037 2088 -0.423088 6.19683 -6.72233 -0.0573616 0.0362073 0.0383899 0.996958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2038 2087 -0.405271 -6.21232 -6.47857 0.0554587 0.0338135 -0.0226686 0.997631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2038 2088 -0.202538 -0.00826378 -6.27212 -0.00721362 0.0272855 0.00469306 0.999591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2038 2089 -0.418058 6.16063 -6.7627 -0.0558131 0.0312802 0.0355227 0.997319 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2039 2088 -0.400362 -6.19351 -6.48187 0.0599055 0.0257039 -0.0337471 0.997302 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2039 2089 -0.211285 -0.00102522 -6.28111 0.00313829 0.034118 -0.004312 0.999404 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2039 2090 -0.417819 6.17488 -6.73891 -0.0575278 0.0296506 0.0402514 0.997091 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2040 2089 -0.404396 -6.17867 -6.47278 0.0473082 0.0165137 -0.0310545 0.998261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2040 2090 -0.20586 0.00226656 -6.27017 -0.00434422 0.0299834 0.00444261 0.999531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2040 2091 -0.416611 6.14224 -6.72261 -0.0569443 0.0305455 0.0235642 0.997632 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2041 2090 -0.423513 -6.16774 -6.483 0.0484762 0.0333028 -0.0297492 0.997826 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2041 2091 -0.191946 -0.00768171 -6.29181 0.000126877 0.0341366 0.000541293 0.999417 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2041 2092 -0.417659 6.12788 -6.72021 -0.0585702 0.030542 0.0366551 0.997142 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2042 2091 -0.401513 -6.15085 -6.48438 0.0507351 0.0274045 -0.0326316 0.997803 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2042 2092 -0.194408 -0.00552822 -6.28033 0.00304794 0.0314698 0.000225578 0.9995 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2042 2093 -0.419096 6.1166 -6.73258 -0.0435075 0.0420837 0.0351975 0.997546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2043 2092 -0.415762 -6.14892 -6.48154 0.0485515 0.0344778 -0.0257646 0.997893 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2043 2093 -0.204498 0.00676441 -6.26248 -0.000336101 0.0251929 -0.00304266 0.999678 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2043 2094 -0.410508 6.10051 -6.72598 -0.0594265 0.0272577 0.0363141 0.997199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2044 2093 -0.401529 -6.12097 -6.47627 0.050539 0.0293403 -0.0395339 0.997508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2044 2094 -0.188285 0.000872854 -6.27805 0.000662016 0.0397255 0.00954543 0.999165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2044 2095 -0.417855 6.09115 -6.71002 -0.0431406 0.0234976 0.0296033 0.998354 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2045 2094 -0.397085 -6.1003 -6.48212 0.0591935 0.0258938 -0.0332162 0.997358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2045 2095 -0.206352 -0.000522269 -6.27542 -0.00419743 0.0273878 -0.000858986 0.999616 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2045 2096 -0.42874 6.07795 -6.72986 -0.0503789 0.0329941 0.0294075 0.997752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2046 2095 -0.398741 -6.10868 -6.46353 0.0526453 0.0385047 -0.0385754 0.997125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2046 2096 -0.201339 0.00870126 -6.29253 -0.00676119 0.0275884 0.000336477 0.999596 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2046 2097 -0.427371 6.0605 -6.73495 -0.0514389 0.038803 0.0439086 0.996956 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2047 2096 -0.383364 -6.0802 -6.48524 0.0505975 0.032079 -0.0417301 0.997331 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2047 2097 -0.200738 0.0106484 -6.28409 0.00118144 0.0339474 0.0014401 0.999422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2047 2098 -0.409859 6.07035 -6.71429 -0.0539799 0.0377363 0.0380028 0.997105 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2048 2097 -0.405686 -6.06139 -6.46484 0.0595789 0.0247721 -0.0345904 0.997317 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2048 2098 -0.197313 -0.00687205 -6.2836 0.00736356 0.0234808 0.0096566 0.999651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2048 2099 -0.403578 6.04222 -6.72473 -0.0518604 0.0356444 0.0312348 0.997529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2049 2098 -0.386186 -6.05484 -6.49208 0.0556459 0.02607 -0.0290526 0.997687 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2049 2099 -0.206518 -0.00252557 -6.27569 -0.000994937 0.0240117 -0.00472331 0.9997 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2049 2100 -0.415982 6.01756 -6.71177 -0.0612695 0.0358247 0.0388137 0.996723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2050 2099 -0.394847 -6.05109 -6.47049 0.055979 0.0295353 -0.0350501 0.997379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2050 2100 -0.189101 0.00033917 -6.2898 0.00160418 0.0320148 0.00155925 0.999485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2050 2101 -0.40965 6.01447 -6.73853 -0.0592675 0.0366441 0.0339694 0.996991 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2051 2100 -0.408897 -6.00481 -6.47122 0.058759 0.0383507 -0.0330808 0.996987 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2051 2101 -0.196053 -0.000179425 -6.26988 0.00723418 0.0398618 -0.00882919 0.99914 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2051 2102 -0.412528 5.993 -6.72762 -0.0513736 0.0282524 0.0277766 0.997893 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2052 2101 -0.38718 -6.01194 -6.47087 0.0608251 0.0289541 -0.0313063 0.997237 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2052 2102 -0.198647 -0.0114618 -6.28869 -0.00638008 0.0269505 0.000101658 0.999616 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2052 2103 -0.411457 5.99044 -6.71641 -0.0564296 0.0331774 0.0310457 0.997372 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2053 2102 -0.384666 -5.99457 -6.46803 0.044389 0.0207099 -0.0270713 0.998433 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2053 2103 -0.201321 -0.0122064 -6.25201 -0.00363678 0.0274843 -0.00508417 0.999603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2053 2104 -0.400888 5.97042 -6.73082 -0.052333 0.021462 0.0295339 0.997962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2054 2103 -0.400573 -5.97042 -6.46653 0.0505331 0.031955 -0.023548 0.997933 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2054 2104 -0.203445 0.000202263 -6.28006 0.00217413 0.0398336 -0.00954335 0.999158 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2054 2105 -0.403897 5.95015 -6.73864 -0.0511914 0.0341716 0.031673 0.997601 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2055 2104 -0.386421 -5.97247 -6.48435 0.0557624 0.0284226 -0.0286046 0.997629 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2055 2105 -0.201578 -0.00994128 -6.28015 -0.000347692 0.030547 -0.00875394 0.999495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2055 2106 -0.389007 5.94045 -6.72108 -0.0472521 0.0255187 0.0345393 0.997959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2056 2105 -0.370239 -5.94993 -6.47899 0.0524235 0.0261874 -0.0275619 0.997901 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2056 2106 -0.198447 -0.0113887 -6.30771 -0.00220587 0.035395 -0.00420133 0.999362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2056 2107 -0.381031 5.92995 -6.72424 -0.0575129 0.0249549 0.0245711 0.99773 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2057 2106 -0.386266 -5.94635 -6.47215 0.0544016 0.0250068 -0.0300456 0.997754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2057 2107 -0.186045 0.0092743 -6.27889 0.000289115 0.0289995 -0.0052017 0.999566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2057 2108 -0.405053 5.92071 -6.72469 -0.0547045 0.0383103 0.0316548 0.997265 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2058 2107 -0.381016 -5.93395 -6.46353 0.0560127 0.0213738 -0.0422 0.997309 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2058 2108 -0.198531 -0.00875073 -6.27304 0.0100577 0.045828 0.00714326 0.998873 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2058 2109 -0.3992 5.89597 -6.72669 -0.0546151 0.0327151 0.0168183 0.99783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2059 2108 -0.399037 -5.92919 -6.48108 0.055846 0.0305443 -0.0296161 0.997533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2059 2109 -0.194927 0.00974771 -6.27376 0.00264534 0.0257042 -0.00476668 0.999655 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2059 2110 -0.40389 5.87403 -6.71873 -0.0561581 0.0373577 0.0355998 0.997087 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2060 2109 -0.367595 -5.90333 -6.48821 0.0438975 0.0281225 -0.0330284 0.998094 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2060 2110 -0.210195 0.00250904 -6.2766 0.00360841 0.0335961 -0.00754734 0.9994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2060 2111 -0.393334 5.89364 -6.72219 -0.0529766 0.040718 0.0322656 0.997243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2061 2110 -0.381701 -5.88602 -6.46093 0.0500293 0.023788 -0.0373793 0.997764 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2061 2111 -0.202707 -0.0190762 -6.26828 0.00622911 0.0304507 -0.00714842 0.999491 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2061 2112 -0.379937 5.8646 -6.71592 -0.0468595 0.0273728 0.0284186 0.998122 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2062 2111 -0.381467 -5.86544 -6.47681 0.048575 0.0337338 -0.0212869 0.998023 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2062 2112 -0.193885 -0.0013069 -6.26934 0.00478122 0.0333902 -0.0038833 0.999423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2062 2113 -0.394518 5.83147 -6.72319 -0.0562394 0.036513 0.0301283 0.997294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2063 2112 -0.401944 -5.86574 -6.46752 0.054528 0.0310827 -0.0295987 0.997589 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2063 2113 -0.203672 0.00994637 -6.26886 0.000564945 0.0240331 0.0032993 0.999706 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2063 2114 -0.400505 5.8115 -6.74249 -0.0602604 0.0272527 0.0256496 0.997481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2064 2113 -0.378885 -5.84638 -6.46186 0.055096 0.0274141 -0.0342351 0.997517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2064 2114 -0.189724 0.0147191 -6.29533 -0.00171449 0.0305275 0.00408025 0.999524 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2064 2115 -0.398129 5.82432 -6.69969 -0.0525202 0.031152 0.0302094 0.997677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2065 2114 -0.378473 -5.83431 -6.46973 0.0444926 0.0438129 -0.033623 0.997482 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2065 2115 -0.191309 -0.00533012 -6.27503 -0.00189622 0.0273793 -0.00161397 0.999622 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2065 2116 -0.402633 5.79079 -6.70326 -0.0478467 0.0321476 0.0292833 0.997908 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2066 2115 -0.37174 -5.81863 -6.47859 0.0571198 0.0288204 -0.0269439 0.997587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2066 2116 -0.18755 0.00532331 -6.284 0.0025203 0.0245634 -0.00733332 0.999668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2066 2117 -0.416794 5.79027 -6.69844 -0.0625369 0.0247491 0.0241391 0.997444 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2067 2116 -0.37732 -5.79216 -6.47418 0.0534585 0.0356692 -0.0372245 0.997238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2067 2117 -0.206792 0.00581302 -6.26723 -0.00524759 0.029842 -0.00529545 0.999527 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2067 2118 -0.40379 5.76235 -6.72127 -0.0486701 0.0328496 0.0266971 0.997918 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2068 2117 -0.367765 -5.79723 -6.46518 0.0584577 0.0304373 -0.0323607 0.997301 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2068 2118 -0.188832 -0.00110927 -6.29151 -0.000608914 0.0342367 0.00343172 0.999408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2068 2119 -0.39077 5.74789 -6.71925 -0.0514628 0.0275916 0.0303691 0.997832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2069 2118 -0.37657 -5.79133 -6.45475 0.0570325 0.0290127 -0.0329177 0.997408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2069 2119 -0.203697 0.00331503 -6.27279 0.00699177 0.0315586 -0.00611105 0.999459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2069 2120 -0.388253 5.73665 -6.71368 -0.0563784 0.0370177 0.0297619 0.997279 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2070 2119 -0.375505 -5.74616 -6.44443 0.0592695 0.0336999 -0.0349054 0.997062 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2070 2120 -0.190027 -0.00319689 -6.27696 -0.00663505 0.0265036 -2.33978e-05 0.999627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2070 2121 -0.386355 5.74394 -6.70834 -0.0529847 0.0327591 0.037116 0.997367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2071 2120 -0.384383 -5.72724 -6.45745 0.0563084 0.0322976 -0.0323412 0.997367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2071 2121 -0.207774 -0.0045226 -6.29338 0.00903024 0.0223027 -0.00867425 0.999673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2071 2122 -0.405228 5.71279 -6.72019 -0.0541964 0.029019 0.0316184 0.997608 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2072 2121 -0.36137 -5.73333 -6.47001 0.0583645 0.033565 -0.0250185 0.997417 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2072 2122 -0.191513 0.000145905 -6.28102 0.00132387 0.0222869 -0.000931056 0.99975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2072 2123 -0.37304 5.71159 -6.72523 -0.0561975 0.0354025 0.0239874 0.997503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2073 2122 -0.383567 -5.69819 -6.45495 0.0582423 0.026706 -0.0208129 0.997728 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2073 2123 -0.213598 -0.0188103 -6.28748 0.0015663 0.0236274 -0.0060773 0.999701 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2073 2124 -0.392589 5.68913 -6.70125 -0.0638102 0.0205697 0.0272582 0.997378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2074 2123 -0.381032 -5.69525 -6.45544 0.0501669 0.0297684 -0.0211572 0.998073 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2074 2124 -0.201725 0.00240223 -6.27639 0.00315737 0.0374863 0.0117641 0.999223 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2074 2125 -0.411146 5.65811 -6.71821 -0.0514606 0.0308428 0.0211367 0.997975 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2075 2124 -0.359916 -5.6977 -6.4567 0.0619478 0.022974 -0.0260381 0.997475 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2075 2125 -0.185293 0.021698 -6.27451 9.11118e-06 0.0309752 -0.00520276 0.999507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2075 2126 -0.388018 5.67239 -6.71106 -0.0615872 0.0328714 0.0348587 0.996951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2076 2125 -0.375032 -5.67744 -6.46199 0.0499922 0.0234512 -0.0289046 0.998056 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2076 2126 -0.192268 -0.000781311 -6.29413 0.00702309 0.0242562 -0.00277055 0.999677 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2076 2127 -0.374493 5.6545 -6.70815 -0.0564909 0.0323545 0.0378307 0.997161 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2077 2126 -0.346432 -5.63595 -6.46831 0.0538554 0.029778 -0.0272655 0.997732 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2077 2127 -0.2004 -0.00849055 -6.30003 -0.00286936 0.0456352 0.00462325 0.998943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2077 2128 -0.376623 5.62942 -6.70629 -0.0573194 0.0305615 0.0272942 0.997515 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2078 2127 -0.362459 -5.64049 -6.46309 0.0580313 0.0315147 -0.0264709 0.997466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2078 2128 -0.182786 -0.00910688 -6.27045 -0.00107013 0.0415689 -0.00455117 0.999125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2078 2129 -0.358892 5.61648 -6.7201 -0.0580887 0.0302637 0.0256433 0.997523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2079 2128 -0.370506 -5.6302 -6.45602 0.0552812 0.0339576 -0.0318198 0.997386 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2079 2129 -0.194774 -0.0100875 -6.27504 -0.00533632 0.0342594 -0.00289128 0.999395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2079 2130 -0.381635 5.60558 -6.7232 -0.0573897 0.0277118 0.0382749 0.997233 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2080 2129 -0.346175 -5.61225 -6.46165 0.0559098 0.0287098 -0.0317995 0.997516 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2080 2130 -0.196647 -0.0186319 -6.28889 -0.00426633 0.0380777 0.00307538 0.999261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2080 2131 -0.395254 5.60191 -6.69434 -0.0571946 0.0350256 0.0272048 0.997378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2081 2130 -0.369564 -5.60968 -6.4607 0.0551401 0.033026 -0.0296445 0.997492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2081 2131 -0.198544 -0.0158455 -6.28455 -0.0129657 0.0268829 -0.00385244 0.999547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2081 2132 -0.370442 5.56411 -6.7063 -0.0546553 0.0408658 0.0284717 0.997262 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2082 2131 -0.365285 -5.6037 -6.46094 0.0571941 0.0354278 -0.0292092 0.997307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2082 2132 -0.189422 -0.00746853 -6.28983 0.00718301 0.0321601 0.0025103 0.999454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2082 2133 -0.36746 5.57026 -6.71327 -0.0549171 0.027468 0.0258794 0.997777 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2083 2132 -0.371458 -5.57059 -6.45732 0.0599222 0.0244546 -0.0233938 0.997629 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2083 2133 -0.196183 -0.00878458 -6.27068 0.00548579 0.0374745 0.00252952 0.999279 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2083 2134 -0.374455 5.52091 -6.711 -0.0542078 0.0375674 0.029649 0.997382 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2084 2133 -0.360239 -5.54341 -6.46052 0.0481853 0.0331145 -0.0322931 0.997767 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2084 2134 -0.183716 0.00164129 -6.2648 -0.00163781 0.0325066 0.00877377 0.999432 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2084 2135 -0.377714 5.53644 -6.72594 -0.0531312 0.0234547 0.0330243 0.997766 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2085 2134 -0.35983 -5.55444 -6.45347 0.057714 0.0311206 -0.0282713 0.997447 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2085 2135 -0.19079 0.00480553 -6.29901 0.000149046 0.0321637 -0.000700221 0.999482 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2085 2136 -0.381744 5.5224 -6.71122 -0.0633941 0.032633 0.031353 0.996962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2086 2135 -0.373695 -5.53134 -6.46745 0.0527902 0.023377 -0.0340137 0.997752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2086 2136 -0.186171 0.0168404 -6.27957 0.00107055 0.027674 -0.000875861 0.999616 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2086 2137 -0.375681 5.51727 -6.70966 -0.0547309 0.0364629 0.0306893 0.997363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2087 2136 -0.372463 -5.51538 -6.4719 0.0534134 0.0369722 -0.0302639 0.997429 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2087 2137 -0.174311 0.00441836 -6.26975 -0.00787025 0.0355863 0.00419743 0.999327 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2087 2138 -0.40697 5.48642 -6.71044 -0.0491548 0.0377734 0.0354905 0.997445 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2088 2137 -0.357525 -5.5076 -6.45687 0.053958 0.0154021 -0.0344498 0.99783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2088 2138 -0.210878 0.0130223 -6.28887 -0.00172442 0.0414331 0.000222298 0.99914 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2088 2139 -0.357941 5.47068 -6.71037 -0.0566631 0.0271081 0.0340154 0.997445 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2089 2138 -0.339708 -5.48284 -6.47333 0.0481416 0.0269573 -0.0237468 0.998194 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2089 2139 -0.206935 -0.00508666 -6.28915 -0.00311368 0.0291427 0.00610376 0.999552 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2089 2140 -0.381906 5.47792 -6.70392 -0.0491788 0.0275768 0.0223043 0.99816 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2090 2139 -0.355946 -5.48557 -6.44924 0.0588245 0.0317933 -0.024169 0.997469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2090 2140 -0.171198 0.00753756 -6.28084 0.00418433 0.0283926 3.78516e-05 0.999588 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2090 2141 -0.380673 5.45672 -6.71395 -0.0535663 0.0347165 0.0259156 0.997624 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2091 2140 -0.34399 -5.4675 -6.44286 0.0612747 0.0278731 -0.0336931 0.997163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2091 2141 -0.180785 0.0227775 -6.30263 -0.00265591 0.0354543 -1.66779e-05 0.999368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2091 2142 -0.372602 5.4351 -6.70784 -0.0543357 0.0339879 0.0286911 0.997532 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2092 2141 -0.369276 -5.45307 -6.44492 0.0571647 0.030205 -0.0255254 0.997581 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2092 2142 -0.205335 0.0163103 -6.29009 -0.00505522 0.0204572 0.00234168 0.999775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2092 2143 -0.381081 5.42043 -6.68619 -0.0553866 0.0252672 0.027705 0.997761 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2093 2142 -0.357328 -5.42861 -6.46145 0.0548651 0.028244 -0.0243697 0.997797 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2093 2143 -0.190274 0.0148002 -6.28065 -0.00568389 0.035634 0.00309425 0.999344 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2093 2144 -0.370259 5.40892 -6.70867 -0.0526468 0.0363987 0.0290198 0.997528 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2094 2143 -0.345599 -5.4194 -6.44432 0.0659155 0.0295841 -0.0168506 0.997244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2094 2144 -0.209352 -0.0144487 -6.2851 0.00610775 0.0291431 0.00225224 0.999554 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2094 2145 -0.386004 5.41117 -6.70944 -0.051802 0.0312372 0.0261112 0.997827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2095 2144 -0.357417 -5.41493 -6.46247 0.0644649 0.0361278 -0.0364337 0.9966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2095 2145 -0.198241 -0.0165949 -6.26308 0.00677039 0.0299006 0.000275777 0.99953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2095 2146 -0.382227 5.37891 -6.69999 -0.0540905 0.0281314 0.03501 0.997526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2096 2145 -0.348612 -5.39502 -6.45476 0.0676979 0.0223492 -0.0314991 0.996958 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2096 2146 -0.205049 0.0142535 -6.28107 0.00414537 0.0316858 -0.00890442 0.99945 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2096 2147 -0.369098 5.37282 -6.69689 -0.0513259 0.0361763 0.0444875 0.997034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2097 2146 -0.353224 -5.366 -6.45327 0.0601424 0.0296041 -0.0412615 0.996897 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2097 2147 -0.195995 -0.00838835 -6.27384 0.00439545 0.0351443 0.00200177 0.999371 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2097 2148 -0.386992 5.34438 -6.70621 -0.0614368 0.025346 0.0334626 0.997228 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2098 2147 -0.354653 -5.33993 -6.44687 0.0577091 0.0242084 -0.0327434 0.997503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2098 2148 -0.201151 -0.00260829 -6.28219 -0.000870896 0.0363048 0.00357074 0.999334 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2098 2149 -0.347433 5.33689 -6.6784 -0.0607264 0.0371956 0.0276384 0.997078 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2099 2148 -0.35705 -5.35382 -6.43313 0.0595943 0.0342493 -0.0280902 0.997239 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2099 2149 -0.19789 0.0220777 -6.26352 -0.00611346 0.0264645 0.0010177 0.999631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2099 2150 -0.371464 5.32751 -6.70013 -0.0566502 0.0341574 0.0327253 0.997273 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2100 2149 -0.345047 -5.33054 -6.44648 0.0606434 0.0346432 -0.0344758 0.996962 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2100 2150 -0.193427 0.0096911 -6.2776 0.000870104 0.0282744 -0.00433733 0.99959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2100 2151 -0.368876 5.30569 -6.68645 -0.0585512 0.032705 0.0329516 0.997204 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2101 2150 -0.362002 -5.31887 -6.45162 0.0548971 0.0261377 -0.0369457 0.997466 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2101 2151 -0.189144 0.0130404 -6.27853 0.00445598 0.0315382 0.00254812 0.999489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2101 2152 -0.368787 5.30324 -6.6861 -0.0535919 0.0323209 0.0193224 0.997853 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2102 2151 -0.351901 -5.30495 -6.46457 0.0566182 0.0294973 -0.0122765 0.997885 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2102 2152 -0.209837 0.0149997 -6.3038 -0.00274212 0.0271553 -0.00139 0.999627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2102 2153 -0.386739 5.2794 -6.70165 -0.0582528 0.043536 0.026362 0.997004 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2103 2152 -0.351437 -5.29265 -6.45984 0.0588838 0.0324376 -0.0279228 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2103 2153 -0.200584 -0.00026232 -6.26051 -0.0100773 0.0328406 -0.000438333 0.99941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2103 2154 -0.369602 5.24876 -6.70088 -0.0560673 0.0440628 0.0174748 0.997301 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2104 2153 -0.340642 -5.28209 -6.45156 0.057638 0.0382025 -0.0211736 0.997382 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2104 2154 -0.222864 0.0092276 -6.29581 -0.00288251 0.034099 -0.0086844 0.999377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2104 2155 -0.367181 5.24807 -6.68339 -0.0529913 0.0246405 0.0254291 0.997967 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2105 2154 -0.338485 -5.27574 -6.443 0.0587971 0.0373421 -0.0254403 0.997247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2105 2155 -0.200932 0.00197408 -6.26697 -0.00380399 0.0372596 0.00279217 0.999294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2105 2156 -0.375637 5.2182 -6.68944 -0.0630472 0.0274071 0.0326674 0.997099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2106 2155 -0.335046 -5.25223 -6.41788 0.0564062 0.0321069 -0.0335723 0.997327 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2106 2156 -0.18644 0.00551372 -6.27536 0.000351839 0.0374803 0.00133827 0.999296 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2106 2157 -0.364997 5.20407 -6.69119 -0.0609852 0.033131 0.0272423 0.997217 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2107 2156 -0.362863 -5.23993 -6.43727 0.0616281 0.0293223 -0.0276849 0.997284 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2107 2157 -0.197388 0.00275423 -6.28513 0.00147002 0.0315107 0.00512782 0.999489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2107 2158 -0.363503 5.20732 -6.70989 -0.0551752 0.0340524 0.0345289 0.997298 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2108 2157 -0.351983 -5.21287 -6.43711 0.0597533 0.027124 -0.0263542 0.997497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2108 2158 -0.198782 0.0051895 -6.28601 -0.00236165 0.0321808 0.00299552 0.999475 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2108 2159 -0.352853 5.18265 -6.68845 -0.0587959 0.0286321 0.0302355 0.997401 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2109 2158 -0.342324 -5.23098 -6.44428 0.0493539 0.0278508 -0.0174077 0.998241 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2109 2159 -0.19497 -0.00115522 -6.27743 0.00263598 0.0306783 0.00598149 0.999508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2109 2160 -0.355773 5.17735 -6.70768 -0.0581675 0.0311487 0.0256423 0.997491 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2110 2159 -0.33761 -5.1974 -6.44656 0.0615153 0.0338528 -0.021766 0.997294 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2110 2160 -0.186671 0.00536732 -6.27747 0.000270522 0.0277927 0.00215551 0.999611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2110 2161 -0.362661 5.16396 -6.69081 -0.0472881 0.0354833 0.0307001 0.997779 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2111 2160 -0.363012 -5.19341 -6.43952 0.0553406 0.0289442 -0.027898 0.997658 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2111 2161 -0.19769 -0.0120734 -6.26437 0.00372794 0.0473356 -0.00143298 0.998871 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2111 2162 -0.351764 5.14669 -6.70513 -0.0621993 0.0369985 0.0307252 0.996904 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2112 2161 -0.342044 -5.14814 -6.4394 0.0573911 0.030163 -0.0224296 0.997644 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2112 2162 -0.196865 0.00544983 -6.27033 0.00332257 0.0337491 -0.00461285 0.999414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2112 2163 -0.365586 5.13847 -6.68842 -0.0631362 0.0400251 0.0361328 0.996547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2113 2162 -0.337166 -5.16092 -6.45136 0.0619848 0.0341955 -0.0277865 0.997104 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2113 2163 -0.195068 -0.0104807 -6.2967 0.00465592 0.0313165 0.000277489 0.999499 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2113 2164 -0.36986 5.10877 -6.67714 -0.0604566 0.027556 0.0248687 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2114 2163 -0.347707 -5.15171 -6.43674 0.0560421 0.026612 -0.0359242 0.997427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2114 2164 -0.198695 -0.00862822 -6.29035 -0.00393317 0.0237199 0.000868085 0.999711 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2114 2165 -0.360828 5.13369 -6.67924 -0.0535426 0.0383575 0.0353211 0.997203 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2115 2164 -0.345967 -5.11064 -6.41792 0.0596181 0.0322404 -0.0377056 0.996988 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2115 2165 -0.177177 0.00360937 -6.27953 -0.00469517 0.0325893 -0.00902423 0.999417 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2115 2166 -0.35272 5.07981 -6.69661 -0.0626369 0.0234464 0.0363927 0.997097 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2116 2165 -0.342904 -5.10361 -6.46174 0.0543439 0.0255288 -0.03038 0.997733 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2116 2166 -0.190467 0.014975 -6.27832 -0.00102399 0.0247337 -0.00555519 0.999678 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2116 2167 -0.361601 5.062 -6.68554 -0.0495919 0.0375187 0.0212344 0.997839 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2117 2166 -0.347016 -5.10579 -6.42927 0.0480818 0.0432963 -0.0284537 0.997499 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2117 2167 -0.201352 0.00252264 -6.27507 0.00148436 0.0389935 0.00576682 0.999222 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2117 2168 -0.348313 5.05342 -6.67015 -0.0576298 0.0356075 0.0256338 0.997373 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2118 2167 -0.347017 -5.08744 -6.43811 0.0562947 0.0285977 -0.021162 0.99778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2118 2168 -0.209936 -0.00276332 -6.28539 0.00226388 0.0360886 0.00723989 0.99932 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2118 2169 -0.351814 5.0406 -6.67374 -0.0610337 0.0348889 0.0351669 0.996906 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2119 2168 -0.335964 -5.05718 -6.44386 0.0526679 0.0363978 -0.0350879 0.997332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2119 2169 -0.201987 -0.0156876 -6.27933 0.0102137 0.0314861 0.0109601 0.999392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2119 2170 -0.339417 5.03586 -6.68948 -0.047441 0.0357151 0.0242839 0.99794 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2120 2169 -0.355532 -5.05721 -6.42036 0.0565441 0.0334066 -0.0291967 0.997414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2120 2170 -0.206436 0.00155953 -6.27122 0.00226957 0.0302334 0.00259134 0.999537 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2120 2171 -0.34385 5.02195 -6.6905 -0.0513303 0.0363361 0.0101983 0.997968 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2121 2170 -0.330152 -5.04143 -6.45456 0.0619819 0.0248753 -0.0281123 0.997371 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2121 2171 -0.211183 -0.00218621 -6.29064 -0.00819359 0.0315852 0.00405069 0.999459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2121 2172 -0.349477 5.01395 -6.68743 -0.0524201 0.0333711 0.0229409 0.997804 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2122 2171 -0.332049 -5.0286 -6.43788 0.0600439 0.0269095 -0.0207095 0.997618 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2122 2172 -0.201029 0.00522107 -6.27094 0.006201 0.0385301 0.000730728 0.999238 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2122 2173 -0.340074 5.00952 -6.67065 -0.0611108 0.0377518 0.0202917 0.99721 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2123 2172 -0.328242 -5.00568 -6.44276 0.0545814 0.0343124 -0.0316361 0.997418 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2123 2173 -0.199127 0.00643216 -6.2784 -0.00159825 0.0310429 -0.0060834 0.999498 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2123 2174 -0.328972 4.96228 -6.68664 -0.0569594 0.034205 0.0253937 0.997467 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2124 2173 -0.351606 -4.98504 -6.42686 0.0575021 0.0332834 -0.0364055 0.997126 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2124 2174 -0.19313 0.00256847 -6.27461 -0.00290289 0.025173 0.00461232 0.999668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2124 2175 -0.356099 4.96191 -6.68373 -0.0545186 0.0387785 0.0359658 0.997111 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2125 2174 -0.319169 -4.98215 -6.44106 0.0519506 0.0294152 -0.0246191 0.997913 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2125 2175 -0.193674 -0.00760762 -6.27914 -0.00414873 0.0374755 -0.000194373 0.999289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2125 2176 -0.345282 4.94204 -6.67643 -0.0548144 0.025405 0.0265995 0.997819 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2126 2175 -0.329191 -4.96419 -6.44109 0.0559891 0.0247321 -0.0281961 0.997727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2126 2176 -0.213759 -0.00109052 -6.27031 -0.00435466 0.0334602 0.000902216 0.99943 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2126 2177 -0.355793 4.94166 -6.67601 -0.0516161 0.0291921 0.0271102 0.997872 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2127 2176 -0.334172 -4.94911 -6.44066 0.0631865 0.0165975 -0.0299487 0.997414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2127 2177 -0.188072 -0.00134359 -6.27111 0.00275258 0.0317883 0.00582218 0.999474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2127 2178 -0.330863 4.91726 -6.68167 -0.0529202 0.0404539 0.0264083 0.997429 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2128 2177 -0.330873 -4.92726 -6.44312 0.0557479 0.0309439 -0.0316142 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2128 2178 -0.185733 0.000377054 -6.26828 -0.00392962 0.0341168 0.000720324 0.99941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2128 2179 -0.350638 4.89817 -6.68737 -0.0513832 0.0333152 0.019867 0.997925 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2129 2178 -0.340417 -4.90792 -6.41091 0.0558298 0.025784 -0.0248816 0.997797 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2129 2179 -0.203257 0.00261235 -6.27892 -0.00698092 0.0386538 -0.00916486 0.999186 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2129 2180 -0.345023 4.90549 -6.6827 -0.0521639 0.0352333 0.0295292 0.99758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2130 2179 -0.335958 -4.89996 -6.43116 0.0550808 0.0306804 -0.0311045 0.997526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2130 2180 -0.199929 -0.00849688 -6.28651 -0.0127113 0.0325641 -0.00266495 0.999385 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2130 2181 -0.328259 4.87667 -6.66974 -0.0560498 0.0387823 0.0250345 0.99736 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2131 2180 -0.317291 -4.88567 -6.43391 0.0512106 0.029799 -0.0329652 0.997699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2131 2181 -0.196865 0.00713418 -6.27534 0.000349629 0.0281524 -0.00961412 0.999557 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2131 2182 -0.337999 4.86277 -6.69216 -0.0587415 0.0350927 0.0229722 0.997392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2132 2181 -0.333388 -4.87192 -6.43887 0.0629922 0.0337239 -0.0295561 0.997006 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2132 2182 -0.189512 -0.0114556 -6.28066 0.00393156 0.0250454 -0.00226163 0.999676 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2132 2183 -0.339468 4.85362 -6.68478 -0.0577442 0.0314258 0.0270124 0.997471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2133 2182 -0.330952 -4.86398 -6.40292 0.0581289 0.0233433 -0.01423 0.997935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2133 2183 -0.180416 0.00803614 -6.28866 0.00277003 0.0342386 0.00575061 0.999393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2133 2184 -0.343977 4.82429 -6.67889 -0.0609126 0.0302954 0.0306943 0.997211 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2134 2183 -0.330764 -4.85015 -6.40781 0.0656651 0.0326103 -0.0280754 0.996913 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2134 2184 -0.208404 8.9748e-05 -6.27195 0.00692405 0.0303944 0.00174761 0.999512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2134 2185 -0.347639 4.81818 -6.68924 -0.0582879 0.0210911 0.0209822 0.997856 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2135 2184 -0.321436 -4.83205 -6.43403 0.0537978 0.03656 -0.0296369 0.997442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2135 2185 -0.201502 0.00395253 -6.28907 -0.00773758 0.0414554 0.00254799 0.999107 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2135 2186 -0.343073 4.81968 -6.68694 -0.0618544 0.0404184 0.0241856 0.996973 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2136 2185 -0.309213 -4.81945 -6.42165 0.0584315 0.032982 -0.0178808 0.997586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2136 2186 -0.209708 -0.00644379 -6.2652 0.00382944 0.0206065 -0.00420381 0.999771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2136 2187 -0.363391 4.77825 -6.69586 -0.0529429 0.031998 0.0280761 0.99769 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2137 2186 -0.326945 -4.80679 -6.42862 0.0515927 0.0305178 -0.0147495 0.998093 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2137 2187 -0.197933 0.00682252 -6.26906 -0.00321641 0.0234874 0.00104547 0.999718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2137 2188 -0.341527 4.79516 -6.66454 -0.0622956 0.0422577 0.0314356 0.996667 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2138 2187 -0.317775 -4.7793 -6.42482 0.0520372 0.024408 -0.0261354 0.998005 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2138 2188 -0.203001 0.0124878 -6.28247 -0.00626038 0.0288171 -0.00528772 0.999551 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2138 2189 -0.318282 4.77358 -6.67087 -0.0651927 0.0297408 0.029648 0.996989 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2139 2188 -0.322564 -4.77751 -6.43538 0.0618766 0.045101 -0.0239738 0.996776 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2139 2189 -0.191102 0.0106008 -6.28772 -0.00174097 0.0355388 -0.000160613 0.999367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2139 2190 -0.32947 4.74632 -6.67308 -0.0599597 0.0383405 0.0263019 0.997117 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2140 2189 -0.333294 -4.74181 -6.4218 0.0566395 0.0313748 -0.0227007 0.997643 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2140 2190 -0.195757 -0.0117344 -6.28326 0.00618815 0.022237 0.00336578 0.999728 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2140 2191 -0.321084 4.72895 -6.65972 -0.0569895 0.021669 0.0311835 0.997652 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2141 2190 -0.329427 -4.72844 -6.43348 0.0539947 0.0372648 -0.0269976 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2141 2191 -0.211039 -0.00182018 -6.29022 0.00169455 0.0338796 0.0059766 0.999407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2141 2192 -0.322709 4.7198 -6.67806 -0.039539 0.0331476 0.0402119 0.997858 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2142 2191 -0.308062 -4.72553 -6.41367 0.0548949 0.0391537 -0.0258922 0.997388 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2142 2192 -0.191478 -0.0114848 -6.28323 -0.00142882 0.0330306 0.00874186 0.999415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2142 2193 -0.342948 4.69517 -6.66405 -0.0683391 0.0349931 0.0264337 0.996698 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2143 2192 -0.305754 -4.71709 -6.41713 0.0608097 0.0277415 -0.0375614 0.997057 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2143 2193 -0.199271 0.00190017 -6.25183 -0.0034996 0.0291147 -0.00304938 0.999565 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2143 2194 -0.338565 4.68022 -6.6631 -0.0638379 0.0314618 0.0202603 0.997258 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2144 2193 -0.315821 -4.69529 -6.41423 0.0633775 0.0303077 -0.0183307 0.997361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2144 2194 -0.196986 -0.000363092 -6.29059 -0.0074813 0.0291267 -0.0010764 0.999547 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2144 2195 -0.344234 4.66955 -6.68306 -0.0569654 0.0315096 0.0255349 0.997552 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2145 2194 -0.32068 -4.67197 -6.41043 0.0615264 0.0310039 -0.0254972 0.997298 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2145 2195 -0.191288 0.00673721 -6.27316 -0.00135773 0.033578 -0.00558808 0.99942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2145 2196 -0.330769 4.66659 -6.65866 -0.0535053 0.0379396 0.0321742 0.997328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2146 2195 -0.319477 -4.67755 -6.42226 0.0541015 0.0283074 -0.0270193 0.997768 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2146 2196 -0.177212 -0.0132551 -6.2849 0.0103077 0.0402253 0.00302796 0.999133 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2146 2197 -0.330805 4.63514 -6.65612 -0.0558372 0.0328429 0.023537 0.997622 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2147 2196 -0.307767 -4.6481 -6.43757 0.058157 0.0283674 -0.0247668 0.997597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2147 2197 -0.192988 -0.0176224 -6.26606 -0.00727512 0.0343376 0.000913874 0.999383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2147 2198 -0.319939 4.63251 -6.67598 -0.0515573 0.0276224 0.021399 0.998059 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2148 2197 -0.325375 -4.65951 -6.41399 0.0548279 0.0323781 -0.0268582 0.997609 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2148 2198 -0.185638 0.00684791 -6.28059 0.00649728 0.0366828 0.000932236 0.999305 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2148 2199 -0.315379 4.6048 -6.67115 -0.0629892 0.036094 0.0196731 0.997167 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2149 2198 -0.306471 -4.62727 -6.42977 0.0596279 0.0289249 -0.0329031 0.997259 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2149 2199 -0.186712 -0.00463497 -6.27613 -0.0030915 0.0382325 0.00359604 0.999258 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2149 2200 -0.324848 4.59615 -6.66943 -0.0641041 0.0369527 0.0397194 0.996468 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2150 2199 -0.295509 -4.61492 -6.40375 0.0644092 0.0238002 -0.0343214 0.997049 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2150 2200 -0.184501 -0.011846 -6.29466 0.00353579 0.0329507 0.0003403 0.999451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2150 2201 -0.326969 4.58578 -6.6639 -0.0581783 0.0298971 0.0254915 0.997533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2151 2200 -0.30291 -4.60026 -6.42287 0.0615898 0.0335362 -0.0306143 0.997068 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2151 2201 -0.186367 -0.0115194 -6.27164 -0.00042003 0.0257527 -0.000137238 0.999668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2151 2202 -0.347792 4.55673 -6.65712 -0.0513575 0.0355361 0.0299702 0.997598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2152 2201 -0.31163 -4.59818 -6.4238 0.0674783 0.0289973 -0.019485 0.997109 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2152 2202 -0.205809 -0.00443983 -6.283 -0.00108755 0.0290647 -0.00401099 0.999569 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2152 2203 -0.312073 4.55439 -6.64921 -0.0631817 0.0351586 0.0213173 0.997155 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2153 2202 -0.322272 -4.57898 -6.43119 0.053183 0.0355719 -0.02459 0.997648 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2153 2203 -0.190392 0.00570824 -6.28149 0.00815182 0.0356206 -0.00175176 0.999331 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2153 2204 -0.338689 4.54998 -6.66852 -0.0613121 0.0252741 0.0170029 0.997654 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2154 2203 -0.302103 -4.54255 -6.41966 0.0616784 0.0290594 -0.0288809 0.997255 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2154 2204 -0.20138 -0.011649 -6.29643 0.00485636 0.0235719 -0.000769385 0.99971 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2154 2205 -0.317573 4.53848 -6.68254 -0.0690454 0.0342862 0.0235494 0.996746 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2155 2204 -0.296702 -4.54208 -6.4059 0.0596687 0.0313742 -0.0262697 0.997379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2155 2205 -0.18597 -0.0100554 -6.29478 -0.00372108 0.0288844 -0.00549182 0.999561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2155 2206 -0.329655 4.51279 -6.65407 -0.0626657 0.0283623 0.0238121 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2156 2205 -0.316251 -4.53251 -6.41683 0.0601037 0.0337538 -0.0247762 0.997314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2156 2206 -0.214111 -0.00490237 -6.27095 0.00206725 0.0223973 0.00362669 0.99974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2156 2207 -0.316587 4.47084 -6.66489 -0.0555749 0.0410673 0.0149935 0.997497 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2157 2206 -0.308581 -4.51902 -6.4086 0.056622 0.0285378 -0.0194869 0.997797 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2157 2207 -0.220259 -0.00601506 -6.25965 0.00564725 0.0359824 -0.00113946 0.999336 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2157 2208 -0.315697 4.48701 -6.63603 -0.0584814 0.0333268 0.0214352 0.997502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2158 2207 -0.309421 -4.49794 -6.40247 0.0633815 0.0228032 -0.0224111 0.997477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2158 2208 -0.198684 0.00918769 -6.28023 -0.00310036 0.0329135 0.00324687 0.999448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2158 2209 -0.3314 4.45205 -6.64631 -0.0511963 0.0315903 0.0281109 0.997793 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2159 2208 -0.298907 -4.47966 -6.40879 0.0635265 0.0310702 -0.0297538 0.997053 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2159 2209 -0.19295 -0.00628952 -6.27493 0.00657294 0.0372188 -0.00100773 0.999285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2159 2210 -0.321849 4.45002 -6.66463 -0.0515486 0.021144 0.0276662 0.998063 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2160 2209 -0.309093 -4.4516 -6.39974 0.064946 0.0287663 -0.019829 0.997277 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2160 2210 -0.193074 0.0112298 -6.27012 -0.0118009 0.0330086 0.00284671 0.999381 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2160 2211 -0.319206 4.43478 -6.65756 -0.0530724 0.0270805 0.0140286 0.998125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2161 2210 -0.307748 -4.45543 -6.39798 0.0546083 0.0289872 -0.0305036 0.997621 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2161 2211 -0.215511 0.000399329 -6.28227 0.00404992 0.0318038 0.00204379 0.999484 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2161 2212 -0.31446 4.42464 -6.63677 -0.061968 0.0290459 0.0299678 0.997205 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2162 2211 -0.315784 -4.45906 -6.40416 0.0634492 0.0269256 -0.0225189 0.997368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2162 2212 -0.200367 -0.00756506 -6.26828 -0.00179583 0.0284695 -0.00588969 0.999576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2162 2213 -0.316978 4.42408 -6.66785 -0.0531996 0.0339078 0.0227527 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2163 2212 -0.284771 -4.43543 -6.41256 0.0532159 0.0327494 -0.0347864 0.997439 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2163 2213 -0.199699 0.0156685 -6.26261 -0.00895148 0.0290547 -0.00221989 0.999535 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2163 2214 -0.305531 4.38939 -6.65501 -0.056491 0.0293334 0.024298 0.997676 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2164 2213 -0.302036 -4.41021 -6.40901 0.0562891 0.0276467 -0.0189691 0.997851 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2164 2214 -0.194339 -0.0123559 -6.28655 0.00910441 0.0307301 -0.004905 0.999474 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2164 2215 -0.308177 4.37265 -6.65949 -0.0689676 0.032858 0.024981 0.996765 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2165 2214 -0.29512 -4.39437 -6.41658 0.0550897 0.039595 -0.0266532 0.99734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2165 2215 -0.195129 -0.00782645 -6.28243 0.00217606 0.028078 0.000142654 0.999603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2165 2216 -0.316652 4.3576 -6.66504 -0.0573511 0.0250501 0.0238065 0.997756 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2166 2215 -0.287981 -4.38126 -6.41449 0.0552417 0.0288829 -0.0216802 0.99782 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2166 2216 -0.185822 0.0179569 -6.27435 -0.0034394 0.0289144 0.0107497 0.999518 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2166 2217 -0.294382 4.36658 -6.65888 -0.0564189 0.0297008 0.0270423 0.997599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2167 2216 -0.298781 -4.35202 -6.42928 0.0612885 0.0183367 -0.0267989 0.997592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2167 2217 -0.177343 0.0188298 -6.27593 0.00111237 0.0322191 -0.010435 0.999426 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2167 2218 -0.334885 4.33311 -6.66397 -0.0587383 0.0231776 0.026721 0.997647 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2168 2217 -0.308357 -4.35744 -6.41256 0.0608036 0.0268138 -0.0169778 0.997645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2168 2218 -0.210669 0.0046153 -6.28641 -0.00362697 0.0302766 0.00764227 0.999506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2168 2219 -0.314423 4.30546 -6.6467 -0.0544289 0.0246986 0.024057 0.997922 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2169 2218 -0.291302 -4.31626 -6.39088 0.0582978 0.0252941 -0.0297402 0.997536 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2169 2219 -0.186352 0.000235968 -6.28589 -0.00317291 0.0228829 0.00191528 0.999731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2169 2220 -0.317887 4.29338 -6.64386 -0.0551477 0.0311886 0.0299297 0.997542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2170 2219 -0.287752 -4.32746 -6.40513 0.0552403 0.0315944 -0.0261997 0.997629 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2170 2220 -0.197233 -0.00410379 -6.28252 -0.00147228 0.035056 -0.0008401 0.999384 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2170 2221 -0.309493 4.29145 -6.65069 -0.0632174 0.0289912 0.020784 0.997362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2171 2220 -0.291282 -4.27877 -6.40881 0.067387 0.0292682 -0.00816771 0.997264 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2171 2221 -0.212541 0.0116373 -6.29565 0.00274456 0.0335108 -0.00252146 0.999431 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2171 2222 -0.312678 4.25773 -6.65076 -0.0600105 0.0387029 0.0284483 0.997041 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2172 2221 -0.292185 -4.28956 -6.39743 0.047975 0.0244199 -0.0141752 0.998449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2172 2222 -0.19648 -0.00412695 -6.29327 0.00367992 0.0296233 0.00239178 0.999551 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2172 2223 -0.31769 4.25334 -6.63284 -0.065372 0.0378681 0.0219462 0.996901 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2173 2222 -0.2969 -4.27127 -6.40045 0.0601589 0.037635 -0.0221053 0.997234 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2173 2223 -0.194119 -0.0161871 -6.27616 0.000267607 0.0245035 0.00188122 0.999698 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2173 2224 -0.305789 4.22629 -6.65694 -0.0618426 0.0359723 0.0227147 0.997179 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2174 2223 -0.300529 -4.27432 -6.40262 0.0612166 0.0263852 -0.0242518 0.997481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2174 2224 -0.202687 -0.0169847 -6.27854 -0.00384874 0.0271713 0.00725141 0.999597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2174 2225 -0.307375 4.22015 -6.6571 -0.0611747 0.0407769 0.0289393 0.996874 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2175 2224 -0.286272 -4.25344 -6.38161 0.0466835 0.0302917 -0.0202645 0.998245 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2175 2225 -0.19787 -0.0171454 -6.2627 -0.0033035 0.0221783 -0.00435839 0.999739 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2175 2226 -0.327533 4.20883 -6.6353 -0.06248 0.0416994 0.0284322 0.996769 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2176 2225 -0.285298 -4.22271 -6.39762 0.0666567 0.0261004 -0.029793 0.996989 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2176 2226 -0.204597 0.00185811 -6.28436 -0.000527677 0.034539 0.00139369 0.999402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2176 2227 -0.294988 4.20084 -6.6342 -0.0579866 0.0354796 0.0228695 0.997425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2177 2226 -0.29983 -4.21435 -6.40885 0.0642005 0.0274332 -0.0219751 0.997318 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2177 2227 -0.203758 -0.0146941 -6.27117 -0.0078087 0.0331842 -0.00116161 0.999418 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2177 2228 -0.323828 4.18531 -6.65541 -0.0647952 0.0353279 0.0214929 0.997041 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2178 2227 -0.309505 -4.2041 -6.40055 0.0583276 0.0341467 -0.0186742 0.997539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2178 2228 -0.209219 -0.00461041 -6.26959 0.000417581 0.0269448 0.000229635 0.999637 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2178 2229 -0.302453 4.16499 -6.64867 -0.0541308 0.0327963 0.0173115 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2179 2228 -0.269385 -4.17437 -6.40626 0.06046 0.0297721 -0.0272324 0.997355 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2179 2229 -0.196944 0.00767716 -6.28031 -0.00762572 0.0325966 -0.00832231 0.999405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2179 2230 -0.290017 4.1578 -6.63417 -0.061145 0.0324967 0.0341084 0.997016 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2180 2229 -0.296453 -4.18963 -6.40606 0.063306 0.0309787 -0.0278583 0.997124 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2180 2230 -0.208708 -0.00293038 -6.27344 -0.00123585 0.02984 -0.00788001 0.999523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2180 2231 -0.305709 4.15379 -6.6453 -0.0765606 0.030703 0.0197912 0.996396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2181 2230 -0.304417 -4.14143 -6.39585 0.0568831 0.040236 -0.0218075 0.997331 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2181 2231 -0.218584 0.0160645 -6.28295 0.00237945 0.0362228 -0.00629586 0.999321 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2181 2232 -0.306553 4.13989 -6.65309 -0.0600708 0.0405252 0.0295877 0.996932 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2182 2231 -0.290961 -4.1351 -6.40494 0.0606126 0.0287318 -0.0299956 0.997297 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2182 2232 -0.215591 -0.00923215 -6.2789 0.00296787 0.0344971 0.001608 0.999399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2182 2233 -0.304273 4.11262 -6.65015 -0.0664528 0.0429822 0.0220643 0.996619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2183 2232 -0.285815 -4.11905 -6.39407 0.0500725 0.0313489 -0.0281734 0.997856 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2183 2233 -0.180604 -0.0107143 -6.28456 0.00255665 0.0350722 0.00290911 0.999377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2183 2234 -0.311766 4.09897 -6.63238 -0.0622633 0.0352538 0.0284615 0.997031 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2184 2233 -0.289083 -4.11185 -6.39944 0.0606455 0.045415 -0.0322909 0.996603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2184 2234 -0.192847 0.00350161 -6.27487 -0.00620653 0.0406127 -0.00715501 0.99913 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2184 2235 -0.301595 4.08059 -6.63235 -0.0549149 0.0314175 0.0269182 0.997634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2185 2234 -0.291985 -4.08365 -6.39595 0.0571821 0.0282328 -0.0132458 0.997877 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2185 2235 -0.193812 -0.0131513 -6.28423 -0.000594389 0.0304552 0.00994614 0.999486 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2185 2236 -0.305174 4.04601 -6.64208 -0.0570117 0.0285838 0.022169 0.997718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2186 2235 -0.294137 -4.08739 -6.39304 0.0632472 0.0285076 -0.0251836 0.997273 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2186 2236 -0.224795 0.013868 -6.28669 0.00248834 0.0319292 -0.00769724 0.999457 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2186 2237 -0.313571 4.05888 -6.63521 -0.0608723 0.0411063 0.0221401 0.997053 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2187 2236 -0.292461 -4.06909 -6.3922 0.0573795 0.0334035 -0.0213183 0.997566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2187 2237 -0.183702 0.00408755 -6.27754 0.00185866 0.0260438 -0.000805077 0.999659 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2187 2238 -0.29921 4.04844 -6.64024 -0.0549878 0.0346484 0.0259101 0.997549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2188 2237 -0.283928 -4.06175 -6.39449 0.0638701 0.0322143 -0.0235749 0.99716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2188 2238 -0.212303 0.00993557 -6.28932 -0.00536146 0.0317489 0.00810385 0.999449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2188 2239 -0.307829 4.0193 -6.64506 -0.0510124 0.0259112 0.0289331 0.997942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2189 2238 -0.275587 -4.02474 -6.38025 0.0574561 0.0288806 -0.0119208 0.997859 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2189 2239 -0.198969 -0.0100291 -6.28833 -0.000637549 0.0351826 -0.00621704 0.999361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2189 2240 -0.314309 3.99813 -6.63945 -0.0553709 0.0287985 0.0152667 0.997934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2190 2239 -0.286444 -4.01169 -6.38501 0.0583015 0.0214694 -0.0212017 0.997843 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2190 2240 -0.202997 -0.00677373 -6.27709 0.0135749 0.0357364 -0.00603417 0.999251 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2190 2241 -0.277095 4.01077 -6.63905 -0.0597275 0.0318714 0.0325742 0.997174 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2191 2240 -0.287007 -4.00733 -6.38699 0.0607477 0.0266849 -0.0230363 0.99753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2191 2241 -0.181534 -0.00585408 -6.2861 -0.00749912 0.0299993 -0.000794583 0.999521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2191 2242 -0.310371 3.97928 -6.63553 -0.0546297 0.0347588 0.027981 0.997509 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2192 2241 -0.285996 -3.99226 -6.39073 0.056998 0.0280409 -0.0230475 0.997714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2192 2242 -0.196605 0.00283933 -6.28166 0.00437202 0.0369222 -0.00392028 0.999301 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2192 2243 -0.290995 3.94112 -6.63073 -0.0559387 0.041544 0.0149123 0.997458 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2193 2242 -0.27978 -3.99296 -6.37715 0.0585851 0.0307653 -0.0254735 0.997483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2193 2243 -0.189914 0.00239684 -6.26493 0.00356289 0.0225713 0.0124869 0.999661 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2193 2244 -0.293167 3.95201 -6.63109 -0.0527405 0.0365384 0.0212296 0.997714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2194 2243 -0.26986 -3.97012 -6.37897 0.06822 0.0314204 -0.0212281 0.996949 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2194 2244 -0.199764 -0.0167847 -6.29188 -0.00110941 0.026797 0.00281167 0.999636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2194 2245 -0.293793 3.91994 -6.64817 -0.0611489 0.0285323 0.0250365 0.997407 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2195 2244 -0.275783 -3.94823 -6.4088 0.0538204 0.0288947 -0.0309853 0.997651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2195 2245 -0.216631 0.010095 -6.29815 -0.00425137 0.0420118 0.00945699 0.999063 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2195 2246 -0.306634 3.91152 -6.65171 -0.0670188 0.0351183 0.0197077 0.996939 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2196 2245 -0.297411 -3.94958 -6.38886 0.0587803 0.0240723 -0.0118456 0.99791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2196 2246 -0.187745 0.0334912 -6.28391 -0.00147884 0.0382215 0.00265194 0.999265 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2196 2247 -0.284183 3.88175 -6.64509 -0.0629901 0.0385495 0.0209281 0.99705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2197 2246 -0.279124 -3.92171 -6.37069 0.0625335 0.0275023 -0.0283639 0.997261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2197 2247 -0.193881 -0.000266659 -6.26793 -0.00127131 0.0313591 0.000590943 0.999507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2197 2248 -0.293315 3.87995 -6.61821 -0.0494854 0.0260147 0.0242188 0.998142 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2198 2247 -0.291476 -3.89522 -6.3777 0.0520378 0.0290027 -0.0165565 0.998087 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2198 2248 -0.20274 0.00334139 -6.29872 0.00297058 0.033667 -0.000839714 0.999428 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2198 2249 -0.284218 3.88541 -6.63485 -0.0629004 0.028815 0.0166909 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2199 2248 -0.282798 -3.88155 -6.36512 0.0574201 0.0302189 -0.0182295 0.997726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2199 2249 -0.195995 0.0180568 -6.26305 0.00642437 0.0312853 -0.00162539 0.999489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2199 2250 -0.291438 3.85682 -6.6462 -0.0641072 0.0281372 0.0198387 0.997349 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2200 2249 -0.282947 -3.85596 -6.37493 0.0654509 0.0316501 -0.00651187 0.997332 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2200 2250 -0.196633 0.0113045 -6.28768 0.00334457 0.0284476 -0.00366861 0.999583 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2200 2251 -0.297189 3.8423 -6.62524 -0.0650253 0.0275558 0.015311 0.997386 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2201 2250 -0.27045 -3.86673 -6.38295 0.0623846 0.0307587 -0.0204414 0.997369 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2201 2251 -0.190676 0.00457109 -6.2909 -0.00401074 0.0311045 0.00220835 0.999506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2201 2252 -0.285281 3.83417 -6.64112 -0.0614431 0.0256047 0.0266251 0.997427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2202 2251 -0.27018 -3.84901 -6.36357 0.062506 0.0327237 -0.0179462 0.997347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2202 2252 -0.196321 0.00120516 -6.27777 -0.0059456 0.0350347 0.0058628 0.999351 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2202 2253 -0.284293 3.79794 -6.62585 -0.0647325 0.0348652 0.0208284 0.997076 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2203 2252 -0.28819 -3.82853 -6.36827 0.0518287 0.0407983 -0.0195497 0.997631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2203 2253 -0.197169 -0.00418006 -6.27433 0.000771852 0.0247473 0.00101949 0.999693 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2203 2254 -0.284766 3.79976 -6.64479 -0.0616687 0.034712 0.0220097 0.99725 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2204 2253 -0.28291 -3.81941 -6.38182 0.0624136 0.0448331 -0.0188361 0.996865 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2204 2254 -0.203128 0.00149295 -6.29877 0.00386633 0.0339932 -0.00446234 0.999405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2204 2255 -0.280489 3.77766 -6.62678 -0.0621904 0.0392106 0.00895536 0.997254 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2205 2254 -0.264856 -3.79149 -6.38794 0.0657034 0.0270823 -0.0294165 0.997038 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2205 2255 -0.186856 0.0209544 -6.25108 -0.00369234 0.0342352 0.00282325 0.999403 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2205 2256 -0.291501 3.7624 -6.63067 -0.0574184 0.0252614 0.0199701 0.997831 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2206 2255 -0.257655 -3.77907 -6.37738 0.0603092 0.0354405 -0.0200246 0.997349 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2206 2256 -0.192897 0.00314735 -6.28583 0.001081 0.0335025 -0.00266001 0.999435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2206 2257 -0.271767 3.75739 -6.62214 -0.058358 0.0337124 0.023108 0.997459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2207 2256 -0.285825 -3.76038 -6.38569 0.0624894 0.0214963 -0.0110163 0.997753 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2207 2257 -0.196543 0.0123151 -6.26659 0.00047634 0.0327773 0.00721057 0.999437 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2207 2258 -0.294126 3.725 -6.62057 -0.057388 0.0316364 0.0258425 0.997516 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2208 2257 -0.276106 -3.74435 -6.38198 0.0534408 0.0362503 -0.0132014 0.997825 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2208 2258 -0.189454 -0.009062 -6.28749 -0.00375266 0.0339963 -0.00875021 0.999377 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2208 2259 -0.284214 3.71412 -6.61979 -0.0708887 0.0381982 0.0203383 0.996545 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2209 2258 -0.278069 -3.7308 -6.36295 0.053741 0.0301516 -0.0264665 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2209 2259 -0.213585 -0.00291691 -6.27042 0.000109959 0.0341491 -0.00066907 0.999417 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2209 2260 -0.31221 3.69422 -6.63309 -0.0580651 0.0387396 0.0106655 0.997504 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2210 2259 -0.275818 -3.73909 -6.38239 0.0537375 0.0305354 -0.0179172 0.997927 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2210 2260 -0.209124 -0.010525 -6.27917 0.00524393 0.0381286 -0.0025505 0.999256 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2210 2261 -0.296964 3.70105 -6.62737 -0.055313 0.0189092 0.0291298 0.997865 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2211 2260 -0.275599 -3.69007 -6.37067 0.0658065 0.0271351 -0.0260819 0.997122 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2211 2261 -0.180368 0.00131632 -6.2787 -0.00010594 0.0339915 0.00343161 0.999416 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2211 2262 -0.274382 3.67732 -6.62983 -0.0616692 0.0282035 0.0167448 0.997558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2212 2261 -0.288603 -3.68877 -6.40475 0.058139 0.0309686 -0.0107138 0.997771 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2212 2262 -0.189909 0.0133653 -6.29398 0.00229627 0.0390782 -0.00362486 0.999227 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2212 2263 -0.298871 3.6589 -6.64768 -0.057269 0.0306336 0.0240388 0.997599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2213 2262 -0.261759 -3.67424 -6.39005 0.0507182 0.0248714 -0.0241686 0.998111 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2213 2263 -0.205725 -0.0207415 -6.28033 0.00350143 0.0290046 0.00709083 0.999548 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2213 2264 -0.275864 3.64902 -6.62189 -0.0593139 0.0303453 0.0196942 0.997584 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2214 2263 -0.278097 -3.68028 -6.36497 0.0619272 0.0305301 -0.0245149 0.997312 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2214 2264 -0.207696 -0.0163564 -6.28482 -0.00453781 0.0280244 0.0048122 0.999585 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2214 2265 -0.287047 3.62695 -6.61705 -0.0554192 0.0363009 0.0209307 0.997584 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2215 2264 -0.283709 -3.64194 -6.37221 0.0573506 0.021466 -0.0219141 0.997883 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2215 2265 -0.190109 0.0078239 -6.2644 0.00265914 0.0334921 -0.00635098 0.999415 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2215 2266 -0.27259 3.6093 -6.59897 -0.0587205 0.0350763 0.0143187 0.997555 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2216 2265 -0.278945 -3.62922 -6.35366 0.0654304 0.0291124 -0.0173086 0.997282 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2216 2266 -0.199159 0.000931982 -6.27583 0.00278785 0.027014 -0.000126336 0.999631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2216 2267 -0.273986 3.61375 -6.60577 -0.0613485 0.0339103 0.0241246 0.997248 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2217 2266 -0.263272 -3.60871 -6.37872 0.0639678 0.0291038 -0.0234229 0.997252 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2217 2267 -0.203368 0.005128 -6.26895 0.00318137 0.0340051 -0.00474666 0.999405 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2217 2268 -0.273751 3.58591 -6.61962 -0.0640049 0.0290783 0.0255154 0.997199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2218 2267 -0.2675 -3.60179 -6.36722 0.056242 0.0347892 -0.0221057 0.997566 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2218 2268 -0.196228 0.00176313 -6.29282 0.00146374 0.0366331 -0.00705656 0.999303 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2218 2269 -0.292636 3.5708 -6.61324 -0.0652398 0.0286878 0.0166022 0.997319 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2219 2268 -0.291267 -3.58378 -6.35686 0.0596894 0.0392866 -0.0229073 0.997181 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2219 2269 -0.200442 -0.00951079 -6.27657 0.00501917 0.0280134 -0.00389942 0.999587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2219 2270 -0.281244 3.55217 -6.60903 -0.0671854 0.0343943 0.0293835 0.996714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2220 2269 -0.262888 -3.58529 -6.36812 0.0558481 0.0349358 -0.0267024 0.997471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2220 2270 -0.192366 -0.015081 -6.27975 0.00623672 0.0262725 -0.00189603 0.999634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2220 2271 -0.273229 3.53086 -6.61408 -0.0610093 0.0360528 0.0154848 0.997366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2221 2270 -0.29264 -3.56774 -6.37453 0.0583448 0.0232382 -0.0277759 0.997639 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2221 2271 -0.206731 0.000717785 -6.27841 -0.0110138 0.0323186 -0.0110028 0.999356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2221 2272 -0.281837 3.52787 -6.61882 -0.0561102 0.0421036 0.0188778 0.997358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2222 2271 -0.274945 -3.54091 -6.37076 0.0662286 0.0377532 -0.0190369 0.996908 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2222 2272 -0.195926 -0.00705802 -6.2834 7.70724e-05 0.0319434 0.000493336 0.99949 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2222 2273 -0.295295 3.52373 -6.59504 -0.0603943 0.037551 0.0398017 0.996674 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2223 2272 -0.277287 -3.52469 -6.38572 0.0693074 0.0277309 -0.014227 0.997108 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2223 2273 -0.182084 -0.0124529 -6.27867 0.006928 0.0302511 0.00456019 0.999508 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2223 2274 -0.283778 3.48418 -6.61016 -0.0588403 0.0259994 0.0226746 0.997671 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2224 2273 -0.263814 -3.53089 -6.35558 0.0581697 0.0351091 -0.0146187 0.997582 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2224 2274 -0.203037 -0.000442014 -6.27205 -0.00395209 0.0314945 -0.000776631 0.999496 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2224 2275 -0.284279 3.49389 -6.61132 -0.0690272 0.034319 0.0208413 0.996806 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2225 2274 -0.256854 -3.48441 -6.37558 0.0705395 0.0265467 -0.0202395 0.99695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2225 2275 -0.184573 0.0137054 -6.26915 0.00485798 0.0335442 0.00499161 0.999413 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2225 2276 -0.308185 3.46632 -6.62602 -0.0551737 0.042052 0.0198812 0.997393 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2226 2275 -0.263508 -3.49927 -6.36376 0.0531444 0.0418012 -0.019874 0.997514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2226 2276 -0.201059 0.00421048 -6.29586 0.0064374 0.0392645 0.00112353 0.999207 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2226 2277 -0.280182 3.45333 -6.59872 -0.0585118 0.0329517 0.0255952 0.997414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2227 2276 -0.261001 -3.46905 -6.34816 0.0641097 0.0343346 -0.025436 0.997028 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2227 2277 -0.202672 -0.00337204 -6.28051 -0.00238231 0.0241532 -0.00935046 0.999662 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2227 2278 -0.283234 3.43477 -6.60594 -0.0585557 0.0355351 0.0114679 0.997586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2228 2277 -0.249344 -3.45036 -6.37382 0.0585832 0.0268213 -0.019472 0.997732 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2228 2278 -0.190696 -0.00890618 -6.26982 -0.00033972 0.0300692 0.00409688 0.999539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2228 2279 -0.283418 3.41124 -6.61428 -0.0608506 0.0340025 0.0216335 0.997333 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2229 2278 -0.269317 -3.436 -6.36973 0.0622678 0.0310143 -0.0176399 0.997422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2229 2279 -0.192395 -0.00590801 -6.28051 -0.000688182 0.0282567 -0.00183355 0.999599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2229 2280 -0.289154 3.41401 -6.6078 -0.0651123 0.0360405 0.026293 0.99688 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2230 2279 -0.247557 -3.41206 -6.33793 0.0640752 0.0264531 -0.0206107 0.997381 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2230 2280 -0.209983 0.000310539 -6.28942 0.00216277 0.0314529 -0.00187451 0.999501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2230 2281 -0.282882 3.39625 -6.60106 -0.0533849 0.0400146 0.0116017 0.997705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2231 2280 -0.271752 -3.38707 -6.35816 0.0643433 0.0305508 -0.018737 0.997284 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2231 2281 -0.204165 -0.0134937 -6.26635 0.00603382 0.0403253 -0.00121567 0.999168 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2231 2282 -0.274625 3.36906 -6.60973 -0.0545957 0.0324497 0.0193883 0.997793 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2232 2281 -0.254368 -3.38205 -6.33858 0.065919 0.0273607 -0.00681081 0.997427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2232 2282 -0.189662 0.0056612 -6.26169 0.00770125 0.0309001 0.000334812 0.999493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2232 2283 -0.263705 3.3606 -6.60983 -0.0581681 0.0380004 0.0190911 0.997401 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2233 2282 -0.253579 -3.38987 -6.36959 0.060561 0.0323112 -0.015463 0.997522 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2233 2283 -0.199486 -0.00648332 -6.2989 -0.00788767 0.0371663 -0.000741738 0.999278 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2233 2284 -0.278197 3.36186 -6.61113 -0.0575903 0.0317544 0.0105366 0.99778 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2234 2283 -0.273006 -3.36916 -6.33957 0.0565121 0.0347476 -0.0125761 0.997718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2234 2284 -0.20365 0.000230943 -6.25444 0.0007726 0.0341021 0.00191646 0.999416 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2234 2285 -0.272875 3.32629 -6.58812 -0.0613353 0.0364158 0.0210381 0.997231 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2235 2284 -0.254401 -3.35801 -6.36418 0.0592049 0.0326583 -0.0121459 0.997638 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2235 2285 -0.201036 0.0159428 -6.26848 0.00366852 0.0321329 0.000346941 0.999477 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2235 2286 -0.257426 3.3128 -6.6041 -0.0579435 0.0321212 0.0224823 0.99755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2236 2285 -0.262449 -3.30931 -6.34789 0.0585262 0.0348856 -0.0176746 0.99752 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2236 2286 -0.19066 0.00793086 -6.279 -0.00745419 0.0263128 -7.53118e-05 0.999626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2236 2287 -0.28494 3.3154 -6.60447 -0.0664794 0.0397225 0.0225643 0.996741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2237 2286 -0.254637 -3.32984 -6.35458 0.0527866 0.0341816 -0.0172383 0.997872 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2237 2287 -0.203581 0.00918446 -6.27251 -0.00476596 0.0324296 -0.00467372 0.999452 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2237 2288 -0.276224 3.29047 -6.60526 -0.0586999 0.0246012 0.0211913 0.997747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2238 2287 -0.254684 -3.29963 -6.3637 0.0585424 0.0294884 -0.0225934 0.997593 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2238 2288 -0.188013 -0.00537581 -6.28369 -0.00321972 0.0338075 0.0117863 0.999354 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2238 2289 -0.276903 3.2797 -6.59306 -0.0588703 0.0297612 0.0138222 0.997726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2239 2288 -0.254672 -3.28037 -6.35662 0.0628617 0.0236372 -0.0118857 0.997672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2239 2289 -0.194064 -0.00989881 -6.27331 -0.000506494 0.0321675 0.00361347 0.999476 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2239 2290 -0.280881 3.23688 -6.6102 -0.0696338 0.031279 0.0144864 0.996977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2240 2289 -0.240749 -3.27771 -6.34842 0.0538543 0.0330989 -0.0141711 0.997899 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2240 2290 -0.19196 0.0083905 -6.27741 0.000567659 0.0260632 0.00237034 0.999657 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2240 2291 -0.267119 3.2354 -6.59036 -0.0588836 0.0347359 0.0206766 0.997446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2241 2290 -0.273385 -3.25878 -6.34883 0.0663385 0.0341151 -0.0128428 0.997131 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2241 2291 -0.202565 0.000103478 -6.29854 -0.00482885 0.0266009 -0.00151193 0.999633 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2241 2292 -0.281779 3.21193 -6.61215 -0.0561973 0.0313373 0.0257979 0.997594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2242 2291 -0.260083 -3.23887 -6.34945 0.0597452 0.0260206 -0.0174402 0.997722 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2242 2292 -0.190453 0.000404572 -6.26768 0.00706565 0.0306475 0.00478964 0.999494 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2242 2293 -0.26215 3.22115 -6.59841 -0.0580325 0.0245392 0.0275266 0.997633 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2243 2292 -0.234132 -3.22757 -6.35213 0.0526515 0.0301675 -0.0195524 0.997966 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2243 2293 -0.178057 -0.0015998 -6.28363 0.00333651 0.0315016 0.00809612 0.999465 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2243 2294 -0.270145 3.1989 -6.59438 -0.0574935 0.0275249 0.0172637 0.997817 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2244 2293 -0.261372 -3.2066 -6.33796 0.0642621 0.0305866 -0.0261084 0.997122 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2244 2294 -0.199961 0.00421875 -6.28593 -0.00861461 0.0300493 -0.0102663 0.999459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2244 2295 -0.280036 3.17153 -6.59923 -0.065001 0.0286553 0.0263086 0.997127 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2245 2294 -0.258398 -3.183 -6.32845 0.0598184 0.0308327 -0.0235184 0.997456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2245 2295 -0.18542 0.0128077 -6.26464 -0.00256755 0.0362891 -0.00162455 0.999337 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2245 2296 -0.258988 3.16263 -6.58308 -0.066281 0.0319327 0.0225699 0.997034 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2246 2295 -0.235532 -3.17709 -6.33661 0.0583851 0.0300201 -0.0160403 0.997714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2246 2296 -0.193485 0.00449374 -6.26752 0.00107987 0.0309368 -0.0047074 0.99951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2246 2297 -0.264265 3.15846 -6.59708 -0.0555754 0.0361724 0.0137595 0.997704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2247 2296 -0.250459 -3.16936 -6.32877 0.0576665 0.0371309 -0.0114404 0.99758 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2247 2297 -0.20163 0.0128831 -6.26767 0.00716604 0.0301153 -0.00354191 0.999514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2247 2298 -0.262263 3.12968 -6.5866 -0.0625355 0.0402205 0.0186522 0.997058 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2248 2297 -0.278581 -3.14959 -6.3274 0.0545557 0.0292607 -0.0198231 0.997885 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2248 2298 -0.186218 -0.00694843 -6.25766 0.00364693 0.0322067 0.0028597 0.99947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2248 2299 -0.273205 3.10899 -6.60557 -0.058326 0.0305603 0.0184471 0.997659 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2249 2298 -0.248558 -3.14443 -6.33487 0.0623832 0.0235985 -0.0236774 0.997492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2249 2299 -0.186856 0.00674787 -6.27821 0.00529843 0.0296187 -0.00395567 0.999539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2249 2300 -0.278022 3.08909 -6.59868 -0.0637812 0.0305024 0.0193805 0.997309 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2250 2299 -0.257034 -3.09648 -6.34313 0.0643548 0.0305054 -0.0244867 0.99716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2250 2300 -0.177724 0.00728265 -6.27706 0.00329296 0.0384941 -0.00158549 0.999252 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2250 2301 -0.270295 3.0894 -6.56846 -0.0537637 0.035325 0.00573551 0.997912 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2251 2300 -0.239286 -3.09837 -6.34351 0.060073 0.0233171 -0.01588 0.997795 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2251 2301 -0.198668 -0.0179597 -6.29635 0.00517469 0.0256313 -0.00498743 0.999646 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2251 2302 -0.25352 3.07186 -6.59407 -0.0633755 0.0256895 0.0155363 0.997538 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2252 2301 -0.239886 -3.08243 -6.34937 0.0605732 0.0293885 -0.015794 0.997606 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2252 2302 -0.188165 0.000381572 -6.29523 -0.00670823 0.0335547 -0.00112473 0.999414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2252 2303 -0.257741 3.05806 -6.5766 -0.0518449 0.0310116 0.017461 0.998021 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2253 2302 -0.267865 -3.0829 -6.33405 0.0572204 0.0277251 -0.0168376 0.997834 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2253 2303 -0.197244 0.0079782 -6.28995 -0.00558523 0.0320732 -0.00447919 0.99946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2253 2304 -0.247545 3.02377 -6.58155 -0.0590671 0.0297446 0.0109803 0.99775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2254 2303 -0.262106 -3.05055 -6.33426 0.0641209 0.0266615 -0.0236317 0.997306 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2254 2304 -0.191855 0.0127995 -6.27325 0.0109221 0.0321709 -0.00332082 0.999417 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2254 2305 -0.268126 3.01597 -6.58079 -0.0603928 0.0395421 0.0195835 0.997199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2255 2304 -0.239408 -3.04334 -6.33457 0.0617012 0.0311278 -0.013994 0.997511 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2255 2305 -0.198591 -0.00632964 -6.27254 -0.00639324 0.0349478 -0.00330252 0.999363 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2255 2306 -0.254438 3.01132 -6.57517 -0.0518882 0.0355682 0.0144536 0.997915 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2256 2305 -0.256245 -3.03903 -6.34254 0.0537296 0.0311931 -0.0214775 0.997837 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2256 2306 -0.195332 -0.00859389 -6.26912 0.0049153 0.0290023 0.00606054 0.999549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2256 2307 -0.260667 2.9726 -6.58296 -0.0647665 0.0323698 0.0140994 0.997276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2257 2306 -0.252133 -3.02397 -6.33724 0.0575974 0.0295903 -0.0177844 0.997743 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2257 2307 -0.193163 -0.00931415 -6.27461 0.00362539 0.0379491 0.0127625 0.999192 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2257 2308 -0.254416 2.97155 -6.58294 -0.0601598 0.0282001 0.0108992 0.997731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2258 2307 -0.244844 -2.99467 -6.30231 0.0576365 0.026452 -0.0197511 0.997792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2258 2308 -0.196166 -0.00458555 -6.26627 -0.00028757 0.0255366 -0.0013075 0.999673 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2258 2309 -0.268335 2.97263 -6.58785 -0.0546428 0.0311218 0.0135874 0.997928 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2259 2308 -0.244447 -2.97776 -6.35944 0.0570728 0.0223012 -0.0156332 0.997998 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2259 2309 -0.192807 0.0106901 -6.27653 0.00462605 0.0276934 -0.00407248 0.999597 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2259 2310 -0.254751 2.94719 -6.57761 -0.0676698 0.0322245 0.0167684 0.997046 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2260 2309 -0.239942 -2.96773 -6.34418 0.0625155 0.0216361 -0.00847293 0.997773 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2260 2310 -0.189001 -0.0048491 -6.28236 -0.00646134 0.0326006 0.000291558 0.999448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2260 2311 -0.259722 2.91782 -6.57573 -0.0562236 0.0318142 0.0116955 0.997843 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2261 2310 -0.239784 -2.94345 -6.31562 0.0458165 0.0405564 -0.0185489 0.997954 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2261 2311 -0.206587 -0.00446894 -6.27585 -0.000693906 0.0391937 0.00336419 0.999226 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2261 2312 -0.245914 2.93012 -6.56698 -0.0664618 0.0234228 0.0108558 0.997455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2262 2311 -0.241517 -2.94025 -6.31811 0.0667986 0.0302859 -0.0193004 0.99712 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2262 2312 -0.191433 0.0097406 -6.27577 -0.00130367 0.0353736 -0.000432872 0.999373 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2262 2313 -0.267929 2.89728 -6.58683 -0.0623746 0.0375499 0.0197539 0.997151 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2263 2312 -0.238279 -2.93045 -6.33601 0.0489091 0.0388459 -0.0199872 0.997847 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2263 2313 -0.208761 -0.00612295 -6.28793 -0.000740143 0.0265566 0.0152524 0.999531 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2263 2314 -0.248416 2.91999 -6.59424 -0.0599605 0.036316 0.0133663 0.99745 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2264 2313 -0.224152 -2.92099 -6.33314 0.0604852 0.0284628 -0.00525573 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2264 2314 -0.199137 -0.000128815 -6.28188 0.01695 0.0340824 0.00139411 0.999274 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2264 2315 -0.268726 2.88368 -6.57253 -0.062927 0.0282778 0.0231413 0.997349 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2265 2314 -0.234149 -2.89932 -6.32635 0.0644709 0.0394214 -0.0202368 0.996935 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2265 2315 -0.190694 -0.0116098 -6.27141 0.00815114 0.0394232 0.00214823 0.999187 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2265 2316 -0.243654 2.84991 -6.60301 -0.0655929 0.031799 0.00890805 0.9973 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2266 2315 -0.25744 -2.87095 -6.32834 0.0580828 0.0286045 -0.0133301 0.997813 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2266 2316 -0.191486 -0.00667498 -6.28347 0.00483852 0.0314694 -0.00486529 0.999481 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2266 2317 -0.254107 2.85345 -6.55493 -0.0579261 0.030539 0.020916 0.997634 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2267 2316 -0.242487 -2.85774 -6.33655 0.0535093 0.0277574 -0.0174285 0.998029 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2267 2317 -0.205043 0.00986201 -6.2907 -0.00504286 0.0338895 0.00139118 0.999412 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2267 2318 -0.262347 2.82423 -6.59312 -0.0631623 0.0305721 0.0242476 0.99724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2268 2317 -0.252686 -2.86035 -6.31871 0.0639315 0.0238194 -0.0207513 0.997454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2268 2318 -0.203773 -0.00612936 -6.28224 0.00177596 0.028756 0.00412538 0.999576 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2268 2319 -0.247265 2.81359 -6.55255 -0.06272 0.0282952 0.0219948 0.997387 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2269 2318 -0.267928 -2.81869 -6.32557 0.0575743 0.0257966 -0.018546 0.997836 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2269 2319 -0.184282 0.0038751 -6.28665 0.00596004 0.0373764 -0.00115734 0.999283 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2269 2320 -0.258272 2.78048 -6.58823 -0.0510734 0.0273344 0.0113816 0.998256 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2270 2319 -0.243468 -2.80938 -6.31534 0.056968 0.0279336 -0.0125204 0.997907 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2270 2320 -0.197198 -0.00194319 -6.27112 -0.00629681 0.037877 0.000310048 0.999263 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2270 2321 -0.250232 2.79847 -6.56957 -0.0635174 0.040277 0.0226809 0.99691 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2271 2320 -0.252198 -2.79701 -6.34697 0.0621494 0.0280021 -0.018501 0.997502 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2271 2321 -0.210684 -0.00959831 -6.28827 0.000974711 0.0325634 8.05404e-05 0.999469 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2271 2322 -0.263763 2.76119 -6.58889 -0.0661031 0.0309787 0.0265908 0.996977 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2272 2321 -0.246202 -2.77124 -6.31985 0.066275 0.0376989 -0.0206755 0.996875 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2272 2322 -0.1956 -0.00587864 -6.27288 0.0020858 0.029701 -0.0096148 0.99951 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2272 2323 -0.252748 2.73452 -6.57217 -0.0635712 0.0309851 0.0183918 0.997327 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2273 2322 -0.249033 -2.75018 -6.30565 0.0706576 0.0308858 -0.0182915 0.996855 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2273 2323 -0.213437 0.0149824 -6.28094 -0.0110642 0.0311874 -0.000657331 0.999452 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2273 2324 -0.285156 2.7399 -6.57364 -0.0631225 0.0271361 0.0185938 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2274 2323 -0.23508 -2.74921 -6.32353 0.0691308 0.0240686 -0.019571 0.997125 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2274 2324 -0.190174 0.0108054 -6.28126 0.00732346 0.0287946 -0.00124998 0.999558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2274 2325 -0.242969 2.70443 -6.56514 -0.064208 0.0320203 0.0184513 0.997252 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2275 2324 -0.220471 -2.73687 -6.33603 0.0598949 0.0300119 -0.0197592 0.997558 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2275 2325 -0.207017 -0.00616816 -6.30344 0.0080104 0.0276182 0.000603034 0.999586 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2275 2326 -0.261557 2.7128 -6.57542 -0.0558446 0.0328793 0.0123375 0.997822 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2276 2325 -0.235236 -2.72048 -6.30216 0.0492938 0.0305574 -0.0153577 0.998199 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2276 2326 -0.210461 -0.00299969 -6.27386 0.000277896 0.0343118 0.0018053 0.99941 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2276 2327 -0.245628 2.67837 -6.56261 -0.0605501 0.0334548 0.0210379 0.997383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2277 2326 -0.24725 -2.68846 -6.30867 0.066382 0.0244632 -0.0132464 0.997406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2277 2327 -0.206356 -0.00214303 -6.26408 0.00290632 0.0369281 -0.000106411 0.999314 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2277 2328 -0.287265 2.67641 -6.56057 -0.0647457 0.0364331 0.0162192 0.997105 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2278 2327 -0.221392 -2.6803 -6.32516 0.057085 0.0279753 -0.0172089 0.997829 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2278 2328 -0.191897 0.000827564 -6.26426 0.00856676 0.0339174 0.0038881 0.99938 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2278 2329 -0.264078 2.67842 -6.56969 -0.0676046 0.0274664 0.0148106 0.997224 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2279 2328 -0.232759 -2.67484 -6.314 0.0518925 0.0319504 -0.0138675 0.998045 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2279 2329 -0.201857 0.020167 -6.2878 0.00456279 0.0402093 0.0034374 0.999175 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2279 2330 -0.248761 2.65048 -6.55131 -0.0605351 0.0371955 0.0124803 0.997395 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2280 2329 -0.221041 -2.66675 -6.31267 0.0621833 0.0255811 -0.0160396 0.997608 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2280 2330 -0.202128 0.00207673 -6.29788 -0.00265523 0.0308772 0.00396419 0.999512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2280 2331 -0.242066 2.61417 -6.56255 -0.0513866 0.0332442 0.00989525 0.998076 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2281 2330 -0.249015 -2.6578 -6.30198 0.0553567 0.0339686 -0.00774364 0.997859 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2281 2331 -0.187714 -0.00763207 -6.27992 0.00116643 0.0353978 0.00393608 0.999365 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2281 2332 -0.237621 2.62156 -6.56291 -0.0735918 0.0292576 0.0193007 0.996672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2282 2331 -0.252547 -2.62347 -6.3156 0.0591454 0.0373193 -0.00940847 0.997507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2282 2332 -0.197724 -0.00519878 -6.26289 -0.00401551 0.0324113 -0.0030936 0.999462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2282 2333 -0.226732 2.6147 -6.56675 -0.0594508 0.0273585 0.0183424 0.997688 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2283 2332 -0.241244 -2.60362 -6.30713 0.0597697 0.0299571 -0.00857423 0.997726 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2283 2333 -0.184198 -0.0106233 -6.27978 -0.00571417 0.0441746 0.00194213 0.999006 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2283 2334 -0.249608 2.58344 -6.5777 -0.0611538 0.0359327 0.016892 0.997338 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2284 2333 -0.250546 -2.60317 -6.30351 0.0600942 0.0284391 -0.00699481 0.997763 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2284 2334 -0.21173 -0.0129531 -6.28235 -0.00242841 0.037286 0.00169421 0.9993 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2284 2335 -0.25276 2.56082 -6.56341 -0.0748416 0.0229863 0.0121805 0.996856 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2285 2334 -0.243863 -2.58137 -6.32157 0.0641862 0.0255582 -0.0195723 0.997419 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2285 2335 -0.197933 0.0110159 -6.29221 -0.00525231 0.030242 -0.00258263 0.999525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2285 2336 -0.245261 2.54293 -6.54838 -0.0663082 0.0298924 0.0157878 0.997226 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2286 2335 -0.221562 -2.57834 -6.29981 0.0515532 0.0303534 -0.0160513 0.99808 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2286 2336 -0.200991 0.0041199 -6.25769 0.00352358 0.0372062 0.00314109 0.999296 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2286 2337 -0.247205 2.53737 -6.54441 -0.0579038 0.0293283 0.0164508 0.997756 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2287 2336 -0.221777 -2.5335 -6.2972 0.0556034 0.0374211 -0.0221732 0.997505 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2287 2337 -0.205915 -0.00715451 -6.28933 0.00517899 0.0274683 -0.00280091 0.999605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2287 2338 -0.247829 2.52735 -6.54986 -0.0599797 0.0293298 0.00792904 0.997737 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2288 2337 -0.234224 -2.52441 -6.29786 0.064124 0.0284662 -0.0122269 0.997461 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2288 2338 -0.210368 0.0157296 -6.28614 0.00840188 0.0255743 0.00802337 0.999605 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2288 2339 -0.256656 2.50318 -6.53777 -0.0571588 0.032358 0.0236031 0.997561 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2289 2338 -0.23878 -2.51562 -6.30459 0.0503902 0.0192603 -0.0247667 0.998237 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2289 2339 -0.205403 -0.0110022 -6.27096 0.00439089 0.040268 0.00260699 0.999176 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2289 2340 -0.241842 2.49255 -6.5491 -0.0561105 0.04023 0.00694748 0.99759 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2290 2339 -0.217501 -2.50417 -6.29017 0.0566901 0.0270278 -0.0190359 0.997844 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2290 2340 -0.207464 0.00624828 -6.28474 0.00324046 0.0158711 -0.0023081 0.999866 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2290 2341 -0.243671 2.45051 -6.56314 -0.0665435 0.0306417 0.00388658 0.997305 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2291 2340 -0.218773 -2.49338 -6.30611 0.0589802 0.0323317 -0.00302463 0.997731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2291 2341 -0.191151 -0.0129776 -6.27339 0.00129804 0.0344741 -0.00474135 0.999394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2291 2342 -0.255656 2.45927 -6.5424 -0.0700854 0.0377843 0.0235179 0.996548 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2292 2341 -0.221782 -2.47917 -6.28134 0.0609509 0.0370087 -0.0132895 0.997366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2292 2342 -0.193952 0.000114747 -6.27648 0.00315509 0.028883 0.00385563 0.99957 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2292 2343 -0.255521 2.44398 -6.57725 -0.0547833 0.0272797 0.0199289 0.997927 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2293 2342 -0.254936 -2.45752 -6.30639 0.055778 0.0244154 -0.0109005 0.998085 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2293 2343 -0.187166 -0.0153438 -6.27225 0.00125005 0.0340155 -0.00304848 0.999416 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2293 2344 -0.223706 2.41924 -6.55008 -0.0586349 0.0347182 0.0143784 0.997572 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2294 2343 -0.236651 -2.4326 -6.29713 0.0668415 0.0304718 -0.0131243 0.997212 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2294 2344 -0.200436 0.00749689 -6.28886 0.00693458 0.0283947 -0.0106952 0.999516 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2294 2345 -0.237583 2.41666 -6.54685 -0.0652979 0.0195668 0.0093379 0.99763 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2295 2344 -0.222404 -2.42222 -6.30446 0.0646557 0.0307351 -0.0177454 0.997276 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2295 2345 -0.199433 -0.00555486 -6.26591 0.00189218 0.0314148 0.0083628 0.99947 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2295 2346 -0.243906 2.39691 -6.53521 -0.0574564 0.0309913 0.0186088 0.997693 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2296 2345 -0.21663 -2.40339 -6.28144 0.0589891 0.0292721 -0.00640153 0.997809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2296 2346 -0.190412 -0.0136655 -6.27239 -0.00153097 0.0255656 0.00597776 0.999654 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2296 2347 -0.267818 2.37478 -6.55914 -0.0650517 0.0386987 0.0147515 0.997022 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2297 2346 -0.233711 -2.39182 -6.31698 0.0678978 0.024628 -0.0241332 0.997096 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2297 2347 -0.193429 0.00420732 -6.27883 0.00365977 0.0348679 0.00579237 0.999368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2297 2348 -0.220643 2.3793 -6.55234 -0.0606805 0.0259657 0.0136149 0.997727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2298 2347 -0.227866 -2.37416 -6.30919 0.0631995 0.0403068 -0.0113503 0.997122 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2298 2348 -0.20426 0.00155378 -6.27978 -0.0121473 0.0351436 -0.00170304 0.999307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2298 2349 -0.240025 2.33724 -6.55257 -0.0597632 0.0375919 0.0180879 0.99734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2299 2348 -0.205878 -2.33866 -6.28674 0.063827 0.0269875 -0.0137674 0.997501 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2299 2349 -0.198131 -0.0131879 -6.27288 -0.00192726 0.0283845 0.00241332 0.999592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2299 2350 -0.251349 2.32874 -6.55755 -0.0696843 0.0264904 0.0127058 0.997136 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2300 2349 -0.218862 -2.34056 -6.29491 0.0644335 0.0322499 -0.00809965 0.997368 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2300 2350 -0.190343 0.0159002 -6.27784 -0.00869822 0.0254126 -0.0011313 0.999639 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2300 2351 -0.237466 2.30762 -6.54216 -0.0538004 0.0395231 0.00759378 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2301 2350 -0.225939 -2.32738 -6.29666 0.0640258 0.0294274 -0.0111439 0.997452 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2301 2351 -0.195536 -0.00742077 -6.258 0.00331972 0.0279981 -0.000770903 0.999602 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2301 2352 -0.229987 2.29708 -6.54033 -0.0637905 0.0322008 0.00846861 0.997408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2302 2351 -0.229951 -2.30605 -6.30889 0.0676953 0.0259838 -0.00919558 0.997325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2302 2352 -0.21367 -0.00776797 -6.27804 -0.00817787 0.0279595 -0.00774447 0.999546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2302 2353 -0.229971 2.2891 -6.53458 -0.0623191 0.0355416 0.0106113 0.997367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2303 2352 -0.213045 -2.31481 -6.29206 0.0624659 0.0302039 -0.0162756 0.997457 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2303 2353 -0.188805 -0.00341393 -6.29504 0.00514698 0.0290823 -0.00905297 0.999523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2303 2354 -0.228249 2.27292 -6.53698 -0.0641164 0.0302281 0.0160338 0.997356 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2304 2353 -0.224216 -2.27985 -6.29069 0.0656822 0.0306634 -0.0149637 0.997257 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2304 2354 -0.201125 -0.0130623 -6.2735 -5.61979e-05 0.0264712 0.0123301 0.999574 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2304 2355 -0.2499 2.24686 -6.55035 -0.0520573 0.0296401 0.0112529 0.998141 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2305 2354 -0.220171 -2.28078 -6.29417 0.0649256 0.0266698 -0.0130837 0.997448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2305 2355 -0.208627 -0.00842145 -6.28691 -0.0131716 0.0363502 0.000136378 0.999252 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2305 2356 -0.228062 2.21921 -6.54414 -0.0636397 0.0344089 0.0148577 0.997269 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2306 2355 -0.216843 -2.26079 -6.29741 0.0689799 0.0345147 -0.0101928 0.996969 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2306 2356 -0.187473 0.00843062 -6.25639 -0.00425913 0.0342989 -0.000821976 0.999402 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2306 2357 -0.231882 2.22591 -6.55234 -0.0577507 0.0334909 0.0101578 0.997717 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2307 2356 -0.208727 -2.23547 -6.28675 0.0673627 0.0275675 -0.00391678 0.99734 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2307 2357 -0.212982 0.00145356 -6.264 -7.85174e-05 0.0285138 -0.000703405 0.999593 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2307 2358 -0.230067 2.21625 -6.53786 -0.0611813 0.0410756 0.0138131 0.997185 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2308 2357 -0.203956 -2.23374 -6.30667 0.0599597 0.0315858 -0.0187695 0.997524 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2308 2358 -0.195631 0.00563424 -6.29063 -0.00189156 0.0365499 -0.00193524 0.999328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2308 2359 -0.2491 2.18407 -6.55471 -0.0608379 0.0330361 0.0145064 0.997495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2309 2358 -0.221485 -2.22092 -6.29756 0.0657298 0.029606 -0.00556306 0.997383 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2309 2359 -0.201246 -0.0123157 -6.28285 -0.0109375 0.0354945 0.00841078 0.999275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2309 2360 -0.254018 2.16991 -6.54538 -0.0696493 0.0321529 0.00955523 0.997007 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2310 2359 -0.202227 -2.20266 -6.28875 0.0637482 0.0195855 -0.0187071 0.997598 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2310 2360 -0.203761 -0.00565207 -6.26729 -0.00280704 0.0353426 0.00107355 0.999371 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2310 2361 -0.243329 2.16424 -6.51779 -0.0657031 0.0318432 0.00466325 0.99732 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2311 2360 -0.225978 -2.1724 -6.293 0.0505681 0.0328429 -0.0164163 0.998045 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2311 2361 -0.191114 0.0150203 -6.2838 0.00296051 0.0355329 0.00235242 0.999361 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2311 2362 -0.246532 2.14266 -6.5458 -0.0731802 0.0309683 0.007571 0.996809 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2312 2361 -0.228551 -2.17238 -6.2747 0.0653395 0.0334768 -0.0204012 0.997093 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2312 2362 -0.194647 0.0183462 -6.27711 0.0085298 0.029637 0.00120869 0.999524 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2312 2363 -0.264311 2.13203 -6.5372 -0.0532355 0.0383776 0.0145371 0.997738 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2313 2362 -0.218719 -2.14937 -6.28128 0.0599617 0.0256426 -0.0099849 0.997821 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2313 2363 -0.194074 -0.00172858 -6.28364 0.00264918 0.0324045 -0.00671453 0.999449 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2313 2364 -0.240956 2.13381 -6.53403 -0.061454 0.0363424 0.00916109 0.997406 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2314 2363 -0.222844 -2.13027 -6.27604 0.0565185 0.0349146 -0.00994472 0.997741 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2314 2364 -0.192238 -0.0122102 -6.28518 0.00453943 0.0306952 -0.000424325 0.999518 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2314 2365 -0.228529 2.09712 -6.54579 -0.0566843 0.0352149 0.00932786 0.997727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2315 2364 -0.220189 -2.11098 -6.27992 0.0576135 0.0246866 -0.0146034 0.997927 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2315 2365 -0.198555 0.00332797 -6.27738 0.00227043 0.0306992 0.000846599 0.999526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2315 2366 -0.256131 2.08683 -6.52542 -0.0653625 0.0306171 0.00510279 0.997379 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2316 2365 -0.20802 -2.10164 -6.26901 0.0622555 0.0326164 -0.0136035 0.997434 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2316 2366 -0.198968 0.00481524 -6.27601 0.00220673 0.0352077 0.00325309 0.999372 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2316 2367 -0.234561 2.07055 -6.52706 -0.0565132 0.0235746 0.0130816 0.998038 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2317 2366 -0.225024 -2.09407 -6.26232 0.0625287 0.03168 -0.00680159 0.997517 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2317 2367 -0.192181 0.0100461 -6.28838 -0.00535287 0.0354561 0.00961294 0.999311 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2317 2368 -0.238236 2.03765 -6.52958 -0.0608215 0.0258849 0.0108183 0.997754 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2318 2367 -0.21269 -2.0697 -6.26245 0.0500392 0.0269534 -0.0155963 0.998262 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2318 2368 -0.175437 0.00340993 -6.25768 0.00705497 0.031192 0.00810444 0.999456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2318 2369 -0.222202 2.03855 -6.5106 -0.0630298 0.0451711 0.0206289 0.996775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2319 2368 -0.209696 -2.06466 -6.26025 0.0652739 0.0322947 -0.0244 0.997046 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2319 2369 -0.196999 -0.0119849 -6.27875 0.00534013 0.02848 0.00424569 0.999571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2319 2370 -0.242529 2.01489 -6.52392 -0.0489942 0.0229757 0.0128875 0.998452 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2320 2369 -0.198257 -2.05024 -6.27302 0.0628572 0.0341945 -0.0156848 0.997313 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2320 2370 -0.205607 -0.0185787 -6.28011 -0.00245811 0.0242698 0.00416172 0.999694 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2320 2371 -0.239113 2.01048 -6.52052 -0.0749949 0.0401034 0.0118582 0.996307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2321 2370 -0.230208 -2.02351 -6.26887 0.0514904 0.0346557 -0.00807179 0.998039 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2321 2371 -0.215858 -0.0035255 -6.25128 -0.00143505 0.0229293 -0.00434294 0.999727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2321 2372 -0.236667 1.989 -6.53325 -0.0634572 0.0333619 0.0171839 0.997279 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2322 2371 -0.208825 -2.01712 -6.27326 0.0591642 0.0332658 -0.0122114 0.997619 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2322 2372 -0.20686 -0.00265563 -6.28402 0.00120832 0.0267468 0.00827303 0.999607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2322 2373 -0.220233 1.98845 -6.52522 -0.066718 0.0286027 0.0155605 0.99724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2323 2372 -0.199024 -1.9965 -6.27901 0.0633401 0.0340472 -0.00986797 0.997362 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2323 2373 -0.199427 0.00271438 -6.27081 0.000333317 0.0244057 0.00247834 0.999699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2323 2374 -0.234456 1.96467 -6.52978 -0.0657377 0.0414126 0.00799646 0.996945 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2324 2373 -0.215501 -1.97481 -6.26563 0.0603274 0.030973 -0.00850865 0.997662 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2324 2374 -0.184111 0.00457261 -6.27848 -0.00257885 0.0432641 -0.00163468 0.999059 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2324 2375 -0.22535 1.94078 -6.51325 -0.0604548 0.0255046 0.0139791 0.997747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2325 2374 -0.229939 -1.97282 -6.27767 0.0647012 0.0246515 -0.0156172 0.997478 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2325 2375 -0.193884 -0.0201924 -6.26009 0.00204474 0.023389 -0.00107941 0.999724 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2325 2376 -0.242708 1.93889 -6.52068 -0.0621035 0.0328504 0.0144026 0.997425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2326 2375 -0.231555 -1.93271 -6.27123 0.0632143 0.0244285 -0.0075733 0.997672 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2326 2376 -0.186815 0.00807081 -6.28878 -9.05386e-05 0.033304 0.00391702 0.999438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2326 2377 -0.236602 1.90684 -6.52657 -0.0578376 0.0308853 0.00571232 0.997832 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2327 2376 -0.22044 -1.92047 -6.26902 0.0592197 0.0342377 -0.0165075 0.997521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2327 2377 -0.196922 -0.000379054 -6.27217 -0.00548624 0.0201024 0.000292184 0.999783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2327 2378 -0.24586 1.90798 -6.51776 -0.0565837 0.0287039 0.00665898 0.997963 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2328 2377 -0.200869 -1.90976 -6.26291 0.0637184 0.0306485 -0.0166516 0.997358 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2328 2378 -0.194762 0.00239825 -6.27675 0.00525356 0.0268042 0.00436272 0.999617 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2328 2379 -0.24008 1.87735 -6.51291 -0.0542932 0.0343197 0.0145859 0.997828 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2329 2378 -0.224756 -1.89234 -6.27838 0.0599274 0.0403425 -0.00739319 0.99736 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2329 2379 -0.208297 0.0119967 -6.27718 0.00552314 0.0356291 0.00255874 0.999347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2329 2380 -0.240061 1.86052 -6.51576 -0.060501 0.0361108 0.00102465 0.997514 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2330 2379 -0.214551 -1.87451 -6.26797 0.0736301 0.0339996 -0.00998633 0.996656 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2330 2380 -0.204265 0.0137031 -6.2717 -0.00774094 0.0306327 -0.00399314 0.999493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2330 2381 -0.225548 1.86097 -6.51161 -0.0567688 0.0322746 0.0179098 0.997705 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2331 2380 -0.220148 -1.86576 -6.2775 0.0581034 0.0339138 -0.0077477 0.997704 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2331 2381 -0.181259 -0.00569787 -6.27592 0.00272824 0.0374842 -0.00122296 0.999293 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2331 2382 -0.209764 1.82694 -6.50923 -0.059512 0.0278874 0.00456871 0.997828 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2332 2381 -0.195016 -1.84732 -6.27048 0.0564743 0.0314429 -0.0108944 0.997849 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2332 2382 -0.18519 0.0132922 -6.29417 0.00827447 0.021847 -0.00625391 0.999708 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2332 2383 -0.245623 1.81902 -6.53172 -0.0643217 0.0379614 0.0146821 0.997099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2333 2382 -0.198554 -1.84128 -6.27186 0.0630023 0.022473 -0.00491166 0.997748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2333 2383 -0.191045 -0.00978964 -6.30404 -0.00208084 0.0404653 -0.00922577 0.999136 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2333 2384 -0.23718 1.80834 -6.51529 -0.0645701 0.0239506 0.00671795 0.997603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2334 2383 -0.218266 -1.81987 -6.26595 0.052358 0.032385 -0.0108322 0.998044 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2334 2384 -0.191259 -0.0114681 -6.29426 -0.0131148 0.0312652 0.000692571 0.999425 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2334 2385 -0.222302 1.78271 -6.51707 -0.0582095 0.0312056 0.0214102 0.997587 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2335 2384 -0.21524 -1.79722 -6.26343 0.0688715 0.0273588 -0.00799129 0.997218 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2335 2385 -0.194067 -0.00650344 -6.27532 -0.00369325 0.0322872 -0.00138264 0.999471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2335 2386 -0.234832 1.76703 -6.51777 -0.0765309 0.0322475 0.0117489 0.996476 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2336 2385 -0.21795 -1.7924 -6.25862 0.0621598 0.0234985 -0.0100242 0.997739 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2336 2386 -0.193455 0.00894794 -6.27289 0.00465602 0.0273704 0.00322593 0.999609 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2336 2387 -0.224914 1.75956 -6.49407 -0.0633391 0.0344574 0.0115648 0.99733 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2337 2386 -0.216414 -1.79418 -6.25587 0.06471 0.0401722 -0.0144687 0.99699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2337 2387 -0.206637 -0.00474963 -6.28642 -0.0123445 0.0328079 -0.00457744 0.999375 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2337 2388 -0.225944 1.7352 -6.50599 -0.0689897 0.0252948 0.00999477 0.997247 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2338 2387 -0.219663 -1.76749 -6.24475 0.0727188 0.033844 -0.0153753 0.99666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2338 2388 -0.198963 0.00370409 -6.27206 -0.00480594 0.037686 -0.0110947 0.999216 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2338 2389 -0.244938 1.73969 -6.5091 -0.0725745 0.0198292 0.00518965 0.997152 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2339 2388 -0.210577 -1.74965 -6.25944 0.061968 0.0165059 -0.0144601 0.997837 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2339 2389 -0.182765 -0.00757121 -6.28162 0.00895481 0.036398 0.00378773 0.99929 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2339 2390 -0.215198 1.71371 -6.51681 -0.0702852 0.0320111 0.00796925 0.996981 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2340 2389 -0.205509 -1.71175 -6.26458 0.0629146 0.0271772 -0.00516082 0.997635 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2340 2390 -0.188219 0.00786123 -6.2781 0.000312038 0.0292675 -0.000677961 0.999571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2340 2391 -0.2363 1.69877 -6.51456 -0.0602822 0.0353372 0.0135433 0.997464 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2341 2390 -0.211763 -1.71734 -6.27046 0.0602678 0.0348704 -0.00982949 0.997525 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2341 2391 -0.203255 -0.00652316 -6.27567 0.00648806 0.0273532 -0.00331903 0.999599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2341 2392 -0.229393 1.69606 -6.51482 -0.0559967 0.0424875 0.00526715 0.997513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2342 2391 -0.211128 -1.67665 -6.27644 0.0633507 0.0331071 -0.0123854 0.997365 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2342 2392 -0.189574 -0.0134489 -6.27764 -0.00769867 0.032717 0.00842657 0.999399 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2342 2393 -0.218565 1.65994 -6.51932 -0.0634072 0.0326091 0.0191919 0.99727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2343 2392 -0.192305 -1.6863 -6.26314 0.0676086 0.0309211 -0.0116577 0.997165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2343 2393 -0.204469 -0.0102938 -6.27355 -0.000534348 0.0359719 0.00439987 0.999343 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2343 2394 -0.225218 1.65605 -6.50386 -0.0679401 0.0238442 0.0105286 0.997349 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2344 2393 -0.220517 -1.6602 -6.23911 0.0615858 0.035778 -0.0136886 0.997366 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2344 2394 -0.198611 0.00172168 -6.28136 -0.000290535 0.0314085 0.000446598 0.999506 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2344 2395 -0.226641 1.64155 -6.50238 -0.0572127 0.0368806 0.0153169 0.997563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2345 2394 -0.20798 -1.6568 -6.2532 0.0634819 0.0324031 -0.00472459 0.997446 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2345 2395 -0.20297 -0.00818656 -6.27056 0.000199313 0.0298776 -0.00287129 0.999549 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2345 2396 -0.212488 1.62779 -6.49851 -0.0661761 0.0326681 0.00761797 0.997244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2346 2395 -0.202241 -1.64312 -6.24324 0.0675971 0.0344945 -0.0142099 0.997015 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2346 2396 -0.211442 0.00873531 -6.28203 -0.00219583 0.0353965 -0.00297202 0.999367 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2346 2397 -0.218605 1.60409 -6.50559 -0.0664001 0.0209988 0.00923631 0.997529 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2347 2396 -0.206408 -1.62293 -6.24849 0.0678238 0.0291977 -0.00956369 0.997224 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2347 2397 -0.190287 -0.0135259 -6.27808 0.00472238 0.0329843 -0.0070877 0.99942 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2347 2398 -0.221158 1.58045 -6.50212 -0.0563334 0.0372732 0.0130236 0.997631 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2348 2397 -0.201406 -1.60499 -6.26563 0.0671044 0.0423573 -0.0180654 0.996683 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2348 2398 -0.202806 -0.0173497 -6.26627 0.00202621 0.0320289 0.00233017 0.999482 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2348 2399 -0.219693 1.55712 -6.51889 -0.0617868 0.0386126 0.0102888 0.997289 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2349 2398 -0.189232 -1.59193 -6.25707 0.0619553 0.0333461 -0.00952141 0.997476 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2349 2399 -0.187155 -0.0153646 -6.28647 0.00249584 0.0365587 0.00273316 0.999325 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2349 2400 -0.220444 1.55738 -6.48883 -0.0579933 0.0393986 0.00103742 0.997539 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2350 2399 -0.221166 -1.57428 -6.25248 0.0722386 0.0252205 -0.00972285 0.997021 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2350 2400 -0.215575 -0.0051028 -6.29581 -0.00802616 0.0373789 0.00768615 0.999239 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2350 2401 -0.242948 1.5426 -6.49575 -0.0606068 0.0339903 0.0106538 0.997526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2351 2400 -0.199069 -1.55932 -6.25306 0.0534525 0.0233561 -0.00671425 0.998275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2351 2401 -0.202152 -0.00510787 -6.26985 -0.00533501 0.0418398 0.004802 0.999099 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2351 2402 -0.206978 1.53837 -6.48552 -0.0736597 0.0285196 0.0150613 0.996762 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2352 2401 -0.212408 -1.53492 -6.24696 0.0591696 0.0380121 -0.00935306 0.99748 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2352 2402 -0.202125 0.00516999 -6.28395 -0.00196891 0.0377248 -0.00152586 0.999285 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2352 2403 -0.232737 1.51126 -6.49625 -0.0570564 0.035517 0.0132646 0.997651 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2353 2402 -0.210238 -1.52299 -6.26649 0.0686787 0.0349705 -0.0135568 0.996934 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2353 2403 -0.18665 0.00832876 -6.26828 0.00252789 0.0264844 0.00234026 0.999643 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2353 2404 -0.20775 1.49232 -6.50115 -0.0628816 0.036646 0.0102877 0.997295 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2354 2403 -0.218596 -1.50786 -6.25641 0.0632268 0.0338408 -0.00873176 0.997387 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2354 2404 -0.201585 -0.0128801 -6.2815 -0.00518283 0.0417779 -0.000166563 0.999113 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2354 2405 -0.219858 1.47015 -6.49782 -0.0628771 0.0342889 0.0151933 0.997316 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2355 2404 -0.204534 -1.48096 -6.25453 0.0648049 0.0332882 -0.00536094 0.997328 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2355 2405 -0.193254 0.00988017 -6.29472 -0.00373362 0.0270106 -0.00160394 0.999627 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2355 2406 -0.216324 1.46725 -6.48358 -0.0585578 0.0325805 0.00237966 0.997749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2356 2405 -0.228264 -1.4745 -6.24791 0.0629052 0.0338328 -0.00523599 0.997432 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2356 2406 -0.211968 0.00399047 -6.26758 -0.00299073 0.0277105 -0.000219757 0.999611 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2356 2407 -0.227066 1.45316 -6.48426 -0.0607903 0.0294112 0.0151623 0.997602 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2357 2406 -0.190047 -1.47321 -6.25992 0.0605107 0.029836 -0.0208072 0.997505 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2357 2407 -0.189037 -0.0027958 -6.28795 0.0102719 0.019996 0.00810338 0.999714 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2357 2408 -0.225092 1.43885 -6.47427 -0.0722364 0.0315813 0.00915523 0.996845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2358 2407 -0.209163 -1.43962 -6.22224 0.0581319 0.0309203 -0.00228165 0.997827 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2358 2408 -0.209872 0.00548264 -6.28489 -0.00460195 0.033937 0.000301597 0.999413 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2358 2409 -0.210771 1.40686 -6.47849 -0.0611298 0.0238009 0.00841503 0.997811 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2359 2408 -0.201591 -1.42635 -6.25035 0.0595631 0.0257901 -0.0194258 0.997702 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2359 2409 -0.209488 0.00859052 -6.27472 0.00605515 0.0273181 -0.00153184 0.999607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2359 2410 -0.224023 1.40874 -6.49677 -0.0695283 0.0239684 0.0166495 0.997153 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2360 2409 -0.225987 -1.41962 -6.2352 0.061893 0.0296488 -0.00967695 0.997595 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2360 2410 -0.193863 -0.00875875 -6.27245 0.0110393 0.0297485 -0.00190835 0.999495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2360 2411 -0.215272 1.38828 -6.48595 -0.0582384 0.0253022 0.00405205 0.997974 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2361 2410 -0.191087 -1.37698 -6.24269 0.0622204 0.0366005 -0.00797012 0.997359 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2361 2411 -0.178406 -1.47947e-05 -6.27634 0.00753899 0.0252697 -0.00567937 0.999636 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2361 2412 -0.226513 1.36351 -6.4933 -0.0678047 0.0389811 0.0100667 0.996886 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2362 2411 -0.201955 -1.37824 -6.23577 0.0601142 0.0265025 -0.00513719 0.997826 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2362 2412 -0.199604 -0.0101615 -6.27426 0.00881346 0.029964 -0.00406965 0.999504 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2362 2413 -0.236101 1.34777 -6.48752 -0.0696525 0.033735 0.00469617 0.99699 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2363 2412 -0.208934 -1.35562 -6.2387 0.0606608 0.0348271 0.00111082 0.99755 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2363 2413 -0.184836 -0.000109466 -6.24967 -0.00275453 0.0406404 -0.013158 0.999083 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2363 2414 -0.234044 1.32906 -6.46938 -0.0584076 0.0384928 0.00402264 0.997542 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2364 2413 -0.216979 -1.35792 -6.24905 0.0649416 0.0358125 0.00217197 0.997244 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2364 2414 -0.192921 -0.0116813 -6.27711 0.000524432 0.0348922 0.00211749 0.999389 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2364 2415 -0.240341 1.32179 -6.4812 -0.0710111 0.0250325 0.00713754 0.997136 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2365 2414 -0.205379 -1.33712 -6.22758 0.0652563 0.0333674 -0.00348128 0.997304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2365 2415 -0.197666 0.00166177 -6.27919 -0.00865998 0.0297904 -0.00325742 0.999513 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2365 2416 -0.230625 1.312 -6.47883 -0.0613094 0.0203651 0.00191974 0.997909 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2366 2415 -0.196344 -1.31842 -6.23567 0.0563185 0.0260999 -0.00485728 0.99806 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2366 2416 -0.186923 0.0103394 -6.28646 0.00311447 0.0385717 0.00173851 0.999249 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2366 2417 -0.230744 1.30764 -6.46385 -0.0609796 0.0403781 0.00692881 0.997298 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2367 2416 -0.20734 -1.30822 -6.22245 0.0674026 0.0227344 -0.011871 0.997396 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2367 2417 -0.216622 -0.00598439 -6.29368 0.0023461 0.0358309 -0.00139639 0.999354 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2367 2418 -0.22336 1.26689 -6.48977 -0.0626025 0.0383801 0.00758546 0.997271 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2368 2417 -0.201502 -1.2843 -6.22761 0.0693164 0.0328009 -0.00912456 0.997014 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2368 2418 -0.194794 -0.0250018 -6.27353 0.00307367 0.0170972 0.00465292 0.999838 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2368 2419 -0.218598 1.2476 -6.48801 -0.0622987 0.0348435 0.0174394 0.997297 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2369 2418 -0.200474 -1.27996 -6.2298 0.0647782 0.0375487 -0.00805963 0.99716 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2369 2419 -0.186773 -0.0142241 -6.2822 -0.00104896 0.0359922 -0.00309405 0.999347 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2369 2420 -0.218703 1.26202 -6.49244 -0.0617388 0.0236689 0.00668861 0.997789 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2370 2419 -0.184148 -1.2621 -6.22042 0.0620653 0.0273355 -0.00169978 0.997696 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2370 2420 -0.204455 0.0086618 -6.28282 0.00162674 0.0294768 0.000920193 0.999564 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2370 2421 -0.233272 1.21905 -6.49426 -0.0620507 0.0288693 0.0064482 0.997635 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2371 2420 -0.20725 -1.24588 -6.22087 0.0678632 0.031215 -0.0141422 0.997106 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2371 2421 -0.193517 -0.00997583 -6.27873 0.00195252 0.0343432 0.00402575 0.9994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2371 2422 -0.217078 1.2177 -6.50535 -0.0636444 0.0367634 0.00513739 0.997282 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2372 2421 -0.206856 -1.22723 -6.2499 0.0611236 0.0249413 -0.0130369 0.997733 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2372 2422 -0.208265 -0.000730366 -6.27475 -0.00280864 0.0426974 0.0076236 0.999055 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2372 2423 -0.21549 1.20154 -6.48168 -0.0647753 0.0300177 0.0071375 0.997423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2373 2422 -0.1991 -1.20516 -6.22594 0.0653171 0.0300918 -0.00802497 0.997378 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2373 2423 -0.197197 -0.00165988 -6.24623 0.00821435 0.0361081 -0.00570412 0.999298 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2373 2424 -0.218129 1.18057 -6.4884 -0.061038 0.0357977 0.00181977 0.997492 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2374 2423 -0.194082 -1.18445 -6.23051 0.0706851 0.0303802 -0.00912313 0.996994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2374 2424 -0.171235 0.00538125 -6.28329 -0.00568774 0.0300008 0.00272098 0.99953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2374 2425 -0.216306 1.17876 -6.48139 -0.069185 0.0154032 0.00821221 0.997451 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2375 2424 -0.193675 -1.17198 -6.21647 0.0617898 0.0278956 -0.0081527 0.997666 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2375 2425 -0.204872 -0.000807203 -6.28474 0.00376689 0.02875 -0.00581976 0.999563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2375 2426 -0.213875 1.16241 -6.47806 -0.0714134 0.037589 0.0136054 0.996645 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2376 2425 -0.229355 -1.16663 -6.22314 0.0632348 0.0247376 -0.0065484 0.997671 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2376 2426 -0.199686 0.00977397 -6.25756 0.000743934 0.0363941 -0.00236379 0.999334 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2376 2427 -0.218536 1.14183 -6.48442 -0.0656763 0.0339574 0.00822535 0.997229 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2377 2426 -0.194133 -1.15556 -6.21837 0.0689955 0.0291742 -0.0151594 0.997075 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2377 2427 -0.21554 -0.00394 -6.29583 0.000374408 0.027071 0.00324569 0.999628 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2377 2428 -0.207373 1.12361 -6.48406 -0.0645532 0.0369508 0.00192143 0.997228 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2378 2427 -0.20034 -1.1526 -6.22096 0.0632038 0.024259 -0.0107128 0.997648 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2378 2428 -0.201597 -0.00530251 -6.27721 0.00447814 0.0261479 0.00276176 0.999644 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2378 2429 -0.226288 1.12937 -6.46117 -0.0639924 0.0208112 0.00612235 0.997715 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2379 2428 -0.2052 -1.12709 -6.21549 0.0649009 0.0225069 -0.00659526 0.997616 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2379 2429 -0.185836 0.0197728 -6.2739 0.00832958 0.0288566 -0.0010273 0.999548 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2379 2430 -0.226655 1.08558 -6.46863 -0.0553441 0.0260403 0.0107651 0.99807 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2380 2429 -0.196824 -1.08798 -6.24956 0.0632852 0.0282961 -0.0145169 0.997489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2380 2430 -0.20772 -0.0046312 -6.28146 0.00601184 0.0308871 0.00109009 0.999504 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2380 2431 -0.222069 1.0882 -6.4692 -0.0549921 0.0283506 0.0114546 0.998018 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2381 2430 -0.203465 -1.09504 -6.23136 0.0622928 0.0235325 -0.00903056 0.99774 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2381 2431 -0.202831 -0.00455158 -6.27306 -0.000830948 0.03299 -0.00522904 0.999442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2381 2432 -0.206101 1.04705 -6.46429 -0.055627 0.0335934 0.0107759 0.997828 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2382 2431 -0.211183 -1.06183 -6.2219 0.0548951 0.0359541 -0.0104726 0.99779 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2382 2432 -0.215837 -0.0117955 -6.28531 0.00551749 0.035424 0.0065001 0.999336 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2382 2433 -0.206697 1.03906 -6.47694 -0.0583754 0.0285203 0.0106568 0.99783 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2383 2432 -0.199926 -1.05972 -6.19512 0.0614645 0.0338961 -0.00507769 0.997521 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2383 2433 -0.18875 -0.00974398 -6.27623 -0.00942186 0.0314625 -0.00125868 0.99946 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2383 2434 -0.22653 1.01526 -6.47114 -0.0546626 0.0407761 0.0072427 0.997646 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2384 2433 -0.186965 -1.04619 -6.22314 0.0625566 0.0252052 -0.00753559 0.997695 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2384 2434 -0.190311 -0.00441684 -6.28159 0.00578421 0.0328931 -0.000123737 0.999442 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2384 2435 -0.218705 0.993866 -6.46298 -0.0634436 0.0374961 0.00407769 0.997272 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2385 2434 -0.190243 -1.01411 -6.22875 0.0552306 0.041815 -0.0134758 0.997507 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2385 2435 -0.200604 -0.00193216 -6.28162 0.0109433 0.0330893 0.00157084 0.999391 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2385 2436 -0.207454 0.999487 -6.46154 -0.0628573 0.0406377 0.00868581 0.997157 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2386 2435 -0.188244 -0.999291 -6.20465 0.0525771 0.0270046 -0.0135751 0.998159 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2386 2436 -0.202145 -0.0139974 -6.27743 -0.00616266 0.0324106 -0.00152263 0.999454 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2386 2437 -0.215084 0.967382 -6.46646 -0.0610487 0.0336861 0.0138362 0.99747 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2387 2436 -0.200734 -0.984923 -6.22452 0.0651197 0.0371979 -0.0065033 0.997163 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2387 2437 -0.196214 0.00462191 -6.27388 0.00790584 0.029197 0.00975583 0.999495 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2387 2438 -0.22049 0.947666 -6.46756 -0.0621273 0.0341575 0.0106325 0.997427 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2388 2437 -0.194105 -0.958778 -6.21776 0.0540031 0.0315671 -0.0197945 0.997845 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2388 2438 -0.207742 0.0165766 -6.27664 5.34372e-05 0.0282731 -0.00401596 0.999592 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2388 2439 -0.216504 0.927615 -6.46341 -0.0542186 0.034269 0.00910842 0.997899 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2389 2438 -0.201248 -0.970292 -6.22231 0.0639139 0.0305743 -0.0112579 0.997423 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2389 2439 -0.189728 0.0019497 -6.27737 0.00222545 0.0342974 -0.00135653 0.999408 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2389 2440 -0.217072 0.932332 -6.45674 -0.0564582 0.0279932 0.00262904 0.998009 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2390 2439 -0.191433 -0.923221 -6.23331 0.0617566 0.0255161 -0.0043028 0.997756 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2390 2440 -0.195233 0.014116 -6.29866 -0.00568594 0.0274528 -0.000846011 0.999607 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2390 2441 -0.225495 0.918929 -6.46739 -0.0616357 0.0407911 0.00529048 0.997251 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2391 2440 -0.190483 -0.913155 -6.21949 0.0654267 0.0248702 -0.00439644 0.997538 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2391 2441 -0.197274 -0.00180846 -6.27284 0.000843714 0.0250814 -0.00155204 0.999684 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2391 2442 -0.204697 0.898855 -6.45896 -0.0660522 0.0221258 0.0131313 0.997484 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2392 2441 -0.17957 -0.92473 -6.19996 0.0675185 0.0302245 -0.0137852 0.997165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2392 2442 -0.204059 -0.0123853 -6.28475 -0.0034718 0.0355861 0.00481939 0.999349 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2392 2443 -0.200593 0.883255 -6.45984 -0.0642811 0.0286327 0.0100345 0.997471 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2393 2442 -0.212946 -0.892676 -6.23266 0.0653908 0.0333386 -0.00690074 0.997279 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2393 2443 -0.193241 -0.00618044 -6.29559 0.00302427 0.0316965 -1.8985e-05 0.999493 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2393 2444 -0.193019 0.866861 -6.45692 -0.065438 0.027686 0.00528682 0.997458 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2394 2443 -0.203916 -0.88425 -6.19988 0.0622396 0.0217432 -0.0126801 0.997744 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2394 2444 -0.188056 0.016689 -6.28739 -0.0103745 0.0332497 -0.00136226 0.999392 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2394 2445 -0.214166 0.848419 -6.47091 -0.0593195 0.0367234 0.0125089 0.997485 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2395 2444 -0.196282 -0.871514 -6.21219 0.0733928 0.0376816 -0.00196952 0.996589 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2395 2445 -0.191086 0.00138581 -6.2832 -0.00222645 0.0410821 -0.002874 0.999149 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2395 2446 -0.217653 0.841223 -6.45092 -0.0569267 0.0319549 0.00325711 0.997862 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2396 2445 -0.188809 -0.842219 -6.20383 0.0610056 0.0326422 -0.00268 0.9976 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2396 2446 -0.194934 0.00666276 -6.28288 0.00380517 0.0313317 0.00501319 0.999489 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2396 2447 -0.219682 0.836066 -6.44591 -0.0589097 0.0349673 0.0124514 0.997573 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2397 2446 -0.202658 -0.83899 -6.19805 0.0629829 0.0317564 -0.00339708 0.997503 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2397 2447 -0.186759 0.0126225 -6.26592 -0.00258548 0.0345739 -0.00491423 0.999387 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2397 2448 -0.215181 0.819319 -6.4384 -0.0625511 0.022467 -0.00531836 0.997775 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2398 2447 -0.200609 -0.793323 -6.18745 0.0551559 0.0369463 0.00200402 0.997792 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2398 2448 -0.202246 -0.0179324 -6.29693 0.00157473 0.0334044 0.00249212 0.999438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2398 2449 -0.208237 0.792782 -6.44723 -0.0570495 0.0391079 0.00468095 0.997594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2399 2448 -0.189247 -0.798506 -6.21143 0.056337 0.0216846 -0.00471333 0.998165 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2399 2449 -0.186114 -0.00138854 -6.28888 -0.00794118 0.0318329 0.000225927 0.999462 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2399 2450 -0.207432 0.772722 -6.47074 -0.0668603 0.0228511 0.0126313 0.997421 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2400 2449 -0.194481 -0.767292 -6.21902 0.0548615 0.0327386 -0.0126291 0.997877 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2400 2450 -0.191746 -0.00554077 -6.2669 -0.000260537 0.0306667 0.000118337 0.99953 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2401 2450 -0.209848 -0.761712 -6.2104 0.0650797 0.033163 -0.0116049 0.997261 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2401 2451 -0.200325 0.0147545 -6.28068 0.00146164 0.0319557 0.00326275 0.999483 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2402 2451 -0.192278 -0.769524 -6.19254 0.0674675 0.0429213 -0.0076085 0.996769 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2402 2452 -0.19385 -0.0145737 -6.27629 1.65399e-05 0.0342476 -0.00510404 0.9994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2403 2452 -0.20887 -0.735224 -6.2013 0.0726401 0.0258343 -0.00622308 0.997004 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2403 2453 -0.192874 0.00384606 -6.27044 0.00193938 0.0408243 0.00531837 0.99915 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2404 2453 -0.190976 -0.725007 -6.2001 0.0665176 0.0314863 -0.00603959 0.99727 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2404 2454 -0.200261 -0.0037252 -6.28825 -0.00339284 0.0289801 0.00889424 0.999535 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2405 2454 -0.183983 -0.716497 -6.178 0.0663653 0.0272553 -0.00156305 0.997422 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2405 2455 -0.195781 -0.00314907 -6.28418 -0.00612788 0.0341521 -0.00290323 0.999394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2406 2455 -0.214504 -0.676339 -6.18871 0.0672429 0.0334357 -0.00635803 0.997156 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2406 2456 -0.220846 0.00597598 -6.27227 0.00242804 0.0265153 0.00769481 0.999616 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2407 2456 -0.190988 -0.665023 -6.20517 0.0562793 0.0230958 -0.00301198 0.998143 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2407 2457 -0.221004 0.0129977 -6.26674 0.00992377 0.0226168 0.00426336 0.999686 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2408 2457 -0.20182 -0.658843 -6.19047 0.0652091 0.0304317 -0.00359311 0.997401 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2408 2458 -0.200965 0.0131517 -6.27309 -0.00387329 0.0343861 -0.00176718 0.9994 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2409 2458 -0.198279 -0.656634 -6.20353 0.0559026 0.0292309 -0.0157386 0.997884 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2409 2459 -0.203458 -0.0145712 -6.26479 -0.000357497 0.0316968 -0.0090564 0.999456 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2410 2459 -0.179479 -0.620541 -6.21108 0.0740796 0.0237077 -0.00954775 0.996925 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2410 2460 -0.199134 0.00797696 -6.28004 -0.0048141 0.0333515 0.00302372 0.999428 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2411 2460 -0.198206 -0.638982 -6.19959 0.0599592 0.032024 -0.00470818 0.997676 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2411 2461 -0.1899 -0.00593844 -6.28606 -0.00123614 0.0320006 -0.00746462 0.999459 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2412 2461 -0.183296 -0.602329 -6.19634 0.0679301 0.0301738 -0.00892439 0.997194 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2412 2462 -0.195472 0.00753963 -6.27878 -0.00410759 0.0301189 0.00318 0.999533 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2413 2462 -0.211124 -0.580115 -6.17557 0.0496195 0.0312197 -0.00319793 0.998275 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2413 2463 -0.188487 0.0175771 -6.29359 -0.00314724 0.0349966 -0.00413604 0.999374 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2414 2463 -0.186679 -0.579017 -6.17 0.0631984 0.0322648 0.00258014 0.997476 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2414 2464 -0.193796 0.00215668 -6.29875 -0.00703564 0.0331319 0.00491477 0.999414 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2415 2464 -0.188842 -0.555323 -6.18177 0.0659132 0.0235939 -0.00325853 0.997541 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2415 2465 -0.191671 -0.00242358 -6.27681 0.00926953 0.0251742 0.00863567 0.999603 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2416 2465 -0.195125 -0.542782 -6.19293 0.0595147 0.024799 -0.00129619 0.997918 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2416 2466 -0.18904 -0.0217762 -6.27914 -0.00314485 0.0322238 -0.00217509 0.999473 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2417 2466 -0.191502 -0.510547 -6.17282 0.0589391 0.0457047 0.000550444 0.997215 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2417 2467 -0.200243 0.00156652 -6.25751 0.00118512 0.0284733 -0.00285912 0.99959 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2418 2467 -0.190163 -0.515355 -6.18469 0.0629835 0.0190751 -0.00607728 0.997814 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2418 2468 -0.1853 0.0026831 -6.28209 0.00434811 0.0369112 -0.00326931 0.999304 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2419 2468 -0.19408 -0.50341 -6.18817 0.0608252 0.0356311 -0.00662288 0.99749 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2419 2469 -0.187384 -0.00885314 -6.27782 0.00122349 0.0284634 -0.000425844 0.999594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2420 2469 -0.188056 -0.470384 -6.18472 0.0723773 0.0236288 0.00572577 0.997081 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2420 2470 -0.209379 -0.00287774 -6.28378 0.00247588 0.0283626 -0.000936845 0.999594 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2421 2470 -0.190307 -0.45805 -6.18353 0.0598476 0.0336254 -0.00458896 0.99763 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2421 2471 -0.204485 0.00578027 -6.2719 0.00988367 0.0379828 0.00254275 0.999226 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2422 2471 -0.180611 -0.436933 -6.18874 0.0657468 0.0373972 -0.00907199 0.997094 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2422 2472 -0.208999 -0.00749001 -6.28741 0.000601489 0.0386241 -0.00686687 0.99923 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2423 2472 -0.191078 -0.427429 -6.17427 0.0638135 0.0378107 -0.0106772 0.997188 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2423 2473 -0.206494 0.00477521 -6.27538 -0.0088158 0.0336708 0.00254073 0.999391 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2424 2473 -0.205829 -0.399001 -6.19376 0.061059 0.0384168 -0.00145411 0.997394 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2424 2474 -0.203354 -0.00169739 -6.28163 0.0038161 0.0374336 0.00169464 0.99929 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2425 2474 -0.189036 -0.395124 -6.1958 0.0557872 0.0230048 -0.00631174 0.998158 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2425 2475 -0.188203 -0.00867764 -6.2771 -0.000401082 0.0287315 0.00911546 0.999546 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2426 2475 -0.17709 -0.387838 -6.15472 0.0649097 0.0363333 0.00181959 0.997228 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2426 2476 -0.188738 -0.0036269 -6.27781 0.00191218 0.0366307 -0.00373849 0.99932 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2427 2476 -0.206267 -0.373511 -6.16167 0.0512278 0.0279714 -0.00333365 0.99829 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2427 2477 -0.197289 -0.0109187 -6.29337 0.00218967 0.0294045 0.00197268 0.999563 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2428 2477 -0.210205 -0.324231 -6.17039 0.0541465 0.034208 -0.0116726 0.997879 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2428 2478 -0.183999 0.0248926 -6.28143 0.00895694 0.0336734 -0.00267806 0.999389 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2429 2478 -0.187911 -0.330829 -6.16135 0.0635055 0.0382053 -0.00507595 0.997237 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2429 2479 -0.212098 -0.00302371 -6.25876 -0.00610171 0.0356231 0.0055081 0.999331 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2430 2479 -0.183774 -0.330518 -6.17152 0.0570201 0.0303435 0.00162307 0.99791 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2430 2480 -0.202879 -0.00471975 -6.28228 0.00433708 0.0301216 0.00520822 0.999523 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2431 2480 -0.196504 -0.295792 -6.16644 0.0566364 0.0398489 0.00555999 0.997584 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2431 2481 -0.199862 -0.00408499 -6.27204 0.0061255 0.0296209 0.007754 0.999512 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2432 2481 -0.21459 -0.28108 -6.17704 0.0661289 0.0269109 -0.0045109 0.997438 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2432 2482 -0.196535 -0.00488009 -6.29291 0.00136209 0.033166 -0.00147572 0.999448 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2433 2482 -0.209009 -0.26998 -6.18207 0.0609478 0.0323592 -0.0145811 0.99751 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2433 2483 -0.189196 0.00816545 -6.27598 0.000487841 0.0299009 -0.000270004 0.999553 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2434 2483 -0.172564 -0.253473 -6.1637 0.0709934 0.0288875 0.00155322 0.997057 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2434 2484 -0.192412 0.000453597 -6.28817 -0.000668708 0.0320946 0.00493136 0.999472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2435 2484 -0.187333 -0.248616 -6.15204 0.056307 0.0332518 -0.00366646 0.997853 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2435 2485 -0.201837 0.0113672 -6.28791 -0.000664572 0.0339313 -0.00496856 0.999412 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2436 2485 -0.191436 -0.207358 -6.1825 0.0631457 0.0229291 0.00670225 0.997718 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2436 2486 -0.189259 0.00359855 -6.2762 -0.00703755 0.0348718 0.00574072 0.999351 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2437 2486 -0.18879 -0.218876 -6.15331 0.0634754 0.0322317 -0.00388161 0.997455 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2437 2487 -0.202026 0.0121159 -6.27563 0.00495013 0.0162365 -0.00238056 0.999853 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2438 2487 -0.20876 -0.195757 -6.15752 0.0665801 0.0323452 0.00478593 0.997245 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2438 2488 -0.196031 0.000151716 -6.29438 0.00190426 0.0234497 0.000619685 0.999723 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2439 2488 -0.185829 -0.156383 -6.1839 0.0639812 0.0402963 -0.00432691 0.997128 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2439 2489 -0.188798 -0.00707121 -6.26795 -0.00214604 0.0290578 0.00286255 0.999571 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2440 2489 -0.189627 -0.173537 -6.15083 0.0655641 0.0370588 0.00275758 0.997156 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2440 2490 -0.200054 -0.0098536 -6.2946 0.000915264 0.0282248 -0.00186145 0.999599 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2441 2490 -0.19486 -0.150899 -6.16268 0.0575634 0.03321 -0.00278726 0.997785 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2441 2491 -0.191259 -0.00972396 -6.28324 0.00713006 0.0381773 -0.00135196 0.999245 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2442 2491 -0.189982 -0.103618 -6.13853 0.0637047 0.0379736 -0.00259357 0.997243 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2442 2492 -0.202405 -0.0133343 -6.28956 -0.012059 0.031217 -0.00301155 0.999435 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2443 2492 -0.19915 -0.113522 -6.16986 0.0663613 0.0220317 -0.000362085 0.997552 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2443 2493 -0.208394 0.00697067 -6.27391 0.00545688 0.0247582 -0.00467736 0.999668 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2444 2493 -0.191161 -0.113773 -6.15917 0.0708643 0.0384823 -0.00488337 0.996731 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2444 2494 -0.184684 -0.000589528 -6.30343 0.00286559 0.0283526 -0.0025027 0.999591 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2445 2494 -0.180171 -0.0771886 -6.17779 0.0558424 0.0266718 -0.00502584 0.998071 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2445 2495 -0.210695 0.0168881 -6.27535 -0.00691823 0.0274883 -0.0120475 0.999526 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2446 2495 -0.192772 -0.0612142 -6.15209 0.0649342 0.0388827 -0.00556031 0.997116 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2446 2496 -0.196922 0.00123475 -6.28709 0.000909986 0.0297056 -0.00587619 0.999541 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2447 2496 -0.182883 -0.0549679 -6.16845 0.066917 0.0375753 0.000202037 0.997051 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2447 2497 -0.201452 -0.00175594 -6.27434 -0.0025338 0.0271012 0.00281801 0.999626 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2448 2497 -0.171078 -0.0546979 -6.14887 0.0665283 0.0307443 -0.00265229 0.997307 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2448 2498 -0.199437 -0.0012734 -6.25328 0.00550077 0.0330451 -0.00331446 0.999433 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2449 2498 -0.189722 -0.0101334 -6.15485 0.0661232 0.0352374 0.000597133 0.997189 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 +EDGE_SE3:QUAT 2449 2499 -0.186998 -0.0161808 -6.29417 -0.00401022 0.0316215 -0.00624077 0.999472 10000 0 0 0 0 0 10000 0 0 0 0 10000 0 0 0 40000 0 0 40000 0 40000 diff --git a/examples/module/pgo/data/torus3D.g2o b/examples/module/pgo/data/torus3D.g2o new file mode 100644 index 0000000..1e142a2 --- /dev/null +++ b/examples/module/pgo/data/torus3D.g2o @@ -0,0 +1,14048 @@ +VERTEX_SE3:QUAT 0 0.000000 0.000000 0.000000 0.0000000 0.0000000 0.0000000 1.0000000 +VERTEX_SE3:QUAT 1 0.070877 -0.137909 -0.005088 -0.2800834 -0.4989760 0.7807569 0.2509877 +VERTEX_SE3:QUAT 2 -0.053162 -0.028240 0.064535 -0.2352595 -0.3025447 -0.5285807 0.7574445 +VERTEX_SE3:QUAT 3 -0.166418 0.030925 0.166568 0.4519115 0.0754033 -0.8227372 0.3364428 +VERTEX_SE3:QUAT 4 -0.135888 0.045534 0.217805 0.5910356 -0.3037155 -0.3833317 0.6414753 +VERTEX_SE3:QUAT 5 -0.225736 0.054963 0.133573 -0.2390067 -0.3894520 -0.4805208 0.7485337 +VERTEX_SE3:QUAT 6 -0.373560 -0.042358 0.267164 0.1256458 -0.0241049 0.2010942 0.9711814 +VERTEX_SE3:QUAT 7 -0.482911 -0.087841 0.460426 0.6559763 -0.1004297 -0.7418230 0.0964761 +VERTEX_SE3:QUAT 8 -0.703561 -0.221863 0.487604 0.0631064 -0.4764020 0.5090314 0.7141048 +VERTEX_SE3:QUAT 9 -0.525086 -0.251575 0.500969 0.0263190 0.3321387 0.2470126 0.9099319 +VERTEX_SE3:QUAT 10 -0.513174 -0.278410 0.620923 0.3868254 0.1526889 -0.5244215 0.7429901 +VERTEX_SE3:QUAT 11 -0.604760 -0.355721 0.656392 0.2674510 -0.0764902 0.0925853 0.9560581 +VERTEX_SE3:QUAT 12 -0.836553 -0.556842 0.710170 0.7721025 -0.2651769 -0.5433285 0.1957882 +VERTEX_SE3:QUAT 13 -0.673061 -0.562811 0.623453 0.4337152 -0.2924323 0.7240629 0.4495635 +VERTEX_SE3:QUAT 14 -0.970307 -0.540970 0.633240 -0.0888079 -0.6283894 -0.1073711 0.7653178 +VERTEX_SE3:QUAT 15 -1.090121 -0.587995 0.620143 -0.4827769 0.0228671 0.8242683 0.2949327 +VERTEX_SE3:QUAT 16 -1.172299 -0.676092 0.737821 0.6879584 0.2115331 -0.0441989 0.6928300 +VERTEX_SE3:QUAT 17 -1.326495 -0.789751 0.731002 0.8367418 -0.1407275 -0.1578849 0.5051052 +VERTEX_SE3:QUAT 18 -1.526493 -0.990751 0.744112 0.3055521 -0.2957919 -0.7004199 0.5731990 +VERTEX_SE3:QUAT 19 -1.692313 -0.959709 0.790403 -0.0729745 -0.7494823 -0.0296840 0.6573202 +VERTEX_SE3:QUAT 20 -1.812862 -1.167663 0.883723 0.5680869 -0.3367005 0.2398704 0.7115984 +VERTEX_SE3:QUAT 21 -2.063870 -1.215131 0.988753 0.1487542 0.4701099 0.7942039 0.3551183 +VERTEX_SE3:QUAT 22 -2.175718 -1.270236 0.823978 -0.0890701 0.0889970 0.1065287 0.9863051 +VERTEX_SE3:QUAT 23 -2.295862 -1.352657 0.644169 -0.6110762 -0.3818089 0.3697963 0.5865651 +VERTEX_SE3:QUAT 24 -2.473597 -1.325644 0.625269 0.1304334 0.5912819 -0.7897578 0.0982625 +VERTEX_SE3:QUAT 25 -2.407234 -1.375511 0.657861 -0.6160138 -0.3637962 0.6712362 0.1939621 +VERTEX_SE3:QUAT 26 -2.626835 -1.329877 0.693426 -0.2016941 -0.6454046 0.1574964 0.7196994 +VERTEX_SE3:QUAT 27 -2.695383 -1.305755 0.665720 0.1040503 -0.3252416 -0.6584259 0.6707211 +VERTEX_SE3:QUAT 28 -2.763603 -1.240617 0.557498 -0.4147537 -0.4805760 0.6946883 0.3382813 +VERTEX_SE3:QUAT 29 -2.743962 -1.239434 0.533661 -0.4302718 -0.6509489 0.4586013 0.4252252 +VERTEX_SE3:QUAT 30 -2.507648 -1.219096 0.456273 0.5025869 -0.2692518 0.7913559 0.2206032 +VERTEX_SE3:QUAT 31 -2.646635 -1.195815 0.380741 0.5475409 0.2230999 0.6285520 0.5053195 +VERTEX_SE3:QUAT 32 -2.596070 -1.050014 0.304475 -0.0672419 0.5127964 -0.7593414 0.3948659 +VERTEX_SE3:QUAT 33 -2.672569 -0.773943 0.348443 0.4020036 -0.3477366 -0.8379509 0.1237360 +VERTEX_SE3:QUAT 34 -2.708475 -0.922321 0.271821 0.2790654 0.2217013 -0.2415303 0.9025708 +VERTEX_SE3:QUAT 35 -2.666172 -0.902543 0.131809 -0.2789093 0.2250885 0.9335576 0.0038757 +VERTEX_SE3:QUAT 36 -2.693258 -0.896196 0.136394 -0.5992585 -0.1561964 0.5996701 0.5068408 +VERTEX_SE3:QUAT 37 -2.763150 -0.850932 0.195975 -0.6968535 -0.3991258 0.5197613 0.2914481 +VERTEX_SE3:QUAT 38 -2.731442 -0.756498 0.319130 -0.2280655 -0.0323415 0.7858840 0.5738697 +VERTEX_SE3:QUAT 39 -2.745531 -0.847577 0.058677 -0.1330522 -0.5594200 -0.3443483 0.7421393 +VERTEX_SE3:QUAT 40 -2.856999 -1.065173 -0.006426 0.0695942 0.1330511 -0.8293879 0.5381169 +VERTEX_SE3:QUAT 41 -2.795976 -0.926721 -0.150345 0.1169122 -0.2532609 0.9575625 0.0725570 +VERTEX_SE3:QUAT 42 -2.937556 -0.851323 -0.108545 -0.0864233 -0.5041960 0.7861454 0.3468327 +VERTEX_SE3:QUAT 43 -2.959701 -0.845046 -0.050107 -0.1709688 0.4401921 -0.5005580 0.7255634 +VERTEX_SE3:QUAT 44 -2.880466 -0.867843 -0.196912 0.7646061 -0.4043684 0.3211937 0.3856141 +VERTEX_SE3:QUAT 45 -2.847214 -0.884779 -0.194817 0.1827943 0.2511762 -0.0479832 0.9493126 +VERTEX_SE3:QUAT 46 -2.691569 -0.986083 -0.282105 0.7359989 -0.2593073 0.2615202 0.5680427 +VERTEX_SE3:QUAT 47 -2.814438 -0.979455 -0.141429 -0.0835702 0.3633936 -0.9199410 0.1211185 +VERTEX_SE3:QUAT 48 -2.727364 -0.935981 -0.269518 -0.0266127 -0.3365504 0.4947674 0.8007689 +VERTEX_SE3:QUAT 49 -2.535668 -1.090325 -0.225383 0.1947425 -0.7422531 0.4883662 0.4154927 +VERTEX_SE3:QUAT 50 -2.535580 -1.034767 -0.269141 0.1322433 -0.4035479 -0.2642483 0.8659293 +VERTEX_SE3:QUAT 51 -2.668052 -0.856540 -0.252820 0.1652081 0.0013432 -0.1779002 0.9700804 +VERTEX_SE3:QUAT 52 -2.517779 -0.953699 -0.066115 -0.0103591 -0.0600994 -0.8392403 0.5403299 +VERTEX_SE3:QUAT 53 -2.443290 -0.865543 -0.064841 -0.0373889 0.0245756 0.5264511 0.8490273 +VERTEX_SE3:QUAT 54 -2.293934 -0.903599 -0.044849 -0.1379860 -0.3109309 -0.4947206 0.7997083 +VERTEX_SE3:QUAT 55 -2.218517 -0.914808 -0.009567 0.4679207 0.1970947 0.2336548 0.8292221 +VERTEX_SE3:QUAT 56 -2.259005 -0.941281 0.067088 0.6596827 -0.3964409 -0.2138562 0.6015969 +VERTEX_SE3:QUAT 57 -2.123728 -1.118281 -0.002121 0.2004443 0.2414774 0.4894718 0.8135896 +VERTEX_SE3:QUAT 58 -1.996927 -1.189264 -0.021211 -0.0308517 -0.8142867 0.5756675 0.0677663 +VERTEX_SE3:QUAT 59 -2.009508 -1.036705 -0.163595 0.0235143 0.3230296 -0.0231073 0.9458145 +VERTEX_SE3:QUAT 60 -1.828249 -1.044766 -0.340448 0.0776234 -0.2533165 0.4405218 0.8577563 +VERTEX_SE3:QUAT 61 -1.623349 -1.067130 -0.579204 0.1859905 0.1486972 -0.0635393 0.9691540 +VERTEX_SE3:QUAT 62 -1.615604 -1.222756 -0.584169 0.3681143 -0.1668680 -0.4086736 0.8183109 +VERTEX_SE3:QUAT 63 -1.736063 -1.289901 -0.582109 0.6273429 0.0824850 0.5477793 0.5473344 +VERTEX_SE3:QUAT 64 -1.788705 -1.302330 -0.636512 -0.3952978 0.4040119 -0.7345715 0.3753913 +VERTEX_SE3:QUAT 65 -1.584454 -1.223694 -0.671701 -0.5005419 0.1679690 0.7795570 0.3369497 +VERTEX_SE3:QUAT 66 -1.504169 -1.218132 -0.701656 0.5560645 0.3360457 -0.0752875 0.7564372 +VERTEX_SE3:QUAT 67 -1.349588 -1.199188 -0.630784 0.2547922 -0.4604027 0.8439540 0.1041727 +VERTEX_SE3:QUAT 68 -1.213458 -1.109557 -0.678065 -0.1002284 -0.7162915 0.2020910 0.6603332 +VERTEX_SE3:QUAT 69 -1.114327 -1.096945 -0.649818 0.5086453 -0.4846536 0.5273131 0.4778407 +VERTEX_SE3:QUAT 70 -1.152117 -1.101767 -0.626183 0.5703563 -0.4569173 0.5104016 0.4532224 +VERTEX_SE3:QUAT 71 -1.288149 -1.072047 -0.668451 0.1855253 -0.7868719 0.0200967 0.5882253 +VERTEX_SE3:QUAT 72 -1.266590 -1.011227 -0.671500 0.6742678 -0.0207873 -0.7273547 0.1260398 +VERTEX_SE3:QUAT 73 -1.398362 -1.035031 -0.456391 0.6245373 -0.2312914 0.6293634 0.4004487 +VERTEX_SE3:QUAT 74 -1.238726 -0.948733 -0.222399 0.2054299 -0.0648470 0.9695276 0.1166605 +VERTEX_SE3:QUAT 75 -1.237945 -0.823536 -0.285792 -0.2009919 -0.3344055 0.8682911 0.3063425 +VERTEX_SE3:QUAT 76 -1.286341 -0.785965 -0.178639 -0.1828775 -0.1925326 0.7608800 0.5920715 +VERTEX_SE3:QUAT 77 -1.313546 -0.695527 -0.026180 -0.1362446 0.1197366 0.9485974 0.2593521 +VERTEX_SE3:QUAT 78 -1.170249 -0.743657 -0.054629 -0.0747701 -0.1402337 0.5853531 0.7950508 +VERTEX_SE3:QUAT 79 -1.245165 -0.649248 -0.133948 -0.0604507 0.7131670 -0.6872651 0.1241179 +VERTEX_SE3:QUAT 80 -1.135814 -0.570140 -0.202518 -0.2338850 -0.5852256 0.1698107 0.7576101 +VERTEX_SE3:QUAT 81 -1.142007 -0.687554 -0.126413 -0.3748341 -0.0289844 0.3155636 0.8712514 +VERTEX_SE3:QUAT 82 -1.290257 -0.776640 0.034296 0.0443000 -0.6841647 0.3188923 0.6544188 +VERTEX_SE3:QUAT 83 -1.326736 -0.713843 -0.000907 0.1091281 -0.7370657 0.1527645 0.6492212 +VERTEX_SE3:QUAT 84 -1.261631 -0.651714 -0.057541 0.1764130 -0.1328943 -0.9640045 0.1480297 +VERTEX_SE3:QUAT 85 -1.309189 -0.566007 0.118202 0.6112718 0.4333507 -0.6582199 0.0728050 +VERTEX_SE3:QUAT 86 -1.423187 -0.534117 0.279904 0.6272630 0.2158803 0.4058677 0.6286559 +VERTEX_SE3:QUAT 87 -1.192123 -0.442507 0.332662 0.0721357 -0.6497422 0.7566918 0.0070034 +VERTEX_SE3:QUAT 88 -1.224558 -0.342284 0.400806 0.4642364 -0.2029329 -0.7464660 0.4313830 +VERTEX_SE3:QUAT 89 -1.078060 -0.407335 0.344191 0.4561865 -0.3030751 0.8341747 0.0647453 +VERTEX_SE3:QUAT 90 -0.994160 -0.556381 0.429492 0.0472126 0.5341082 -0.8435222 0.0311399 +VERTEX_SE3:QUAT 91 -0.933128 -0.532906 0.457751 0.2738058 -0.3245156 -0.4733508 0.7717895 +VERTEX_SE3:QUAT 92 -1.088515 -0.629433 0.476257 -0.0314480 -0.0099941 0.6779397 0.7343765 +VERTEX_SE3:QUAT 93 -1.042950 -0.602515 0.443215 0.2954656 -0.5502523 0.6481119 0.4357446 +VERTEX_SE3:QUAT 94 -1.141004 -0.808253 0.421128 0.4766566 -0.3506670 0.4681158 0.6562764 +VERTEX_SE3:QUAT 95 -1.067339 -0.829459 0.559363 0.4262365 -0.5251497 -0.2097812 0.7060680 +VERTEX_SE3:QUAT 96 -0.999812 -0.810316 0.560656 0.4475422 0.4047904 -0.7174330 0.3480526 +VERTEX_SE3:QUAT 97 -1.030799 -0.829358 0.699643 0.6061671 -0.4977866 -0.5849313 0.2064591 +VERTEX_SE3:QUAT 98 -0.968954 -0.775721 0.730081 0.0037375 0.4723549 -0.2448384 0.8467119 +VERTEX_SE3:QUAT 99 -0.900886 -0.930247 0.780775 -0.3305358 -0.2270055 0.6899379 0.6026610 +VERTEX_SE3:QUAT 100 -0.913514 -1.014108 0.776793 -0.0416355 0.5924437 -0.7378912 0.3206142 +VERTEX_SE3:QUAT 101 -1.039947 -1.029303 0.852695 -0.2388164 -0.7757898 0.4140718 0.4118997 +VERTEX_SE3:QUAT 102 -1.139577 -1.059063 0.966004 0.5029446 -0.5006737 0.6307222 0.3139460 +VERTEX_SE3:QUAT 103 -1.111089 -1.164175 0.962470 0.3380200 -0.7089569 0.5495596 0.2847926 +VERTEX_SE3:QUAT 104 -1.041680 -1.145875 0.906186 0.3879780 -0.6189360 0.5715147 0.3738478 +VERTEX_SE3:QUAT 105 -1.193615 -1.435401 0.885421 0.2060230 -0.0177925 0.3923878 0.8962532 +VERTEX_SE3:QUAT 106 -1.420317 -1.700036 0.816638 0.1157475 0.2089479 0.6256347 0.7426470 +VERTEX_SE3:QUAT 107 -1.360763 -1.922575 0.993415 0.3076686 0.8123005 -0.4767756 0.1348813 +VERTEX_SE3:QUAT 108 -1.356080 -2.041003 0.960908 0.2447006 0.1817661 -0.6191006 0.7237383 +VERTEX_SE3:QUAT 109 -1.408406 -2.038094 1.105362 0.7982644 -0.2467261 0.0380040 0.5481386 +VERTEX_SE3:QUAT 110 -1.443074 -1.907375 1.076968 -0.1585540 -0.6198434 0.6760517 0.3655255 +VERTEX_SE3:QUAT 111 -1.208567 -1.891734 1.065526 -0.5963019 -0.2996569 0.7239421 0.1747503 +VERTEX_SE3:QUAT 112 -1.183481 -1.757728 1.028622 0.1038087 -0.2743837 -0.4462117 0.8454776 +VERTEX_SE3:QUAT 113 -1.207669 -1.930700 1.174685 0.3857406 -0.3578172 -0.8467295 0.0788678 +VERTEX_SE3:QUAT 114 -1.324617 -1.766068 1.243313 0.1944647 -0.1813721 0.3603056 0.8941295 +VERTEX_SE3:QUAT 115 -1.402794 -1.876512 1.325223 -0.3435853 -0.0009511 -0.6296866 0.6967374 +VERTEX_SE3:QUAT 116 -1.366045 -1.671459 1.400361 0.0610012 -0.7938650 0.5701677 0.2024004 +VERTEX_SE3:QUAT 117 -1.551649 -1.691601 1.333379 0.3136434 -0.0855010 0.1646482 0.9312402 +VERTEX_SE3:QUAT 118 -1.645780 -1.782146 1.127931 0.2364730 0.4592629 -0.5605205 0.6472827 +VERTEX_SE3:QUAT 119 -1.636840 -1.824023 0.891030 0.2798234 0.5369028 -0.0784158 0.7920134 +VERTEX_SE3:QUAT 120 -1.708154 -1.824578 0.734961 -0.4061398 -0.8168463 0.4071411 0.0452624 +VERTEX_SE3:QUAT 121 -1.608607 -1.992596 0.874073 0.7697974 -0.3544421 0.4927096 0.1975347 +VERTEX_SE3:QUAT 122 -1.805326 -1.926523 0.770516 0.8731937 -0.0633298 -0.4495270 0.1773348 +VERTEX_SE3:QUAT 123 -1.795803 -2.033082 0.797324 -0.4685090 -0.4927349 0.6607951 0.3179016 +VERTEX_SE3:QUAT 124 -1.814397 -1.847495 0.685534 0.0346798 -0.7408845 0.2017155 0.6396861 +VERTEX_SE3:QUAT 125 -1.990930 -1.710064 0.561780 0.0878138 -0.0605844 -0.8510941 0.5140594 +VERTEX_SE3:QUAT 126 -2.086356 -1.692212 0.500943 0.5403802 -0.3582538 0.6008503 0.4675708 +VERTEX_SE3:QUAT 127 -2.287485 -1.595071 0.568112 0.1982456 0.7785924 -0.3469133 0.4838841 +VERTEX_SE3:QUAT 128 -2.207309 -1.616934 0.484753 -0.3413878 0.6977802 -0.4978452 0.3856258 +VERTEX_SE3:QUAT 129 -2.078640 -1.601267 0.437775 0.2855727 -0.6164227 0.2932500 0.6726631 +VERTEX_SE3:QUAT 130 -2.060746 -1.590771 0.404858 -0.4021055 0.1749803 -0.8967761 0.0590391 +VERTEX_SE3:QUAT 131 -2.031146 -1.666403 0.320829 -0.1280416 -0.7144843 0.3371544 0.5995368 +VERTEX_SE3:QUAT 132 -1.927298 -1.748984 0.181806 0.6474824 -0.4973031 -0.3693153 0.4439171 +VERTEX_SE3:QUAT 133 -1.917672 -1.702715 0.177823 0.0150614 -0.1705312 -0.4588015 0.8718907 +VERTEX_SE3:QUAT 134 -1.796868 -1.645910 0.138486 0.1742071 -0.4740849 0.8525624 0.1342861 +VERTEX_SE3:QUAT 135 -1.835061 -1.650781 0.087025 -0.2737497 -0.0828504 -0.9449160 0.1591559 +VERTEX_SE3:QUAT 136 -1.717935 -1.674844 -0.036820 0.6967717 0.0236592 -0.4226455 0.5790683 +VERTEX_SE3:QUAT 137 -1.741287 -1.844348 -0.130069 0.6555746 -0.1513158 0.4837165 0.5597712 +VERTEX_SE3:QUAT 138 -1.611846 -1.717676 -0.162533 0.0242821 0.2461029 -0.8294190 0.5009070 +VERTEX_SE3:QUAT 139 -1.565096 -1.763176 -0.266518 0.1030297 0.3173546 -0.7226216 0.6053833 +VERTEX_SE3:QUAT 140 -1.606324 -1.637881 -0.211229 0.5861768 -0.2513925 0.3284945 0.6966275 +VERTEX_SE3:QUAT 141 -1.684734 -1.690623 -0.132358 0.2121701 -0.7469598 0.0650784 0.6267374 +VERTEX_SE3:QUAT 142 -1.754579 -1.478533 -0.069176 -0.1204396 0.6018785 -0.7500831 0.2461949 +VERTEX_SE3:QUAT 143 -1.703057 -1.382709 -0.092996 -0.1100547 -0.1940114 -0.6726649 0.7055278 +VERTEX_SE3:QUAT 144 -1.691049 -1.313826 -0.170230 0.1037530 -0.2993558 0.7198490 0.6176074 +VERTEX_SE3:QUAT 145 -1.649367 -1.177926 -0.025962 0.0978766 -0.0263016 0.7714233 0.6281994 +VERTEX_SE3:QUAT 146 -1.569075 -1.111474 -0.153371 0.0501230 -0.1267166 -0.1987293 0.9705345 +VERTEX_SE3:QUAT 147 -1.490391 -1.054944 -0.218114 0.6459023 -0.2952526 0.0433431 0.7026788 +VERTEX_SE3:QUAT 148 -1.356452 -1.099689 -0.214762 -0.4258030 -0.0510937 0.7959330 0.4272844 +VERTEX_SE3:QUAT 149 -1.311046 -1.100709 -0.373929 0.5791938 -0.5015185 0.1605112 0.6222940 +VERTEX_SE3:QUAT 150 -1.300316 -1.053510 -0.288831 0.0954430 0.2914912 -0.4393667 0.8443225 +VERTEX_SE3:QUAT 151 -1.233507 -0.968520 -0.176885 -0.0253276 -0.1286707 0.0770035 0.9883688 +VERTEX_SE3:QUAT 152 -1.417433 -0.965619 -0.355235 0.6793673 -0.2165452 0.3146096 0.6265692 +VERTEX_SE3:QUAT 153 -1.321708 -0.746952 -0.194308 -0.1378750 -0.2501841 0.9291167 0.2348201 +VERTEX_SE3:QUAT 154 -1.560875 -0.739417 -0.219565 -0.0176753 -0.7123391 0.2044509 0.6711635 +VERTEX_SE3:QUAT 155 -1.712811 -0.772916 -0.412982 0.2160697 -0.7344967 0.3157018 0.5605005 +VERTEX_SE3:QUAT 156 -1.807192 -0.633931 -0.373409 0.2283723 -0.2891861 0.2875525 0.8840424 +VERTEX_SE3:QUAT 157 -1.857106 -0.551214 -0.396422 -0.2234043 -0.7958160 0.4125851 0.3828067 +VERTEX_SE3:QUAT 158 -1.897712 -0.415574 -0.464857 -0.0388913 0.1057610 -0.9912309 0.0690169 +VERTEX_SE3:QUAT 159 -1.882634 -0.362018 -0.594768 -0.5413213 -0.6970283 0.2134050 0.4190241 +VERTEX_SE3:QUAT 160 -1.842404 -0.266565 -0.603972 -0.4877364 -0.2006383 0.8456147 0.0824206 +VERTEX_SE3:QUAT 161 -1.877453 -0.218819 -0.584749 -0.1052472 0.4857860 -0.7722018 0.3957769 +VERTEX_SE3:QUAT 162 -1.674495 -0.306134 -0.690975 -0.5580179 -0.6634682 0.3887660 0.3119086 +VERTEX_SE3:QUAT 163 -1.582338 -0.223848 -0.769331 0.7275092 -0.5247100 -0.2861539 0.3369360 +VERTEX_SE3:QUAT 164 -1.435108 -0.167340 -0.628048 0.0807178 -0.3023865 0.0465244 0.9486214 +VERTEX_SE3:QUAT 165 -1.427566 -0.015966 -0.509032 0.3077121 -0.6113719 -0.4160816 0.5986766 +VERTEX_SE3:QUAT 166 -1.515788 0.169562 -0.425874 -0.1065253 0.6066686 -0.6572552 0.4343053 +VERTEX_SE3:QUAT 167 -1.561180 0.229029 -0.609358 0.5686362 0.1396420 0.1180582 0.8020070 +VERTEX_SE3:QUAT 168 -1.370568 0.346730 -0.536328 0.6349857 0.4839654 -0.2341083 0.5547648 +VERTEX_SE3:QUAT 169 -1.265390 0.324679 -0.560420 0.1581051 -0.4072851 -0.2019829 0.8765413 +VERTEX_SE3:QUAT 170 -1.168580 0.298411 -0.494498 0.0814989 0.2393942 0.6566003 0.7105803 +VERTEX_SE3:QUAT 171 -1.006807 0.410509 -0.380041 -0.0701982 -0.5365068 -0.0935529 0.8357515 +VERTEX_SE3:QUAT 172 -0.972828 0.630518 -0.386882 0.3883858 -0.7289106 -0.0114435 0.5636619 +VERTEX_SE3:QUAT 173 -1.091421 0.621547 -0.302537 0.7928738 0.3826248 -0.3702835 0.2963774 +VERTEX_SE3:QUAT 174 -1.031471 0.791568 -0.159915 0.3269701 -0.4015288 0.4836039 0.7056858 +VERTEX_SE3:QUAT 175 -1.004699 0.758303 -0.026884 -0.3618397 -0.7651167 0.5184684 0.1218975 +VERTEX_SE3:QUAT 176 -1.026482 0.759440 -0.029127 0.0229421 -0.0486326 0.7572103 0.6509540 +VERTEX_SE3:QUAT 177 -1.257380 0.818189 -0.130483 0.0747008 -0.7205567 0.6787450 0.1205122 +VERTEX_SE3:QUAT 178 -1.389916 0.843706 -0.143288 0.3083316 -0.5078416 -0.2061374 0.7775191 +VERTEX_SE3:QUAT 179 -1.465261 1.034917 -0.206131 0.3043050 0.1040129 -0.0895739 0.9426326 +VERTEX_SE3:QUAT 180 -1.565134 0.931231 -0.110277 0.1474822 0.1622498 0.9731095 0.0705832 +VERTEX_SE3:QUAT 181 -1.783534 0.984993 -0.145429 0.0039579 0.1411725 -0.9834388 0.1135904 +VERTEX_SE3:QUAT 182 -1.723251 0.872665 -0.138227 0.1946640 -0.0215655 -0.3213733 0.9264772 +VERTEX_SE3:QUAT 183 -1.904595 0.871594 -0.043743 -0.0913073 0.1283546 0.8223418 0.5467560 +VERTEX_SE3:QUAT 184 -1.786749 0.916628 -0.334303 0.6362635 -0.1052979 0.5606566 0.5193701 +VERTEX_SE3:QUAT 185 -1.625012 0.929359 -0.316919 0.0453924 -0.7891648 0.5112176 0.3373649 +VERTEX_SE3:QUAT 186 -1.531523 1.086555 -0.190250 0.0843562 -0.5741987 -0.3159568 0.7505672 +VERTEX_SE3:QUAT 187 -1.480758 1.082758 -0.063573 -0.5316813 -0.2256304 0.0974307 0.8105018 +VERTEX_SE3:QUAT 188 -1.425966 1.149225 0.066952 0.0256978 0.1308014 -0.8130058 0.5667912 +VERTEX_SE3:QUAT 189 -1.397709 1.205099 0.070260 -0.0436804 0.4533157 -0.8513902 0.2602531 +VERTEX_SE3:QUAT 190 -1.291162 1.116224 0.036171 0.1402309 0.4754769 -0.1320994 0.8583745 +VERTEX_SE3:QUAT 191 -1.295899 1.024659 0.012023 -0.1861694 -0.8739485 0.1357157 0.4279441 +VERTEX_SE3:QUAT 192 -1.183238 1.122331 -0.049805 -0.1399130 -0.0163313 0.5911939 0.7941331 +VERTEX_SE3:QUAT 193 -1.368349 1.118120 -0.054783 0.1597291 0.1037201 0.9245183 0.3301434 +VERTEX_SE3:QUAT 194 -1.209909 1.185689 0.000030 -0.1837937 0.2787390 -0.5601159 0.7581521 +VERTEX_SE3:QUAT 195 -1.206645 1.179327 0.116707 -0.2554897 -0.8060434 0.4886876 0.2149498 +VERTEX_SE3:QUAT 196 -1.052089 0.949021 0.015134 0.1334159 -0.6666425 -0.0000725 0.7333403 +VERTEX_SE3:QUAT 197 -0.916654 0.827590 0.034466 -0.1241737 0.4733532 -0.7476805 0.4488780 +VERTEX_SE3:QUAT 198 -0.986048 0.881324 0.141466 0.9003308 -0.1675035 -0.3492721 0.1983834 +VERTEX_SE3:QUAT 199 -0.837252 0.901839 -0.057930 -0.0066037 -0.1430481 0.9117196 0.3850467 +VERTEX_SE3:QUAT 200 -1.058998 0.882461 -0.078615 0.6764477 -0.1188299 0.5111820 0.5167117 +VERTEX_SE3:QUAT 201 -1.064475 0.835148 -0.108548 0.1177361 0.7475817 -0.6518624 0.0483237 +VERTEX_SE3:QUAT 202 -1.092810 0.808870 0.032709 0.1005076 -0.1097662 -0.8130536 0.5628441 +VERTEX_SE3:QUAT 203 -1.092057 0.818120 -0.086546 0.8391963 0.1640695 -0.3995811 0.3304025 +VERTEX_SE3:QUAT 204 -1.070673 0.737920 -0.234313 0.6304602 -0.0270689 0.4058632 0.6611068 +VERTEX_SE3:QUAT 205 -1.056192 0.614811 -0.187167 0.3501520 -0.4765105 -0.2318975 0.7723696 +VERTEX_SE3:QUAT 206 -1.168792 0.585264 -0.224638 -0.2958166 -0.7915222 0.5037178 0.1795928 +VERTEX_SE3:QUAT 207 -1.220038 0.494612 -0.177750 0.7528744 -0.3049365 -0.1186148 0.5710731 +VERTEX_SE3:QUAT 208 -1.187330 0.667659 -0.152105 0.6345004 -0.3498358 -0.6884830 0.0318640 +VERTEX_SE3:QUAT 209 -1.100974 0.735404 -0.244914 0.0883421 0.1836115 0.9758657 0.0785402 +VERTEX_SE3:QUAT 210 -1.136603 0.654270 -0.165102 -0.2111236 -0.8495102 0.4183549 0.2423599 +VERTEX_SE3:QUAT 211 -1.159984 0.787694 -0.255550 -0.0858695 -0.8259934 0.5184184 0.2039700 +VERTEX_SE3:QUAT 212 -1.027290 0.690892 -0.174561 0.0170555 -0.5022735 0.5930168 0.6290957 +VERTEX_SE3:QUAT 213 -0.959407 0.574941 -0.114817 0.1530403 -0.7614661 0.0333162 0.6289977 +VERTEX_SE3:QUAT 214 -0.924277 0.537894 -0.170732 -0.6017387 -0.2529585 0.3157232 0.6886519 +VERTEX_SE3:QUAT 215 -1.070232 0.483686 -0.182379 -0.5066807 0.5368465 0.6726107 0.0516271 +VERTEX_SE3:QUAT 216 -1.040755 0.491963 -0.256266 0.3698869 -0.5761490 -0.4660767 0.5603647 +VERTEX_SE3:QUAT 217 -1.158588 0.447221 -0.378704 -0.0249990 -0.9208567 0.3777279 0.0933793 +VERTEX_SE3:QUAT 218 -1.141877 0.341054 -0.327873 0.8602754 -0.0491389 -0.1478339 0.4854450 +VERTEX_SE3:QUAT 219 -1.280975 0.246674 -0.287189 0.5359138 0.0673197 -0.7352008 0.4095659 +VERTEX_SE3:QUAT 220 -1.175587 0.193090 -0.356888 0.2291790 -0.1925315 -0.9444343 0.1358399 +VERTEX_SE3:QUAT 221 -1.348717 0.359762 -0.499825 -0.0679112 -0.3806921 0.9206431 0.0536459 +VERTEX_SE3:QUAT 222 -1.441927 0.260629 -0.569654 0.0967056 -0.6286326 0.7145637 0.2913208 +VERTEX_SE3:QUAT 223 -1.367814 0.125717 -0.639984 0.0922128 0.0632663 0.9937233 0.0028459 +VERTEX_SE3:QUAT 224 -1.309270 0.142925 -0.649651 0.1881404 0.5151063 -0.6284908 0.5516050 +VERTEX_SE3:QUAT 225 -1.438906 0.183449 -0.934934 -0.5527248 0.4248961 0.7147739 0.0552880 +VERTEX_SE3:QUAT 226 -1.657822 0.071962 -1.047261 -0.6682914 -0.3560486 0.6473313 0.0870524 +VERTEX_SE3:QUAT 227 -1.787544 -0.068662 -0.877828 0.1267011 -0.1464920 0.4630050 0.8649354 +VERTEX_SE3:QUAT 228 -1.894814 -0.227528 -0.833676 0.1671401 -0.0301677 -0.4332525 0.8851250 +VERTEX_SE3:QUAT 229 -1.882989 -0.317120 -0.764907 -0.5252470 0.0208502 0.6784452 0.5132183 +VERTEX_SE3:QUAT 230 -1.943734 -0.314567 -0.869267 -0.1110985 0.1411268 -0.9541127 0.2396025 +VERTEX_SE3:QUAT 231 -1.862521 -0.292071 -1.059659 0.6923056 -0.0188200 -0.4826404 0.5361129 +VERTEX_SE3:QUAT 232 -1.931614 -0.487920 -1.171038 0.4604285 -0.2560658 0.0935985 0.8447930 +VERTEX_SE3:QUAT 233 -1.786606 -0.521898 -1.190652 0.2401864 0.0774200 -0.2440757 0.9363459 +VERTEX_SE3:QUAT 234 -1.597263 -0.407113 -1.190311 -0.2835848 0.1700897 0.7253115 0.6037983 +VERTEX_SE3:QUAT 235 -1.598405 -0.537773 -1.145750 0.2022110 0.5610756 -0.3007762 0.7442033 +VERTEX_SE3:QUAT 236 -1.567688 -0.528070 -1.067053 -0.3879779 0.2069889 -0.7748914 0.4540617 +VERTEX_SE3:QUAT 237 -1.664109 -0.656024 -1.029507 0.4070559 0.0621888 -0.6161263 0.6714361 +VERTEX_SE3:QUAT 238 -1.642706 -0.655488 -1.105704 -0.1778587 0.0144824 -0.8446404 0.5047170 +VERTEX_SE3:QUAT 239 -1.788048 -0.606359 -1.214111 -0.2178083 0.0447150 -0.7791763 0.5860413 +VERTEX_SE3:QUAT 240 -1.732263 -0.564918 -1.124865 -0.2259361 -0.4960782 0.5788677 0.6064417 +VERTEX_SE3:QUAT 241 -1.682433 -0.424527 -1.201162 -0.2301032 0.2758664 -0.9311728 0.0621887 +VERTEX_SE3:QUAT 242 -1.596554 -0.291154 -1.114515 0.6305754 0.2496557 -0.7345501 0.0219730 +VERTEX_SE3:QUAT 243 -1.548082 -0.256160 -1.062540 -0.1179350 0.4957062 -0.6291044 0.5870216 +VERTEX_SE3:QUAT 244 -1.605327 -0.322186 -1.233792 0.4795602 -0.5144302 0.5227819 0.4817496 +VERTEX_SE3:QUAT 245 -1.729682 -0.224500 -1.266890 -0.0255142 -0.3360351 0.3195675 0.8856105 +VERTEX_SE3:QUAT 246 -1.757100 -0.223250 -1.431506 0.1168737 -0.0043162 0.8415774 0.5273228 +VERTEX_SE3:QUAT 247 -1.796099 -0.059358 -1.462379 0.3186950 -0.7057450 0.6321451 0.0273884 +VERTEX_SE3:QUAT 248 -1.941106 -0.135187 -1.369875 0.4705004 -0.1829642 0.4824839 0.7157952 +VERTEX_SE3:QUAT 249 -1.698357 -0.073136 -1.357559 -0.6125185 -0.5819634 0.5324128 0.0517328 +VERTEX_SE3:QUAT 250 -1.543524 -0.051850 -1.406114 0.6080668 0.3947076 -0.6773642 0.1250539 +VERTEX_SE3:QUAT 251 -1.633244 0.052100 -1.334657 0.2002782 -0.1872453 -0.8351429 0.4768272 +VERTEX_SE3:QUAT 252 -1.671115 0.258128 -1.386004 0.4805579 -0.3417660 0.2225791 0.7763496 +VERTEX_SE3:QUAT 253 -1.517740 0.315685 -1.438155 0.7916071 -0.1004806 0.4689250 0.3786438 +VERTEX_SE3:QUAT 254 -1.525043 0.339772 -1.587544 -0.3578216 -0.8380216 0.2393307 0.3352675 +VERTEX_SE3:QUAT 255 -1.494359 0.343521 -1.555358 -0.1512276 -0.8017186 0.5581644 0.1510959 +VERTEX_SE3:QUAT 256 -1.375424 0.442377 -1.503935 0.4160113 -0.4904864 0.2674719 0.7175071 +VERTEX_SE3:QUAT 257 -1.417067 0.517791 -1.414206 0.6508275 -0.2631980 0.5762760 0.4183973 +VERTEX_SE3:QUAT 258 -1.194921 0.495726 -1.414562 0.0985534 -0.4009015 0.7912839 0.4510377 +VERTEX_SE3:QUAT 259 -1.112364 0.580861 -1.586859 0.8164982 -0.2511180 -0.0171399 0.5195928 +VERTEX_SE3:QUAT 260 -1.058421 0.624425 -1.402469 -0.0222184 0.1095414 0.8430451 0.5261007 +VERTEX_SE3:QUAT 261 -1.137603 0.767398 -1.558063 -0.2063077 -0.2377805 -0.4947937 0.8099856 +VERTEX_SE3:QUAT 262 -1.189188 0.898627 -1.651857 0.5884906 -0.4238707 -0.6689585 0.1628095 +VERTEX_SE3:QUAT 263 -1.139167 1.031292 -1.687108 0.2454308 -0.2330787 0.5661161 0.7516320 +VERTEX_SE3:QUAT 264 -1.085131 1.156237 -1.703023 0.8644094 0.1502532 -0.0683069 0.4749259 +VERTEX_SE3:QUAT 265 -0.998983 1.089213 -1.735010 0.4567019 -0.4995575 0.3937252 0.6219695 +VERTEX_SE3:QUAT 266 -0.910909 1.142733 -1.740719 -0.3442678 -0.2967466 0.7895590 0.4123320 +VERTEX_SE3:QUAT 267 -0.944632 1.168543 -1.688269 0.0527768 -0.4729069 -0.8405831 0.2588314 +VERTEX_SE3:QUAT 268 -0.877410 1.338466 -1.730554 -0.0982545 0.1063175 0.2009293 0.9688499 +VERTEX_SE3:QUAT 269 -0.827513 1.348162 -1.806809 0.6800755 -0.0935319 0.4689443 0.5557340 +VERTEX_SE3:QUAT 270 -0.885926 1.329373 -1.835890 0.0306415 -0.9155438 0.2832172 0.2839519 +VERTEX_SE3:QUAT 271 -0.937967 1.480747 -1.694815 0.1215212 0.3842671 -0.8101404 0.4257276 +VERTEX_SE3:QUAT 272 -0.910306 1.454613 -1.736076 0.5396273 -0.6405894 0.1902926 0.5120901 +VERTEX_SE3:QUAT 273 -0.956296 1.367670 -1.722058 -0.0412652 0.5642082 -0.7970428 0.2113978 +VERTEX_SE3:QUAT 274 -0.897764 1.527799 -1.553473 0.5497227 -0.2823199 -0.7565141 0.2139785 +VERTEX_SE3:QUAT 275 -0.967969 1.456537 -1.565205 -0.6104557 -0.4930710 0.5557466 0.2745370 +VERTEX_SE3:QUAT 276 -0.928466 1.420281 -1.356467 -0.0773832 0.0007044 0.9900032 0.1179195 +VERTEX_SE3:QUAT 277 -0.995405 1.451089 -1.293224 -0.3180390 -0.1188722 0.6782112 0.6517286 +VERTEX_SE3:QUAT 278 -1.055571 1.498821 -1.387586 0.3504851 0.6464873 -0.6745751 0.0645194 +VERTEX_SE3:QUAT 279 -1.131755 1.472868 -1.287833 -0.1843223 -0.2769887 0.9027167 0.2727731 +VERTEX_SE3:QUAT 280 -0.958658 1.376395 -0.994127 -0.7143788 0.1814671 0.6627582 0.1322277 +VERTEX_SE3:QUAT 281 -0.972928 1.240116 -0.976346 -0.4106858 -0.1234646 0.8993173 0.0855696 +VERTEX_SE3:QUAT 282 -0.975190 1.348102 -1.143014 -0.6196639 -0.4429447 0.6460122 0.0498483 +VERTEX_SE3:QUAT 283 -0.804823 1.371008 -1.265594 0.1228480 -0.5962632 0.6162946 0.4995593 +VERTEX_SE3:QUAT 284 -0.839379 1.375758 -1.171006 0.1153300 -0.5412158 -0.4155426 0.7218787 +VERTEX_SE3:QUAT 285 -0.935934 1.428711 -1.118850 0.6728174 0.4231943 -0.5957157 0.1155250 +VERTEX_SE3:QUAT 286 -0.945851 1.420810 -1.091150 0.4028118 -0.4983158 0.7030257 0.3085108 +VERTEX_SE3:QUAT 287 -1.038084 1.297836 -0.947524 0.8846247 0.2696962 -0.0919495 0.3691184 +VERTEX_SE3:QUAT 288 -0.987110 1.222479 -0.831752 0.2529105 -0.3933488 -0.8689720 0.1618664 +VERTEX_SE3:QUAT 289 -0.916028 1.216458 -0.773885 -0.1159554 -0.1211369 -0.7154704 0.6782200 +VERTEX_SE3:QUAT 290 -0.959232 1.084665 -0.673110 0.7255833 -0.5959382 -0.0143787 0.3437730 +VERTEX_SE3:QUAT 291 -0.917096 1.058760 -0.839101 -0.0183467 -0.4400043 -0.5178062 0.7334415 +VERTEX_SE3:QUAT 292 -1.171843 1.101063 -0.933818 0.1652742 0.6714717 -0.6653759 0.2812207 +VERTEX_SE3:QUAT 293 -1.223561 1.164525 -0.862613 0.6898666 0.0202679 -0.1971948 0.6962668 +VERTEX_SE3:QUAT 294 -1.396298 1.300245 -0.687657 0.3519219 -0.5303071 0.2256932 0.7375554 +VERTEX_SE3:QUAT 295 -1.393639 1.340206 -0.717796 0.0408217 0.4871560 -0.7496565 0.4461253 +VERTEX_SE3:QUAT 296 -1.538726 1.154444 -0.679270 0.3447942 -0.4003825 -0.0850068 0.8447394 +VERTEX_SE3:QUAT 297 -1.616892 1.109835 -0.662400 0.1065851 -0.3205901 -0.7753795 0.5335243 +VERTEX_SE3:QUAT 298 -1.561347 1.134126 -0.614175 0.0936879 -0.4877351 0.7136195 0.4940489 +VERTEX_SE3:QUAT 299 -1.552561 0.933672 -0.763875 0.5438193 0.5566873 -0.5895464 0.2163213 +VERTEX_SE3:QUAT 300 -1.591183 0.948771 -0.959156 -0.2732264 0.1375397 -0.6159019 0.7260131 +VERTEX_SE3:QUAT 301 -1.628140 1.036672 -0.838420 0.4899438 0.6639104 -0.4377525 0.3571426 +VERTEX_SE3:QUAT 302 -1.672524 0.975162 -0.707540 0.1832745 -0.5523663 0.3041140 0.7541993 +VERTEX_SE3:QUAT 303 -1.541434 0.961778 -0.747145 0.3128198 0.1472993 0.8628452 0.3687070 +VERTEX_SE3:QUAT 304 -1.568420 0.880580 -0.550174 0.0017814 0.7976526 -0.5660164 0.2082610 +VERTEX_SE3:QUAT 305 -1.678094 0.871806 -0.402796 0.1976452 0.3197619 0.8529926 0.3620668 +VERTEX_SE3:QUAT 306 -1.847659 1.001714 -0.345673 0.5264759 0.2116391 0.5500344 0.6127758 +VERTEX_SE3:QUAT 307 -1.637999 0.811169 -0.369975 -0.1792159 -0.3282195 -0.1602395 0.9134971 +VERTEX_SE3:QUAT 308 -1.654735 0.736614 -0.382510 0.8130474 0.2930767 -0.0697569 0.4981906 +VERTEX_SE3:QUAT 309 -1.733332 0.674486 -0.453425 -0.0737501 -0.7261910 0.3108045 0.6087759 +VERTEX_SE3:QUAT 310 -1.661902 0.618449 -0.528789 0.2577536 -0.7164593 0.6174217 0.1975846 +VERTEX_SE3:QUAT 311 -1.639580 0.578515 -0.286358 0.3191290 0.6814306 -0.5884623 0.2958397 +VERTEX_SE3:QUAT 312 -1.675319 0.469642 -0.286186 0.2315201 -0.4552223 0.6921654 0.5099786 +VERTEX_SE3:QUAT 313 -1.859470 0.667000 -0.263425 0.3003677 -0.1532600 -0.8897837 0.3075316 +VERTEX_SE3:QUAT 314 -1.848277 0.643349 -0.385191 0.2245091 -0.2816488 -0.4838084 0.7976209 +VERTEX_SE3:QUAT 315 -1.737479 0.725916 -0.319072 0.5107992 -0.1440304 0.2137096 0.8201632 +VERTEX_SE3:QUAT 316 -1.664497 0.496625 -0.218300 0.4677128 0.5557129 -0.5726790 0.3800877 +VERTEX_SE3:QUAT 317 -1.653171 0.404776 0.044410 0.2278737 0.3218160 0.7450999 0.5378979 +VERTEX_SE3:QUAT 318 -1.768401 0.361249 0.039010 -0.3153261 0.3759125 -0.8152966 0.3074909 +VERTEX_SE3:QUAT 319 -1.900472 0.195737 0.032512 0.0279540 -0.4640058 0.0972268 0.8800364 +VERTEX_SE3:QUAT 320 -1.985140 0.319747 0.155012 -0.1416755 0.6047445 -0.7265013 0.2939524 +VERTEX_SE3:QUAT 321 -2.119934 0.313550 0.197809 0.1694908 0.5644935 -0.6671012 0.4556269 +VERTEX_SE3:QUAT 322 -2.123754 0.243064 0.271135 -0.4241511 -0.3288859 0.2984646 0.7892077 +VERTEX_SE3:QUAT 323 -2.046142 0.267986 0.331317 -0.2072401 -0.2074938 0.5661946 0.7703385 +VERTEX_SE3:QUAT 324 -2.081101 0.251234 0.379046 0.0132603 0.0487534 0.9180572 0.3932153 +VERTEX_SE3:QUAT 325 -2.304759 0.199077 0.324287 0.1830811 0.0990427 0.9762121 0.0606782 +VERTEX_SE3:QUAT 326 -2.229498 0.236520 0.370400 0.0838910 -0.3417034 -0.7877346 0.5056434 +VERTEX_SE3:QUAT 327 -2.330273 0.160795 0.191368 0.0974952 0.2111821 0.6553873 0.7185850 +VERTEX_SE3:QUAT 328 -2.444116 0.059897 0.173014 -0.2715997 -0.3532007 0.0599321 0.8932475 +VERTEX_SE3:QUAT 329 -2.510515 0.073640 0.128592 0.3297352 0.1948839 -0.9145332 0.1300927 +VERTEX_SE3:QUAT 330 -2.417047 0.031837 -0.051430 0.3141050 0.0379963 -0.4766060 0.8202079 +VERTEX_SE3:QUAT 331 -2.314157 0.008103 -0.029128 0.7951628 -0.2307275 -0.4089393 0.3837311 +VERTEX_SE3:QUAT 332 -2.280775 0.055121 -0.052932 -0.4941736 -0.1894212 0.8277689 0.1863082 +VERTEX_SE3:QUAT 333 -2.217943 0.000891 -0.173275 -0.5987280 0.3196796 0.6420931 0.3564354 +VERTEX_SE3:QUAT 334 -2.120071 0.018770 -0.154984 0.3952576 0.1539486 0.8754395 0.2316828 +VERTEX_SE3:QUAT 335 -2.132624 0.092896 -0.056746 0.4090374 0.6010981 -0.3907054 0.5645519 +VERTEX_SE3:QUAT 336 -2.102151 0.122414 -0.130006 0.8008727 -0.0625940 -0.3852764 0.4541443 +VERTEX_SE3:QUAT 337 -2.188158 -0.016564 -0.020786 -0.0710821 -0.3922644 0.1146447 0.9099080 +VERTEX_SE3:QUAT 338 -2.322176 0.011498 -0.201947 -0.3950458 -0.0755304 -0.0162730 0.9154066 +VERTEX_SE3:QUAT 339 -2.421988 0.057063 -0.146886 -0.0051844 0.0578138 0.9296747 0.3637796 +VERTEX_SE3:QUAT 340 -2.303761 0.081406 -0.307393 0.1090469 -0.3800598 0.4808791 0.7825718 +VERTEX_SE3:QUAT 341 -2.198755 0.064171 -0.461700 -0.0164663 -0.1708891 0.5826169 0.7944076 +VERTEX_SE3:QUAT 342 -1.822022 -0.013327 -0.584743 -0.2458988 -0.1537278 -0.5197195 0.8036126 +VERTEX_SE3:QUAT 343 -1.811687 0.026757 -0.631224 0.2759374 -0.0507783 -0.9462436 0.1609447 +VERTEX_SE3:QUAT 344 -1.923722 -0.057739 -0.687889 0.0016035 -0.6645641 0.2619914 0.6997946 +VERTEX_SE3:QUAT 345 -1.828937 -0.004882 -0.733026 0.1938508 -0.6591913 -0.6374924 0.3485572 +VERTEX_SE3:QUAT 346 -1.733837 0.116887 -0.752360 0.2460861 -0.6315384 0.2061629 0.7057604 +VERTEX_SE3:QUAT 347 -1.674130 0.207145 -0.770212 -0.3761643 -0.5142138 0.0005124 0.7707687 +VERTEX_SE3:QUAT 348 -1.567744 0.380916 -0.898392 0.1597457 0.2394939 0.6583010 0.6955313 +VERTEX_SE3:QUAT 349 -1.589258 0.443602 -0.752980 0.0796651 0.8258747 -0.5556619 0.0531451 +VERTEX_SE3:QUAT 350 -1.501389 0.575034 -0.919683 0.4393123 -0.5112663 0.5186162 0.5259741 +VERTEX_SE3:QUAT 351 -1.483063 0.662120 -0.962574 0.6177582 -0.2213274 0.4731216 0.5878307 +VERTEX_SE3:QUAT 352 -1.507496 0.703762 -1.027313 -0.6147984 -0.5548496 0.5082417 0.2363373 +VERTEX_SE3:QUAT 353 -1.573818 0.833846 -1.059452 -0.2786091 0.3193269 0.1399749 0.8948823 +VERTEX_SE3:QUAT 354 -1.462290 0.920403 -1.041296 0.6998317 0.1669252 -0.5510127 0.4227961 +VERTEX_SE3:QUAT 355 -1.391597 1.004694 -1.173920 0.0236542 0.4910981 0.5984856 0.6325172 +VERTEX_SE3:QUAT 356 -1.323868 1.019087 -1.137304 0.7115077 0.0611024 -0.2588311 0.6504074 +VERTEX_SE3:QUAT 357 -1.310508 0.958642 -1.136648 -0.4074154 -0.1054996 -0.6336319 0.6491480 +VERTEX_SE3:QUAT 358 -1.154069 1.165430 -1.178766 -0.2627312 0.2787163 -0.0388647 0.9229188 +VERTEX_SE3:QUAT 359 -1.054512 1.253812 -1.276563 -0.5280060 0.1512624 0.8152454 0.1835872 +VERTEX_SE3:QUAT 360 -0.946584 1.350339 -1.349503 0.2940152 -0.1587506 0.7860807 0.5200292 +VERTEX_SE3:QUAT 361 -0.944575 1.409564 -1.481354 -0.0125561 0.4541141 -0.1233982 0.8822673 +VERTEX_SE3:QUAT 362 -0.768306 1.321151 -1.439735 0.0377449 0.6504313 -0.7555617 0.0681245 +VERTEX_SE3:QUAT 363 -0.901307 1.227680 -1.586427 0.2052378 -0.4144110 -0.5648771 0.6834141 +VERTEX_SE3:QUAT 364 -0.817902 1.115547 -1.713159 0.3301446 0.4433931 -0.8331377 0.0169891 +VERTEX_SE3:QUAT 365 -0.784102 1.205613 -1.697676 0.5273005 0.1115626 -0.7711078 0.3389700 +VERTEX_SE3:QUAT 366 -0.734085 1.114472 -1.841215 0.3418182 -0.4745348 -0.6865791 0.4319563 +VERTEX_SE3:QUAT 367 -0.583025 1.274350 -1.888088 0.4565902 -0.3594157 -0.3999523 0.7087905 +VERTEX_SE3:QUAT 368 -0.534712 1.351003 -1.827820 0.1457585 -0.6414511 -0.6341130 0.4064426 +VERTEX_SE3:QUAT 369 -0.457409 1.327661 -1.780088 0.1751869 0.4015999 -0.8824577 0.1711589 +VERTEX_SE3:QUAT 370 -0.262341 1.267171 -1.726915 0.0365449 0.1831265 -0.9635513 0.1915671 +VERTEX_SE3:QUAT 371 -0.191998 1.331200 -1.612773 0.1073665 0.0164918 -0.4458934 0.8884703 +VERTEX_SE3:QUAT 372 -0.078316 1.177798 -1.653189 -0.3432893 -0.4220870 -0.2859352 0.7888194 +VERTEX_SE3:QUAT 373 0.024695 1.280376 -1.637249 -0.4640772 -0.6259627 0.5897524 0.2121208 +VERTEX_SE3:QUAT 374 -0.125191 1.352967 -1.499335 0.4128733 0.2915850 -0.1705554 0.8458278 +VERTEX_SE3:QUAT 375 -0.146068 1.568329 -1.620406 0.3900586 -0.1279497 -0.2587849 0.8743646 +VERTEX_SE3:QUAT 376 -0.249528 1.615546 -1.622655 0.5316446 -0.3645578 0.1417939 0.7512297 +VERTEX_SE3:QUAT 377 -0.314052 1.691763 -1.654361 -0.1826353 -0.1125324 0.6153474 0.7585041 +VERTEX_SE3:QUAT 378 -0.306295 1.654338 -1.624372 -0.2675523 0.1040006 -0.8508462 0.4400685 +VERTEX_SE3:QUAT 379 -0.254730 1.665710 -1.629673 0.2013523 0.5876895 -0.5705375 0.5371826 +VERTEX_SE3:QUAT 380 -0.233789 1.801169 -1.673665 0.5485840 0.2473103 -0.2608272 0.7548923 +VERTEX_SE3:QUAT 381 -0.234440 1.692266 -1.719897 -0.2201429 0.2641558 0.9230611 0.1723859 +VERTEX_SE3:QUAT 382 -0.196312 1.663843 -1.496379 0.3457058 0.2909860 -0.7764504 0.4392487 +VERTEX_SE3:QUAT 383 -0.201691 1.761076 -1.495053 0.6037308 -0.1218300 0.1960802 0.7630328 +VERTEX_SE3:QUAT 384 -0.053869 1.686992 -1.600464 -0.5889089 0.0615563 0.7640671 0.2561222 +VERTEX_SE3:QUAT 385 -0.000439 1.691315 -1.581572 0.1161588 -0.6545129 0.1922197 0.7219221 +VERTEX_SE3:QUAT 386 0.044961 1.497636 -1.595953 0.3279021 -0.7344033 0.5902912 0.0684712 +VERTEX_SE3:QUAT 387 0.183352 1.437557 -1.577056 0.2700366 -0.1438983 -0.6529354 0.6928556 +VERTEX_SE3:QUAT 388 0.087902 1.279206 -1.418257 0.1925380 0.0537447 0.8055216 0.5578311 +VERTEX_SE3:QUAT 389 0.129949 1.260564 -1.505771 -0.1211355 0.1494880 -0.1492580 0.9698977 +VERTEX_SE3:QUAT 390 0.316253 1.186283 -1.612275 0.0836614 0.0060105 -0.1130632 0.9900411 +VERTEX_SE3:QUAT 391 0.435517 1.190125 -1.602741 -0.4338134 -0.1086298 0.5307760 0.7199183 +VERTEX_SE3:QUAT 392 0.466953 0.921076 -1.658089 0.3747132 0.3477184 -0.3402426 0.7892509 +VERTEX_SE3:QUAT 393 0.585760 0.893255 -1.591721 0.3921667 -0.4411473 0.2779161 0.7578634 +VERTEX_SE3:QUAT 394 0.665756 0.835854 -1.644256 -0.4723298 -0.2107100 0.8398742 0.1646730 +VERTEX_SE3:QUAT 395 0.568059 0.760239 -1.567223 0.0222703 -0.4246277 -0.1162864 0.8975928 +VERTEX_SE3:QUAT 396 0.530860 0.820380 -1.637144 0.2259458 -0.5113551 0.8291288 0.0031504 +VERTEX_SE3:QUAT 397 0.483510 0.903972 -1.578407 -0.5462317 0.1669126 -0.6600118 0.4880118 +VERTEX_SE3:QUAT 398 0.667325 0.917815 -1.625541 0.4779775 -0.6135190 -0.1352746 0.6138670 +VERTEX_SE3:QUAT 399 0.675613 0.871864 -1.687009 0.5819022 -0.3674518 0.2414493 0.6841573 +VERTEX_SE3:QUAT 400 0.602498 0.837438 -1.711807 0.2526947 -0.3247218 0.7911630 0.4525067 +VERTEX_SE3:QUAT 401 0.740567 0.864486 -1.696538 -0.4712911 0.0543686 0.8799329 0.0254314 +VERTEX_SE3:QUAT 402 0.698053 0.693309 -1.727442 -0.4421578 -0.2881650 0.8378184 0.1397060 +VERTEX_SE3:QUAT 403 0.565980 0.560706 -1.656124 -0.0776680 -0.1052790 -0.5997247 0.7894392 +VERTEX_SE3:QUAT 404 0.575112 0.307392 -1.734701 0.3048911 0.2774780 0.8899323 0.1951102 +VERTEX_SE3:QUAT 405 0.637142 0.271599 -1.739495 -0.1133127 0.4095179 0.0282485 0.9047968 +VERTEX_SE3:QUAT 406 0.864208 -0.136563 -1.722016 -0.1880547 0.1868044 -0.5849205 0.7665556 +VERTEX_SE3:QUAT 407 0.886067 -0.125289 -1.758796 0.3999867 -0.0053114 -0.0957050 0.9114949 +VERTEX_SE3:QUAT 408 0.882378 -0.137061 -1.743097 -0.3454079 -0.0892159 0.6574739 0.6636731 +VERTEX_SE3:QUAT 409 0.863065 0.057921 -1.722821 0.0372331 -0.2376585 0.6949818 0.6775932 +VERTEX_SE3:QUAT 410 0.810230 0.162415 -1.692580 0.2869703 -0.2668018 -0.6457310 0.6553597 +VERTEX_SE3:QUAT 411 0.868920 0.158926 -1.637987 0.1376928 -0.1792529 0.8180453 0.5288771 +VERTEX_SE3:QUAT 412 0.828491 0.082765 -1.453538 0.2709403 0.4188934 0.7787423 0.3803682 +VERTEX_SE3:QUAT 413 0.774763 0.117234 -1.475009 0.0602486 -0.0774033 0.7985912 0.5938273 +VERTEX_SE3:QUAT 414 0.633556 0.003888 -1.447147 0.2953661 0.7126276 -0.6156470 0.1609331 +VERTEX_SE3:QUAT 415 0.355884 -0.252163 -1.370591 -0.3495576 -0.2477991 0.1811281 0.8852105 +VERTEX_SE3:QUAT 416 0.384768 -0.386256 -1.292838 0.3792441 -0.0442825 0.9134118 0.1410388 +VERTEX_SE3:QUAT 417 0.356104 -0.351748 -1.155997 0.1577156 0.7479644 -0.5954274 0.2472676 +VERTEX_SE3:QUAT 418 0.321754 -0.421700 -1.214712 0.2792407 0.1249156 -0.7334619 0.6070044 +VERTEX_SE3:QUAT 419 0.501782 -0.472080 -1.294537 0.2758156 0.6910813 -0.0502627 0.6661877 +VERTEX_SE3:QUAT 420 0.394490 -0.487192 -1.496931 -0.7469584 -0.1229921 -0.6406113 0.1286201 +VERTEX_SE3:QUAT 421 0.462190 -0.467716 -1.540887 0.6951995 0.3771620 -0.2163194 0.5724092 +VERTEX_SE3:QUAT 422 0.437791 -0.593571 -1.734313 0.8729398 0.1720264 0.4303178 0.1523469 +VERTEX_SE3:QUAT 423 0.513939 -0.675012 -1.769211 -0.0257902 -0.5030890 0.8607241 0.0734190 +VERTEX_SE3:QUAT 424 0.585630 -0.517711 -1.834495 -0.6467081 0.2508737 -0.4919533 0.5261302 +VERTEX_SE3:QUAT 425 0.693523 -0.438909 -1.820433 -0.3835017 0.0371799 0.4089257 0.8272387 +VERTEX_SE3:QUAT 426 0.661698 -0.474691 -1.939137 -0.2978870 0.5864990 -0.7442572 0.1156007 +VERTEX_SE3:QUAT 427 0.687763 -0.573106 -1.962696 0.2586754 0.4336140 0.7828219 0.3636700 +VERTEX_SE3:QUAT 428 0.559181 -0.809701 -1.967031 -0.5206993 0.3890844 -0.7599046 0.0055324 +VERTEX_SE3:QUAT 429 0.261172 -0.844075 -2.043880 -0.1089065 0.3297585 -0.7032006 0.6204092 +VERTEX_SE3:QUAT 430 0.460307 -0.883430 -2.116033 0.4257103 -0.0431257 0.2726450 0.8617283 +VERTEX_SE3:QUAT 431 0.386531 -0.989147 -2.088996 0.3743719 -0.0752298 0.8371280 0.3916667 +VERTEX_SE3:QUAT 432 0.300716 -0.979193 -1.933036 0.3716389 -0.0450128 0.2922673 0.8800217 +VERTEX_SE3:QUAT 433 0.174791 -1.043635 -1.900875 0.4830821 0.1941024 0.5084384 0.6858910 +VERTEX_SE3:QUAT 434 0.055805 -1.131126 -1.844357 -0.8044809 0.3081525 -0.4917242 0.1267274 +VERTEX_SE3:QUAT 435 0.074859 -1.092564 -1.807930 0.3999126 0.6493293 -0.1715594 0.6237056 +VERTEX_SE3:QUAT 436 0.097217 -1.048578 -1.704342 0.5942628 -0.0015260 -0.0608515 0.8019642 +VERTEX_SE3:QUAT 437 0.183282 -1.055542 -1.800077 0.5610659 0.1635010 0.2598283 0.7687404 +VERTEX_SE3:QUAT 438 0.032429 -1.162029 -1.950612 0.3240501 0.7788344 0.1541674 0.5144326 +VERTEX_SE3:QUAT 439 -0.081615 -1.124188 -2.067611 -0.0397897 -0.1305659 -0.8997056 0.4146072 +VERTEX_SE3:QUAT 440 -0.148198 -1.166735 -2.144599 -0.0658031 0.5273239 -0.3107530 0.7880559 +VERTEX_SE3:QUAT 441 -0.178527 -1.053029 -2.152762 0.2260227 0.0680801 0.3724171 0.8975435 +VERTEX_SE3:QUAT 442 -0.458345 -1.017466 -2.011379 -0.6772799 0.2540199 -0.4588315 0.5159840 +VERTEX_SE3:QUAT 443 -0.606570 -1.088923 -2.085214 0.6973588 -0.3136876 0.5464994 0.3415102 +VERTEX_SE3:QUAT 444 -0.611278 -1.256073 -2.191298 -0.7052785 0.3127330 -0.5344773 0.3451293 +VERTEX_SE3:QUAT 445 -0.658154 -1.311778 -2.191888 -0.3547019 0.5935893 -0.5187032 0.5027775 +VERTEX_SE3:QUAT 446 -0.790644 -1.360404 -2.266731 -0.1436676 0.3199012 0.9352312 0.0486347 +VERTEX_SE3:QUAT 447 -0.897049 -1.421221 -2.308793 -0.4742805 0.6871144 -0.5452131 0.0753289 +VERTEX_SE3:QUAT 448 -0.924613 -1.422216 -2.444718 0.2413276 0.3255280 -0.3455546 0.8463950 +VERTEX_SE3:QUAT 449 -0.971714 -1.339688 -2.461598 0.4260332 0.2305134 0.0736469 0.8717427 +VERTEX_SE3:QUAT 450 -1.208822 -1.573017 -2.524926 0.1458781 -0.4770846 0.3668772 0.7851822 +VERTEX_SE3:QUAT 451 -1.279244 -1.668815 -2.671680 0.7691223 0.0749014 0.3867262 0.5032727 +VERTEX_SE3:QUAT 452 -1.211262 -1.779552 -2.704620 0.1598688 0.4518126 0.8528437 0.2072800 +VERTEX_SE3:QUAT 453 -1.269245 -1.718219 -2.695962 0.1229270 -0.3030822 0.0859546 0.9410855 +VERTEX_SE3:QUAT 454 -1.132038 -1.765520 -2.668179 0.2242295 0.5893606 -0.7698600 0.0984417 +VERTEX_SE3:QUAT 455 -1.278150 -1.660055 -2.641022 -0.0937426 0.7370705 -0.4904414 0.4554191 +VERTEX_SE3:QUAT 456 -1.311877 -1.742674 -2.638647 0.1363987 -0.2665162 0.9415836 0.1542234 +VERTEX_SE3:QUAT 457 -1.185726 -1.745331 -2.745625 0.6306185 0.3804730 0.6754210 0.0369735 +VERTEX_SE3:QUAT 458 -1.357648 -1.661016 -2.924687 0.7687064 0.4819241 0.2711764 0.3214078 +VERTEX_SE3:QUAT 459 -1.415567 -1.672634 -3.173407 0.4366546 -0.1552055 0.8711261 0.1624296 +VERTEX_SE3:QUAT 460 -1.399115 -1.646417 -3.130663 -0.0022869 -0.1211128 0.9770456 0.1752380 +VERTEX_SE3:QUAT 461 -1.337012 -1.895770 -3.146926 0.0520844 0.0109879 0.3879225 0.9201536 +VERTEX_SE3:QUAT 462 -1.357219 -1.842255 -3.018580 0.7533442 -0.0567420 0.6539340 0.0402895 +VERTEX_SE3:QUAT 463 -1.163702 -2.062524 -3.080798 0.2411199 0.6529924 0.0357976 0.7170639 +VERTEX_SE3:QUAT 464 -1.005331 -1.997174 -3.128498 0.0816624 0.7294558 -0.5864521 0.3424900 +VERTEX_SE3:QUAT 465 -0.907842 -2.097131 -3.211352 -0.2312761 0.5057220 0.2335371 0.7976321 +VERTEX_SE3:QUAT 466 -0.888185 -2.096311 -3.122502 0.2941661 0.4345137 0.3385664 0.7810486 +VERTEX_SE3:QUAT 467 -0.913550 -1.890531 -3.052083 -0.2701533 0.7721597 -0.4522050 0.3553832 +VERTEX_SE3:QUAT 468 -0.750443 -1.981670 -2.989824 -0.1077900 0.3799330 0.9173714 0.0496180 +VERTEX_SE3:QUAT 469 -0.613991 -2.000685 -3.106372 0.0032418 0.2756307 -0.1417998 0.9507418 +VERTEX_SE3:QUAT 470 -0.577647 -2.090795 -3.232517 0.2761309 0.6823989 -0.1651208 0.6563677 +VERTEX_SE3:QUAT 471 -0.856470 -1.993146 -3.323251 0.2078941 -0.1287479 0.8380107 0.4877931 +VERTEX_SE3:QUAT 472 -0.859907 -1.934017 -3.392402 0.1229819 0.0747000 -0.9132213 0.3812116 +VERTEX_SE3:QUAT 473 -0.871079 -1.935534 -3.492922 -0.4406739 0.1273746 -0.7027154 0.5438504 +VERTEX_SE3:QUAT 474 -1.029445 -1.902708 -3.591021 0.1148543 0.1466453 -0.9795947 0.0754841 +VERTEX_SE3:QUAT 475 -0.988398 -2.089930 -3.663023 0.2947819 0.3988849 0.1393113 0.8570804 +VERTEX_SE3:QUAT 476 -0.800926 -2.079662 -3.670793 -0.4499026 -0.0198600 0.1426963 0.8813801 +VERTEX_SE3:QUAT 477 -0.589465 -2.111455 -3.538307 0.1919377 0.5206055 0.8226788 0.1238117 +VERTEX_SE3:QUAT 478 -0.544349 -2.226551 -3.648983 -0.0548547 0.0325049 0.5360209 0.8417933 +VERTEX_SE3:QUAT 479 -0.592192 -2.279431 -3.711436 -0.1171162 0.8446455 -0.4301604 0.2963441 +VERTEX_SE3:QUAT 480 -0.783189 -2.258696 -3.821702 -0.0892202 -0.0506563 0.2985116 0.9488754 +VERTEX_SE3:QUAT 481 -0.577195 -2.230887 -3.736461 -0.1309006 -0.2842229 0.6941378 0.6482708 +VERTEX_SE3:QUAT 482 -0.510563 -2.096738 -3.836242 0.0712746 -0.2185053 0.2065528 0.9510580 +VERTEX_SE3:QUAT 483 -0.283011 -2.034634 -3.754719 0.1229261 0.0129675 0.4703907 0.8737583 +VERTEX_SE3:QUAT 484 -0.314720 -1.887749 -3.755146 -0.2842235 0.5466220 0.1943312 0.7633195 +VERTEX_SE3:QUAT 485 -0.224952 -1.953299 -3.690486 0.8469755 0.2233713 0.4792717 0.0551037 +VERTEX_SE3:QUAT 486 -0.188652 -1.933003 -3.732999 -0.0896334 0.8237611 -0.5309349 0.1774588 +VERTEX_SE3:QUAT 487 -0.019770 -1.910212 -3.757894 -0.2165286 -0.1959380 0.9265866 0.2369828 +VERTEX_SE3:QUAT 488 -0.021652 -1.828910 -3.801689 0.2701009 -0.0645715 -0.9148858 0.2930187 +VERTEX_SE3:QUAT 489 -0.017540 -1.755641 -3.777443 -0.0258513 0.2340413 0.9589782 0.1578516 +VERTEX_SE3:QUAT 490 0.024483 -1.726358 -3.811826 0.3908310 0.6123056 0.6026197 0.3304277 +VERTEX_SE3:QUAT 491 -0.025048 -1.763201 -3.774735 -0.2513546 0.0017003 0.8089867 0.5313741 +VERTEX_SE3:QUAT 492 -0.051528 -1.728143 -3.757764 0.7316915 0.2597380 0.1413078 0.6141627 +VERTEX_SE3:QUAT 493 -0.089751 -1.835110 -3.577465 -0.1794902 0.0618630 -0.5690649 0.8000758 +VERTEX_SE3:QUAT 494 0.007822 -1.863417 -3.756134 -0.3246301 -0.1510724 0.7065034 0.6104468 +VERTEX_SE3:QUAT 495 0.069000 -1.776847 -3.821759 -0.3905014 0.3411814 0.4680145 0.7155881 +VERTEX_SE3:QUAT 496 0.068049 -1.655106 -3.806983 -0.6326444 0.1957343 -0.5893729 0.4626972 +VERTEX_SE3:QUAT 497 0.339251 -1.667750 -3.792605 0.3465367 0.0625473 0.0424577 0.9349853 +VERTEX_SE3:QUAT 498 0.420725 -1.467923 -3.791591 -0.7077784 0.3887096 -0.2608009 0.5290913 +VERTEX_SE3:QUAT 499 0.618519 -1.597120 -3.854414 0.2691622 0.4979454 0.2016109 0.7993467 +VERTEX_SE3:QUAT 500 0.597879 -1.653597 -3.640923 0.6151873 0.3082228 0.2177800 0.6921815 +VERTEX_SE3:QUAT 501 0.667664 -1.781226 -3.784334 -0.1368395 -0.1674276 0.2045001 0.9546846 +VERTEX_SE3:QUAT 502 0.756937 -1.878353 -3.694017 0.5894232 0.6268186 0.4675073 0.2027701 +VERTEX_SE3:QUAT 503 0.725522 -1.848840 -3.555843 0.4442982 -0.0753045 0.6641726 0.5964924 +VERTEX_SE3:QUAT 504 0.681330 -1.801393 -3.473901 -0.3899245 0.2639848 0.2957256 0.8311542 +VERTEX_SE3:QUAT 505 0.647948 -1.924274 -3.368655 0.7791386 0.1405240 0.4154015 0.4479259 +VERTEX_SE3:QUAT 506 0.789504 -2.107315 -3.289049 -0.4813559 -0.1771130 -0.7764383 0.3661572 +VERTEX_SE3:QUAT 507 0.778502 -1.972450 -3.219011 0.2289862 -0.2729784 0.7302644 0.5828910 +VERTEX_SE3:QUAT 508 0.666717 -1.931320 -3.038443 0.3312452 0.6674308 -0.4755418 0.4676246 +VERTEX_SE3:QUAT 509 0.828376 -1.842483 -2.896463 0.1415282 -0.0086379 0.3863855 0.9113733 +VERTEX_SE3:QUAT 510 0.828985 -1.876802 -2.915675 0.1927333 -0.1210137 -0.1983692 0.9533411 +VERTEX_SE3:QUAT 511 0.833666 -1.882821 -2.781890 -0.0326083 -0.4637065 0.8493644 0.2499860 +VERTEX_SE3:QUAT 512 0.645433 -1.813636 -2.717330 0.3709984 0.4537508 -0.2532674 0.7696272 +VERTEX_SE3:QUAT 513 0.840115 -1.843433 -2.596884 0.5371384 0.0245300 0.3645923 0.7602322 +VERTEX_SE3:QUAT 514 0.766103 -1.977185 -2.408343 -0.1991484 0.5294069 -0.1365409 0.8132803 +VERTEX_SE3:QUAT 515 0.789515 -1.995086 -2.463546 0.1556016 0.3013212 -0.0660205 0.9384215 +VERTEX_SE3:QUAT 516 1.065179 -1.885347 -2.331753 -0.1171828 0.6241215 0.1693705 0.7536937 +VERTEX_SE3:QUAT 517 1.079619 -1.827124 -2.154422 0.3935782 -0.0826965 0.9154256 0.0159187 +VERTEX_SE3:QUAT 518 1.360260 -1.775041 -2.022441 -0.6865568 0.5844934 -0.3134366 0.2979340 +VERTEX_SE3:QUAT 519 1.319008 -1.715845 -1.920025 0.2713786 -0.2648656 0.2532429 0.8899820 +VERTEX_SE3:QUAT 520 1.360881 -1.716031 -1.966928 -0.7229857 0.2544680 -0.5851888 0.2647485 +VERTEX_SE3:QUAT 521 1.325914 -1.742295 -1.893500 0.2855702 0.5608031 0.4508543 0.6329929 +VERTEX_SE3:QUAT 522 1.404533 -1.900664 -1.816819 0.3936555 -0.4394088 0.3926197 0.7055530 +VERTEX_SE3:QUAT 523 1.391308 -1.829662 -1.549928 -0.1736164 -0.0864942 0.8204866 0.5377527 +VERTEX_SE3:QUAT 524 1.483354 -1.737854 -1.481329 0.2480029 0.0794513 0.9608170 0.0949350 +VERTEX_SE3:QUAT 525 1.538626 -1.665991 -1.446511 0.3868039 -0.0915654 0.9019877 0.1685726 +VERTEX_SE3:QUAT 526 1.475880 -1.682226 -1.342851 0.8176825 0.0944193 0.2222456 0.5225775 +VERTEX_SE3:QUAT 527 1.518383 -1.534012 -1.341636 0.0328425 0.2616827 0.9139310 0.3085023 +VERTEX_SE3:QUAT 528 1.360509 -1.563010 -1.316970 -0.0762406 0.1110249 0.7516956 0.6456118 +VERTEX_SE3:QUAT 529 1.357330 -1.675322 -1.222786 -0.1228743 -0.4207372 0.5329618 0.7237637 +VERTEX_SE3:QUAT 530 1.317187 -1.610210 -1.147063 0.6547736 0.3055571 0.6303168 0.2839139 +VERTEX_SE3:QUAT 531 1.267642 -1.482516 -1.030744 0.2493980 -0.4216300 0.3850920 0.7821335 +VERTEX_SE3:QUAT 532 1.266085 -1.453554 -0.920834 0.0224432 0.3940148 0.9180036 0.0389612 +VERTEX_SE3:QUAT 533 1.192539 -1.577410 -0.789904 0.0475025 0.0542402 0.0205430 0.9971858 +VERTEX_SE3:QUAT 534 1.148673 -1.688301 -0.802801 0.1290968 -0.1056959 -0.5845325 0.7940303 +VERTEX_SE3:QUAT 535 1.208314 -1.579052 -0.726018 -0.0148387 0.3871344 -0.4605389 0.7986305 +VERTEX_SE3:QUAT 536 1.170676 -1.470042 -0.756602 0.6906173 0.0373729 0.2032695 0.6930603 +VERTEX_SE3:QUAT 537 1.159677 -1.425650 -0.520276 0.5621393 0.1044592 -0.4916657 0.6567744 +VERTEX_SE3:QUAT 538 1.000013 -1.523863 -0.662832 0.5112661 0.5026713 -0.5637971 0.4099529 +VERTEX_SE3:QUAT 539 1.013750 -1.457601 -0.602205 -0.0060046 -0.3735912 0.8961893 0.2392454 +VERTEX_SE3:QUAT 540 0.971780 -1.292734 -0.370416 0.2715808 -0.2021442 0.1800797 0.9235545 +VERTEX_SE3:QUAT 541 0.928664 -1.334021 -0.470947 0.6812792 0.3586004 0.1069982 0.6291389 +VERTEX_SE3:QUAT 542 0.844467 -1.297169 -0.562369 -0.2131682 0.8445325 -0.4737591 0.1299095 +VERTEX_SE3:QUAT 543 0.757569 -1.184309 -0.635297 -0.4884375 0.5880290 -0.5144926 0.3885203 +VERTEX_SE3:QUAT 544 0.686443 -1.352306 -0.658616 0.5257773 0.6525517 0.3228550 0.4398855 +VERTEX_SE3:QUAT 545 0.738311 -1.180002 -0.418588 -0.1294790 0.4533655 0.1729879 0.8647370 +VERTEX_SE3:QUAT 546 0.479034 -1.037944 -0.342578 -0.2680829 0.3059665 0.3141300 0.8578102 +VERTEX_SE3:QUAT 547 0.326026 -0.892900 -0.409220 0.2647064 -0.1522948 -0.5318019 0.7898883 +VERTEX_SE3:QUAT 548 0.397558 -0.807942 -0.281964 -0.0445442 0.0828859 0.9953984 0.0181020 +VERTEX_SE3:QUAT 549 0.305972 -0.725295 -0.379835 -0.0388336 0.4912523 -0.8290346 0.2643196 +VERTEX_SE3:QUAT 550 0.311783 -0.761148 -0.372778 0.3234002 0.6384507 -0.1326525 0.6857086 +VERTEX_SE3:QUAT 551 0.199533 -0.722020 -0.262512 0.6185343 -0.0688034 0.2381519 0.7456307 +VERTEX_SE3:QUAT 552 0.182963 -0.697939 -0.481824 -0.5609404 -0.0208422 -0.7859809 0.2591244 +VERTEX_SE3:QUAT 553 0.192739 -0.584155 -0.551850 0.2788863 0.5050782 -0.2315131 0.7832752 +VERTEX_SE3:QUAT 554 0.210451 -0.454420 -0.629638 -0.1912149 0.5058590 -0.8109538 0.2233774 +VERTEX_SE3:QUAT 555 0.155877 -0.567426 -0.844891 -0.5876357 0.0830460 -0.5676580 0.5705717 +VERTEX_SE3:QUAT 556 -0.019971 -0.512120 -0.763447 0.0772741 0.1958508 -0.0772113 0.9745304 +VERTEX_SE3:QUAT 557 -0.081588 -0.473934 -0.865345 -0.2782518 -0.2806244 0.5908943 0.7033277 +VERTEX_SE3:QUAT 558 -0.283582 -0.557368 -1.071043 0.1617408 0.6372033 -0.1678977 0.7345899 +VERTEX_SE3:QUAT 559 -0.251283 -0.550039 -1.036474 0.5916646 0.0299581 -0.4659886 0.6571835 +VERTEX_SE3:QUAT 560 -0.325553 -0.566638 -1.092197 -0.7662710 0.1743568 -0.3677702 0.4971654 +VERTEX_SE3:QUAT 561 -0.261147 -0.591807 -0.891888 -0.2707471 -0.0476806 0.1230637 0.9535606 +VERTEX_SE3:QUAT 562 -0.188844 -0.608230 -0.862279 0.0956199 0.0644897 0.9856995 0.1228590 +VERTEX_SE3:QUAT 563 -0.346686 -0.588516 -0.873111 -0.2279621 0.5819735 -0.6909837 0.3631551 +VERTEX_SE3:QUAT 564 -0.352951 -0.616026 -0.880878 0.1939847 0.0932759 -0.8164512 0.5357957 +VERTEX_SE3:QUAT 565 -0.401097 -0.676643 -0.979692 0.1139652 0.6405581 0.1615767 0.7420177 +VERTEX_SE3:QUAT 566 -0.483343 -1.064207 -0.934092 -0.2326446 -0.4629169 0.8443279 0.1367289 +VERTEX_SE3:QUAT 567 -0.415192 -1.008586 -1.210744 0.3539930 0.4741950 0.7550623 0.2823278 +VERTEX_SE3:QUAT 568 -0.133699 -1.089485 -1.349609 -0.0867063 -0.1729821 0.1791982 0.9645969 +VERTEX_SE3:QUAT 569 -0.104908 -1.173235 -1.511417 -0.3947801 0.2877650 0.7020687 0.5181115 +VERTEX_SE3:QUAT 570 -0.244055 -1.300008 -1.444111 0.1182968 -0.2082388 0.4296339 0.8706648 +VERTEX_SE3:QUAT 571 -0.130533 -1.403066 -1.605321 0.3894874 -0.2538474 -0.8232163 0.3258465 +VERTEX_SE3:QUAT 572 -0.000533 -1.323170 -1.721534 0.0113073 -0.4995984 -0.2910127 0.8158340 +VERTEX_SE3:QUAT 573 0.334517 -1.189046 -1.823819 0.1041291 0.3001992 -0.8035234 0.5033764 +VERTEX_SE3:QUAT 574 0.339346 -1.210814 -1.772901 -0.6049097 -0.0142805 -0.5486822 0.5769125 +VERTEX_SE3:QUAT 575 0.607837 -1.216541 -1.757035 0.4517498 0.6168835 0.5534279 0.3302944 +VERTEX_SE3:QUAT 576 0.500528 -1.221298 -1.700549 0.4064321 -0.0153874 0.4546749 0.7923679 +VERTEX_SE3:QUAT 577 0.524244 -1.251249 -1.902778 -0.3026521 -0.0170212 -0.9008686 0.3107214 +VERTEX_SE3:QUAT 578 0.449295 -1.297848 -1.971623 -0.7086620 0.2076094 -0.1452376 0.6584851 +VERTEX_SE3:QUAT 579 0.593853 -1.349123 -1.904543 0.0907379 0.4874204 -0.1371876 0.8575358 +VERTEX_SE3:QUAT 580 0.595495 -1.577905 -1.945679 -0.6464963 0.2473445 0.0061537 0.7216823 +VERTEX_SE3:QUAT 581 0.498081 -1.551169 -2.036249 -0.3578764 -0.2620923 -0.4117016 0.7960740 +VERTEX_SE3:QUAT 582 0.515544 -1.523270 -1.856178 -0.5961949 0.1306805 0.6912375 0.3868656 +VERTEX_SE3:QUAT 583 0.679113 -1.404421 -1.914698 0.5307205 0.1173000 0.7735196 0.3259507 +VERTEX_SE3:QUAT 584 0.838053 -1.248553 -1.972042 0.2520201 0.0868141 -0.9569371 0.1149809 +VERTEX_SE3:QUAT 585 0.828856 -1.098367 -1.964160 -0.0325624 -0.3244568 0.7401937 0.5880313 +VERTEX_SE3:QUAT 586 0.877414 -1.157985 -1.946524 0.1616061 -0.2324554 0.8059192 0.5199444 +VERTEX_SE3:QUAT 587 0.805623 -1.299407 -2.053302 0.0175912 -0.2518954 0.1056937 0.9618046 +VERTEX_SE3:QUAT 588 1.026746 -1.282671 -1.991075 0.0958286 0.0561041 -0.8704729 0.4795271 +VERTEX_SE3:QUAT 589 1.107593 -1.376252 -1.782548 -0.0317720 0.8246995 0.3968118 0.4017483 +VERTEX_SE3:QUAT 590 1.145426 -1.503923 -1.800901 -0.5198939 -0.3952522 0.1782116 0.7360208 +VERTEX_SE3:QUAT 591 1.391604 -1.444352 -1.658816 0.5832902 -0.1613872 0.7957533 0.0224386 +VERTEX_SE3:QUAT 592 1.627756 -1.345883 -1.537392 -0.1756713 -0.0035861 -0.5070364 0.8438251 +VERTEX_SE3:QUAT 593 1.580934 -1.288257 -1.529367 -0.4703274 -0.6218456 -0.6197347 0.0896052 +VERTEX_SE3:QUAT 594 1.664046 -1.283044 -1.642605 -0.1314356 0.3492213 0.0592286 0.9258840 +VERTEX_SE3:QUAT 595 1.770545 -1.317324 -1.614553 -0.5589076 0.0835231 0.6410827 0.5192872 +VERTEX_SE3:QUAT 596 1.775982 -1.340971 -1.570087 -0.0404230 0.7971516 0.5572357 0.2289185 +VERTEX_SE3:QUAT 597 1.833751 -1.182439 -1.517448 0.0610488 -0.2943762 -0.0731659 0.9509272 +VERTEX_SE3:QUAT 598 1.796205 -1.265574 -1.579914 -0.3676895 0.3677932 0.8436400 0.1334325 +VERTEX_SE3:QUAT 599 1.746630 -1.180967 -1.604617 -0.2260702 0.2283989 0.2490247 0.9136262 +VERTEX_SE3:QUAT 600 1.763565 -1.256758 -1.572892 0.1489413 -0.4144752 -0.6200632 0.6492676 +VERTEX_SE3:QUAT 601 1.778334 -1.166829 -1.626513 0.4331969 -0.1377252 0.8789351 0.1443793 +VERTEX_SE3:QUAT 602 1.557378 -1.093398 -1.630165 -0.2099938 0.7284718 0.6376550 0.1364831 +VERTEX_SE3:QUAT 603 1.564135 -0.856461 -1.531409 -0.7262128 0.0511848 0.1119304 0.6763628 +VERTEX_SE3:QUAT 604 1.608709 -0.812471 -1.588703 -0.1870934 -0.5947668 -0.6267322 0.4673920 +VERTEX_SE3:QUAT 605 1.600510 -0.689301 -1.461648 0.2273978 -0.3419189 0.6812594 0.6060259 +VERTEX_SE3:QUAT 606 1.461469 -0.636118 -1.342837 -0.0652687 -0.1801475 -0.2354697 0.9528068 +VERTEX_SE3:QUAT 607 1.309722 -0.383844 -1.400888 0.0523087 -0.2539940 -0.8273833 0.4981844 +VERTEX_SE3:QUAT 608 1.283986 -0.266433 -1.307482 0.3530482 -0.4347116 0.7654895 0.3168731 +VERTEX_SE3:QUAT 609 1.093566 -0.199038 -1.237761 -0.6827993 -0.4775723 -0.5373614 0.1302017 +VERTEX_SE3:QUAT 610 1.119737 -0.161805 -1.062163 0.5413180 0.4668713 0.6943110 0.0832959 +VERTEX_SE3:QUAT 611 0.956275 -0.072633 -1.029399 -0.4055188 0.2797846 0.7554072 0.4320127 +VERTEX_SE3:QUAT 612 0.826057 -0.071876 -0.916783 0.3290702 -0.3865257 0.8400707 0.1912903 +VERTEX_SE3:QUAT 613 0.831283 -0.169615 -0.953591 0.0775004 0.5417874 -0.8171545 0.1808826 +VERTEX_SE3:QUAT 614 0.746891 -0.090939 -0.863806 -0.1459066 0.7482775 0.6018924 0.2377343 +VERTEX_SE3:QUAT 615 0.734699 -0.118640 -0.888998 -0.4827495 0.2340070 -0.1912477 0.8219598 +VERTEX_SE3:QUAT 616 0.772469 0.031237 -0.717600 -0.2496492 0.4979363 0.8303037 0.0181786 +VERTEX_SE3:QUAT 617 0.887913 0.002601 -0.657688 -0.2558077 -0.1635696 -0.7659828 0.5666373 +VERTEX_SE3:QUAT 618 0.827892 0.105403 -0.487964 -0.1171684 -0.2706718 -0.9249970 0.2395599 +VERTEX_SE3:QUAT 619 0.747023 0.048566 -0.425639 0.3147791 -0.1427903 0.5228232 0.7792182 +VERTEX_SE3:QUAT 620 0.659263 0.106663 -0.400135 0.4484306 -0.3513387 0.8165449 0.0934103 +VERTEX_SE3:QUAT 621 0.759408 0.100505 -0.362879 0.5102815 0.2659541 0.7301732 0.3684133 +VERTEX_SE3:QUAT 622 0.670674 0.214019 -0.496003 -0.4106269 0.1247943 -0.8619975 0.2697634 +VERTEX_SE3:QUAT 623 0.546128 0.508715 -0.408639 -0.3761447 0.1668722 0.9104465 0.0419036 +VERTEX_SE3:QUAT 624 0.411274 0.483696 -0.522911 -0.1098905 0.3422926 0.7803972 0.5116054 +VERTEX_SE3:QUAT 625 0.399432 0.474231 -0.332075 -0.8126285 -0.2184849 -0.2889137 0.4565393 +VERTEX_SE3:QUAT 626 0.269306 0.518741 -0.307855 -0.0464866 0.3235608 -0.1696958 0.9297047 +VERTEX_SE3:QUAT 627 0.169866 0.436699 -0.404759 -0.2644243 0.5895474 0.5151143 0.5631793 +VERTEX_SE3:QUAT 628 0.157000 0.429476 -0.372919 0.4459815 -0.1594546 0.8551572 0.2106678 +VERTEX_SE3:QUAT 629 0.120541 0.479356 -0.176754 -0.3519584 -0.1685054 -0.9190086 0.0561641 +VERTEX_SE3:QUAT 630 0.153896 0.490945 -0.185351 -0.2041674 0.4510951 0.3637885 0.7889783 +VERTEX_SE3:QUAT 631 0.245220 0.510593 -0.282540 -0.6996997 0.3619892 0.2787561 0.5492532 +VERTEX_SE3:QUAT 632 0.254841 0.615633 -0.406375 0.4086343 0.2253330 0.4004892 0.7885756 +VERTEX_SE3:QUAT 633 0.064851 0.707935 -0.322045 -0.6461036 0.4150782 -0.1103999 0.6309296 +VERTEX_SE3:QUAT 634 0.129890 0.933422 -0.428331 0.3800274 -0.4531917 -0.7044080 0.3924357 +VERTEX_SE3:QUAT 635 0.024547 1.091056 -0.522758 -0.1536522 -0.3666857 -0.8377610 0.3742848 +VERTEX_SE3:QUAT 636 -0.052266 1.144220 -0.457612 0.0037608 0.2852393 -0.9251841 0.2503172 +VERTEX_SE3:QUAT 637 -0.084280 1.145486 -0.512282 -0.0789373 -0.3550431 -0.7529547 0.5484273 +VERTEX_SE3:QUAT 638 -0.362727 1.211720 -0.690578 -0.2529818 0.2008536 -0.6803932 0.6578169 +VERTEX_SE3:QUAT 639 -0.517714 1.258421 -0.824568 0.1723551 0.3217998 -0.8786552 0.3077397 +VERTEX_SE3:QUAT 640 -0.583024 1.361871 -0.847543 0.5500919 -0.0178959 0.8232653 0.1389707 +VERTEX_SE3:QUAT 641 -0.564014 1.556456 -1.037357 -0.5065850 0.2275974 -0.2092903 0.8048408 +VERTEX_SE3:QUAT 642 -0.660079 1.535807 -1.246813 -0.5827614 0.1749618 -0.6430387 0.4650578 +VERTEX_SE3:QUAT 643 -0.776351 1.571428 -1.269398 -0.6813559 -0.0230165 0.7195200 0.1323457 +VERTEX_SE3:QUAT 644 -0.877010 1.556942 -1.087699 0.2100464 -0.0338341 -0.8219674 0.5283042 +VERTEX_SE3:QUAT 645 -0.814815 1.553093 -1.184382 0.0781641 -0.3106200 0.8920423 0.3188513 +VERTEX_SE3:QUAT 646 -0.682503 1.665940 -1.053027 0.2668414 0.1186973 0.5532933 0.7801110 +VERTEX_SE3:QUAT 647 -0.706166 1.629577 -1.093484 0.4204463 0.2021960 0.2978974 0.8328258 +VERTEX_SE3:QUAT 648 -0.907967 1.791730 -1.204047 -0.0528127 0.6212376 -0.7357661 0.2644293 +VERTEX_SE3:QUAT 649 -0.992994 1.920382 -1.251187 0.1960388 -0.4747549 -0.8393633 0.1778930 +VERTEX_SE3:QUAT 650 -1.059096 1.794667 -1.354992 -0.0801505 0.3773476 -0.7571241 0.5272076 +VERTEX_SE3:QUAT 651 -0.832052 1.681830 -1.421243 -0.4102997 -0.1680876 -0.8266085 0.3465821 +VERTEX_SE3:QUAT 652 -0.687935 1.692590 -1.469006 -0.0622001 -0.2884965 0.8004864 0.5216535 +VERTEX_SE3:QUAT 653 -0.736467 1.471237 -1.578362 0.2588757 -0.0393651 0.7919649 0.5515662 +VERTEX_SE3:QUAT 654 -0.725924 1.535727 -1.705846 0.0092966 -0.4645568 -0.8411836 0.2766056 +VERTEX_SE3:QUAT 655 -0.929787 1.606940 -1.667083 -0.4680982 0.3616892 -0.0203234 0.8060099 +VERTEX_SE3:QUAT 656 -0.817153 1.431049 -1.756566 -0.1278154 -0.3306085 -0.4719766 0.8072170 +VERTEX_SE3:QUAT 657 -0.625735 1.397328 -1.808574 0.1521032 0.2625484 0.7851475 0.5398855 +VERTEX_SE3:QUAT 658 -0.627853 1.532145 -2.006354 0.2020333 -0.6960339 0.6588661 0.2015313 +VERTEX_SE3:QUAT 659 -0.639704 1.531925 -1.878499 -0.2785136 0.2371122 0.3891965 0.8454195 +VERTEX_SE3:QUAT 660 -0.576385 1.427924 -2.039175 0.3178459 -0.1180541 -0.8986464 0.2783378 +VERTEX_SE3:QUAT 661 -0.762018 1.358160 -2.140943 0.4124414 0.4815988 0.2322027 0.7375884 +VERTEX_SE3:QUAT 662 -0.668691 1.307818 -2.096858 0.2662579 0.6703416 -0.6902840 0.0570685 +VERTEX_SE3:QUAT 663 -0.815878 1.325067 -2.052098 -0.0512125 -0.3766835 -0.3137284 0.8700927 +VERTEX_SE3:QUAT 664 -0.783065 1.361485 -2.194154 -0.2615306 0.3177651 -0.6633120 0.6250154 +VERTEX_SE3:QUAT 665 -0.644771 1.448888 -2.224828 -0.5775621 -0.1326113 0.6981855 0.4017129 +VERTEX_SE3:QUAT 666 -0.506765 1.468590 -2.220193 0.4098070 0.4332171 -0.3355494 0.7292378 +VERTEX_SE3:QUAT 667 -0.474837 1.305111 -2.207521 0.5384481 0.0592541 -0.8005127 0.2564023 +VERTEX_SE3:QUAT 668 -0.313650 1.366710 -2.196379 -0.3910418 -0.2160703 -0.8435591 0.2980066 +VERTEX_SE3:QUAT 669 -0.412558 1.466390 -2.099492 -0.2524101 -0.6595217 0.6939179 0.1407063 +VERTEX_SE3:QUAT 670 -0.231939 1.333891 -2.376333 -0.1266448 0.3566667 -0.2475162 0.8919000 +VERTEX_SE3:QUAT 671 -0.219005 1.327588 -2.310559 0.1001886 -0.3205767 -0.7502040 0.5695497 +VERTEX_SE3:QUAT 672 -0.124003 1.358047 -2.260551 -0.1014732 -0.1739755 -0.9556138 0.2150301 +VERTEX_SE3:QUAT 673 -0.065045 1.552147 -2.227220 -0.6197134 -0.0903768 0.1150635 0.7710692 +VERTEX_SE3:QUAT 674 0.077512 1.492691 -2.229535 -0.2621988 0.3021976 0.7421502 0.5377188 +VERTEX_SE3:QUAT 675 0.193394 1.502723 -2.162071 0.4792675 0.5308944 -0.0301461 0.6982442 +VERTEX_SE3:QUAT 676 0.280318 1.314149 -2.122513 -0.5337089 -0.3475689 0.5879514 0.4986620 +VERTEX_SE3:QUAT 677 0.287655 1.359095 -2.015878 -0.1643698 0.0061321 0.9667754 0.1956792 +VERTEX_SE3:QUAT 678 0.200372 1.132261 -1.984947 0.1633100 0.4145477 -0.0176107 0.8950810 +VERTEX_SE3:QUAT 679 0.185966 0.936091 -1.952893 0.0397086 0.3832837 -0.0325585 0.9222021 +VERTEX_SE3:QUAT 680 0.161250 0.853156 -1.970461 0.1032469 0.3551408 -0.6154935 0.6959762 +VERTEX_SE3:QUAT 681 0.320238 0.800428 -1.961712 0.3855597 0.3255460 -0.3548779 0.7870357 +VERTEX_SE3:QUAT 682 0.330378 0.809979 -1.790889 -0.0631880 0.7215092 -0.5484902 0.4178399 +VERTEX_SE3:QUAT 683 0.424190 0.841744 -1.692824 -0.2432456 -0.4222147 0.6434891 0.5903288 +VERTEX_SE3:QUAT 684 0.468326 0.901857 -1.778759 -0.2522351 0.3730533 -0.5936810 0.6668969 +VERTEX_SE3:QUAT 685 0.284116 0.757961 -1.761945 0.5401586 -0.2192778 0.7734215 0.2489281 +VERTEX_SE3:QUAT 686 0.167132 0.821550 -1.883925 0.7290886 -0.0627952 0.6388661 0.2373535 +VERTEX_SE3:QUAT 687 0.288887 0.737274 -1.781404 -0.5053965 0.3089557 -0.6935332 0.4100395 +VERTEX_SE3:QUAT 688 0.337901 0.708353 -1.723343 -0.1019879 0.1919905 -0.9681950 0.1238411 +VERTEX_SE3:QUAT 689 0.518378 0.583930 -1.734050 0.1873765 0.2007330 0.7297608 0.6261354 +VERTEX_SE3:QUAT 690 0.449834 0.332356 -1.948105 -0.4681289 0.0317096 -0.7140496 0.5195989 +VERTEX_SE3:QUAT 691 0.472138 0.386536 -1.840713 0.1974360 -0.4815485 -0.7383839 0.4288581 +VERTEX_SE3:QUAT 692 0.558615 0.424968 -1.671135 0.4803317 0.0366894 0.7255226 0.4914796 +VERTEX_SE3:QUAT 693 0.685103 0.346374 -1.558792 0.1965020 -0.5667291 -0.4895094 0.6329183 +VERTEX_SE3:QUAT 694 0.755630 0.266798 -1.464789 0.1599998 -0.7713294 0.6154327 0.0263370 +VERTEX_SE3:QUAT 695 0.957565 0.275159 -1.447539 -0.6414953 0.2391417 0.7248959 0.0762958 +VERTEX_SE3:QUAT 696 0.920653 0.229278 -1.413738 -0.2823895 -0.0310176 -0.9127459 0.2935798 +VERTEX_SE3:QUAT 697 0.926795 0.385004 -1.273907 -0.5197240 0.0246278 0.3822028 0.7636763 +VERTEX_SE3:QUAT 698 0.933897 0.560556 -1.007051 -0.3500952 -0.0366522 0.7324575 0.5827486 +VERTEX_SE3:QUAT 699 0.847671 0.526338 -1.171085 0.0527440 -0.7102980 0.4073142 0.5716554 +VERTEX_SE3:QUAT 700 0.969595 0.653511 -1.107266 0.3660896 -0.4843399 0.0147062 0.7944665 +VERTEX_SE3:QUAT 701 1.041870 0.750253 -1.049654 0.0428034 -0.2745612 -0.4594092 0.8436393 +VERTEX_SE3:QUAT 702 1.074770 0.740340 -1.023531 -0.0441677 -0.4630292 -0.3893443 0.7950246 +VERTEX_SE3:QUAT 703 0.831027 0.817472 -0.807919 -0.2315073 -0.1087961 0.6276384 0.7352808 +VERTEX_SE3:QUAT 704 0.794825 0.836364 -0.841744 -0.1083175 0.5940813 -0.0734277 0.7936895 +VERTEX_SE3:QUAT 705 0.904983 0.897357 -0.625663 0.3513851 0.2716496 -0.8494750 0.2848283 +VERTEX_SE3:QUAT 706 0.928097 0.873704 -0.628810 0.1580531 -0.3253360 0.4748327 0.8023152 +VERTEX_SE3:QUAT 707 0.955370 0.874975 -0.578783 -0.0529084 -0.4504107 0.6895520 0.5646672 +VERTEX_SE3:QUAT 708 0.702636 0.831139 -0.487448 0.2218428 0.0433761 0.1332787 0.9649565 +VERTEX_SE3:QUAT 709 0.648373 0.910600 -0.439898 0.2978832 0.1023910 0.9417102 0.1181673 +VERTEX_SE3:QUAT 710 0.661788 0.986779 -0.427768 -0.0104312 -0.2376727 -0.2541482 0.9374495 +VERTEX_SE3:QUAT 711 0.571002 0.967757 -0.551720 -0.4984968 -0.1447413 0.6448121 0.5610421 +VERTEX_SE3:QUAT 712 0.532597 0.983740 -0.495447 0.1521071 0.4322420 0.8006798 0.3859304 +VERTEX_SE3:QUAT 713 0.404551 0.997281 -0.436835 0.5234752 -0.2290332 -0.6769970 0.4638885 +VERTEX_SE3:QUAT 714 0.328913 0.869264 -0.350772 -0.0437893 -0.7006730 0.6047618 0.3760359 +VERTEX_SE3:QUAT 715 0.226176 0.935579 -0.304960 -0.0384285 0.3031568 0.4567283 0.8354750 +VERTEX_SE3:QUAT 716 0.230186 0.832792 -0.087339 0.3222334 -0.0311303 0.8523893 0.4106446 +VERTEX_SE3:QUAT 717 0.110620 0.683445 -0.054946 0.0634025 -0.2795108 -0.2158974 0.9334035 +VERTEX_SE3:QUAT 718 0.154176 0.517954 0.116492 -0.0802995 -0.6085210 0.6458708 0.4539879 +VERTEX_SE3:QUAT 719 -0.045384 0.616125 0.085024 -0.0406422 -0.1618270 0.9833587 0.0718744 +VERTEX_SE3:QUAT 720 -0.065601 0.597248 0.271085 0.6760375 0.0013497 -0.6758787 0.2935292 +VERTEX_SE3:QUAT 721 -0.088811 0.557989 0.301733 0.1695343 0.1762887 -0.9679977 0.0562224 +VERTEX_SE3:QUAT 722 -0.234901 0.388766 0.362959 0.2643879 -0.4870263 -0.5928641 0.5843087 +VERTEX_SE3:QUAT 723 -0.163181 0.544478 0.333765 0.3270061 -0.3858026 -0.1301054 0.8528165 +VERTEX_SE3:QUAT 724 -0.182643 0.540366 0.571927 -0.0959307 0.3193807 0.6218469 0.7085899 +VERTEX_SE3:QUAT 725 -0.293714 0.621084 0.566348 -0.4272879 -0.1353715 0.8931968 0.0360420 +VERTEX_SE3:QUAT 726 -0.356678 0.498536 0.396702 -0.2201037 0.2320704 0.5537590 0.7687969 +VERTEX_SE3:QUAT 727 -0.404153 0.539932 0.370457 0.6049488 0.1175847 -0.4910467 0.6156979 +VERTEX_SE3:QUAT 728 -0.392217 0.526431 0.243276 -0.3677427 -0.2951503 -0.3031059 0.8281174 +VERTEX_SE3:QUAT 729 -0.520654 0.422897 0.417112 0.5319911 -0.4615886 -0.0234370 0.7094872 +VERTEX_SE3:QUAT 730 -0.511963 0.681342 0.364778 0.2418441 -0.1230233 0.1432932 0.9517582 +VERTEX_SE3:QUAT 731 -0.724270 0.604772 0.204510 -0.6009947 -0.2224207 0.2915043 0.7101828 +VERTEX_SE3:QUAT 732 -0.994536 0.678244 0.410729 -0.0744177 -0.6598413 -0.7089810 0.2375235 +VERTEX_SE3:QUAT 733 -1.137413 0.861582 0.437651 -0.1118222 0.2748502 -0.9499513 0.0977023 +VERTEX_SE3:QUAT 734 -1.121282 1.006757 0.354149 0.0125391 0.4731802 0.7764329 0.4160471 +VERTEX_SE3:QUAT 735 -1.139439 0.767930 0.354951 0.1135984 -0.1979272 -0.7905257 0.5683216 +VERTEX_SE3:QUAT 736 -1.088139 0.647362 0.234639 -0.0166104 0.3533545 0.1700216 0.9197594 +VERTEX_SE3:QUAT 737 -1.073297 0.577676 0.125367 -0.6171391 0.1649143 -0.0931547 0.7637177 +VERTEX_SE3:QUAT 738 -0.982808 0.659319 0.297402 0.3291653 0.2196898 0.6895565 0.6065463 +VERTEX_SE3:QUAT 739 -0.948607 0.688217 0.017179 0.5094024 -0.2848644 0.2879366 0.7592457 +VERTEX_SE3:QUAT 740 -1.217927 0.602259 0.059985 -0.2855952 0.4258202 0.6655370 0.5423772 +VERTEX_SE3:QUAT 741 -1.394339 0.683601 0.070394 -0.6100650 -0.0636281 0.7387064 0.2794371 +VERTEX_SE3:QUAT 742 -1.216354 0.878053 0.111712 -0.7367790 -0.1632523 -0.1250423 0.6441039 +VERTEX_SE3:QUAT 743 -1.158409 0.778129 -0.047795 0.5007242 -0.0383990 0.2739777 0.8202055 +VERTEX_SE3:QUAT 744 -1.232886 0.853885 -0.046445 -0.1902212 -0.0033078 0.8626952 0.4685743 +VERTEX_SE3:QUAT 745 -1.112604 0.885198 -0.212526 -0.1730436 -0.2958428 -0.4330077 0.8336889 +VERTEX_SE3:QUAT 746 -1.144905 0.720548 -0.322535 0.1109579 -0.4692713 -0.7468313 0.4579474 +VERTEX_SE3:QUAT 747 -1.129113 0.794048 -0.513984 -0.1490440 0.6633863 0.3244590 0.6575948 +VERTEX_SE3:QUAT 748 -1.056325 0.764654 -0.606420 -0.1633179 -0.0896216 0.3186953 0.9293700 +VERTEX_SE3:QUAT 749 -1.127114 0.646614 -0.825826 0.4189815 -0.0161886 0.8040806 0.4214818 +VERTEX_SE3:QUAT 750 -1.088824 0.649852 -0.780376 -0.5654415 0.3331785 0.4146912 0.6303168 +VERTEX_SE3:QUAT 751 -1.179418 0.585857 -0.841489 0.2982021 0.1997434 -0.2006325 0.9115507 +VERTEX_SE3:QUAT 752 -1.073225 0.676949 -0.815175 -0.4712109 0.2344227 -0.7180478 0.4554268 +VERTEX_SE3:QUAT 753 -0.885677 0.512550 -0.756859 -0.4375402 0.6011274 -0.1851580 0.6425892 +VERTEX_SE3:QUAT 754 -0.803425 0.481568 -0.804411 -0.1598050 -0.2002396 0.0104426 0.9665699 +VERTEX_SE3:QUAT 755 -0.797781 0.482740 -0.717044 -0.2686690 -0.6332706 -0.6265006 0.3664456 +VERTEX_SE3:QUAT 756 -0.681341 0.549891 -0.712474 0.1194772 0.0275931 0.8149543 0.5664039 +VERTEX_SE3:QUAT 757 -0.688317 0.552484 -0.809008 -0.0576456 -0.6708676 -0.7159258 0.1845640 +VERTEX_SE3:QUAT 758 -0.816621 0.550579 -0.952402 -0.2961171 0.3429241 -0.2754045 0.8478621 +VERTEX_SE3:QUAT 759 -0.960470 0.732854 -0.989037 -0.1998023 0.4574021 -0.8665143 0.0039209 +VERTEX_SE3:QUAT 760 -0.913136 0.679881 -1.206000 -0.4645559 -0.0619531 0.5439006 0.6960759 +VERTEX_SE3:QUAT 761 -0.777787 0.591395 -1.271983 -0.3843566 0.3377633 0.8591381 0.0082305 +VERTEX_SE3:QUAT 762 -0.846146 0.569058 -1.331365 0.1283804 0.2192463 -0.8393496 0.4805639 +VERTEX_SE3:QUAT 763 -0.821838 0.409680 -1.516384 0.4394677 0.0565325 -0.5830867 0.6809421 +VERTEX_SE3:QUAT 764 -0.894227 0.565154 -1.595819 -0.0356717 0.2996434 0.5446638 0.7824849 +VERTEX_SE3:QUAT 765 -1.035471 0.654281 -1.699999 0.1703413 0.1397405 0.6802656 0.6990673 +VERTEX_SE3:QUAT 766 -1.244129 0.743948 -1.702916 0.4548502 -0.2296313 -0.7914103 0.3377137 +VERTEX_SE3:QUAT 767 -1.106494 0.728412 -1.675060 0.1768183 -0.4742952 -0.2263243 0.8321999 +VERTEX_SE3:QUAT 768 -1.163736 0.787529 -1.533224 -0.4654106 -0.4291403 0.0674417 0.7711571 +VERTEX_SE3:QUAT 769 -1.026807 0.746375 -1.655375 -0.1511633 0.0260158 -0.5888575 0.7935488 +VERTEX_SE3:QUAT 770 -0.982211 0.710815 -1.549218 -0.4588726 0.4143821 0.7605660 0.1981486 +VERTEX_SE3:QUAT 771 -0.903559 0.609036 -1.612828 0.4321778 -0.5823159 -0.6884894 0.0106246 +VERTEX_SE3:QUAT 772 -0.838815 0.579424 -1.511962 -0.1004380 0.3007339 0.8635541 0.3921042 +VERTEX_SE3:QUAT 773 -0.645292 0.716393 -1.430830 -0.4420302 0.2203700 0.3518907 0.7951222 +VERTEX_SE3:QUAT 774 -0.682053 0.814680 -1.423323 -0.7599107 0.1523955 0.3085199 0.5514769 +VERTEX_SE3:QUAT 775 -0.660206 0.636555 -1.439664 -0.2492661 0.1090148 -0.0098548 0.9622292 +VERTEX_SE3:QUAT 776 -0.631301 0.667632 -1.417752 0.2674643 0.1165741 -0.9554116 0.0454083 +VERTEX_SE3:QUAT 777 -0.577472 0.812877 -1.330712 0.2487902 0.1962830 0.8923582 0.3213616 +VERTEX_SE3:QUAT 778 -0.728286 0.863524 -1.391839 -0.6912851 -0.1578225 -0.4192516 0.5669613 +VERTEX_SE3:QUAT 779 -0.534376 0.951920 -1.402787 -0.0875549 0.6050099 0.7212087 0.3258148 +VERTEX_SE3:QUAT 780 -0.698206 1.090554 -1.313967 0.0729076 0.3597588 0.1283336 0.9212972 +VERTEX_SE3:QUAT 781 -0.390940 1.085582 -1.310208 -0.2182615 -0.7095840 -0.6397819 0.1988254 +VERTEX_SE3:QUAT 782 -0.354735 0.945981 -1.275305 0.3425989 -0.2112741 -0.1628141 0.9008223 +VERTEX_SE3:QUAT 783 -0.427280 0.980825 -1.096395 -0.4820171 0.2177382 0.8358220 0.1471434 +VERTEX_SE3:QUAT 784 -0.277619 0.992307 -0.980084 -0.2861989 -0.3619268 -0.4404512 0.7701311 +VERTEX_SE3:QUAT 785 -0.319087 0.922338 -0.811972 -0.4506427 -0.4774448 -0.7361654 0.1644026 +VERTEX_SE3:QUAT 786 -0.196200 0.986813 -0.675470 -0.6114063 -0.1741715 -0.4840107 0.6013155 +VERTEX_SE3:QUAT 787 -0.103082 0.988528 -0.648864 -0.1038706 0.4407275 0.7141336 0.5338383 +VERTEX_SE3:QUAT 788 0.019478 0.924799 -0.553434 0.1766140 0.1542021 -0.0146012 0.9720165 +VERTEX_SE3:QUAT 789 0.105266 0.931040 -0.703619 0.4145987 -0.1563474 0.8622829 0.2452176 +VERTEX_SE3:QUAT 790 0.161153 0.995797 -0.619882 0.0572901 -0.2409807 -0.9686363 0.0197426 +VERTEX_SE3:QUAT 791 0.060403 1.189400 -0.683127 0.4975095 0.2806050 0.4830678 0.6636194 +VERTEX_SE3:QUAT 792 0.117053 1.320506 -0.762299 -0.4983409 -0.4485082 0.1263605 0.7311154 +VERTEX_SE3:QUAT 793 0.075576 1.274094 -0.671096 -0.6429405 0.2800415 -0.3594310 0.6156408 +VERTEX_SE3:QUAT 794 -0.063397 1.323077 -0.805540 0.3139154 -0.0869681 -0.8267687 0.4586362 +VERTEX_SE3:QUAT 795 -0.005963 1.419048 -0.595582 0.3611428 -0.1876714 -0.8033588 0.4347068 +VERTEX_SE3:QUAT 796 -0.092107 1.472516 -0.656279 0.3040399 0.1440597 -0.0780295 0.9384657 +VERTEX_SE3:QUAT 797 -0.039939 1.729331 -0.490982 0.1477350 -0.1896625 0.8663952 0.4376778 +VERTEX_SE3:QUAT 798 0.207803 1.719200 -0.607763 -0.5193649 0.2006334 0.4555370 0.6946167 +VERTEX_SE3:QUAT 799 0.147206 1.740373 -0.508268 0.3050908 -0.5180838 -0.6229862 0.5003968 +VERTEX_SE3:QUAT 800 0.049940 1.702427 -0.635024 -0.0234418 0.3475144 0.3597052 0.8656191 +VERTEX_SE3:QUAT 801 -0.106429 1.762604 -0.665082 -0.2963671 -0.3052187 0.5415706 0.7250582 +VERTEX_SE3:QUAT 802 0.167274 1.910886 -0.597138 0.4786343 0.0921636 0.5235803 0.6987695 +VERTEX_SE3:QUAT 803 0.168893 2.082751 -0.566672 -0.0814298 -0.3967786 -0.0763843 0.9110990 +VERTEX_SE3:QUAT 804 0.078716 2.096920 -0.578638 -0.1450522 -0.2040908 -0.8900377 0.3809720 +VERTEX_SE3:QUAT 805 0.150451 2.052385 -0.559319 0.0845448 -0.4902979 -0.1772611 0.8491399 +VERTEX_SE3:QUAT 806 0.141459 2.000294 -0.414546 0.2221985 -0.0398059 0.9611821 0.1586576 +VERTEX_SE3:QUAT 807 0.252358 1.918169 -0.466864 -0.4462587 0.1007440 -0.0330542 0.8886007 +VERTEX_SE3:QUAT 808 0.248465 2.082922 -0.569274 -0.3652662 -0.0148301 -0.0912813 0.9262982 +VERTEX_SE3:QUAT 809 0.144271 2.078738 -0.425437 -0.3056679 0.2535702 0.2158501 0.8920078 +VERTEX_SE3:QUAT 810 0.227708 1.967442 -0.289733 0.4146311 -0.0932728 0.2194584 0.8781909 +VERTEX_SE3:QUAT 811 0.117871 2.135065 -0.419650 0.4162499 0.2887577 -0.1712559 0.8450008 +VERTEX_SE3:QUAT 812 -0.166161 1.984407 -0.326246 -0.0845018 0.3620901 -0.3911373 0.8418799 +VERTEX_SE3:QUAT 813 -0.281263 1.838060 -0.210585 -0.2380768 0.5750242 -0.3938189 0.6764416 +VERTEX_SE3:QUAT 814 -0.516732 1.882580 -0.138207 0.2596491 -0.1622842 0.5536865 0.7743884 +VERTEX_SE3:QUAT 815 -0.539914 2.130290 0.133823 0.4533342 -0.3010144 0.8193503 0.1803983 +VERTEX_SE3:QUAT 816 -0.559155 2.102672 -0.019949 -0.3925887 -0.2027957 -0.7200838 0.5350022 +VERTEX_SE3:QUAT 817 -0.733191 2.097569 0.025336 -0.0947249 -0.3365514 -0.4361920 0.8291543 +VERTEX_SE3:QUAT 818 -0.719825 2.129251 0.021229 0.3726551 0.4586528 -0.4367435 0.6782484 +VERTEX_SE3:QUAT 819 -0.766400 2.146373 -0.011578 0.3953508 0.6426741 0.2657336 0.6000445 +VERTEX_SE3:QUAT 820 -0.737844 2.389586 -0.102015 0.6729790 0.2468399 0.4878661 0.4981527 +VERTEX_SE3:QUAT 821 -1.083106 2.377514 -0.073843 -0.1320877 0.4690951 -0.8453817 0.2187060 +VERTEX_SE3:QUAT 822 -1.191485 2.458733 0.010859 0.1344351 0.6227848 0.2976776 0.7109531 +VERTEX_SE3:QUAT 823 -1.196640 2.568004 0.154390 0.1854849 -0.4007260 -0.5567080 0.7036265 +VERTEX_SE3:QUAT 824 -1.145871 2.554171 0.210916 0.6989500 0.1100306 0.0438333 0.7052948 +VERTEX_SE3:QUAT 825 -1.106117 2.394192 0.191042 0.1000338 0.2858152 0.7409294 0.5994385 +VERTEX_SE3:QUAT 826 -1.371845 2.415118 0.149347 0.0415613 0.0224744 0.5742647 0.8173051 +VERTEX_SE3:QUAT 827 -1.463052 2.258493 0.066619 -0.1326257 0.3498290 -0.2948171 0.8792684 +VERTEX_SE3:QUAT 828 -1.485640 2.398564 0.138212 0.0238758 0.6547571 -0.2283704 0.7201180 +VERTEX_SE3:QUAT 829 -1.619078 2.300079 0.014334 0.0739790 -0.3705594 -0.2323378 0.8962321 +VERTEX_SE3:QUAT 830 -1.760201 2.287287 0.148471 -0.2345465 0.3379903 0.8056038 0.4263249 +VERTEX_SE3:QUAT 831 -1.801516 2.438720 0.198671 -0.3849321 0.1552467 -0.6277865 0.6584906 +VERTEX_SE3:QUAT 832 -1.764984 2.229965 0.166677 0.3060246 -0.3059467 -0.5739494 0.6952177 +VERTEX_SE3:QUAT 833 -1.632457 2.061204 0.089214 0.1234167 -0.0490602 -0.9523324 0.2746352 +VERTEX_SE3:QUAT 834 -1.754693 2.109985 0.040419 0.4379147 0.0763905 0.8587807 0.2547371 +VERTEX_SE3:QUAT 835 -1.746650 2.130256 0.025229 -0.4024342 0.2888720 0.5481274 0.6739110 +VERTEX_SE3:QUAT 836 -1.765396 2.365512 0.100275 0.2591690 -0.4012318 -0.1266176 0.8693748 +VERTEX_SE3:QUAT 837 -1.892004 2.325891 -0.035856 -0.1062821 0.1377244 -0.4670822 0.8669316 +VERTEX_SE3:QUAT 838 -1.875054 2.359722 -0.050804 0.3626214 -0.6084883 0.4690720 0.5274649 +VERTEX_SE3:QUAT 839 -2.025294 2.353770 -0.137157 -0.5696746 0.5732816 -0.5831740 0.0820192 +VERTEX_SE3:QUAT 840 -2.121862 2.304857 -0.223058 -0.4149795 -0.2607453 -0.8652674 0.1054336 +VERTEX_SE3:QUAT 841 -2.119156 2.077394 -0.178650 0.0065115 0.1274898 0.1108467 0.9856049 +VERTEX_SE3:QUAT 842 -2.048264 2.121690 -0.256353 0.3621942 0.5208239 0.1439291 0.7595013 +VERTEX_SE3:QUAT 843 -2.163161 2.276920 -0.390628 -0.3565396 0.0905558 -0.8940324 0.2557055 +VERTEX_SE3:QUAT 844 -2.179074 2.304911 -0.463783 0.7221671 0.2004119 -0.3965758 0.5301295 +VERTEX_SE3:QUAT 845 -2.257251 2.212823 -0.407505 0.3725287 0.2949049 -0.4825370 0.7358067 +VERTEX_SE3:QUAT 846 -2.274063 2.132036 -0.372160 0.3022862 -0.3532912 -0.1228817 0.8767602 +VERTEX_SE3:QUAT 847 -2.317743 2.185816 -0.720133 -0.1346772 -0.3249036 -0.1552057 0.9231527 +VERTEX_SE3:QUAT 848 -2.288577 2.281648 -0.861518 0.3196195 0.1539443 0.4776211 0.8037553 +VERTEX_SE3:QUAT 849 -2.386722 2.362832 -0.886842 0.3291467 -0.0853493 0.5401121 0.7698421 +VERTEX_SE3:QUAT 850 -2.258466 2.408391 -0.960298 0.1439503 -0.1376740 0.4145862 0.8879428 +VERTEX_SE3:QUAT 851 -2.348823 2.395099 -1.050028 -0.5315311 -0.3388683 0.5465651 0.5512799 +VERTEX_SE3:QUAT 852 -2.115030 2.289797 -0.983194 -0.4003980 -0.5791852 0.4800699 0.5232197 +VERTEX_SE3:QUAT 853 -2.217320 2.249474 -1.049127 0.5125428 0.0942033 0.8440517 0.1265001 +VERTEX_SE3:QUAT 854 -2.299595 2.147608 -1.364219 -0.0906113 0.5051577 0.7988664 0.3137161 +VERTEX_SE3:QUAT 855 -2.237504 1.887311 -1.340480 0.2054829 0.0358259 0.4505234 0.8680564 +VERTEX_SE3:QUAT 856 -2.179414 2.018985 -1.254358 -0.0668540 0.7475142 -0.3832487 0.5383990 +VERTEX_SE3:QUAT 857 -2.193719 1.934723 -1.300271 0.3638776 -0.6774967 0.4999023 0.3983579 +VERTEX_SE3:QUAT 858 -2.375927 2.045284 -1.334411 -0.6683784 -0.2627854 -0.6946534 0.0408761 +VERTEX_SE3:QUAT 859 -2.495023 2.072707 -1.553514 -0.3375111 0.1470305 0.0014295 0.9297668 +VERTEX_SE3:QUAT 860 -2.508149 2.148510 -1.533066 0.5246289 0.0402039 -0.2106882 0.8238681 +VERTEX_SE3:QUAT 861 -2.336253 2.073438 -1.671307 -0.2163199 0.3285409 0.8973371 0.2001318 +VERTEX_SE3:QUAT 862 -2.308804 2.036258 -1.654270 0.4207064 0.4445372 -0.3392090 0.7143739 +VERTEX_SE3:QUAT 863 -2.226908 2.215369 -1.718043 -0.3838851 0.4590167 -0.2110824 0.7729037 +VERTEX_SE3:QUAT 864 -2.217709 2.203782 -1.791779 0.6166415 -0.1853178 -0.6769046 0.3566661 +VERTEX_SE3:QUAT 865 -1.998224 2.237530 -1.829256 0.6113567 0.0399926 0.7762929 0.1483676 +VERTEX_SE3:QUAT 866 -1.987582 2.178849 -1.944933 -0.3075229 0.3413992 -0.4397873 0.7716627 +VERTEX_SE3:QUAT 867 -2.010960 2.187832 -1.851077 0.2076621 0.2203877 0.9204841 0.2470116 +VERTEX_SE3:QUAT 868 -1.989331 2.028878 -1.876606 0.6136541 0.3615903 0.5061325 0.4863240 +VERTEX_SE3:QUAT 869 -1.997863 2.042233 -2.132763 0.4886717 -0.5034299 -0.4488303 0.5534525 +VERTEX_SE3:QUAT 870 -2.044414 2.004978 -2.236620 0.1861360 0.4706706 -0.5553904 0.6598213 +VERTEX_SE3:QUAT 871 -2.084583 2.063193 -2.204169 -0.4418477 -0.2299802 -0.5887621 0.6365838 +VERTEX_SE3:QUAT 872 -1.994225 2.100914 -2.355306 -0.6046990 0.2332000 -0.1393122 0.7486982 +VERTEX_SE3:QUAT 873 -1.897397 1.872253 -2.287647 0.0874458 -0.1389521 0.1740987 0.9709455 +VERTEX_SE3:QUAT 874 -1.888522 1.959165 -2.285956 0.4453915 -0.5164166 -0.7030835 0.2015288 +VERTEX_SE3:QUAT 875 -1.842254 1.888251 -2.289103 -0.1319081 -0.0865655 -0.0846492 0.9838400 +VERTEX_SE3:QUAT 876 -1.777778 1.881342 -2.375275 -0.4319860 -0.0224863 -0.8238551 0.3662585 +VERTEX_SE3:QUAT 877 -1.823694 1.840234 -2.345298 -0.0745937 0.3909201 0.3356974 0.8537708 +VERTEX_SE3:QUAT 878 -1.806517 1.760566 -2.097714 0.2009458 -0.4356143 0.2346387 0.8454618 +VERTEX_SE3:QUAT 879 -1.563354 1.807355 -2.101849 -0.2445111 -0.1997199 -0.6604411 0.6812810 +VERTEX_SE3:QUAT 880 -1.435942 1.794259 -2.135366 0.5131750 -0.3340318 0.5367536 0.5804909 +VERTEX_SE3:QUAT 881 -1.401893 2.036308 -1.907714 -0.1019026 0.2615056 -0.8329055 0.4769687 +VERTEX_SE3:QUAT 882 -1.434299 1.958978 -1.802011 -0.1626790 0.0657056 -0.6999098 0.6923471 +VERTEX_SE3:QUAT 883 -1.255659 1.801211 -1.690319 -0.1679037 0.5526064 -0.7844288 0.2260664 +VERTEX_SE3:QUAT 884 -1.218739 1.748487 -1.672789 -0.5825133 -0.2548141 0.3040215 0.7094497 +VERTEX_SE3:QUAT 885 -1.097707 1.603558 -1.787675 0.1312709 0.3988520 -0.2687703 0.8668607 +VERTEX_SE3:QUAT 886 -1.122704 1.609684 -1.974506 0.5133383 0.3916478 -0.5373790 0.5425123 +VERTEX_SE3:QUAT 887 -1.148033 1.415661 -1.964692 -0.2869729 0.2727790 0.9156252 0.0697762 +VERTEX_SE3:QUAT 888 -0.950845 1.422969 -2.034856 0.3524636 -0.1338679 -0.9235666 0.0698116 +VERTEX_SE3:QUAT 889 -0.901429 1.592339 -1.924264 -0.2892452 0.1642485 0.2538352 0.9082551 +VERTEX_SE3:QUAT 890 -0.925373 1.647622 -1.975133 0.1330111 0.3117587 0.8953830 0.2887972 +VERTEX_SE3:QUAT 891 -0.921761 1.626710 -1.907436 0.4903122 -0.0007452 0.8431311 0.2207336 +VERTEX_SE3:QUAT 892 -1.093815 1.464944 -1.782062 0.0461746 -0.5686584 0.2913194 0.7678727 +VERTEX_SE3:QUAT 893 -1.097149 1.396303 -1.801299 0.0215704 0.0250665 0.2751700 0.9608266 +VERTEX_SE3:QUAT 894 -1.083518 1.316476 -1.788174 -0.3549431 -0.4985708 -0.3867195 0.6898482 +VERTEX_SE3:QUAT 895 -1.160292 1.245330 -1.623648 -0.1630395 -0.7520635 0.3826067 0.5113030 +VERTEX_SE3:QUAT 896 -1.166288 1.242053 -1.546327 -0.3081961 -0.4440362 -0.3287010 0.7744693 +VERTEX_SE3:QUAT 897 -1.035387 1.114866 -1.356455 -0.3827939 0.0068877 -0.9222985 0.0527914 +VERTEX_SE3:QUAT 898 -1.027166 1.017452 -1.345314 -0.3598077 -0.3828040 -0.3403897 0.7798297 +VERTEX_SE3:QUAT 899 -1.065526 1.040348 -1.326336 0.3129607 0.4516253 -0.0752506 0.8321223 +VERTEX_SE3:QUAT 900 -1.051410 1.158248 -1.123409 -0.3281930 0.1245703 0.5570799 0.7526178 +VERTEX_SE3:QUAT 901 -0.996905 1.180759 -1.249749 -0.4561653 -0.1584408 -0.3151794 0.8169894 +VERTEX_SE3:QUAT 902 -0.914583 1.123333 -1.003235 -0.2827771 -0.1101170 0.9526231 0.0205103 +VERTEX_SE3:QUAT 903 -0.785538 1.045156 -0.857529 0.1958784 -0.5242400 -0.7887389 0.2543521 +VERTEX_SE3:QUAT 904 -0.771623 1.049577 -0.787898 -0.1786280 -0.6338751 0.1772145 0.7313613 +VERTEX_SE3:QUAT 905 -0.739321 0.903597 -0.712543 0.1459851 -0.0617297 0.9681796 0.1936646 +VERTEX_SE3:QUAT 906 -0.755292 0.858769 -0.574403 -0.0771139 0.1963545 0.9745239 0.0761681 +VERTEX_SE3:QUAT 907 -0.668768 0.857183 -0.581845 -0.3311208 0.2440390 -0.6450035 0.6440298 +VERTEX_SE3:QUAT 908 -0.549796 0.890847 -0.592235 0.1411975 0.4670938 0.4788102 0.7298132 +VERTEX_SE3:QUAT 909 -0.589221 1.031960 -0.570898 0.6537558 0.0581944 -0.6522598 0.3791753 +VERTEX_SE3:QUAT 910 -0.610396 1.083089 -0.495634 -0.4398470 0.0749932 -0.5838532 0.6782522 +VERTEX_SE3:QUAT 911 -0.760841 1.151512 -0.422878 0.4542036 0.3373855 -0.4910574 0.6623690 +VERTEX_SE3:QUAT 912 -0.676062 1.025038 -0.318010 0.3633233 0.5540816 -0.6621509 0.3500657 +VERTEX_SE3:QUAT 913 -0.765772 1.078676 -0.438326 0.1853548 0.4063380 0.7737990 0.4491860 +VERTEX_SE3:QUAT 914 -0.668321 1.181920 -0.331602 0.3740301 -0.0658345 0.5662515 0.7315234 +VERTEX_SE3:QUAT 915 -0.558553 1.228860 -0.329841 0.3419624 0.2781003 -0.8968865 0.0362835 +VERTEX_SE3:QUAT 916 -0.594041 1.325487 -0.242101 0.2646107 -0.1304396 -0.9443827 0.1452856 +VERTEX_SE3:QUAT 917 -0.384006 1.384127 -0.392703 0.0853370 -0.4283619 -0.7694527 0.4660109 +VERTEX_SE3:QUAT 918 -0.304271 1.385070 -0.245950 0.6161170 0.4420006 -0.1884986 0.6241022 +VERTEX_SE3:QUAT 919 -0.281590 1.512756 -0.186770 -0.1000970 -0.6754857 0.5089863 0.5240540 +VERTEX_SE3:QUAT 920 -0.268230 1.506798 -0.065600 0.2652646 -0.1112183 -0.4018468 0.8693586 +VERTEX_SE3:QUAT 921 -0.339810 1.493315 -0.125929 -0.2999052 -0.5218437 0.6056946 0.5204518 +VERTEX_SE3:QUAT 922 -0.459924 1.494884 -0.299088 0.4046876 -0.3394258 -0.7941188 0.3006549 +VERTEX_SE3:QUAT 923 -0.398521 1.485867 -0.457149 0.6426467 -0.1182784 0.2257069 0.7225454 +VERTEX_SE3:QUAT 924 -0.361444 1.657010 -0.431389 -0.1538807 -0.1731464 -0.0332382 0.9722326 +VERTEX_SE3:QUAT 925 -0.329968 1.700673 -0.415528 0.4990072 -0.1275829 -0.8565268 0.0328069 +VERTEX_SE3:QUAT 926 -0.273666 1.915063 -0.481780 0.4958244 0.0973038 -0.6385342 0.5804862 +VERTEX_SE3:QUAT 927 -0.209974 1.882143 -0.589021 -0.3362501 -0.4915677 -0.7510313 0.2850423 +VERTEX_SE3:QUAT 928 -0.313201 1.919100 -0.560315 -0.1484663 -0.0293274 0.1007129 0.9833385 +VERTEX_SE3:QUAT 929 -0.385368 2.042788 -0.563669 0.4905893 0.2254220 0.7843952 0.3053381 +VERTEX_SE3:QUAT 930 -0.630354 1.916609 -0.734854 -0.4932455 -0.2524544 -0.2658920 0.7888454 +VERTEX_SE3:QUAT 931 -0.530551 1.821043 -0.841046 -0.4161865 -0.0127069 0.8735442 0.2520871 +VERTEX_SE3:QUAT 932 -0.418236 1.771322 -0.955960 -0.3078905 -0.0436683 -0.9170720 0.2495507 +VERTEX_SE3:QUAT 933 -0.317598 1.840393 -0.936380 -0.2400957 -0.3662683 0.1341592 0.8889336 +VERTEX_SE3:QUAT 934 -0.393810 1.903147 -0.938122 0.7391054 0.2016057 -0.6056444 0.2151120 +VERTEX_SE3:QUAT 935 -0.382768 1.772399 -0.913809 0.1725439 0.5342983 -0.8229945 0.0862204 +VERTEX_SE3:QUAT 936 -0.376911 1.810504 -0.941658 -0.1966851 0.3306283 -0.7555667 0.5302064 +VERTEX_SE3:QUAT 937 -0.555332 1.757960 -1.128371 0.3511601 -0.4224093 0.3525606 0.7576001 +VERTEX_SE3:QUAT 938 -0.684377 1.511379 -1.073941 0.0064210 -0.6428077 0.6719410 0.3677667 +VERTEX_SE3:QUAT 939 -0.633580 1.598570 -1.152336 0.4678125 -0.1848864 0.6760437 0.5384547 +VERTEX_SE3:QUAT 940 -0.671892 1.524443 -1.043632 -0.3839502 0.3037636 0.0693285 0.8691970 +VERTEX_SE3:QUAT 941 -0.653899 1.655750 -1.014546 0.1331738 0.4067259 0.6628630 0.6143707 +VERTEX_SE3:QUAT 942 -0.952468 1.757002 -1.096124 -0.4022351 -0.2645752 0.7724203 0.4142146 +VERTEX_SE3:QUAT 943 -1.045452 1.813311 -0.964182 0.3480149 -0.0924202 -0.5544688 0.7502723 +VERTEX_SE3:QUAT 944 -0.970264 1.768279 -0.850893 0.8185493 -0.0586233 0.5201128 0.2366918 +VERTEX_SE3:QUAT 945 -1.004964 1.948351 -0.925254 -0.1209469 0.4833933 0.0992111 0.8613129 +VERTEX_SE3:QUAT 946 -1.009910 1.901057 -0.991192 0.1784580 -0.4827955 -0.5090285 0.6898922 +VERTEX_SE3:QUAT 947 -0.982724 2.065161 -1.020855 -0.3165752 0.3392470 -0.8852314 0.0325105 +VERTEX_SE3:QUAT 948 -1.055772 1.971858 -1.086835 0.8216218 0.1650739 -0.2999264 0.4557766 +VERTEX_SE3:QUAT 949 -1.273899 2.094217 -1.064522 0.2473951 -0.4747950 0.7917443 0.2941197 +VERTEX_SE3:QUAT 950 -1.140638 2.178265 -1.009729 0.4855081 -0.4365998 0.6774218 0.3387657 +VERTEX_SE3:QUAT 951 -1.037953 2.160929 -1.005650 0.5737041 0.4360294 0.4826455 0.4977905 +VERTEX_SE3:QUAT 952 -0.999129 2.204546 -1.038783 0.5235623 0.0836457 -0.7443758 0.4059441 +VERTEX_SE3:QUAT 953 -0.923262 2.223275 -1.346814 -0.3833268 0.0834813 -0.5329959 0.7496712 +VERTEX_SE3:QUAT 954 -1.023988 2.347366 -1.351601 0.3049282 -0.3936369 -0.4454478 0.7440733 +VERTEX_SE3:QUAT 955 -1.024444 2.352493 -1.538515 0.1100074 0.2908666 -0.2368476 0.9204337 +VERTEX_SE3:QUAT 956 -1.016747 2.448740 -1.592225 -0.2955113 -0.1018476 0.3560045 0.8806594 +VERTEX_SE3:QUAT 957 -1.030773 2.434270 -1.891030 0.1576972 -0.0984530 -0.3485076 0.9186844 +VERTEX_SE3:QUAT 958 -0.847802 2.323030 -1.984660 0.3679388 -0.5531566 0.2909740 0.6884570 +VERTEX_SE3:QUAT 959 -0.918960 2.489697 -2.085675 0.1762507 -0.1523655 0.9679804 0.0934576 +VERTEX_SE3:QUAT 960 -0.756331 2.504955 -2.079273 -0.1449329 -0.2260901 -0.8772003 0.3979917 +VERTEX_SE3:QUAT 961 -0.740824 2.749758 -2.166117 0.4462490 0.1383254 -0.4206763 0.7776628 +VERTEX_SE3:QUAT 962 -0.537033 2.867979 -2.254166 0.3053127 0.0152130 0.9121745 0.2729293 +VERTEX_SE3:QUAT 963 -0.452954 2.712308 -2.315329 0.3478057 0.4602145 -0.8026343 0.1516969 +VERTEX_SE3:QUAT 964 -0.366361 2.729795 -2.641165 -0.0872709 -0.2992204 0.9241755 0.2207955 +VERTEX_SE3:QUAT 965 -0.267780 2.626715 -2.701467 0.1978927 0.0825399 0.9518958 0.2189063 +VERTEX_SE3:QUAT 966 -0.335307 2.702030 -2.671699 -0.1142526 -0.2117028 -0.7500495 0.6160796 +VERTEX_SE3:QUAT 967 -0.308349 2.581941 -2.712158 0.3702211 -0.3765215 -0.7352567 0.4249300 +VERTEX_SE3:QUAT 968 -0.009872 2.546152 -2.582308 0.4428716 0.4509948 -0.0230536 0.7745560 +VERTEX_SE3:QUAT 969 0.022029 2.646054 -2.616646 0.1628464 0.6727010 -0.2605552 0.6731014 +VERTEX_SE3:QUAT 970 0.126467 2.714303 -2.628606 -0.5962762 0.4611572 -0.6217248 0.2127135 +VERTEX_SE3:QUAT 971 -0.003851 2.661402 -2.575781 -0.3388463 -0.4193223 0.8140871 0.2159033 +VERTEX_SE3:QUAT 972 0.211242 2.700808 -2.584274 0.2944092 0.0047063 -0.9149689 0.2759222 +VERTEX_SE3:QUAT 973 0.429247 2.620042 -2.709390 0.6155910 0.1049698 -0.7736322 0.1073422 +VERTEX_SE3:QUAT 974 0.467739 2.760613 -2.702081 0.4190619 -0.3458804 -0.6650566 0.5123022 +VERTEX_SE3:QUAT 975 0.409891 2.551085 -2.648884 0.6774248 0.0475248 -0.1504060 0.7184811 +VERTEX_SE3:QUAT 976 0.513023 2.548669 -2.653343 0.0433826 0.0271082 0.2285051 0.9721978 +VERTEX_SE3:QUAT 977 0.701031 2.488249 -2.727131 -0.4422442 -0.5334010 0.6988678 0.1774464 +VERTEX_SE3:QUAT 978 0.851999 2.213063 -2.759650 0.1804507 -0.7406528 0.3094477 0.5684304 +VERTEX_SE3:QUAT 979 0.912176 2.094356 -2.824087 0.0304362 0.3951436 0.8755348 0.2763583 +VERTEX_SE3:QUAT 980 1.066297 1.953632 -2.601127 -0.3381442 0.0658429 -0.9387653 0.0065560 +VERTEX_SE3:QUAT 981 1.213767 1.862619 -2.633379 -0.1708088 -0.1260525 -0.5632001 0.7985867 +VERTEX_SE3:QUAT 982 1.167849 1.822737 -2.569760 0.3750910 -0.5910337 0.6357324 0.3253155 +VERTEX_SE3:QUAT 983 1.059273 1.948997 -2.588418 -0.1623987 0.1313529 0.8502386 0.4831847 +VERTEX_SE3:QUAT 984 1.090482 1.919714 -2.757861 -0.1063758 -0.5315011 0.8127802 0.2134926 +VERTEX_SE3:QUAT 985 1.227440 1.970627 -2.797061 -0.2415717 0.1201676 -0.9421604 0.1988380 +VERTEX_SE3:QUAT 986 1.411301 1.983930 -2.779402 0.2410363 0.2213847 -0.0773233 0.9417598 +VERTEX_SE3:QUAT 987 1.403454 1.807598 -2.853575 0.0145104 0.4564200 -0.8381635 0.2982485 +VERTEX_SE3:QUAT 988 1.495150 1.757880 -2.928056 0.7809271 -0.4276467 -0.0055445 0.4552367 +VERTEX_SE3:QUAT 989 1.514691 1.617291 -2.772989 0.7439131 -0.1579143 -0.1948102 0.6194396 +VERTEX_SE3:QUAT 990 1.559633 1.550184 -2.566470 0.0007560 -0.5497058 0.2875593 0.7843039 +VERTEX_SE3:QUAT 991 1.542979 1.553309 -2.488425 0.3951001 -0.3259987 -0.0793236 0.8551775 +VERTEX_SE3:QUAT 992 1.518259 1.390303 -2.550110 0.5460821 0.4369171 0.2187949 0.6804606 +VERTEX_SE3:QUAT 993 1.600080 1.386128 -2.481381 0.3623805 0.7058053 -0.2809864 0.5399684 +VERTEX_SE3:QUAT 994 1.570167 1.413192 -2.665159 0.3458191 -0.4490500 0.1519163 0.8097436 +VERTEX_SE3:QUAT 995 1.793867 1.286734 -2.714011 -0.1581790 -0.1827989 0.8751928 0.4190484 +VERTEX_SE3:QUAT 996 1.920733 1.348486 -2.718848 0.1640769 0.3527119 0.2625869 0.8830182 +VERTEX_SE3:QUAT 997 2.079741 1.455733 -2.646254 0.2729796 -0.8107452 0.3277951 0.4009048 +VERTEX_SE3:QUAT 998 2.082902 1.416526 -2.639510 -0.1402263 0.3339954 -0.8982717 0.2487804 +VERTEX_SE3:QUAT 999 2.079074 1.445064 -2.632013 -0.2539539 -0.2513324 0.8375506 0.4133382 +VERTEX_SE3:QUAT 1000 2.106907 1.484433 -2.735300 0.0129640 -0.6786650 0.4843048 0.5519915 +VERTEX_SE3:QUAT 1001 2.132329 1.325780 -2.787804 0.7519279 0.1491719 0.6160855 0.1810824 +VERTEX_SE3:QUAT 1002 2.285258 1.307587 -2.751525 0.0652275 -0.4013062 0.9080096 0.1010802 +VERTEX_SE3:QUAT 1003 2.268677 1.332802 -2.801050 0.5706733 0.4608833 -0.3003958 0.6096564 +VERTEX_SE3:QUAT 1004 2.315933 1.360747 -2.788362 0.5774410 0.1406305 -0.7644927 0.2496714 +VERTEX_SE3:QUAT 1005 2.123662 1.208120 -2.610779 0.7653237 0.4093164 -0.1608388 0.4699688 +VERTEX_SE3:QUAT 1006 2.083910 1.213993 -2.549698 0.7245704 0.2334545 -0.1168073 0.6378501 +VERTEX_SE3:QUAT 1007 1.944132 1.134184 -2.622504 0.0556082 0.5498963 -0.7574169 0.3476224 +VERTEX_SE3:QUAT 1008 1.793950 1.232853 -2.484627 0.5768282 0.1919638 0.6025055 0.5171134 +VERTEX_SE3:QUAT 1009 1.809726 1.174598 -2.596539 0.3131172 -0.3364835 0.8646251 0.2028790 +VERTEX_SE3:QUAT 1010 1.792374 1.106098 -2.497599 -0.3206254 0.1725652 -0.4942358 0.7893995 +VERTEX_SE3:QUAT 1011 1.692841 1.077883 -2.404492 0.2392194 0.5253124 0.0545447 0.8147674 +VERTEX_SE3:QUAT 1012 1.848103 1.074215 -2.249717 0.5059712 -0.2504907 0.8252996 0.0113196 +VERTEX_SE3:QUAT 1013 1.945899 1.119358 -2.105544 0.2440197 -0.1891322 0.8074588 0.5026865 +VERTEX_SE3:QUAT 1014 1.892008 0.816240 -2.008340 0.2397759 -0.0660071 -0.7796840 0.5746681 +VERTEX_SE3:QUAT 1015 2.060873 0.652966 -1.995586 0.6247486 0.0461946 -0.1972359 0.7540910 +VERTEX_SE3:QUAT 1016 1.945512 0.526262 -1.867492 -0.2542900 0.3049973 0.2340942 0.8874194 +VERTEX_SE3:QUAT 1017 2.028610 0.482777 -1.834983 0.5229473 0.2101704 -0.4330180 0.7034557 +VERTEX_SE3:QUAT 1018 1.962362 0.449554 -1.747558 0.1651874 -0.6495953 0.2335290 0.7044170 +VERTEX_SE3:QUAT 1019 1.874633 0.304869 -1.706284 0.7519438 0.3373368 -0.3804478 0.4195758 +VERTEX_SE3:QUAT 1020 1.781284 0.404007 -1.654255 0.3315641 0.3715751 0.7072370 0.5018097 +VERTEX_SE3:QUAT 1021 1.703656 0.328422 -1.660504 -0.5448388 0.0180054 -0.7096343 0.4463694 +VERTEX_SE3:QUAT 1022 1.617930 0.360045 -1.541744 0.1285812 -0.1744552 0.8278670 0.5173669 +VERTEX_SE3:QUAT 1023 1.491512 0.325020 -1.596731 -0.0065429 0.7915526 -0.0208112 0.6107116 +VERTEX_SE3:QUAT 1024 1.431370 0.097594 -1.522213 0.2574287 -0.4318554 0.8560636 0.1199438 +VERTEX_SE3:QUAT 1025 1.337337 0.124357 -1.617066 0.5165406 -0.0387152 0.1733918 0.8376289 +VERTEX_SE3:QUAT 1026 1.334797 0.133527 -1.883365 0.8941129 -0.1237484 0.2436793 0.3547800 +VERTEX_SE3:QUAT 1027 1.184746 0.123515 -1.885581 -0.0265880 -0.4137019 0.8864023 0.2059969 +VERTEX_SE3:QUAT 1028 1.071510 0.170822 -1.848138 -0.2116346 0.6156885 0.1311680 0.7476185 +VERTEX_SE3:QUAT 1029 1.091595 0.209496 -1.910736 -0.1117481 -0.0160244 -0.6172647 0.7786141 +VERTEX_SE3:QUAT 1030 1.119158 0.193890 -1.748363 0.0179610 0.0049063 0.4599624 0.8877432 +VERTEX_SE3:QUAT 1031 1.086053 0.160552 -1.780680 -0.2591465 -0.7844297 0.5553568 0.0953513 +VERTEX_SE3:QUAT 1032 1.022044 0.103888 -1.749888 0.6252892 0.1559682 -0.7478636 0.1593342 +VERTEX_SE3:QUAT 1033 0.942858 0.242867 -1.717407 0.7242064 0.3565340 0.1511352 0.5705846 +VERTEX_SE3:QUAT 1034 0.851915 0.283592 -1.780859 0.8086096 -0.2546304 -0.1366897 0.5124742 +VERTEX_SE3:QUAT 1035 0.917031 0.165994 -1.696287 0.2728215 -0.1629220 -0.2357178 0.9184019 +VERTEX_SE3:QUAT 1036 0.915531 0.330101 -1.474551 -0.3639368 -0.2291800 0.6160163 0.6599625 +VERTEX_SE3:QUAT 1037 0.954145 0.441250 -1.688537 -0.3238784 -0.0146434 -0.3450784 0.8808003 +VERTEX_SE3:QUAT 1038 1.007368 0.444022 -1.707497 -0.3098837 0.2721074 -0.9093390 0.0550657 +VERTEX_SE3:QUAT 1039 1.032939 0.479667 -1.737760 -0.1113994 -0.3044238 0.1714557 0.9303329 +VERTEX_SE3:QUAT 1040 0.913900 0.479010 -1.531290 0.1619436 0.6945477 -0.4000525 0.5756177 +VERTEX_SE3:QUAT 1041 0.777397 0.541382 -1.470242 -0.2480007 0.1132711 0.9609600 0.0471289 +VERTEX_SE3:QUAT 1042 0.775333 0.635778 -1.561732 -0.0902783 0.2862465 -0.2539531 0.9194676 +VERTEX_SE3:QUAT 1043 0.650605 0.533416 -1.537909 -0.2579977 -0.0239889 0.9658475 0.0005375 +VERTEX_SE3:QUAT 1044 0.688029 0.681733 -1.652740 0.7199660 0.2849185 -0.3798240 0.5061661 +VERTEX_SE3:QUAT 1045 0.607720 0.792508 -1.665333 -0.0279412 0.3101605 0.0543735 0.9487167 +VERTEX_SE3:QUAT 1046 0.502075 0.815692 -1.659472 0.4234391 -0.0554234 -0.3552712 0.8315107 +VERTEX_SE3:QUAT 1047 0.369773 0.756207 -1.710600 0.1396091 0.3453374 0.2730254 0.8869659 +VERTEX_SE3:QUAT 1048 0.335259 0.846767 -1.600707 0.5681411 0.0994204 0.3757844 0.7253394 +VERTEX_SE3:QUAT 1049 0.216053 0.958357 -1.707124 0.7207956 -0.3629435 0.4487082 0.3839097 +VERTEX_SE3:QUAT 1050 0.266455 0.990415 -1.927963 0.1598379 0.3228268 0.2980170 0.8839800 +VERTEX_SE3:QUAT 1051 0.246728 0.968125 -1.996925 -0.1864232 0.2720870 0.9292859 0.1662611 +VERTEX_SE3:QUAT 1052 0.354247 1.036976 -2.209765 0.2540783 -0.6163804 0.3155410 0.6752432 +VERTEX_SE3:QUAT 1053 0.568801 1.091649 -2.403292 0.4883427 -0.3766542 -0.6693812 0.4142244 +VERTEX_SE3:QUAT 1054 0.569613 1.200362 -2.474753 -0.0673551 -0.0691281 0.3917840 0.9149808 +VERTEX_SE3:QUAT 1055 0.792026 1.252274 -2.519493 -0.2512351 -0.3757339 0.5928911 0.6664722 +VERTEX_SE3:QUAT 1056 0.902552 1.449585 -2.478389 0.2100212 -0.1931283 -0.1566800 0.9455390 +VERTEX_SE3:QUAT 1057 0.953056 1.330835 -2.510484 -0.2854552 -0.2098013 -0.8716806 0.3386321 +VERTEX_SE3:QUAT 1058 0.984350 1.397362 -2.531631 -0.0931659 -0.3072665 0.1868040 0.9284458 +VERTEX_SE3:QUAT 1059 1.163324 1.388587 -2.544490 -0.5379997 0.3741566 -0.6966928 0.2918601 +VERTEX_SE3:QUAT 1060 1.100190 1.336072 -2.665095 -0.0044670 -0.8306032 0.4747720 0.2909808 +VERTEX_SE3:QUAT 1061 1.195011 1.465437 -2.598893 0.0995622 0.1660235 0.8546799 0.4817114 +VERTEX_SE3:QUAT 1062 1.212279 1.651118 -2.553691 0.7874865 0.1118770 0.2288095 0.5612439 +VERTEX_SE3:QUAT 1063 1.143039 1.625820 -2.479664 0.0656310 -0.4185743 -0.6152632 0.6647851 +VERTEX_SE3:QUAT 1064 1.239433 1.477753 -2.531329 0.0802928 -0.2918036 0.9501879 0.0744758 +VERTEX_SE3:QUAT 1065 1.385465 1.615727 -2.509984 -0.0127885 -0.5039734 -0.6403139 0.5795218 +VERTEX_SE3:QUAT 1066 1.315281 1.598771 -2.950862 0.4801003 -0.0926149 -0.3581675 0.7953881 +VERTEX_SE3:QUAT 1067 1.473193 1.551983 -2.846742 0.6625792 0.1731430 0.2203981 0.6945754 +VERTEX_SE3:QUAT 1068 1.608147 1.679041 -2.790507 -0.5673930 -0.4750534 0.3088351 0.5975034 +VERTEX_SE3:QUAT 1069 1.666900 1.659842 -2.763046 0.3310643 -0.6435371 -0.4627531 0.5119727 +VERTEX_SE3:QUAT 1070 1.704274 1.727569 -2.797057 0.4527665 -0.3809222 0.7795327 0.2054982 +VERTEX_SE3:QUAT 1071 1.668747 1.558805 -2.819371 -0.3764170 0.1011727 0.7659915 0.5112058 +VERTEX_SE3:QUAT 1072 1.740192 1.699473 -3.019114 0.2747675 0.0713691 0.3940201 0.8741610 +VERTEX_SE3:QUAT 1073 1.910697 1.726887 -3.069125 -0.3938796 0.6732306 -0.6257906 0.0023341 +VERTEX_SE3:QUAT 1074 1.927649 1.824204 -2.940524 0.1249964 -0.4096290 -0.3645880 0.8268347 +VERTEX_SE3:QUAT 1075 2.026480 1.764485 -2.783709 -0.2867728 -0.5150830 0.3923577 0.7060498 +VERTEX_SE3:QUAT 1076 2.281979 1.785642 -2.692169 -0.1778638 -0.2702635 -0.3748796 0.8687850 +VERTEX_SE3:QUAT 1077 2.261387 1.644566 -2.723855 0.0386056 -0.0376308 0.8161091 0.5753776 +VERTEX_SE3:QUAT 1078 2.350231 1.543031 -2.627872 -0.0076820 0.2745279 0.9497356 0.1502589 +VERTEX_SE3:QUAT 1079 2.308229 1.589626 -2.675176 0.5126664 0.2106637 -0.6716354 0.4916297 +VERTEX_SE3:QUAT 1080 2.469481 1.627416 -2.546497 0.0032013 0.0167335 -0.9643077 0.2642354 +VERTEX_SE3:QUAT 1081 2.429744 1.546940 -2.554516 0.0667940 -0.6130542 0.7252490 0.3061323 +VERTEX_SE3:QUAT 1082 2.489989 1.515105 -2.430686 0.4517264 -0.3707659 0.7335631 0.3469309 +VERTEX_SE3:QUAT 1083 2.454904 1.460735 -2.541920 0.5156952 0.3524901 0.5140719 0.5878258 +VERTEX_SE3:QUAT 1084 2.444708 1.475188 -2.417324 -0.4140098 0.0714115 -0.2760585 0.8644582 +VERTEX_SE3:QUAT 1085 2.522513 1.184391 -2.402562 0.0024905 -0.4227047 0.1486222 0.8939944 +VERTEX_SE3:QUAT 1086 2.529308 1.162291 -2.420038 -0.6519667 -0.4121742 0.6233175 0.1285578 +VERTEX_SE3:QUAT 1087 2.742820 1.311947 -2.332646 -0.0207090 -0.0692435 0.1534114 0.9855158 +VERTEX_SE3:QUAT 1088 2.699908 1.334371 -2.149426 -0.0248555 -0.0410436 -0.5992920 0.7990912 +VERTEX_SE3:QUAT 1089 2.711560 1.451091 -1.990777 0.3713354 0.2576915 0.3931107 0.8007303 +VERTEX_SE3:QUAT 1090 2.484631 1.602224 -1.981734 -0.0657757 -0.4020456 -0.6772642 0.6126550 +VERTEX_SE3:QUAT 1091 2.410313 1.595301 -1.915971 0.5810353 0.2640832 -0.0739908 0.7662789 +VERTEX_SE3:QUAT 1092 2.291257 1.646776 -1.832162 -0.0374402 -0.4062472 0.2709585 0.8718618 +VERTEX_SE3:QUAT 1093 2.222092 1.587275 -1.844122 0.0404054 0.6070903 -0.6319746 0.4800177 +VERTEX_SE3:QUAT 1094 2.284771 1.518305 -1.789808 -0.3697562 0.3684050 -0.6204276 0.5853441 +VERTEX_SE3:QUAT 1095 2.362208 1.464644 -1.671561 0.3134244 0.5214950 -0.3833002 0.6949022 +VERTEX_SE3:QUAT 1096 2.356022 1.416047 -1.547291 0.3402796 -0.1717819 -0.9160611 0.1246307 +VERTEX_SE3:QUAT 1097 2.425435 1.359008 -1.506838 0.2898490 -0.0576341 0.6844072 0.6665228 +VERTEX_SE3:QUAT 1098 2.284745 1.279980 -1.370588 0.0284426 0.1256658 0.6367201 0.7602543 +VERTEX_SE3:QUAT 1099 2.295711 1.179963 -1.329321 0.4493632 -0.2101627 0.0716586 0.8653146 +VERTEX_SE3:QUAT 1100 2.446221 1.072356 -1.274353 0.3020272 -0.5057294 0.7538406 0.2911043 +VERTEX_SE3:QUAT 1101 2.464222 1.017895 -1.160348 -0.0971800 -0.2919929 -0.1111588 0.9449550 +VERTEX_SE3:QUAT 1102 2.454634 1.013153 -1.290136 0.1101338 -0.7811326 0.4100398 0.4577878 +VERTEX_SE3:QUAT 1103 2.367448 1.204510 -1.227725 0.5157114 0.1547596 0.2763110 0.7960801 +VERTEX_SE3:QUAT 1104 2.619694 1.073421 -1.273692 0.5518508 0.0188693 -0.7558116 0.3519282 +VERTEX_SE3:QUAT 1105 2.592892 1.137847 -1.463520 -0.0304965 -0.3622608 -0.8709336 0.3306232 +VERTEX_SE3:QUAT 1106 2.597320 1.028787 -1.464929 -0.4582470 -0.4716883 0.5218541 0.5433122 +VERTEX_SE3:QUAT 1107 2.483991 0.973904 -1.311045 -0.3962023 0.2921439 0.8456428 0.2063104 +VERTEX_SE3:QUAT 1108 2.731981 1.134320 -1.368375 0.0673202 0.6453660 -0.5499676 0.5258387 +VERTEX_SE3:QUAT 1109 2.576768 1.270164 -1.534658 -0.1842722 -0.7359374 -0.0753073 0.6471234 +VERTEX_SE3:QUAT 1110 2.487142 1.406302 -1.344532 0.3613912 0.1705871 0.3127134 0.8616883 +VERTEX_SE3:QUAT 1111 2.414023 1.389254 -1.180529 -0.2560586 0.6268772 -0.7344841 0.0446321 +VERTEX_SE3:QUAT 1112 2.270043 1.355451 -1.246655 0.3815524 0.3410969 0.2600508 0.8188066 +VERTEX_SE3:QUAT 1113 2.232335 1.432128 -1.174414 0.8184066 -0.0742815 -0.0353422 0.5687212 +VERTEX_SE3:QUAT 1114 1.996718 1.251761 -1.264305 0.5210204 -0.2900855 0.3669611 0.7139522 +VERTEX_SE3:QUAT 1115 1.940640 1.249316 -1.282962 0.4549493 -0.0782185 0.1106791 0.8801438 +VERTEX_SE3:QUAT 1116 1.902715 1.265982 -1.337681 -0.0833077 0.0412581 -0.7810227 0.6175444 +VERTEX_SE3:QUAT 1117 1.941127 1.175308 -1.309475 -0.6598988 0.1183984 0.7201596 0.1785653 +VERTEX_SE3:QUAT 1118 1.851101 1.207777 -1.207797 -0.0062752 -0.6851444 0.1777582 0.7063567 +VERTEX_SE3:QUAT 1119 1.787802 1.190276 -1.340258 0.6565452 0.0350027 0.2179367 0.7212675 +VERTEX_SE3:QUAT 1120 1.741719 1.145600 -1.484647 -0.2022136 0.1263985 0.9552347 0.1750991 +VERTEX_SE3:QUAT 1121 1.802209 1.130479 -1.572753 -0.0821073 -0.2028111 -0.5935298 0.7744988 +VERTEX_SE3:QUAT 1122 1.552109 1.139096 -1.679372 0.2535212 -0.4748978 0.8369180 0.0988301 +VERTEX_SE3:QUAT 1123 1.353300 1.188596 -1.770454 -0.4067068 -0.5308430 0.4267695 0.6088210 +VERTEX_SE3:QUAT 1124 1.336593 1.274081 -1.656326 0.0660255 0.5155682 -0.3351136 0.7858301 +VERTEX_SE3:QUAT 1125 1.571747 1.298764 -1.656578 0.5751858 0.3429358 -0.2058431 0.7135720 +VERTEX_SE3:QUAT 1126 1.538529 1.266051 -1.721592 0.2868241 -0.1862221 0.8634694 0.3707746 +VERTEX_SE3:QUAT 1127 1.607701 1.320243 -1.850811 0.3297070 0.3738365 -0.4924243 0.7134829 +VERTEX_SE3:QUAT 1128 1.421496 1.363687 -1.804677 -0.1687285 0.1603896 -0.6074340 0.7594931 +VERTEX_SE3:QUAT 1129 1.300126 1.627930 -1.791881 0.2382601 0.1547820 0.8920980 0.3513344 +VERTEX_SE3:QUAT 1130 1.195878 1.601912 -1.746619 0.2135013 -0.4592294 -0.5494302 0.6645690 +VERTEX_SE3:QUAT 1131 1.076093 1.608307 -1.682026 -0.1452844 0.2168859 0.1783743 0.9487020 +VERTEX_SE3:QUAT 1132 0.987635 1.721985 -1.760573 0.1100993 0.2945673 -0.7302878 0.6064553 +VERTEX_SE3:QUAT 1133 0.831937 1.702486 -1.807797 0.7590394 0.1203233 -0.1754930 0.6152916 +VERTEX_SE3:QUAT 1134 0.826805 1.832835 -1.867288 -0.0590654 -0.4909794 -0.8531676 0.1659986 +VERTEX_SE3:QUAT 1135 0.953292 1.841896 -1.829036 0.0106013 0.4653697 -0.5917440 0.6581472 +VERTEX_SE3:QUAT 1136 0.891373 1.852310 -2.073371 0.5806517 -0.0970325 0.3433790 0.7317918 +VERTEX_SE3:QUAT 1137 0.755107 1.877245 -1.929107 0.8468835 0.2151868 0.0203382 0.4858697 +VERTEX_SE3:QUAT 1138 0.828546 2.017656 -2.005277 -0.3219611 0.1357661 -0.3668309 0.8621738 +VERTEX_SE3:QUAT 1139 0.807442 2.193707 -2.141822 -0.3800601 -0.1971146 0.8999865 0.0820030 +VERTEX_SE3:QUAT 1140 0.755040 2.360275 -2.108606 0.0570201 -0.7385476 0.5638892 0.3651372 +VERTEX_SE3:QUAT 1141 0.638525 2.469842 -2.121049 -0.2466695 -0.5456007 0.7401372 0.3060571 +VERTEX_SE3:QUAT 1142 0.684450 2.537147 -2.120002 0.8064471 0.2550689 0.2166500 0.4874891 +VERTEX_SE3:QUAT 1143 0.640178 2.547406 -2.137636 0.1097244 0.2904681 -0.4745316 0.8236556 +VERTEX_SE3:QUAT 1144 0.797094 2.575481 -2.178942 -0.1514577 -0.4317709 0.1359557 0.8787209 +VERTEX_SE3:QUAT 1145 0.805413 2.728396 -2.268127 0.2450366 0.5601310 0.0033349 0.7913275 +VERTEX_SE3:QUAT 1146 0.840040 2.676922 -2.366745 -0.3743293 0.2194930 -0.1401495 0.8899767 +VERTEX_SE3:QUAT 1147 0.660660 2.714497 -2.357866 0.0245470 -0.3127934 0.2705458 0.9101443 +VERTEX_SE3:QUAT 1148 0.507137 2.941880 -2.399966 0.3601651 0.2168661 0.3820177 0.8229901 +VERTEX_SE3:QUAT 1149 0.400250 3.059704 -2.450719 0.0604579 0.7233641 -0.1008300 0.6803841 +VERTEX_SE3:QUAT 1150 0.260469 3.059714 -2.525729 0.5706736 0.3711152 -0.0236141 0.7321526 +VERTEX_SE3:QUAT 1151 0.309549 3.141786 -2.755125 -0.1372154 0.5167510 -0.2577508 0.8048011 +VERTEX_SE3:QUAT 1152 0.222409 3.294107 -2.754589 0.2451684 -0.0168005 0.3107097 0.9181883 +VERTEX_SE3:QUAT 1153 0.331338 3.321834 -2.822540 0.2206699 -0.2630239 0.7238360 0.5984853 +VERTEX_SE3:QUAT 1154 0.187868 3.401437 -2.935632 0.4848173 0.0445154 -0.7157761 0.5006347 +VERTEX_SE3:QUAT 1155 0.172155 3.293210 -2.900903 -0.0729055 -0.2071480 0.9176816 0.3311118 +VERTEX_SE3:QUAT 1156 0.289718 3.220093 -3.106534 -0.1208630 0.2367569 0.9457159 0.1869753 +VERTEX_SE3:QUAT 1157 0.397185 3.212952 -3.043720 0.2198334 0.6135396 -0.6668067 0.3614019 +VERTEX_SE3:QUAT 1158 0.398008 3.301837 -3.288359 -0.1447235 -0.4208689 0.7737713 0.4507798 +VERTEX_SE3:QUAT 1159 0.387663 3.395260 -3.400472 -0.1876978 0.3775803 -0.5702768 0.7049731 +VERTEX_SE3:QUAT 1160 0.567665 3.391702 -3.291835 0.4160025 -0.1919336 -0.6458223 0.6107512 +VERTEX_SE3:QUAT 1161 0.587982 3.585389 -3.440800 0.0033715 0.4063905 0.0365472 0.9129620 +VERTEX_SE3:QUAT 1162 0.698815 3.626178 -3.376446 0.1391851 0.6590350 -0.5032501 0.5413313 +VERTEX_SE3:QUAT 1163 0.641922 3.574447 -3.528739 0.7552260 -0.0558565 0.0776936 0.6484424 +VERTEX_SE3:QUAT 1164 0.529785 3.494045 -3.518813 0.3853492 0.3379504 -0.4142672 0.7521158 +VERTEX_SE3:QUAT 1165 0.660890 3.508474 -3.576182 -0.3029553 -0.5009609 0.6581440 0.4733950 +VERTEX_SE3:QUAT 1166 0.804623 3.493037 -3.630304 0.0612486 0.4638552 -0.1905243 0.8630107 +VERTEX_SE3:QUAT 1167 0.956264 3.598050 -3.787868 0.4696881 0.4845898 0.1848974 0.7144080 +VERTEX_SE3:QUAT 1168 1.140104 3.694819 -3.890884 -0.0068462 -0.1631136 0.1973768 0.9666382 +VERTEX_SE3:QUAT 1169 1.048474 3.447347 -4.001844 0.0749897 -0.7304405 0.3511229 0.5809870 +VERTEX_SE3:QUAT 1170 1.165147 3.496371 -3.936149 0.5165279 0.0537214 0.3314020 0.7877091 +VERTEX_SE3:QUAT 1171 1.178751 3.402832 -4.027064 0.3265311 -0.7495328 0.5757085 0.0117351 +VERTEX_SE3:QUAT 1172 1.017089 3.214486 -3.950016 -0.3374817 -0.2317850 0.8025865 0.4338627 +VERTEX_SE3:QUAT 1173 0.894894 3.069030 -4.073562 0.4528996 -0.2170063 -0.2517016 0.8273068 +VERTEX_SE3:QUAT 1174 0.871238 3.107607 -3.991888 0.5550109 0.5832290 0.3672936 0.4657276 +VERTEX_SE3:QUAT 1175 0.916220 3.213846 -3.951200 -0.1438898 0.4729078 0.8188777 0.2917075 +VERTEX_SE3:QUAT 1176 1.087815 3.333436 -3.876741 0.2109862 -0.3081983 -0.8384651 0.3968311 +VERTEX_SE3:QUAT 1177 1.071430 3.266491 -3.820535 -0.5410936 0.5718969 -0.5908854 0.1760853 +VERTEX_SE3:QUAT 1178 1.140516 3.169696 -3.784392 0.0959128 -0.3650780 0.1928126 0.9057274 +VERTEX_SE3:QUAT 1179 1.260404 2.979308 -3.892228 0.2479143 0.5447094 -0.2112403 0.7727921 +VERTEX_SE3:QUAT 1180 1.453511 3.052087 -3.880843 -0.0956972 0.3891132 -0.5705313 0.7168870 +VERTEX_SE3:QUAT 1181 1.405565 3.156889 -4.002689 0.1198630 0.2359438 -0.6547479 0.7080033 +VERTEX_SE3:QUAT 1182 1.639936 3.167935 -3.803649 0.4357133 -0.2121917 0.6830055 0.5464724 +VERTEX_SE3:QUAT 1183 1.566883 3.215063 -3.683451 0.5182741 0.1392038 -0.8275098 0.1650510 +VERTEX_SE3:QUAT 1184 1.737327 3.229690 -3.661186 -0.3992319 0.1947606 -0.8823831 0.1551846 +VERTEX_SE3:QUAT 1185 1.732026 3.041850 -3.523135 -0.1651676 0.4258936 0.8294122 0.3215736 +VERTEX_SE3:QUAT 1186 1.742897 3.019157 -3.622292 0.4018474 0.5385742 -0.4740118 0.5690073 +VERTEX_SE3:QUAT 1187 1.890300 2.991122 -3.727098 0.2556333 0.4751405 -0.1105306 0.8346713 +VERTEX_SE3:QUAT 1188 1.827228 3.008825 -3.726180 0.2873041 -0.1885129 0.6726304 0.6553531 +VERTEX_SE3:QUAT 1189 1.877579 2.914818 -3.760813 -0.6974045 0.3362776 -0.3675303 0.5152337 +VERTEX_SE3:QUAT 1190 1.949582 2.884550 -3.582481 0.1657015 0.5374877 -0.5946430 0.5744995 +VERTEX_SE3:QUAT 1191 2.002508 2.907434 -3.536013 0.0114018 0.5915079 -0.7877221 0.1717040 +VERTEX_SE3:QUAT 1192 2.107862 2.812702 -3.637185 -0.4215127 -0.0881524 0.2915393 0.8541434 +VERTEX_SE3:QUAT 1193 2.090074 2.800839 -3.685767 0.3672004 0.0094878 0.6721998 0.6428229 +VERTEX_SE3:QUAT 1194 2.238665 2.801459 -3.680795 -0.1388127 -0.2051501 0.2382228 0.9390923 +VERTEX_SE3:QUAT 1195 2.260069 2.821034 -3.573377 0.6517130 0.2973906 0.6967463 0.0370609 +VERTEX_SE3:QUAT 1196 2.348209 2.744901 -3.472689 0.3069875 -0.4063360 0.6387470 0.5767599 +VERTEX_SE3:QUAT 1197 2.369177 2.847553 -3.402780 0.0505643 0.7143036 -0.5243557 0.4607220 +VERTEX_SE3:QUAT 1198 2.404676 2.700397 -3.436402 0.3232106 0.3020401 -0.3660078 0.8187459 +VERTEX_SE3:QUAT 1199 2.442615 2.760927 -3.382542 -0.2147721 -0.2001555 0.8445665 0.4477925 +VERTEX_SE3:QUAT 1200 2.526350 2.712472 -3.310295 -0.2653178 0.2752419 0.4582521 0.8024048 +VERTEX_SE3:QUAT 1201 2.444040 2.637089 -3.322547 -0.3368150 0.0601452 0.2969421 0.8914952 +VERTEX_SE3:QUAT 1202 2.453885 2.680370 -3.227809 0.1128403 0.6010267 0.1496923 0.7769338 +VERTEX_SE3:QUAT 1203 2.402007 2.699827 -3.080132 -0.2493886 0.6165515 -0.7074346 0.2391776 +VERTEX_SE3:QUAT 1204 2.471504 2.694721 -3.230990 -0.2565145 -0.2401376 0.0076764 0.9362026 +VERTEX_SE3:QUAT 1205 2.421794 2.629203 -3.072462 -0.0307748 -0.0583541 -0.0313175 0.9973299 +VERTEX_SE3:QUAT 1206 2.398674 2.710738 -3.020349 0.1065368 -0.8279416 0.5377553 0.1182451 +VERTEX_SE3:QUAT 1207 2.303502 2.548119 -2.818558 0.1754708 -0.3676197 -0.9101375 0.0756009 +VERTEX_SE3:QUAT 1208 2.318746 2.450855 -2.838473 0.2585621 -0.2224107 -0.8651953 0.3675815 +VERTEX_SE3:QUAT 1209 2.298918 2.427733 -2.863761 0.1935202 0.5560440 -0.7707960 0.2433897 +VERTEX_SE3:QUAT 1210 2.304351 2.415509 -2.890470 0.4518162 0.4696651 -0.5668000 0.5039986 +VERTEX_SE3:QUAT 1211 2.306653 2.376663 -2.888498 -0.1549490 0.3223798 -0.5886005 0.7249907 +VERTEX_SE3:QUAT 1212 2.281296 2.325957 -2.754466 0.3296918 0.4590807 -0.4671131 0.6799658 +VERTEX_SE3:QUAT 1213 2.321371 2.285698 -2.797482 -0.4569056 0.2895230 -0.3583396 0.7609247 +VERTEX_SE3:QUAT 1214 2.424659 2.395651 -2.764477 0.7266007 0.0690795 0.4988505 0.4673625 +VERTEX_SE3:QUAT 1215 2.386799 2.368980 -2.751185 0.0709285 0.7538120 -0.6408852 0.1265021 +VERTEX_SE3:QUAT 1216 2.366875 2.373429 -2.740999 -0.3746475 0.2309495 -0.4241975 0.7914279 +VERTEX_SE3:QUAT 1217 2.266123 2.237792 -2.711766 0.7381548 0.2359953 -0.5314690 0.3420152 +VERTEX_SE3:QUAT 1218 2.128652 2.266006 -2.685261 -0.1074519 -0.3036392 0.8963854 0.3045498 +VERTEX_SE3:QUAT 1219 2.002744 2.193767 -2.770026 0.1225895 0.5079276 -0.8511900 0.0495677 +VERTEX_SE3:QUAT 1220 1.782676 2.149470 -2.665070 0.6277204 0.4670750 -0.4238292 0.4562640 +VERTEX_SE3:QUAT 1221 1.710895 2.052521 -2.822183 0.6903096 0.5294259 -0.0779158 0.4869394 +VERTEX_SE3:QUAT 1222 1.634970 1.941752 -2.691470 0.1327909 -0.3558459 -0.6478044 0.6603709 +VERTEX_SE3:QUAT 1223 1.557714 2.145510 -2.609614 -0.4986485 0.7280028 -0.4675925 0.0521420 +VERTEX_SE3:QUAT 1224 1.401205 2.082999 -2.551206 0.4911438 -0.4466864 0.7073800 0.2426159 +VERTEX_SE3:QUAT 1225 1.520418 2.218978 -2.400415 0.1323010 0.0676269 0.2813071 0.9480450 +VERTEX_SE3:QUAT 1226 1.626055 2.207612 -2.452607 0.3393898 0.5578247 -0.7418839 0.1524940 +VERTEX_SE3:QUAT 1227 1.558431 2.392089 -2.358444 0.8528718 -0.2035100 0.2644399 0.4015781 +VERTEX_SE3:QUAT 1228 1.474388 2.369241 -2.384230 -0.1895586 -0.4717985 0.7514051 0.4205522 +VERTEX_SE3:QUAT 1229 1.435288 2.332976 -2.312925 0.1504694 -0.2632648 -0.3949484 0.8672176 +VERTEX_SE3:QUAT 1230 1.543782 2.383856 -2.364388 -0.0486270 0.8514723 -0.5011843 0.1464400 +VERTEX_SE3:QUAT 1231 1.636594 2.448204 -2.460283 -0.3744553 -0.5217256 0.7368257 0.2113610 +VERTEX_SE3:QUAT 1232 1.283421 2.260444 -2.460619 -0.4174009 0.1523680 -0.1101969 0.8890541 +VERTEX_SE3:QUAT 1233 1.242392 2.148616 -2.473720 0.1740781 0.4015691 0.3785505 0.8155603 +VERTEX_SE3:QUAT 1234 1.287691 2.141069 -2.414684 0.4365803 -0.4082582 0.1188294 0.7928445 +VERTEX_SE3:QUAT 1235 1.351949 1.973247 -2.350169 0.1816869 -0.7428440 0.6359833 0.1034307 +VERTEX_SE3:QUAT 1236 1.418674 1.983941 -2.253963 0.0431923 -0.3796584 0.3106010 0.8703568 +VERTEX_SE3:QUAT 1237 1.415235 1.968435 -2.311903 -0.1344609 -0.5614163 0.8140090 0.0641977 +VERTEX_SE3:QUAT 1238 1.504799 2.061083 -2.361364 -0.1622662 0.2156938 0.4517320 0.8503435 +VERTEX_SE3:QUAT 1239 1.408021 2.159999 -2.302726 0.7474647 0.1746753 -0.3773834 0.5180413 +VERTEX_SE3:QUAT 1240 1.520375 2.277341 -2.258891 0.7102435 0.0300862 0.6200864 0.3318763 +VERTEX_SE3:QUAT 1241 1.486201 2.214836 -2.223976 0.7249054 0.3609458 -0.4287188 0.4005378 +VERTEX_SE3:QUAT 1242 1.184657 2.392245 -2.227537 -0.4531299 0.0411319 -0.2180435 0.8633878 +VERTEX_SE3:QUAT 1243 1.297138 2.446835 -2.109685 0.0554149 0.1794744 0.6994796 0.6895263 +VERTEX_SE3:QUAT 1244 1.425240 2.424051 -2.088374 -0.0656001 -0.4435120 0.3407154 0.8263817 +VERTEX_SE3:QUAT 1245 1.333431 2.502578 -2.317253 0.5598356 0.2811203 0.5329318 0.5688050 +VERTEX_SE3:QUAT 1246 1.285391 2.568867 -2.487050 -0.2066383 0.4798796 -0.0449896 0.8514647 +VERTEX_SE3:QUAT 1247 1.073498 2.606459 -2.687136 -0.3627224 0.1827941 0.9137862 0.0036926 +VERTEX_SE3:QUAT 1248 0.956184 2.582161 -2.594802 0.4654095 -0.3959945 0.7318991 0.3015063 +VERTEX_SE3:QUAT 1249 1.072050 2.485275 -2.778405 -0.2926918 0.1021003 0.9294297 0.2001688 +VERTEX_SE3:QUAT 1250 1.242132 2.596802 -2.906438 -0.0610448 0.2756711 -0.6122233 0.7385537 +VERTEX_SE3:QUAT 1251 1.265657 2.560177 -3.050958 0.2377958 0.3440114 0.3887581 0.8209607 +VERTEX_SE3:QUAT 1252 1.206478 2.419793 -3.012643 0.7494495 -0.0534809 -0.2478838 0.6115709 +VERTEX_SE3:QUAT 1253 1.365681 2.524766 -3.180616 0.4992527 -0.4201949 -0.6635572 0.3658890 +VERTEX_SE3:QUAT 1254 1.239758 2.485367 -3.051257 -0.2172016 0.4751099 0.0901052 0.8479240 +VERTEX_SE3:QUAT 1255 1.061118 2.523689 -3.125167 0.2661422 -0.5839025 -0.4994740 0.5820240 +VERTEX_SE3:QUAT 1256 1.160688 2.665479 -3.141527 -0.1575548 0.0654301 -0.5551997 0.8140323 +VERTEX_SE3:QUAT 1257 1.395269 2.706635 -3.086970 0.5684031 -0.1819440 0.0476983 0.8009614 +VERTEX_SE3:QUAT 1258 1.519201 2.799725 -3.266438 -0.2015769 0.0719077 -0.9757487 0.0459402 +VERTEX_SE3:QUAT 1259 1.644042 2.815682 -3.342466 -0.6239176 -0.1465307 0.7660964 0.0484965 +VERTEX_SE3:QUAT 1260 1.514466 2.875576 -3.398607 -0.2608776 0.1995042 -0.6926309 0.6421864 +VERTEX_SE3:QUAT 1261 1.637027 2.852924 -3.556188 0.1221498 0.2434235 -0.8133183 0.5141379 +VERTEX_SE3:QUAT 1262 1.584432 2.899555 -3.557576 -0.1048855 0.1772047 0.8099830 0.5491130 +VERTEX_SE3:QUAT 1263 1.634240 2.999927 -3.672607 0.2467955 0.1951785 0.7648524 0.5621371 +VERTEX_SE3:QUAT 1264 1.643440 3.082974 -3.626968 0.0038020 -0.0632880 0.6038342 0.7945845 +VERTEX_SE3:QUAT 1265 1.677506 2.817098 -3.650776 0.5710435 -0.0795871 0.5967187 0.5581237 +VERTEX_SE3:QUAT 1266 1.740016 2.978609 -3.562138 0.0814363 -0.3808031 0.6355368 0.6666709 +VERTEX_SE3:QUAT 1267 1.697259 2.964383 -3.650480 0.1733995 -0.1947331 -0.4420432 0.8582596 +VERTEX_SE3:QUAT 1268 1.786212 3.013573 -3.585295 0.5041647 0.1400740 0.1439399 0.8399277 +VERTEX_SE3:QUAT 1269 1.888179 2.921249 -3.393901 0.0165633 -0.5333305 -0.8397529 0.1004956 +VERTEX_SE3:QUAT 1270 1.831632 3.072542 -3.605562 -0.6316645 -0.0446013 0.7535306 0.1766416 +VERTEX_SE3:QUAT 1271 1.907665 2.960453 -3.684751 -0.1760851 0.0936498 0.3971094 0.8958392 +VERTEX_SE3:QUAT 1272 2.072842 2.649819 -3.705933 -0.0985775 0.3129807 0.8831784 0.3351440 +VERTEX_SE3:QUAT 1273 2.100136 2.547232 -3.749968 -0.6006945 -0.1724002 0.7176305 0.3073284 +VERTEX_SE3:QUAT 1274 2.104140 2.516504 -3.742585 0.1471803 -0.2305693 -0.5798031 0.7674660 +VERTEX_SE3:QUAT 1275 2.280937 2.482938 -3.728452 -0.5816275 -0.2690834 0.7333083 0.2270739 +VERTEX_SE3:QUAT 1276 2.353903 2.611159 -3.619820 0.6717746 -0.5393242 -0.0491385 0.5054046 +VERTEX_SE3:QUAT 1277 2.311529 2.529186 -3.433594 0.2627145 0.0949700 0.5015918 0.8187597 +VERTEX_SE3:QUAT 1278 2.309607 2.623525 -3.412604 0.5631379 -0.5425397 0.3026533 0.5449105 +VERTEX_SE3:QUAT 1279 2.312693 2.747651 -3.482632 -0.2025582 0.2972398 0.0020891 0.9330671 +VERTEX_SE3:QUAT 1280 2.501898 2.671601 -3.419016 -0.0569010 -0.1591218 0.2061518 0.9638174 +VERTEX_SE3:QUAT 1281 2.583208 2.667959 -3.576028 0.0456022 -0.6102560 -0.3620085 0.7031770 +VERTEX_SE3:QUAT 1282 2.749294 2.594200 -3.313292 0.4716818 -0.2889696 0.4470699 0.7029519 +VERTEX_SE3:QUAT 1283 2.829255 2.662396 -3.103065 -0.3410459 0.1558316 -0.8435690 0.3844420 +VERTEX_SE3:QUAT 1284 2.858042 2.721386 -3.058366 0.1007414 -0.4000245 0.5946223 0.6901130 +VERTEX_SE3:QUAT 1285 2.893329 2.597917 -3.013273 -0.1864875 0.5796926 -0.7921844 0.0402835 +VERTEX_SE3:QUAT 1286 2.809382 2.579268 -2.891795 0.0232357 -0.4190056 -0.9028272 0.0937949 +VERTEX_SE3:QUAT 1287 2.849101 2.465268 -2.820053 0.4932666 -0.6386097 0.1976231 0.5566065 +VERTEX_SE3:QUAT 1288 2.536940 2.316978 -2.844046 -0.3085477 0.1164537 0.6533297 0.6814669 +VERTEX_SE3:QUAT 1289 2.457509 2.350888 -2.799682 -0.3268736 0.1837376 0.5184789 0.7684880 +VERTEX_SE3:QUAT 1290 2.444088 2.433838 -2.641882 -0.0942649 0.4300948 0.8365154 0.3261510 +VERTEX_SE3:QUAT 1291 2.354528 2.086097 -2.603532 -0.1541721 -0.4568117 -0.6847941 0.5464531 +VERTEX_SE3:QUAT 1292 2.451525 1.985209 -2.476655 -0.4190762 0.2289030 0.6255620 0.6169690 +VERTEX_SE3:QUAT 1293 2.394309 2.000587 -2.426205 0.4596303 -0.0410998 -0.5201313 0.7186892 +VERTEX_SE3:QUAT 1294 2.286295 2.206128 -2.416997 0.3260373 -0.6406368 -0.6789019 0.1495877 +VERTEX_SE3:QUAT 1295 2.356044 2.086883 -2.483480 0.4216112 0.3992538 -0.7997462 0.1524676 +VERTEX_SE3:QUAT 1296 2.370740 1.952676 -2.198932 -0.0566835 0.2191563 0.9697138 0.0917204 +VERTEX_SE3:QUAT 1297 2.582148 1.863713 -2.191873 0.2035764 -0.0908409 0.5590556 0.7985997 +VERTEX_SE3:QUAT 1298 2.428485 1.835587 -2.049927 0.0514242 0.5665264 -0.7379864 0.3630145 +VERTEX_SE3:QUAT 1299 2.637981 1.806299 -2.038085 0.0966629 0.0512516 0.9251253 0.3635557 +VERTEX_SE3:QUAT 1300 2.754409 1.821913 -2.018546 0.1795329 0.0082786 0.7223785 0.6677340 +VERTEX_SE3:QUAT 1301 2.779580 1.715840 -1.956050 0.3502949 0.2342649 0.5965087 0.6830745 +VERTEX_SE3:QUAT 1302 2.675582 1.696797 -1.812235 -0.1529018 -0.5830461 0.4710043 0.6440755 +VERTEX_SE3:QUAT 1303 2.709342 1.650539 -1.786821 -0.4284145 0.1316100 -0.3809962 0.8086914 +VERTEX_SE3:QUAT 1304 2.944810 1.730422 -1.723627 -0.4030917 0.1833833 0.7151249 0.5408179 +VERTEX_SE3:QUAT 1305 2.989751 1.814114 -1.640468 0.3643273 0.3253359 -0.8663221 0.1044426 +VERTEX_SE3:QUAT 1306 2.976981 1.823058 -1.554385 0.2704207 -0.2608437 -0.3448572 0.8601783 +VERTEX_SE3:QUAT 1307 2.996456 1.744419 -1.600566 -0.1773832 -0.2887631 0.6199521 0.7076796 +VERTEX_SE3:QUAT 1308 2.992569 1.898027 -1.532546 0.4643897 0.2668034 -0.7628628 0.3622134 +VERTEX_SE3:QUAT 1309 3.041195 1.926360 -1.575762 0.2342211 -0.2418727 0.3926447 0.8558436 +VERTEX_SE3:QUAT 1310 2.843920 2.064421 -1.549006 -0.0551044 -0.5528531 -0.5247954 0.6449083 +VERTEX_SE3:QUAT 1311 2.724529 2.029108 -1.679927 -0.2065565 0.3013345 -0.5474550 0.7528778 +VERTEX_SE3:QUAT 1312 2.805716 2.014425 -1.575961 -0.3636044 0.2483967 0.8726989 0.2109209 +VERTEX_SE3:QUAT 1313 2.562712 2.000964 -1.579422 0.1657558 0.3501587 0.7088186 0.5894828 +VERTEX_SE3:QUAT 1314 2.315066 2.124247 -1.517480 0.0863173 0.2385092 -0.0513271 0.9659339 +VERTEX_SE3:QUAT 1315 2.366130 2.107839 -1.519499 -0.2035942 -0.3684113 0.5721649 0.7038820 +VERTEX_SE3:QUAT 1316 2.314357 2.112947 -1.329066 -0.5232077 0.2565149 -0.5223545 0.6225749 +VERTEX_SE3:QUAT 1317 2.251148 2.101103 -1.367942 -0.2463684 0.3056263 -0.9126611 0.1137760 +VERTEX_SE3:QUAT 1318 2.019962 2.189875 -1.556800 -0.5676879 -0.3998791 0.3170396 0.6459977 +VERTEX_SE3:QUAT 1319 2.019917 2.221275 -1.481837 0.0258820 -0.2470332 -0.9637377 0.0975415 +VERTEX_SE3:QUAT 1320 1.897955 2.242434 -1.422405 0.5021735 -0.4960828 -0.3280152 0.6277974 +VERTEX_SE3:QUAT 1321 1.738649 2.237691 -1.426832 0.3932109 -0.2692500 0.6216169 0.6216768 +VERTEX_SE3:QUAT 1322 1.820130 2.480715 -1.389161 -0.4880362 -0.2584878 -0.8295532 0.0827420 +VERTEX_SE3:QUAT 1323 1.887990 2.242648 -1.497162 -0.0871206 -0.5273703 0.7520297 0.3856708 +VERTEX_SE3:QUAT 1324 1.930721 2.338802 -1.541720 -0.2491617 0.3149956 -0.8169452 0.4138801 +VERTEX_SE3:QUAT 1325 1.992096 2.480648 -1.599766 0.4544055 0.4378681 0.2035923 0.7485568 +VERTEX_SE3:QUAT 1326 1.898129 2.547355 -1.567431 -0.0584455 -0.2211999 -0.1517603 0.9615735 +VERTEX_SE3:QUAT 1327 1.942322 2.684526 -1.636553 0.0281678 -0.1323625 -0.4058549 0.9038631 +VERTEX_SE3:QUAT 1328 1.872340 2.725244 -1.667446 0.3950169 -0.4691668 -0.3031687 0.7293373 +VERTEX_SE3:QUAT 1329 1.900459 2.731420 -1.644359 0.1115598 -0.2215977 -0.5042835 0.8271318 +VERTEX_SE3:QUAT 1330 2.086629 2.853430 -1.623902 -0.2494559 -0.2790873 0.9125200 0.1648914 +VERTEX_SE3:QUAT 1331 2.127916 3.019435 -1.677540 0.4074376 -0.3161756 0.0197734 0.8565259 +VERTEX_SE3:QUAT 1332 2.085880 3.168300 -1.839489 -0.3272487 -0.4953373 -0.1723802 0.7860244 +VERTEX_SE3:QUAT 1333 2.158738 3.153406 -1.938047 -0.2037156 -0.2581877 0.3479231 0.8779457 +VERTEX_SE3:QUAT 1334 2.126244 3.230683 -1.989389 -0.5213349 -0.1447609 -0.8371777 0.0799232 +VERTEX_SE3:QUAT 1335 2.102428 3.440206 -1.955710 0.1172421 0.1748681 0.5814786 0.7858486 +VERTEX_SE3:QUAT 1336 1.909952 3.554817 -2.020035 0.2772751 -0.1994484 -0.7981578 0.4962691 +VERTEX_SE3:QUAT 1337 1.951777 3.529218 -2.197257 -0.1096885 0.3900709 0.1930107 0.8936219 +VERTEX_SE3:QUAT 1338 2.090272 3.580091 -2.262876 0.1614284 -0.0272531 -0.8517781 0.4976667 +VERTEX_SE3:QUAT 1339 2.179954 3.591017 -2.358284 -0.2183049 -0.3785136 0.4456596 0.7813180 +VERTEX_SE3:QUAT 1340 2.203391 3.528665 -2.360464 0.1430606 -0.2752132 -0.4863293 0.8168691 +VERTEX_SE3:QUAT 1341 2.075648 3.700845 -2.562593 0.3320463 -0.5732897 -0.6114169 0.4327280 +VERTEX_SE3:QUAT 1342 2.080007 3.655011 -2.672505 -0.0771347 0.5120738 -0.2153029 0.8279344 +VERTEX_SE3:QUAT 1343 2.074398 3.665426 -2.764578 0.2464948 0.0277436 -0.8491985 0.4661894 +VERTEX_SE3:QUAT 1344 2.067841 3.764771 -2.803920 0.0495753 0.4167453 -0.1025963 0.9018535 +VERTEX_SE3:QUAT 1345 2.150570 3.942451 -3.011698 0.2237699 0.1452418 0.6422226 0.7185973 +VERTEX_SE3:QUAT 1346 2.147065 3.995877 -3.042925 -0.5379122 -0.0298208 0.8337301 0.1210592 +VERTEX_SE3:QUAT 1347 2.169779 4.079496 -3.096765 -0.4946524 -0.3941537 0.7046321 0.3216450 +VERTEX_SE3:QUAT 1348 2.155305 4.094017 -3.244921 0.0208179 0.2737774 0.5107730 0.8146923 +VERTEX_SE3:QUAT 1349 1.880924 3.924588 -3.350969 -0.4667935 -0.5209414 0.3000731 0.6485985 +VERTEX_SE3:QUAT 1350 1.942119 4.039457 -3.460776 -0.6734523 0.0112926 0.4569464 0.5809771 +VERTEX_SE3:QUAT 1351 1.925301 4.082202 -3.529313 0.0397993 0.5955479 0.4207411 0.6831659 +VERTEX_SE3:QUAT 1352 1.979532 4.058617 -3.653622 0.3051653 0.3116066 -0.8893226 0.1374071 +VERTEX_SE3:QUAT 1353 1.916663 4.208193 -3.650431 0.1104629 0.4891590 0.5531023 0.6652814 +VERTEX_SE3:QUAT 1354 1.880020 4.203472 -3.736916 0.1106309 -0.6249837 0.6244165 0.4552584 +VERTEX_SE3:QUAT 1355 2.013939 4.124724 -3.791027 0.0884137 -0.3899643 -0.3669979 0.8398949 +VERTEX_SE3:QUAT 1356 1.894269 4.235631 -3.735986 -0.2006701 -0.6591742 -0.7176734 0.1008253 +VERTEX_SE3:QUAT 1357 2.050538 4.213900 -3.928029 -0.4235121 0.1706243 -0.7056049 0.5418917 +VERTEX_SE3:QUAT 1358 2.182330 4.316537 -3.932720 -0.1921454 0.3471219 0.8767078 0.2719742 +VERTEX_SE3:QUAT 1359 2.010212 4.522873 -4.155171 -0.2961234 0.2163364 0.9302650 0.0107943 +VERTEX_SE3:QUAT 1360 2.034439 4.465774 -4.018389 0.3700476 -0.4390325 0.6720178 0.4676616 +VERTEX_SE3:QUAT 1361 2.217906 4.380754 -4.006186 -0.2037087 0.5674507 0.7696553 0.2100791 +VERTEX_SE3:QUAT 1362 2.241424 4.452458 -4.150666 -0.7658591 0.1472370 -0.4764075 0.4059766 +VERTEX_SE3:QUAT 1363 2.458198 4.454116 -4.217213 0.3242052 -0.3815813 0.6553097 0.5655580 +VERTEX_SE3:QUAT 1364 2.455456 4.314222 -4.213358 0.0172510 0.3149981 -0.6961107 0.6449097 +VERTEX_SE3:QUAT 1365 2.552741 4.402985 -4.118992 -0.2221446 0.0826188 0.9693144 0.0652345 +VERTEX_SE3:QUAT 1366 2.537929 4.438491 -4.183984 -0.3594590 -0.4318918 0.2630350 0.7842648 +VERTEX_SE3:QUAT 1367 2.724901 4.361537 -4.350700 0.4323463 0.4009858 -0.2283174 0.7746988 +VERTEX_SE3:QUAT 1368 2.753924 4.379536 -4.425302 0.0155797 -0.4863879 -0.4331477 0.7586614 +VERTEX_SE3:QUAT 1369 2.820207 4.464437 -4.583408 -0.2778237 0.6610010 -0.1108411 0.6881903 +VERTEX_SE3:QUAT 1370 2.917737 4.458645 -4.497692 0.3582380 0.4911359 -0.3966327 0.6878471 +VERTEX_SE3:QUAT 1371 3.014175 4.601762 -4.503254 0.2609373 0.1934367 -0.5194124 0.7903826 +VERTEX_SE3:QUAT 1372 2.763912 4.394232 -4.733359 -0.3324168 -0.2481173 0.8917846 0.1807130 +VERTEX_SE3:QUAT 1373 2.859016 4.474682 -4.683019 0.2812285 -0.2600585 0.3068555 0.8712748 +VERTEX_SE3:QUAT 1374 2.849687 4.604332 -4.777300 0.6248371 0.3866340 0.5748199 0.3601039 +VERTEX_SE3:QUAT 1375 2.845499 4.485741 -4.939155 0.4927812 -0.0101227 -0.4693264 0.7326643 +VERTEX_SE3:QUAT 1376 2.821977 4.459744 -4.900896 -0.0601358 0.3041126 0.9507014 0.0081248 +VERTEX_SE3:QUAT 1377 2.867271 4.389061 -4.921539 0.0533330 0.1975903 -0.9523605 0.2261042 +VERTEX_SE3:QUAT 1378 2.955851 4.531953 -5.203311 0.0510472 -0.2184730 -0.7795893 0.5847258 +VERTEX_SE3:QUAT 1379 2.987335 4.534522 -5.264850 -0.5480845 0.3240233 -0.5673643 0.5222165 +VERTEX_SE3:QUAT 1380 2.990873 4.386129 -5.155678 0.3079060 0.2555419 -0.7687494 0.4989155 +VERTEX_SE3:QUAT 1381 2.895841 4.364539 -5.103489 -0.0945868 0.4177521 0.7915601 0.4358544 +VERTEX_SE3:QUAT 1382 3.021356 4.280155 -5.115636 -0.1319216 0.2344609 0.8355185 0.4790966 +VERTEX_SE3:QUAT 1383 3.114475 4.272875 -5.301458 -0.1782029 0.0932561 0.8039610 0.5596372 +VERTEX_SE3:QUAT 1384 3.272258 4.257372 -5.298278 0.0599593 0.5274178 -0.3389670 0.7767475 +VERTEX_SE3:QUAT 1385 3.388751 4.225108 -5.121194 0.4554905 -0.1502532 0.8458292 0.2335064 +VERTEX_SE3:QUAT 1386 3.372736 3.972851 -5.161210 0.3348586 0.2393690 -0.8664818 0.2824562 +VERTEX_SE3:QUAT 1387 3.472917 4.177392 -5.142109 0.1604390 0.2632104 0.7707936 0.5575454 +VERTEX_SE3:QUAT 1388 3.626030 4.139268 -5.114738 0.0772243 0.0649064 0.9457607 0.3088046 +VERTEX_SE3:QUAT 1389 3.726488 4.132937 -5.129533 0.2286208 0.2163076 -0.9489039 0.0229101 +VERTEX_SE3:QUAT 1390 3.874966 4.101551 -5.081881 0.4582323 -0.3096606 -0.0401239 0.8321800 +VERTEX_SE3:QUAT 1391 3.863612 3.982186 -4.848706 -0.3286975 0.3659104 -0.8547370 0.1658075 +VERTEX_SE3:QUAT 1392 3.999850 4.038319 -4.748124 0.5462389 0.3637417 0.6902964 0.3046407 +VERTEX_SE3:QUAT 1393 4.049895 3.991945 -4.804244 -0.3777674 0.0869203 -0.8196403 0.4218133 +VERTEX_SE3:QUAT 1394 4.128038 4.019032 -4.829681 0.7741072 -0.0739788 0.5973826 0.1960084 +VERTEX_SE3:QUAT 1395 3.948651 4.077992 -4.733989 0.4245334 -0.3680130 -0.8058319 0.1870101 +VERTEX_SE3:QUAT 1396 3.962419 4.048809 -4.707645 0.5450580 0.0897009 0.3151355 0.7717222 +VERTEX_SE3:QUAT 1397 3.863977 3.892097 -4.800267 0.7029843 -0.2920066 -0.0910903 0.6420652 +VERTEX_SE3:QUAT 1398 3.881259 3.757618 -4.787077 0.0944752 -0.2583079 0.4278041 0.8610082 +VERTEX_SE3:QUAT 1399 3.714691 3.746679 -4.744190 0.1762854 0.1424957 -0.4448172 0.8664618 +VERTEX_SE3:QUAT 1400 3.541824 3.597813 -4.649097 -0.1059933 -0.6279975 0.7641100 0.1025688 +VERTEX_SE3:QUAT 1401 3.456534 3.635489 -4.466117 0.1951476 0.5159961 0.8296282 0.0859212 +VERTEX_SE3:QUAT 1402 3.585605 3.562216 -4.351135 -0.0946546 0.6796384 -0.6138639 0.3902605 +VERTEX_SE3:QUAT 1403 3.610305 3.638514 -4.365857 0.1719604 -0.2858457 -0.7755823 0.5359048 +VERTEX_SE3:QUAT 1404 3.583349 3.629167 -4.351819 0.0510379 0.4760401 0.8210107 0.3110023 +VERTEX_SE3:QUAT 1405 3.530810 3.709922 -4.081486 -0.2838033 0.5649683 -0.5611426 0.5342148 +VERTEX_SE3:QUAT 1406 3.471507 3.932737 -4.046764 0.1562935 -0.1960614 0.0355282 0.9674038 +VERTEX_SE3:QUAT 1407 3.481340 3.828678 -3.930410 0.3458035 -0.4488978 -0.3558577 0.7431527 +VERTEX_SE3:QUAT 1408 3.533278 3.673792 -3.826665 0.5465542 0.0118778 0.7433448 0.3854554 +VERTEX_SE3:QUAT 1409 3.597212 3.773307 -3.792635 0.2492378 0.5258614 -0.8131668 0.0104918 +VERTEX_SE3:QUAT 1410 3.509832 3.831704 -3.808225 -0.0590009 0.2802701 0.6161722 0.7336889 +VERTEX_SE3:QUAT 1411 3.572786 3.713625 -3.715376 0.0963294 -0.5736118 0.7435233 0.3299443 +VERTEX_SE3:QUAT 1412 3.658761 3.677281 -3.739394 0.7423461 -0.1669172 0.0181578 0.6486380 +VERTEX_SE3:QUAT 1413 3.747675 3.651651 -3.809257 -0.5399923 0.1656121 -0.6771315 0.4716714 +VERTEX_SE3:QUAT 1414 3.620899 3.531594 -3.618496 0.0999586 0.2075296 0.4449022 0.8654489 +VERTEX_SE3:QUAT 1415 3.631581 3.524759 -3.502578 -0.1103483 0.0557058 0.5170144 0.8470043 +VERTEX_SE3:QUAT 1416 3.577478 3.575173 -3.473491 0.5813378 -0.1521274 0.7793658 0.1774615 +VERTEX_SE3:QUAT 1417 3.566758 3.561958 -3.266977 0.4348298 -0.2962252 -0.3302330 0.7836580 +VERTEX_SE3:QUAT 1418 3.514093 3.697251 -3.253440 0.0681204 -0.0003988 0.6896459 0.7209355 +VERTEX_SE3:QUAT 1419 3.267158 3.776950 -3.180058 0.2765729 0.1596253 -0.6814074 0.6585675 +VERTEX_SE3:QUAT 1420 3.210426 3.717679 -3.232657 -0.1169343 -0.3340908 0.6310683 0.6902627 +VERTEX_SE3:QUAT 1421 3.141002 3.768314 -3.106737 -0.3622752 -0.1012051 -0.1801863 0.9088713 +VERTEX_SE3:QUAT 1422 3.076928 3.915494 -3.135809 0.6533309 0.3525961 0.5571362 0.3720671 +VERTEX_SE3:QUAT 1423 3.255998 4.056006 -3.094636 0.0219491 -0.7897517 0.6003336 0.1241376 +VERTEX_SE3:QUAT 1424 3.238616 3.952423 -3.020544 0.2083379 0.0051410 -0.8023299 0.5593171 +VERTEX_SE3:QUAT 1425 3.248391 3.902833 -2.867157 -0.3684781 0.1079172 0.9176680 0.1022897 +VERTEX_SE3:QUAT 1426 3.100515 3.897223 -2.846044 0.0393424 0.4785202 0.3048120 0.8225328 +VERTEX_SE3:QUAT 1427 3.132939 3.861794 -2.751777 -0.3298094 0.5724048 -0.6816096 0.3146216 +VERTEX_SE3:QUAT 1428 3.086942 4.040454 -2.704864 0.2973655 0.1471158 0.5518109 0.7651375 +VERTEX_SE3:QUAT 1429 3.057369 4.247779 -3.078787 0.1533787 -0.2934446 0.1211393 0.9357834 +VERTEX_SE3:QUAT 1430 3.247303 4.304719 -3.128952 -0.2847821 0.2646115 -0.6785985 0.6232047 +VERTEX_SE3:QUAT 1431 3.215332 4.461433 -3.029659 -0.0083213 -0.2339007 -0.2370232 0.9428898 +VERTEX_SE3:QUAT 1432 3.337082 4.502423 -3.022592 0.2367037 -0.5070662 0.8200387 0.1199661 +VERTEX_SE3:QUAT 1433 3.235454 4.451617 -3.093253 0.2975441 0.0909994 0.9378779 0.1535308 +VERTEX_SE3:QUAT 1434 3.079687 4.522130 -3.084319 0.1441485 0.0827852 0.9003919 0.4020726 +VERTEX_SE3:QUAT 1435 3.003944 4.555160 -3.079383 -0.4537129 -0.5228643 0.6597292 0.2924292 +VERTEX_SE3:QUAT 1436 2.864494 4.511109 -2.942729 0.1869192 0.7613278 -0.1702204 0.5970479 +VERTEX_SE3:QUAT 1437 2.770593 4.846945 -2.684186 0.5555237 0.1240094 -0.6494819 0.5041710 +VERTEX_SE3:QUAT 1438 2.916670 4.945348 -2.758909 -0.1523837 -0.6248426 0.5647985 0.5170624 +VERTEX_SE3:QUAT 1439 3.009870 4.969792 -2.873518 0.6244956 -0.2585535 -0.1902934 0.7119999 +VERTEX_SE3:QUAT 1440 3.022324 5.060696 -2.927973 -0.0828112 0.0641741 -0.4996785 0.8598520 +VERTEX_SE3:QUAT 1441 2.837406 5.087923 -2.985492 0.5910811 -0.5578832 0.4867291 0.3201315 +VERTEX_SE3:QUAT 1442 2.931319 5.063254 -2.965778 -0.0491471 -0.4439485 0.1370962 0.8841374 +VERTEX_SE3:QUAT 1443 2.883217 5.001428 -3.175267 0.4687574 0.5655970 -0.6581779 0.1648283 +VERTEX_SE3:QUAT 1444 3.037505 4.954700 -3.219270 0.2678594 -0.4070728 -0.2322294 0.8417913 +VERTEX_SE3:QUAT 1445 3.015208 5.002157 -3.106688 -0.0569258 0.6119248 -0.2465851 0.7493352 +VERTEX_SE3:QUAT 1446 3.021455 4.866246 -3.106888 -0.4239346 0.2280608 -0.4499497 0.7522054 +VERTEX_SE3:QUAT 1447 3.177005 5.043469 -3.019637 -0.0743725 0.4856803 -0.2501158 0.8342814 +VERTEX_SE3:QUAT 1448 3.118894 4.969521 -3.111479 0.7848812 -0.3330729 -0.1355501 0.5046288 +VERTEX_SE3:QUAT 1449 3.324472 5.134840 -3.086907 -0.0827260 0.7325412 -0.6716018 0.0741002 +VERTEX_SE3:QUAT 1450 3.414254 5.249345 -3.248378 -0.1219254 0.0153875 0.2730104 0.9541293 +VERTEX_SE3:QUAT 1451 3.225930 5.464692 -3.308161 -0.1305830 -0.5204237 -0.3448420 0.7701891 +VERTEX_SE3:QUAT 1452 3.176313 5.398534 -3.434235 0.5170792 -0.2963161 -0.6942572 0.4035254 +VERTEX_SE3:QUAT 1453 3.157744 5.404166 -3.418358 -0.2174618 -0.2368393 0.8928846 0.3152374 +VERTEX_SE3:QUAT 1454 3.187834 5.556918 -3.485121 -0.2476880 -0.2742279 -0.1305793 0.9199993 +VERTEX_SE3:QUAT 1455 3.204111 5.544236 -3.452543 0.2440261 0.1107369 0.9179722 0.2924305 +VERTEX_SE3:QUAT 1456 3.472556 5.642325 -3.452598 0.2257153 0.4550303 -0.8168542 0.2734031 +VERTEX_SE3:QUAT 1457 3.308641 5.406877 -3.681575 -0.3298550 -0.7559622 0.4434010 0.3508738 +VERTEX_SE3:QUAT 1458 3.172939 5.521933 -3.767917 0.5038211 0.4815688 -0.1944627 0.6902464 +VERTEX_SE3:QUAT 1459 3.134264 5.543193 -3.710800 0.0023931 0.7578527 -0.3577257 0.5456061 +VERTEX_SE3:QUAT 1460 3.180065 5.572310 -3.820673 0.1971130 -0.8446809 0.4975820 0.0085296 +VERTEX_SE3:QUAT 1461 3.027154 5.706342 -3.878755 0.2679056 0.1231157 0.5915890 0.7503943 +VERTEX_SE3:QUAT 1462 2.939324 5.808348 -3.973593 0.5460280 0.2934984 -0.7437361 0.2501372 +VERTEX_SE3:QUAT 1463 2.914059 5.862918 -4.154954 0.4871124 0.5217493 -0.3692842 0.5950868 +VERTEX_SE3:QUAT 1464 2.855808 5.859107 -4.044166 0.3167394 0.5575112 -0.6880561 0.3397590 +VERTEX_SE3:QUAT 1465 3.024812 5.841415 -4.017337 0.4303326 -0.0234007 0.8853606 0.1743642 +VERTEX_SE3:QUAT 1466 3.076501 5.907492 -4.090676 0.8313999 -0.0569438 0.1016167 0.5433283 +VERTEX_SE3:QUAT 1467 3.174415 5.764625 -4.203837 0.4085270 -0.7233401 0.5405396 0.1330478 +VERTEX_SE3:QUAT 1468 3.510758 5.572509 -4.354449 0.4331553 -0.3612480 0.3490729 0.7483478 +VERTEX_SE3:QUAT 1469 3.391495 5.498340 -4.418472 -0.3300982 0.2372257 -0.9094491 0.0875297 +VERTEX_SE3:QUAT 1470 3.420739 5.390704 -4.667338 0.2027196 -0.1597928 0.6057372 0.7526311 +VERTEX_SE3:QUAT 1471 3.447246 5.504271 -4.719393 -0.1371239 -0.4076872 -0.0501107 0.9013751 +VERTEX_SE3:QUAT 1472 3.514977 5.434023 -4.779392 -0.2613236 -0.2559964 0.1402332 0.9200600 +VERTEX_SE3:QUAT 1473 3.571101 5.535109 -4.739123 0.2634249 -0.2279216 -0.8111322 0.4698124 +VERTEX_SE3:QUAT 1474 3.566720 5.532892 -4.775562 0.1006590 -0.1030970 0.2922135 0.9454364 +VERTEX_SE3:QUAT 1475 3.509943 5.417531 -4.754515 0.9060053 -0.0195640 0.1719236 0.3862823 +VERTEX_SE3:QUAT 1476 3.486712 5.405413 -4.906316 0.5572712 0.1193806 0.3334307 0.7510134 +VERTEX_SE3:QUAT 1477 3.587332 5.276081 -4.785911 -0.0338995 -0.5308477 0.8451830 0.0521273 +VERTEX_SE3:QUAT 1478 3.637257 5.243272 -4.814122 -0.3144179 -0.5127929 0.5750396 0.5545396 +VERTEX_SE3:QUAT 1479 3.806863 5.264116 -4.911597 0.5014420 -0.5047433 -0.1543698 0.6855364 +VERTEX_SE3:QUAT 1480 3.706451 5.327618 -4.884298 0.2514690 -0.3418923 -0.1265988 0.8965744 +VERTEX_SE3:QUAT 1481 3.663306 5.284672 -4.925492 -0.0120350 -0.2258608 -0.8723495 0.4334149 +VERTEX_SE3:QUAT 1482 3.777098 5.252467 -4.956399 -0.0322072 -0.0293829 -0.3850534 0.9218640 +VERTEX_SE3:QUAT 1483 3.877309 5.352986 -4.806356 -0.0222664 -0.0709558 -0.4475965 0.8911380 +VERTEX_SE3:QUAT 1484 3.870172 5.277925 -4.765153 0.8304760 0.1137788 0.1424884 0.5263658 +VERTEX_SE3:QUAT 1485 4.145036 5.143039 -4.889043 -0.2639016 0.7649572 -0.4312362 0.3990386 +VERTEX_SE3:QUAT 1486 4.236466 5.108542 -4.738713 0.6214556 -0.3845353 -0.6149275 0.2962932 +VERTEX_SE3:QUAT 1487 4.071269 5.150207 -4.921192 0.8181037 -0.3776427 0.4057051 0.1532828 +VERTEX_SE3:QUAT 1488 4.212920 5.076619 -5.008747 0.8042164 -0.0709009 0.1975018 0.5560595 +VERTEX_SE3:QUAT 1489 4.203563 5.053707 -4.954237 -0.2830104 -0.0274133 0.7776834 0.5606801 +VERTEX_SE3:QUAT 1490 4.334065 5.218931 -4.954373 0.5727704 0.2656933 -0.6565555 0.4126452 +VERTEX_SE3:QUAT 1491 4.412333 5.106360 -4.989821 0.5798118 -0.4664832 0.0760096 0.6636522 +VERTEX_SE3:QUAT 1492 4.392230 5.182969 -5.078056 -0.1053096 0.5983005 -0.6114547 0.5070203 +VERTEX_SE3:QUAT 1493 4.474059 5.188342 -4.964308 0.1748582 -0.3641405 -0.5552244 0.7270159 +VERTEX_SE3:QUAT 1494 4.373959 5.020745 -4.975457 0.7342313 -0.4905794 0.2866924 0.3715423 +VERTEX_SE3:QUAT 1495 4.172948 4.958358 -4.875219 -0.0991787 0.2113149 -0.9538205 0.1890395 +VERTEX_SE3:QUAT 1496 4.338104 5.012008 -4.951792 0.3074170 0.4993679 -0.1505108 0.7959101 +VERTEX_SE3:QUAT 1497 4.441307 4.734901 -5.006445 0.0545000 -0.8548956 0.5156610 0.0166422 +VERTEX_SE3:QUAT 1498 4.434107 4.611131 -4.925697 0.1545106 -0.6572273 0.7086525 0.2049156 +VERTEX_SE3:QUAT 1499 4.331710 4.527834 -4.798921 0.4715889 -0.4571404 -0.4335585 0.6169714 +VERTEX_SE3:QUAT 1500 4.305429 4.440207 -4.830214 -0.0261900 0.3574688 -0.8540370 0.3770291 +VERTEX_SE3:QUAT 1501 4.408570 4.427792 -4.758221 0.3003617 -0.3023159 0.8012675 0.4199503 +VERTEX_SE3:QUAT 1502 4.261180 4.242726 -4.490583 0.1960130 0.1760197 0.8548765 0.4469699 +VERTEX_SE3:QUAT 1503 4.396390 4.119530 -4.483095 0.5143132 -0.4404660 0.6771588 0.2879717 +VERTEX_SE3:QUAT 1504 4.356622 4.184856 -4.561897 0.5392208 0.1683871 0.6933912 0.4473203 +VERTEX_SE3:QUAT 1505 4.296394 4.133921 -4.481172 -0.1144294 -0.5542131 0.8206739 0.0790442 +VERTEX_SE3:QUAT 1506 4.300968 4.140365 -4.384111 -0.1136669 -0.4263274 -0.5517587 0.7077338 +VERTEX_SE3:QUAT 1507 4.232951 4.038071 -4.372623 -0.1152164 0.6372904 -0.7524687 0.1199040 +VERTEX_SE3:QUAT 1508 4.077750 4.034867 -4.220758 0.1874594 -0.6317251 0.3866433 0.6452049 +VERTEX_SE3:QUAT 1509 4.180940 4.007254 -4.191821 -0.1761950 -0.0470538 -0.6514905 0.7364112 +VERTEX_SE3:QUAT 1510 4.064971 4.011512 -4.203906 0.4935128 0.2897666 -0.2760040 0.7722061 +VERTEX_SE3:QUAT 1511 3.926784 4.069399 -4.324789 0.2206038 0.1321003 0.0789383 0.9631470 +VERTEX_SE3:QUAT 1512 3.693197 4.090566 -4.267540 0.7621947 0.0558991 -0.6060307 0.2205931 +VERTEX_SE3:QUAT 1513 3.674340 4.071896 -4.096958 0.0971454 -0.4812099 -0.1362053 0.8604928 +VERTEX_SE3:QUAT 1514 3.958598 3.881591 -4.046323 0.2587426 0.2547285 -0.1312740 0.9224602 +VERTEX_SE3:QUAT 1515 4.061805 3.914743 -4.037166 0.0842164 0.7473433 -0.6456935 0.1321571 +VERTEX_SE3:QUAT 1516 4.267144 4.115532 -3.977386 0.8247248 0.0903099 -0.0216523 0.5578569 +VERTEX_SE3:QUAT 1517 4.243419 4.244865 -3.824937 0.6151433 0.1055932 -0.0434574 0.7801027 +VERTEX_SE3:QUAT 1518 4.171442 4.207474 -3.835350 0.2910783 0.2746557 0.2109379 0.8918200 +VERTEX_SE3:QUAT 1519 4.072293 4.337555 -3.901511 -0.3465145 -0.4973117 0.7604926 0.2329375 +VERTEX_SE3:QUAT 1520 4.299157 4.415709 -3.824722 -0.1549090 -0.0593438 0.1260642 0.9780538 +VERTEX_SE3:QUAT 1521 4.080566 4.413882 -3.739798 0.2795719 -0.4374135 -0.6268948 0.5809577 +VERTEX_SE3:QUAT 1522 4.033599 4.423374 -3.882830 0.3489176 0.2299849 -0.8283071 0.3731900 +VERTEX_SE3:QUAT 1523 4.002570 4.438321 -3.949904 -0.4444655 -0.5921837 0.5545991 0.3797219 +VERTEX_SE3:QUAT 1524 3.918024 4.526112 -3.755161 -0.0275346 -0.0471264 -0.8747686 0.4814570 +VERTEX_SE3:QUAT 1525 3.922678 4.676271 -3.559027 0.3401763 0.7503734 -0.4867699 0.2903016 +VERTEX_SE3:QUAT 1526 4.033075 4.757903 -3.609746 0.2903572 0.8250119 -0.4552061 0.1668395 +VERTEX_SE3:QUAT 1527 4.121337 4.785620 -3.599336 -0.1324900 -0.0107523 0.6260722 0.7683517 +VERTEX_SE3:QUAT 1528 4.141135 4.876533 -3.692562 0.5165061 -0.2073512 -0.7339154 0.3893521 +VERTEX_SE3:QUAT 1529 4.017565 4.910510 -3.665023 0.3804547 0.3901372 -0.7716675 0.3279884 +VERTEX_SE3:QUAT 1530 3.996285 4.821376 -3.664981 -0.5031738 -0.4662385 0.5455059 0.4815196 +VERTEX_SE3:QUAT 1531 3.999070 4.847718 -3.702748 0.6567117 -0.2750968 0.6935298 0.1098539 +VERTEX_SE3:QUAT 1532 3.857741 4.918091 -3.649786 0.7710103 0.0145371 0.5809252 0.2604950 +VERTEX_SE3:QUAT 1533 3.747688 4.909725 -3.666254 0.2307932 0.2896534 0.0947837 0.9240408 +VERTEX_SE3:QUAT 1534 3.556866 4.978891 -3.572047 0.0171970 -0.7568952 0.3514861 0.5507009 +VERTEX_SE3:QUAT 1535 3.485116 5.013349 -3.463057 0.1960454 -0.1885220 -0.9344186 0.2299729 +VERTEX_SE3:QUAT 1536 3.570026 5.129027 -3.590022 -0.1127333 0.1397729 -0.6882555 0.7028934 +VERTEX_SE3:QUAT 1537 3.602240 5.119051 -3.629145 0.0701865 -0.6594003 0.7254461 0.1843718 +VERTEX_SE3:QUAT 1538 3.754962 5.058106 -3.506271 -0.0967712 0.3988383 -0.5555607 0.7231291 +VERTEX_SE3:QUAT 1539 3.881802 5.238917 -3.485046 0.0223245 0.6195390 -0.2272511 0.7510193 +VERTEX_SE3:QUAT 1540 3.764014 5.512220 -3.465457 0.1590367 -0.7566298 -0.1546403 0.6150651 +VERTEX_SE3:QUAT 1541 3.645481 5.546936 -3.347080 -0.0656928 -0.2603853 0.1770443 0.9468576 +VERTEX_SE3:QUAT 1542 3.600844 5.570110 -3.321366 0.5618879 0.3777712 -0.6646888 0.3158475 +VERTEX_SE3:QUAT 1543 3.689073 5.836351 -3.071386 -0.3400260 0.7656999 -0.3817867 0.3902883 +VERTEX_SE3:QUAT 1544 3.793830 6.023265 -3.136139 -0.1654035 -0.1332591 -0.8976242 0.3862052 +VERTEX_SE3:QUAT 1545 3.913506 6.059041 -3.035237 0.8344506 0.0718165 0.4344791 0.3313042 +VERTEX_SE3:QUAT 1546 4.003573 6.129292 -3.179774 0.4545129 0.2401512 0.5212372 0.6812175 +VERTEX_SE3:QUAT 1547 4.074895 6.061992 -3.243337 0.1297111 -0.0901860 -0.8504213 0.5018218 +VERTEX_SE3:QUAT 1548 3.991119 6.121312 -3.272866 -0.0482182 -0.1174439 -0.1799740 0.9754441 +VERTEX_SE3:QUAT 1549 3.972153 6.099738 -3.208361 -0.4407454 0.1187119 0.8586539 0.2331618 +VERTEX_SE3:QUAT 1550 4.097823 6.324331 -3.173162 0.2801842 -0.0490886 -0.2819393 0.9162954 +VERTEX_SE3:QUAT 1551 3.779179 6.490045 -3.406470 -0.3583742 -0.6324113 0.2754824 0.6290734 +VERTEX_SE3:QUAT 1552 3.825469 6.496000 -3.614275 0.2726690 0.7407842 -0.3224937 0.5223871 +VERTEX_SE3:QUAT 1553 3.853850 6.563202 -3.704452 -0.1365344 0.1665202 0.3897145 0.8954060 +VERTEX_SE3:QUAT 1554 4.061994 6.584322 -3.695786 -0.1914641 0.3286048 -0.4019203 0.8329588 +VERTEX_SE3:QUAT 1555 4.105834 6.668335 -3.696826 0.5758349 0.3614818 0.5101729 0.5267531 +VERTEX_SE3:QUAT 1556 4.122047 6.795670 -3.922708 0.5261762 0.2991706 0.1028132 0.7893447 +VERTEX_SE3:QUAT 1557 4.250458 6.920333 -4.070675 -0.1982071 -0.8477984 0.3364267 0.3588438 +VERTEX_SE3:QUAT 1558 4.211027 6.973340 -3.947862 0.6674930 0.0334765 -0.7395838 0.0796754 +VERTEX_SE3:QUAT 1559 4.270174 7.016367 -4.051320 0.3906038 0.1898374 0.7002431 0.5666128 +VERTEX_SE3:QUAT 1560 4.264308 6.953388 -4.078236 0.8170109 -0.3297133 0.0875691 0.4648805 +VERTEX_SE3:QUAT 1561 4.303920 6.970308 -4.132236 -0.0705477 0.0949606 0.7868225 0.6057358 +VERTEX_SE3:QUAT 1562 4.442075 7.041220 -4.096990 -0.3197295 0.3711918 -0.7958418 0.3558449 +VERTEX_SE3:QUAT 1563 4.644247 7.025700 -4.015400 -0.6761723 -0.1175625 0.7226027 0.0825554 +VERTEX_SE3:QUAT 1564 4.615958 6.855471 -4.269786 0.1068014 -0.0955774 -0.7916741 0.5938944 +VERTEX_SE3:QUAT 1565 4.615334 7.016015 -4.465072 0.8392393 0.1180378 -0.2366434 0.4751256 +VERTEX_SE3:QUAT 1566 4.809778 7.047356 -4.551413 0.1297446 0.2082497 0.9514310 0.1859501 +VERTEX_SE3:QUAT 1567 5.005875 7.053289 -4.564129 -0.2011149 -0.0169658 0.4635051 0.8628024 +VERTEX_SE3:QUAT 1568 5.027718 7.042889 -4.711968 -0.0358938 0.5276137 -0.4922347 0.6914047 +VERTEX_SE3:QUAT 1569 5.031111 6.990056 -4.605448 0.4542789 -0.1428538 -0.8497849 0.2260289 +VERTEX_SE3:QUAT 1570 5.123749 6.885809 -4.643490 0.0046210 -0.0679828 -0.9892858 0.1291149 +VERTEX_SE3:QUAT 1571 5.238576 7.023373 -4.797630 -0.3133334 0.2634316 -0.6846902 0.6030136 +VERTEX_SE3:QUAT 1572 5.397997 6.930849 -4.888858 0.3522825 0.3991000 -0.3183741 0.7843814 +VERTEX_SE3:QUAT 1573 5.431091 6.854179 -4.981689 0.6213427 0.1278519 0.5622416 0.5305389 +VERTEX_SE3:QUAT 1574 5.384989 6.866149 -4.961104 -0.4447491 -0.3452834 0.7524310 0.3417972 +VERTEX_SE3:QUAT 1575 5.617385 6.915503 -5.026893 0.3105028 -0.1825002 0.1403004 0.9222784 +VERTEX_SE3:QUAT 1576 5.514035 6.993735 -4.958624 0.2858724 0.0164806 0.1743116 0.9421363 +VERTEX_SE3:QUAT 1577 5.681456 7.030249 -5.129897 0.6368131 -0.5336824 -0.1423968 0.5379361 +VERTEX_SE3:QUAT 1578 5.711117 7.044741 -5.279202 0.2735299 -0.7426442 0.5873072 0.1695031 +VERTEX_SE3:QUAT 1579 5.851553 6.707222 -5.279725 0.4548057 -0.3738678 0.7793959 0.2142818 +VERTEX_SE3:QUAT 1580 5.871546 6.882281 -5.405229 -0.1335461 -0.2400544 -0.0106999 0.9614701 +VERTEX_SE3:QUAT 1581 5.836516 6.687897 -5.315685 -0.8034219 -0.1880873 0.5648807 0.0067952 +VERTEX_SE3:QUAT 1582 5.990004 6.676884 -5.394938 0.8670078 -0.3434405 -0.1653031 0.3209687 +VERTEX_SE3:QUAT 1583 5.988375 6.627118 -5.543279 -0.3625535 -0.2023005 0.6999436 0.5811269 +VERTEX_SE3:QUAT 1584 5.944505 6.633220 -5.566323 0.2795744 -0.0455301 -0.8348096 0.4720784 +VERTEX_SE3:QUAT 1585 5.902379 6.368170 -5.609289 -0.3253780 -0.2459641 0.2228766 0.8854134 +VERTEX_SE3:QUAT 1586 6.008541 6.282432 -5.669673 -0.2434526 -0.4807072 -0.0796795 0.8386314 +VERTEX_SE3:QUAT 1587 6.054856 6.522795 -5.553612 0.4871088 -0.1728413 -0.5730496 0.6359757 +VERTEX_SE3:QUAT 1588 6.182227 6.711540 -5.717578 0.1109202 -0.8238305 0.4001697 0.3858293 +VERTEX_SE3:QUAT 1589 5.921039 6.737958 -5.686126 -0.6595324 -0.1469844 0.7371621 0.0021668 +VERTEX_SE3:QUAT 1590 5.969784 6.773031 -5.702287 0.1372446 0.2616154 0.9436638 0.1490637 +VERTEX_SE3:QUAT 1591 6.035375 6.721603 -5.801416 -0.1786303 0.5193970 -0.8128360 0.1939475 +VERTEX_SE3:QUAT 1592 6.004441 6.817683 -5.755272 0.6081809 0.3051465 0.1416422 0.7189848 +VERTEX_SE3:QUAT 1593 6.071538 6.830149 -5.735038 -0.2382252 0.3864819 -0.0524553 0.8894543 +VERTEX_SE3:QUAT 1594 6.280329 6.883216 -5.742482 0.4349311 -0.1791465 0.0177686 0.8822844 +VERTEX_SE3:QUAT 1595 6.230204 6.825795 -5.740321 0.8633909 -0.2058487 -0.1976441 0.4160761 +VERTEX_SE3:QUAT 1596 6.255752 6.880319 -5.789556 -0.1626717 0.3559129 -0.7826985 0.4839907 +VERTEX_SE3:QUAT 1597 6.243561 6.866499 -5.826350 0.6816196 0.0240589 -0.7120882 0.1665724 +VERTEX_SE3:QUAT 1598 6.360286 6.938049 -5.754741 -0.0631805 0.0692049 0.3989985 0.9121508 +VERTEX_SE3:QUAT 1599 6.501857 6.967144 -5.730860 0.4547405 0.1612993 0.5943542 0.6433791 +VERTEX_SE3:QUAT 1600 6.428030 6.862703 -5.705377 0.1287308 -0.1673949 -0.8878995 0.4087075 +VERTEX_SE3:QUAT 1601 6.215788 6.933436 -5.566114 -0.0687982 -0.2039678 -0.9504886 0.2241325 +VERTEX_SE3:QUAT 1602 6.219542 6.924705 -5.566169 0.2025043 -0.2960465 0.6897329 0.6289810 +VERTEX_SE3:QUAT 1603 6.139238 6.959522 -5.531285 -0.3662179 -0.2341397 0.8649308 0.2509137 +VERTEX_SE3:QUAT 1604 6.290935 6.711571 -5.457342 0.0146194 0.8325651 -0.5039367 0.2294984 +VERTEX_SE3:QUAT 1605 6.321314 6.597317 -5.249951 0.2640887 0.1355363 -0.9483701 0.1117197 +VERTEX_SE3:QUAT 1606 6.380499 6.505078 -5.319223 0.2906062 0.2753501 -0.3158545 0.8602129 +VERTEX_SE3:QUAT 1607 6.520493 6.399215 -5.171166 0.6971056 -0.1020376 0.5965753 0.3843567 +VERTEX_SE3:QUAT 1608 6.635014 6.397843 -5.150346 -0.5180215 -0.0222410 0.8425818 0.1456534 +VERTEX_SE3:QUAT 1609 6.797564 6.275598 -5.147676 -0.1465190 -0.6403673 0.4568109 0.5998214 +VERTEX_SE3:QUAT 1610 6.788090 6.232721 -5.048160 0.1171103 0.5890989 -0.0014252 0.7995284 +VERTEX_SE3:QUAT 1611 6.684056 6.135770 -5.067121 -0.1380013 -0.1754571 -0.9270085 0.3013730 +VERTEX_SE3:QUAT 1612 6.860197 5.953329 -4.991503 0.3699995 0.0808979 -0.5522030 0.7427165 +VERTEX_SE3:QUAT 1613 6.685171 5.828821 -4.944493 0.2606496 0.7107437 -0.4490546 0.4746106 +VERTEX_SE3:QUAT 1614 6.735076 5.878036 -4.925235 0.4621760 0.2592296 -0.2510837 0.8100311 +VERTEX_SE3:QUAT 1615 6.648417 5.838463 -4.942847 0.2879083 0.4197203 -0.5607748 0.6530508 +VERTEX_SE3:QUAT 1616 6.724974 5.887932 -4.873178 0.5454185 -0.4519980 0.1870508 0.6806089 +VERTEX_SE3:QUAT 1617 6.658830 5.876875 -4.849793 -0.1967921 -0.0368107 -0.9785917 0.0477090 +VERTEX_SE3:QUAT 1618 6.594655 5.963149 -4.887295 0.3930671 0.3124470 0.2764935 0.8194061 +VERTEX_SE3:QUAT 1619 6.477879 5.852592 -4.718991 0.4569453 -0.5458589 0.5254595 0.4659736 +VERTEX_SE3:QUAT 1620 6.329991 6.102085 -4.701282 0.2174800 0.0499699 -0.3399365 0.9135911 +VERTEX_SE3:QUAT 1621 6.322399 6.162960 -4.734082 -0.2640915 0.5036795 -0.7013168 0.4297876 +VERTEX_SE3:QUAT 1622 6.368403 6.066519 -4.725576 0.0397852 -0.5870479 0.6220005 0.5166307 +VERTEX_SE3:QUAT 1623 6.252332 6.043148 -4.755750 0.5104745 -0.2732790 0.3337830 0.7438570 +VERTEX_SE3:QUAT 1624 6.219570 6.087892 -4.715961 0.4864624 0.5405453 -0.6119509 0.3109361 +VERTEX_SE3:QUAT 1625 6.273376 6.085083 -4.706508 0.5265016 0.2154516 0.4516273 0.6873205 +VERTEX_SE3:QUAT 1626 6.146973 6.008894 -4.688633 -0.3837541 -0.1770464 -0.4092438 0.8086450 +VERTEX_SE3:QUAT 1627 6.244535 5.849996 -4.626264 -0.2035979 0.0991972 -0.9391732 0.2581889 +VERTEX_SE3:QUAT 1628 6.094540 5.902125 -4.590858 0.5507358 -0.2218462 -0.6069217 0.5283184 +VERTEX_SE3:QUAT 1629 5.956889 5.842237 -4.596894 -0.1144659 -0.7323048 0.2491123 0.6233540 +VERTEX_SE3:QUAT 1630 6.153005 5.664201 -4.671011 -0.5509760 0.1829637 -0.6250422 0.5217969 +VERTEX_SE3:QUAT 1631 6.182607 5.689972 -4.600487 0.0290073 0.3884009 -0.2760849 0.8786811 +VERTEX_SE3:QUAT 1632 5.977097 5.821145 -4.663055 0.2111547 -0.3314241 -0.2082023 0.8956694 +VERTEX_SE3:QUAT 1633 6.007357 5.779775 -4.591174 0.5460492 -0.2917144 -0.7000743 0.3558496 +VERTEX_SE3:QUAT 1634 5.979291 5.918584 -4.687683 0.4491835 -0.1448023 0.4910217 0.7322323 +VERTEX_SE3:QUAT 1635 5.926274 5.824061 -4.767920 -0.3910877 0.0806979 0.5895219 0.7021411 +VERTEX_SE3:QUAT 1636 5.875976 5.757747 -4.789877 -0.4809268 0.1616998 0.8495970 0.1440400 +VERTEX_SE3:QUAT 1637 6.040300 5.880266 -4.869115 -0.0037327 -0.2373528 -0.8475542 0.4746595 +VERTEX_SE3:QUAT 1638 6.121975 6.045695 -4.801892 0.2643050 -0.2677928 -0.5501491 0.7454970 +VERTEX_SE3:QUAT 1639 6.169383 5.980325 -4.788049 0.1125195 0.0256544 0.3021465 0.9462498 +VERTEX_SE3:QUAT 1640 6.200937 5.973093 -4.956966 0.2546448 -0.8241104 0.4895763 0.1277228 +VERTEX_SE3:QUAT 1641 6.514376 5.918442 -4.886628 -0.1388186 -0.0116283 -0.9356254 0.3243443 +VERTEX_SE3:QUAT 1642 6.445499 6.030893 -4.916334 -0.2259414 0.1147179 0.9669359 0.0287282 +VERTEX_SE3:QUAT 1643 6.488302 5.956479 -5.032221 -0.3724883 0.1514056 -0.6203601 0.6734108 +VERTEX_SE3:QUAT 1644 6.452516 6.116902 -5.065588 0.5692449 0.1032344 -0.7563115 0.3054436 +VERTEX_SE3:QUAT 1645 6.350363 6.263293 -5.098682 0.0511799 -0.0351614 -0.4213246 0.9047817 +VERTEX_SE3:QUAT 1646 6.294106 6.383632 -5.199789 -0.1071760 0.0011472 0.4633787 0.8796546 +VERTEX_SE3:QUAT 1647 6.240542 6.577486 -5.384295 -0.0903709 -0.1039082 0.9698074 0.2012706 +VERTEX_SE3:QUAT 1648 6.120832 6.584067 -5.655568 0.3914039 0.0454348 -0.2087895 0.8950674 +VERTEX_SE3:QUAT 1649 6.196164 6.635163 -5.681645 -0.4247941 0.0773565 0.9016814 0.0231630 +VERTEX_SE3:QUAT 1650 6.274601 6.791980 -5.726630 -0.2475792 0.0715667 0.7558886 0.6018431 +VERTEX_SE3:QUAT 1651 6.169391 6.810730 -5.921224 0.2660865 -0.4949253 -0.7228658 0.4021343 +VERTEX_SE3:QUAT 1652 6.251357 6.891661 -5.945220 0.3411353 -0.5879428 -0.3925400 0.6195662 +VERTEX_SE3:QUAT 1653 6.077932 7.021814 -6.094618 0.2648441 0.3892709 0.5324968 0.7034009 +VERTEX_SE3:QUAT 1654 6.143233 7.132440 -6.208026 -0.3737876 -0.4928483 0.4260588 0.6601949 +VERTEX_SE3:QUAT 1655 6.056848 7.218686 -6.232139 -0.0343765 -0.0684951 -0.1445255 0.9865288 +VERTEX_SE3:QUAT 1656 6.025212 7.324071 -6.349633 0.6244079 -0.1032379 -0.7736515 0.0303339 +VERTEX_SE3:QUAT 1657 6.030329 7.215156 -6.399919 0.3189137 -0.4949497 -0.7486578 0.3046806 +VERTEX_SE3:QUAT 1658 5.958126 7.237724 -6.476698 0.1871797 -0.5691932 0.7980900 0.0635230 +VERTEX_SE3:QUAT 1659 5.965629 7.118052 -6.756374 0.2245614 -0.6188051 -0.5899976 0.4674990 +VERTEX_SE3:QUAT 1660 6.042900 7.145922 -6.760642 0.2906989 -0.5196441 0.7722780 0.2214745 +VERTEX_SE3:QUAT 1661 6.039334 7.162825 -6.518111 0.5021783 0.3920113 0.1710357 0.7515922 +VERTEX_SE3:QUAT 1662 6.195540 7.102509 -6.557054 -0.0774956 -0.3669930 0.4350499 0.8185610 +VERTEX_SE3:QUAT 1663 6.258654 7.126147 -6.563777 0.2024265 -0.5463272 -0.2646708 0.7684396 +VERTEX_SE3:QUAT 1664 6.269677 7.220990 -6.682577 0.4484787 -0.0835679 0.6589722 0.5980292 +VERTEX_SE3:QUAT 1665 6.458461 7.271541 -6.622535 0.3788338 0.4563162 0.6705600 0.4456566 +VERTEX_SE3:QUAT 1666 6.388409 7.359611 -6.725452 0.1564716 0.3954184 -0.0379939 0.9042773 +VERTEX_SE3:QUAT 1667 6.387344 7.359121 -6.865707 -0.4464728 0.0867707 0.8905610 0.0058200 +VERTEX_SE3:QUAT 1668 6.419856 7.406699 -6.849275 0.5318719 -0.1682520 0.1678036 0.8128011 +VERTEX_SE3:QUAT 1669 6.492311 7.413199 -6.840268 0.0980162 0.2021470 -0.9483156 0.2241135 +VERTEX_SE3:QUAT 1670 6.536369 7.551781 -6.758579 -0.2221622 0.2840270 0.6281753 0.6894697 +VERTEX_SE3:QUAT 1671 6.500003 7.481309 -6.604591 0.3461644 -0.5455152 -0.5074320 0.5701721 +VERTEX_SE3:QUAT 1672 6.561388 7.439356 -6.524344 0.3588420 0.2046008 0.6980414 0.5849009 +VERTEX_SE3:QUAT 1673 6.710573 7.330202 -6.479819 0.5924299 0.0109651 -0.5860842 0.5526408 +VERTEX_SE3:QUAT 1674 6.698841 7.212688 -6.468810 0.2692271 -0.3016176 -0.0527568 0.9131047 +VERTEX_SE3:QUAT 1675 6.818825 7.150604 -6.380623 -0.1151482 0.2054052 0.8879227 0.3951491 +VERTEX_SE3:QUAT 1676 6.746064 6.933498 -6.571312 0.3430857 -0.5408304 0.5509424 0.5350300 +VERTEX_SE3:QUAT 1677 6.817056 6.859329 -6.542033 -0.3657652 0.3479487 -0.6859266 0.5240727 +VERTEX_SE3:QUAT 1678 6.787862 6.903091 -6.530136 -0.0913143 0.4368761 -0.8631400 0.2361999 +VERTEX_SE3:QUAT 1679 6.787645 6.843416 -6.461536 -0.0656413 0.0445223 -0.7562539 0.6494529 +VERTEX_SE3:QUAT 1680 6.959511 6.801980 -6.400518 0.2990644 -0.2360135 -0.2529313 0.8893165 +VERTEX_SE3:QUAT 1681 6.969579 6.913487 -6.368965 0.2640761 0.4158141 -0.3723114 0.7866045 +VERTEX_SE3:QUAT 1682 7.050568 7.028746 -6.355419 0.2489444 0.2015707 0.8118661 0.4881285 +VERTEX_SE3:QUAT 1683 6.893894 7.033162 -6.216060 0.3556253 -0.2023915 0.7299643 0.5474674 +VERTEX_SE3:QUAT 1684 6.848070 7.108860 -6.310207 0.2648820 0.3233579 -0.0048947 0.9084345 +VERTEX_SE3:QUAT 1685 6.830227 6.971344 -6.217424 -0.0959007 -0.6068904 -0.7711028 0.1669955 +VERTEX_SE3:QUAT 1686 6.772955 6.886922 -6.274951 0.0233037 0.4457794 -0.4780313 0.7564548 +VERTEX_SE3:QUAT 1687 6.684795 6.901769 -6.394409 -0.1564947 0.0367579 -0.7530574 0.6380147 +VERTEX_SE3:QUAT 1688 6.735304 6.947842 -6.558765 0.4373370 -0.0596975 0.8627407 0.2466799 +VERTEX_SE3:QUAT 1689 6.937689 6.771843 -6.517353 0.6674608 0.2382428 -0.1693963 0.6848660 +VERTEX_SE3:QUAT 1690 6.855434 6.766819 -6.458705 0.4193481 -0.2904561 0.6432166 0.5710121 +VERTEX_SE3:QUAT 1691 6.792294 6.764441 -6.395998 0.2119513 0.3426218 0.0475818 0.9140147 +VERTEX_SE3:QUAT 1692 6.892114 6.650014 -6.319749 -0.4131612 0.3917299 -0.0609168 0.8198382 +VERTEX_SE3:QUAT 1693 6.927135 6.455498 -6.180602 0.6622815 0.0442119 0.2019760 0.7201626 +VERTEX_SE3:QUAT 1694 6.813258 6.688650 -6.125868 0.2537960 -0.2488094 0.6926817 0.6275934 +VERTEX_SE3:QUAT 1695 6.723781 6.608877 -6.108856 -0.1580385 -0.6154583 0.7326624 0.2438048 +VERTEX_SE3:QUAT 1696 6.619823 6.486767 -6.036506 -0.1168038 -0.7437783 0.5701204 0.3288062 +VERTEX_SE3:QUAT 1697 6.606767 6.486339 -6.060546 0.0758379 -0.2942236 -0.9119945 0.2755850 +VERTEX_SE3:QUAT 1698 6.447652 6.318249 -5.990978 0.0981815 -0.3141397 0.7297552 0.5992779 +VERTEX_SE3:QUAT 1699 6.422603 6.432372 -5.993081 -0.0760187 0.4121422 -0.5026637 0.7561013 +VERTEX_SE3:QUAT 1700 6.375229 6.195769 -5.797932 0.3168508 0.5337431 -0.6894760 0.3732917 +VERTEX_SE3:QUAT 1701 6.690048 6.354311 -5.634736 -0.5164872 -0.2593037 -0.2239340 0.7847650 +VERTEX_SE3:QUAT 1702 6.428257 6.413327 -5.535469 0.1232547 0.2462493 -0.4847575 0.8301685 +VERTEX_SE3:QUAT 1703 6.528157 6.407788 -5.602927 0.4411796 0.6477914 -0.5278153 0.3273193 +VERTEX_SE3:QUAT 1704 6.410118 6.370819 -5.529637 0.0115444 -0.6393695 0.4547836 0.6198752 +VERTEX_SE3:QUAT 1705 6.445752 6.410182 -5.376794 -0.1005411 0.2834863 0.0934970 0.9490971 +VERTEX_SE3:QUAT 1706 6.528730 6.403864 -5.242447 0.0722250 0.0987616 -0.2558469 0.9589432 +VERTEX_SE3:QUAT 1707 6.360786 6.396059 -5.225013 0.2712285 0.2530607 -0.3443146 0.8624632 +VERTEX_SE3:QUAT 1708 6.461410 6.499425 -5.112366 -0.1997898 -0.5280661 0.7814246 0.2657177 +VERTEX_SE3:QUAT 1709 6.401628 6.445226 -5.142196 0.2765608 0.3080264 0.4181948 0.8085462 +VERTEX_SE3:QUAT 1710 6.387379 6.332240 -4.997061 0.1918708 0.5823405 -0.3934815 0.6850091 +VERTEX_SE3:QUAT 1711 6.325879 6.475973 -5.044899 0.5806264 0.3451691 0.3668818 0.6396320 +VERTEX_SE3:QUAT 1712 6.321052 6.359172 -5.019722 -0.4560051 0.4142817 -0.6916789 0.3768425 +VERTEX_SE3:QUAT 1713 6.237702 6.294036 -4.917280 0.2458277 0.0679503 0.7834149 0.5667562 +VERTEX_SE3:QUAT 1714 6.237054 6.398571 -4.887397 -0.2222172 -0.2815811 0.5641755 0.7436650 +VERTEX_SE3:QUAT 1715 6.097572 6.513573 -4.814195 0.3972361 -0.0649356 -0.8391707 0.3657587 +VERTEX_SE3:QUAT 1716 6.050351 6.357408 -4.546082 -0.1138867 -0.4220858 0.6937660 0.5723305 +VERTEX_SE3:QUAT 1717 6.064654 6.481118 -4.540383 0.0444523 -0.0158128 0.1021186 0.9936527 +VERTEX_SE3:QUAT 1718 6.085031 6.574452 -4.474427 0.6021368 -0.1325451 -0.7627184 0.1952528 +VERTEX_SE3:QUAT 1719 5.912638 6.622046 -4.324210 0.3638535 0.1699094 0.3962875 0.8256498 +VERTEX_SE3:QUAT 1720 5.785234 6.584909 -4.167195 0.1827448 -0.1205596 -0.6477915 0.7296821 +VERTEX_SE3:QUAT 1721 5.750304 6.515223 -4.244052 -0.0318435 -0.0315786 0.2475930 0.9678257 +VERTEX_SE3:QUAT 1722 5.635645 6.527565 -4.127812 0.3094570 0.4453479 -0.5967841 0.5913970 +VERTEX_SE3:QUAT 1723 5.632050 6.541157 -4.165533 -0.3030200 -0.2273559 0.5970205 0.7071454 +VERTEX_SE3:QUAT 1724 5.608598 6.460933 -4.060668 -0.0517519 -0.7281467 0.2647051 0.6301233 +VERTEX_SE3:QUAT 1725 5.640349 6.313330 -3.965678 -0.3543679 0.3904867 -0.0735529 0.8464830 +VERTEX_SE3:QUAT 1726 5.620800 6.309585 -3.896512 -0.3307583 -0.2315297 0.1480314 0.9028176 +VERTEX_SE3:QUAT 1727 5.674804 6.406731 -3.968954 0.5349707 -0.4614825 0.6530773 0.2726359 +VERTEX_SE3:QUAT 1728 5.473749 6.336300 -3.932636 0.0886716 -0.4286885 -0.7606663 0.4793228 +VERTEX_SE3:QUAT 1729 5.337294 6.405436 -3.880764 -0.2579995 0.1702644 -0.5762842 0.7565334 +VERTEX_SE3:QUAT 1730 5.409183 6.396582 -3.727161 -0.4020667 -0.1967983 0.5174838 0.7292622 +VERTEX_SE3:QUAT 1731 5.173897 6.369923 -3.627814 0.0903585 0.4283821 0.7866861 0.4352575 +VERTEX_SE3:QUAT 1732 5.027614 6.248423 -3.815543 -0.1989042 0.3320159 0.3703027 0.8444397 +VERTEX_SE3:QUAT 1733 5.023133 6.302609 -3.744506 0.3127707 -0.6955458 0.3240595 0.5598000 +VERTEX_SE3:QUAT 1734 4.940532 6.313301 -3.820494 0.1917451 0.3474475 0.5087782 0.7639757 +VERTEX_SE3:QUAT 1735 4.986965 6.459801 -3.856965 0.4130000 0.3481947 0.6694338 0.5099508 +VERTEX_SE3:QUAT 1736 4.912195 6.391177 -3.820520 0.4539817 0.2398510 0.3949794 0.7618158 +VERTEX_SE3:QUAT 1737 4.792105 6.344311 -3.843058 0.5239927 -0.4121250 -0.0808145 0.7409815 +VERTEX_SE3:QUAT 1738 4.753289 6.308345 -3.857280 0.4606936 0.0995050 0.5101120 0.7194762 +VERTEX_SE3:QUAT 1739 4.535560 6.341553 -4.034370 0.3754562 -0.0281506 0.6435051 0.6664394 +VERTEX_SE3:QUAT 1740 4.411990 6.096347 -3.954958 0.3250263 0.4299698 -0.7259936 0.4271031 +VERTEX_SE3:QUAT 1741 4.370201 6.119322 -4.116859 -0.1282526 0.2805961 0.8935375 0.3262022 +VERTEX_SE3:QUAT 1742 4.284825 6.282117 -4.133009 -0.4411494 0.1622146 -0.8820154 0.0335045 +VERTEX_SE3:QUAT 1743 4.107598 6.270211 -4.282299 -0.0205098 -0.6504090 -0.0881031 0.7541786 +VERTEX_SE3:QUAT 1744 4.266038 6.324820 -4.381625 0.2524089 0.3502479 -0.7298230 0.5300703 +VERTEX_SE3:QUAT 1745 4.179613 6.278848 -4.439556 -0.1006238 0.6867305 -0.4473177 0.5640771 +VERTEX_SE3:QUAT 1746 4.343207 6.178944 -4.661043 -0.3789056 0.0783296 -0.5253956 0.7577958 +VERTEX_SE3:QUAT 1747 4.513625 6.210162 -4.727215 0.3173038 -0.2447611 -0.0604461 0.9141972 +VERTEX_SE3:QUAT 1748 4.585696 6.208196 -4.915291 0.4620697 0.5608932 -0.6746489 0.1293802 +VERTEX_SE3:QUAT 1749 4.711468 6.232343 -4.989474 0.1289506 0.2121845 0.9375717 0.2435340 +VERTEX_SE3:QUAT 1750 4.767567 6.208027 -5.154256 0.5519659 -0.0643280 -0.3856322 0.7365347 +VERTEX_SE3:QUAT 1751 4.840995 6.092018 -5.181523 -0.0080511 -0.5011335 -0.4025954 0.7659748 +VERTEX_SE3:QUAT 1752 4.915237 6.172064 -5.104500 -0.1411293 -0.0468204 -0.6960386 0.7024391 +VERTEX_SE3:QUAT 1753 4.900152 6.221566 -5.229657 0.3086126 0.4627027 -0.2419495 0.7950628 +VERTEX_SE3:QUAT 1754 4.998889 6.178704 -5.340303 0.6772401 0.0469867 -0.0725157 0.7306706 +VERTEX_SE3:QUAT 1755 4.900423 6.237204 -5.337302 0.5425029 -0.6404280 0.2333086 0.4910292 +VERTEX_SE3:QUAT 1756 5.048077 6.271973 -5.357319 -0.1296700 -0.0171413 -0.4759241 0.8697058 +VERTEX_SE3:QUAT 1757 5.139573 6.418069 -5.487403 0.3711685 0.7295363 -0.3280813 0.4715648 +VERTEX_SE3:QUAT 1758 5.169708 6.548841 -5.329238 0.5939160 -0.3525475 0.5652837 0.4510303 +VERTEX_SE3:QUAT 1759 5.151988 6.470851 -5.281443 0.4603734 -0.1567034 0.8364256 0.2527697 +VERTEX_SE3:QUAT 1760 5.280231 6.517957 -5.275005 0.3289051 -0.6621437 0.2230195 0.6353341 +VERTEX_SE3:QUAT 1761 5.350372 6.485898 -5.359374 0.4361007 0.1775446 0.4109497 0.7806500 +VERTEX_SE3:QUAT 1762 5.565835 6.574662 -5.332679 0.4544716 -0.2605802 -0.8517926 0.0017185 +VERTEX_SE3:QUAT 1763 5.675159 6.702457 -5.393949 -0.1588090 -0.8101348 0.1265711 0.5499464 +VERTEX_SE3:QUAT 1764 5.721042 6.569161 -5.399704 0.2225638 -0.6882114 0.0860652 0.6851447 +VERTEX_SE3:QUAT 1765 6.037148 6.693072 -5.097755 0.6752553 0.0733988 -0.6820065 0.2711272 +VERTEX_SE3:QUAT 1766 5.994273 6.758408 -5.181615 0.7415107 0.2186390 0.0630103 0.6311803 +VERTEX_SE3:QUAT 1767 6.102098 6.710507 -5.078937 0.4519814 0.6676353 -0.4262339 0.4102446 +VERTEX_SE3:QUAT 1768 6.270691 6.819392 -5.017869 0.1838497 0.5269068 -0.3809872 0.7371684 +VERTEX_SE3:QUAT 1769 6.230878 6.773468 -4.895744 0.2171682 0.2396926 -0.6573509 0.6806432 +VERTEX_SE3:QUAT 1770 6.134263 6.652227 -4.730883 0.3671434 -0.5047228 0.6382934 0.4506020 +VERTEX_SE3:QUAT 1771 6.246875 6.735658 -4.535861 0.2683075 0.4032090 -0.8141784 0.3202297 +VERTEX_SE3:QUAT 1772 6.081532 6.747317 -4.384665 0.0530803 0.0960784 0.9272209 0.3580681 +VERTEX_SE3:QUAT 1773 6.021435 6.731717 -4.350507 0.7381898 -0.2281766 -0.6003804 0.2062878 +VERTEX_SE3:QUAT 1774 6.081617 6.490771 -4.137794 0.0895613 -0.8464561 -0.0798230 0.5187669 +VERTEX_SE3:QUAT 1775 6.197770 6.362940 -4.077851 0.0901520 0.0017313 -0.9411893 0.3256261 +VERTEX_SE3:QUAT 1776 6.451158 6.306002 -3.880085 0.3828890 0.7520633 -0.0340977 0.5353823 +VERTEX_SE3:QUAT 1777 6.503241 6.293530 -3.686420 0.5453142 0.3572432 0.1103246 0.7502254 +VERTEX_SE3:QUAT 1778 6.630663 6.350189 -3.575282 0.6423304 0.0661060 -0.5258134 0.5536803 +VERTEX_SE3:QUAT 1779 6.661810 6.438617 -3.619883 0.0775446 -0.0229160 0.9027418 0.4225151 +VERTEX_SE3:QUAT 1780 6.695176 6.379206 -3.626929 0.4158443 -0.2708369 -0.4989122 0.7104981 +VERTEX_SE3:QUAT 1781 6.942083 6.168576 -3.500955 0.4576985 0.6323591 -0.2775562 0.5599970 +VERTEX_SE3:QUAT 1782 7.028639 6.110895 -3.356735 0.3718265 -0.8580334 0.3372896 0.1084413 +VERTEX_SE3:QUAT 1783 6.951110 5.993183 -3.104564 -0.5576329 -0.2907633 0.7755860 0.0544850 +VERTEX_SE3:QUAT 1784 6.936837 6.045200 -3.074189 -0.2441236 0.6710603 -0.6641316 0.2213842 +VERTEX_SE3:QUAT 1785 7.014621 5.975292 -2.959240 0.4985812 -0.5624813 -0.2487101 0.6108804 +VERTEX_SE3:QUAT 1786 7.069288 6.088916 -2.970636 -0.0447905 0.9581084 -0.2626163 0.1051421 +VERTEX_SE3:QUAT 1787 7.033825 6.137010 -2.909079 0.2615487 0.3832718 0.1425923 0.8742783 +VERTEX_SE3:QUAT 1788 7.078687 6.085676 -2.724794 -0.5887628 -0.7300326 0.3427545 0.0541308 +VERTEX_SE3:QUAT 1789 7.056492 5.960052 -2.729616 -0.0942721 -0.6058960 0.4553266 0.6455080 +VERTEX_SE3:QUAT 1790 7.260623 5.801484 -2.922731 -0.1796409 0.9280055 -0.3246149 0.0340609 +VERTEX_SE3:QUAT 1791 7.202142 5.845311 -2.910995 -0.8225327 0.0601471 0.5272410 0.2045464 +VERTEX_SE3:QUAT 1792 7.054950 5.859149 -2.666410 -0.1754438 0.3710810 -0.8991531 0.1517960 +VERTEX_SE3:QUAT 1793 6.921795 5.962323 -2.692286 -0.5633579 0.5089557 -0.6458220 0.0806588 +VERTEX_SE3:QUAT 1794 7.073162 5.874100 -2.627456 -0.4808305 -0.0149071 0.8728217 0.0822317 +VERTEX_SE3:QUAT 1795 7.243761 5.750015 -2.491034 0.1499656 -0.9101119 0.3798002 0.0704163 +VERTEX_SE3:QUAT 1796 7.283910 5.708266 -2.550467 -0.4237565 -0.2951051 0.8562482 0.0135093 +VERTEX_SE3:QUAT 1797 7.196079 5.600813 -2.559799 0.1540519 -0.1510084 0.9385599 0.2693878 +VERTEX_SE3:QUAT 1798 7.217980 5.645066 -2.530060 0.6366575 -0.5798181 0.2938104 0.4149140 +VERTEX_SE3:QUAT 1799 7.286506 5.757639 -2.663261 -0.8021835 -0.2548890 0.4992009 0.2057466 +VERTEX_SE3:QUAT 1800 7.201241 5.389655 -2.466811 -0.9650650 -0.1515193 0.2075988 0.0509333 +VERTEX_SE3:QUAT 1801 7.280351 5.306694 -2.444502 0.3771149 -0.4099626 0.1296322 0.8203112 +VERTEX_SE3:QUAT 1802 7.278962 5.256969 -2.383777 -0.2574900 -0.8746965 0.3284316 0.2464498 +VERTEX_SE3:QUAT 1803 7.274955 5.241069 -2.470538 0.2726370 0.6329760 -0.6867982 0.2309082 +VERTEX_SE3:QUAT 1804 7.081450 5.242133 -2.443005 0.9867729 0.1466238 -0.0686281 0.0084206 +VERTEX_SE3:QUAT 1805 6.889598 5.337489 -2.452365 -0.0167987 -0.2380213 0.5936807 0.7685095 +VERTEX_SE3:QUAT 1806 6.833378 5.465252 -2.491989 0.5467783 -0.0392849 -0.6261740 0.5544333 +VERTEX_SE3:QUAT 1807 6.634004 5.381335 -2.500801 -0.8965497 -0.0606091 0.3691188 0.2372268 +VERTEX_SE3:QUAT 1808 6.558573 5.279259 -2.509774 -0.1405424 -0.4111951 0.8857572 0.1630967 +VERTEX_SE3:QUAT 1809 6.485186 5.311463 -2.536459 -0.1659664 -0.9625394 0.1539003 0.1492911 +VERTEX_SE3:QUAT 1810 6.364449 5.278993 -2.582915 0.4096994 0.6790364 -0.1887276 0.5791700 +VERTEX_SE3:QUAT 1811 6.314864 5.251370 -2.681806 -0.3294605 -0.5956399 0.6180439 0.3933072 +VERTEX_SE3:QUAT 1812 6.266127 5.325159 -2.660418 0.3707918 -0.6942820 0.2862000 0.5464206 +VERTEX_SE3:QUAT 1813 6.341784 5.399851 -2.690634 0.2782079 -0.0541488 0.1011109 0.9536482 +VERTEX_SE3:QUAT 1814 6.418363 5.358357 -2.720200 0.9599309 0.0228211 0.0703632 0.2702976 +VERTEX_SE3:QUAT 1815 6.419211 5.232433 -2.876365 -0.0244474 -0.0786265 0.8959099 0.4365383 +VERTEX_SE3:QUAT 1816 6.427397 5.129842 -2.935725 -0.0180203 -0.3782447 0.3430596 0.8596024 +VERTEX_SE3:QUAT 1817 6.339907 5.236344 -2.865840 0.7630098 -0.3120322 0.5329216 0.1909100 +VERTEX_SE3:QUAT 1818 6.381970 5.174354 -2.920744 -0.2109526 -0.3521831 0.6969857 0.5879430 +VERTEX_SE3:QUAT 1819 6.288637 5.124239 -2.993109 -0.0503227 0.0059163 0.9737852 0.2217542 +VERTEX_SE3:QUAT 1820 6.354964 5.145606 -3.137150 -0.5477997 -0.5549897 0.2764652 0.5616662 +VERTEX_SE3:QUAT 1821 6.291627 5.073168 -3.163180 0.1079248 -0.7211470 0.4012438 0.5543489 +VERTEX_SE3:QUAT 1822 6.215889 5.152621 -3.182149 -0.7734629 -0.5724586 0.2241732 0.1542486 +VERTEX_SE3:QUAT 1823 6.248442 5.047945 -3.223832 0.7023638 -0.5229863 0.4654165 0.1286774 +VERTEX_SE3:QUAT 1824 6.128446 5.116688 -3.013624 0.6931938 0.2720015 -0.5086714 0.4321470 +VERTEX_SE3:QUAT 1825 6.168543 5.164291 -3.088386 0.6906963 -0.5406415 -0.4716072 0.0907307 +VERTEX_SE3:QUAT 1826 6.301726 5.193069 -2.895088 0.1118985 -0.6585953 0.4777084 0.5705486 +VERTEX_SE3:QUAT 1827 6.245283 5.256786 -2.915362 -0.0869428 -0.8620416 -0.3240441 0.3798956 +VERTEX_SE3:QUAT 1828 6.362635 5.282594 -2.927015 0.4774851 -0.0072815 -0.5423330 0.6912524 +VERTEX_SE3:QUAT 1829 6.312676 5.200457 -3.081945 0.2560988 -0.6076203 -0.3883794 0.6437177 +VERTEX_SE3:QUAT 1830 6.466185 5.352850 -3.189213 -0.6821990 -0.3534788 0.6320346 0.1009433 +VERTEX_SE3:QUAT 1831 6.435685 5.267441 -3.287601 -0.4098349 -0.3997981 0.7346331 0.3640208 +VERTEX_SE3:QUAT 1832 6.477868 5.363763 -3.220704 0.1508424 -0.5355142 0.7611695 0.3333048 +VERTEX_SE3:QUAT 1833 6.504614 5.348246 -3.402010 -0.1007458 -0.7600328 0.5044069 0.3972080 +VERTEX_SE3:QUAT 1834 6.479232 5.263165 -3.355039 0.5276882 -0.6894788 0.4010761 0.2920651 +VERTEX_SE3:QUAT 1835 6.558739 5.286263 -3.357497 0.4218775 0.8776490 -0.1830759 0.1350365 +VERTEX_SE3:QUAT 1836 6.665992 5.319963 -3.339018 0.0437299 -0.0595308 -0.5716345 0.8171767 +VERTEX_SE3:QUAT 1837 6.549200 5.461931 -3.533918 0.1919388 -0.4363179 -0.5266143 0.7038917 +VERTEX_SE3:QUAT 1838 6.521773 5.522930 -3.798976 0.8285810 0.4925414 -0.2083825 0.1656299 +VERTEX_SE3:QUAT 1839 6.498986 5.630076 -3.933793 0.0392403 -0.2958935 0.5028463 0.8112046 +VERTEX_SE3:QUAT 1840 6.615424 5.714862 -3.996898 -0.5359020 0.2780552 0.7773923 0.1765094 +VERTEX_SE3:QUAT 1841 6.673672 5.615142 -4.156480 0.1709812 -0.1179072 0.1917073 0.9592245 +VERTEX_SE3:QUAT 1842 6.732096 5.665022 -4.126919 0.9390644 -0.2193109 -0.0547871 0.2589579 +VERTEX_SE3:QUAT 1843 6.767511 5.794582 -4.151794 0.5066412 -0.4025121 0.6769752 0.3507182 +VERTEX_SE3:QUAT 1844 6.893721 5.941935 -4.135604 0.6226155 -0.4647160 -0.6232316 0.0892822 +VERTEX_SE3:QUAT 1845 6.916243 6.052525 -4.025595 0.8163121 -0.1144554 -0.1923485 0.5324815 +VERTEX_SE3:QUAT 1846 6.833572 6.057704 -4.160387 -0.0923672 -0.7846303 0.2039996 0.5781070 +VERTEX_SE3:QUAT 1847 6.831036 6.233657 -4.117781 0.1536905 0.4467886 -0.7937534 0.3830337 +VERTEX_SE3:QUAT 1848 6.745255 6.278908 -3.971479 0.2951835 0.2878168 -0.7578661 0.5056353 +VERTEX_SE3:QUAT 1849 6.602817 6.431926 -3.827513 0.2770700 -0.2470535 -0.9190560 0.1324116 +VERTEX_SE3:QUAT 1850 6.605949 6.413211 -3.893875 0.6025014 -0.2824280 -0.7400503 0.0977347 +VERTEX_SE3:QUAT 1851 6.704664 6.291377 -3.917559 0.7638030 0.1499817 0.0844974 0.6220696 +VERTEX_SE3:QUAT 1852 6.808959 6.414049 -3.891784 0.5557956 -0.2394972 0.5063084 0.6143160 +VERTEX_SE3:QUAT 1853 6.740348 6.336199 -3.916434 0.6005680 -0.5265055 -0.3152590 0.5125639 +VERTEX_SE3:QUAT 1854 6.831255 6.458178 -3.787785 0.5572333 -0.7497597 0.2627059 0.2415306 +VERTEX_SE3:QUAT 1855 6.878413 6.575777 -3.756048 -0.2778038 -0.4139869 0.8666634 0.0182881 +VERTEX_SE3:QUAT 1856 7.008563 6.707658 -3.791701 0.7361256 -0.5684767 -0.2930914 0.2214740 +VERTEX_SE3:QUAT 1857 7.071845 6.705368 -3.564743 0.3757104 0.1652019 -0.0700336 0.9092004 +VERTEX_SE3:QUAT 1858 7.038247 6.604355 -3.600226 0.0415427 0.8362487 -0.2180514 0.5014139 +VERTEX_SE3:QUAT 1859 7.244096 6.606870 -3.499131 0.6781255 -0.1971698 0.5561518 0.4381381 +VERTEX_SE3:QUAT 1860 7.350519 6.509896 -3.263138 0.3973906 -0.3567871 0.3891916 0.7505422 +VERTEX_SE3:QUAT 1861 7.599545 6.570158 -3.167487 0.6018659 0.6842364 -0.1773809 0.3716368 +VERTEX_SE3:QUAT 1862 7.705840 6.527300 -3.140979 0.2367355 0.5648825 0.0829138 0.7861230 +VERTEX_SE3:QUAT 1863 7.869868 6.486377 -3.235330 0.7464260 -0.2602713 0.5758148 0.2086732 +VERTEX_SE3:QUAT 1864 7.979559 6.487232 -3.236626 0.1270071 0.7484813 -0.0824868 0.6456321 +VERTEX_SE3:QUAT 1865 7.980628 6.451490 -2.983686 -0.0720702 -0.3948641 0.1674890 0.9004642 +VERTEX_SE3:QUAT 1866 8.111756 6.472671 -2.970007 0.6543086 -0.3611815 0.6643395 0.0090115 +VERTEX_SE3:QUAT 1867 8.293205 6.522482 -2.927187 -0.1885890 0.5926696 -0.7628743 0.1766343 +VERTEX_SE3:QUAT 1868 8.420996 6.574299 -2.879132 0.0332751 -0.1716745 0.9186279 0.3543211 +VERTEX_SE3:QUAT 1869 8.488406 6.698802 -2.975102 0.4161224 0.2761599 -0.6063686 0.6187851 +VERTEX_SE3:QUAT 1870 8.407094 6.642027 -2.823892 -0.0227915 0.8272896 -0.4866384 0.2797418 +VERTEX_SE3:QUAT 1871 8.345613 6.561006 -2.826321 0.6901210 -0.2391758 0.2346305 0.6414643 +VERTEX_SE3:QUAT 1872 8.624024 6.611327 -3.001090 -0.1349277 -0.9564557 0.1748187 0.1908545 +VERTEX_SE3:QUAT 1873 8.582726 6.586615 -3.068433 -0.1114241 -0.1581547 0.9777384 0.0812363 +VERTEX_SE3:QUAT 1874 8.615021 6.645466 -2.995136 -0.4831337 -0.8094061 0.3280858 0.0616706 +VERTEX_SE3:QUAT 1875 8.583548 6.413596 -3.106825 0.8381825 0.2443195 0.3925066 0.2893036 +VERTEX_SE3:QUAT 1876 8.644752 6.231591 -3.162431 0.5464028 0.1894749 0.1154348 0.8076002 +VERTEX_SE3:QUAT 1877 8.614810 6.157809 -3.034315 0.5881653 0.0304491 0.5590909 0.5835682 +VERTEX_SE3:QUAT 1878 8.661735 5.985919 -2.996175 0.3748388 0.2375384 -0.2456045 0.8618293 +VERTEX_SE3:QUAT 1879 8.727568 5.946064 -3.142661 0.5396713 0.7352142 0.1127662 0.3943332 +VERTEX_SE3:QUAT 1880 8.760523 5.843316 -3.180227 0.4057115 0.3673805 -0.3772101 0.7470892 +VERTEX_SE3:QUAT 1881 8.789428 5.895242 -2.990850 -0.2722366 -0.6987953 0.6583903 0.0639881 +VERTEX_SE3:QUAT 1882 8.763861 5.846152 -3.085196 -0.0317499 0.3424744 -0.3810509 0.8581978 +VERTEX_SE3:QUAT 1883 8.818422 5.661965 -3.189944 0.2333443 0.8431223 -0.2188864 0.4321851 +VERTEX_SE3:QUAT 1884 8.887313 5.506650 -3.229111 -0.3829846 0.9121661 -0.0691797 0.1284133 +VERTEX_SE3:QUAT 1885 8.915375 5.436233 -3.307454 0.1679002 -0.5763554 0.3705808 0.7087269 +VERTEX_SE3:QUAT 1886 8.943993 5.504672 -3.295314 0.1187588 0.5325189 -0.5145082 0.6615144 +VERTEX_SE3:QUAT 1887 9.076067 5.634015 -3.177693 -0.1494798 -0.2382408 0.8934367 0.3502398 +VERTEX_SE3:QUAT 1888 9.154319 5.544100 -3.317790 -0.4339321 -0.8592849 0.2506545 0.1024922 +VERTEX_SE3:QUAT 1889 9.160766 5.483921 -3.372504 -0.1378539 0.2120420 -0.9634593 0.0882082 +VERTEX_SE3:QUAT 1890 9.000543 5.612042 -3.246909 -0.1619486 0.1924215 -0.8646351 0.4349170 +VERTEX_SE3:QUAT 1891 9.122972 5.663392 -3.155912 0.3160833 -0.1536437 0.5472464 0.7596094 +VERTEX_SE3:QUAT 1892 9.095682 5.578387 -3.170197 -0.6906829 -0.5700723 0.4429599 0.0419665 +VERTEX_SE3:QUAT 1893 8.991366 5.489342 -3.205439 -0.1374317 -0.3955315 0.8976461 0.1374729 +VERTEX_SE3:QUAT 1894 8.885923 5.403761 -3.180212 0.3052672 -0.9451419 0.0273642 0.1130042 +VERTEX_SE3:QUAT 1895 9.097899 5.601144 -3.209510 -0.1436889 -0.7879999 0.5911161 0.0948237 +VERTEX_SE3:QUAT 1896 9.158283 5.636840 -3.411172 0.1872227 -0.5687274 0.6676621 0.4424072 +VERTEX_SE3:QUAT 1897 9.240409 5.412432 -3.291083 -0.3666551 0.6341136 -0.5005642 0.4614102 +VERTEX_SE3:QUAT 1898 9.204477 5.281987 -3.327128 0.8060189 0.4099030 -0.2120729 0.3705916 +VERTEX_SE3:QUAT 1899 9.131981 5.310849 -3.415488 0.4334323 -0.7914616 0.3847209 0.1942031 +VERTEX_SE3:QUAT 1900 9.078169 5.129631 -3.597952 0.5486305 0.1294675 0.1359286 0.8147185 +VERTEX_SE3:QUAT 1901 9.092055 5.325645 -3.820019 0.3793043 0.2267719 0.6241134 0.6443487 +VERTEX_SE3:QUAT 1902 9.185885 5.196032 -3.792685 0.5301780 0.3654710 0.5123333 0.5682049 +VERTEX_SE3:QUAT 1903 9.242439 5.242552 -3.874355 -0.1060299 -0.9493644 0.2084541 0.2097899 +VERTEX_SE3:QUAT 1904 9.365368 5.210276 -3.905209 -0.0742243 -0.9926297 0.0470205 0.0834629 +VERTEX_SE3:QUAT 1905 9.201247 5.154604 -3.829608 0.7803243 0.0496554 -0.4726757 0.4064553 +VERTEX_SE3:QUAT 1906 9.076358 5.117652 -3.871253 0.3676424 -0.9191763 0.1295388 0.0563355 +VERTEX_SE3:QUAT 1907 9.164251 5.063189 -3.943364 -0.7374961 -0.6028274 0.2254386 0.2046362 +VERTEX_SE3:QUAT 1908 9.191886 4.944865 -4.008155 0.3612497 -0.0336841 0.5937557 0.7182048 +VERTEX_SE3:QUAT 1909 9.352514 4.829613 -4.045197 0.4131796 -0.2124322 0.3112543 0.8290211 +VERTEX_SE3:QUAT 1910 9.439929 4.713649 -4.146085 0.3159397 -0.7829777 0.1349859 0.5185622 +VERTEX_SE3:QUAT 1911 9.405176 4.644132 -4.017184 0.4092987 -0.2852386 0.6285340 0.5967064 +VERTEX_SE3:QUAT 1912 9.458257 4.721428 -4.017270 0.6708741 0.5238708 0.4027445 0.3365772 +VERTEX_SE3:QUAT 1913 9.444729 4.761564 -3.997224 0.8723568 -0.2832162 -0.0289690 0.3974204 +VERTEX_SE3:QUAT 1914 9.399404 4.793044 -3.928458 -0.9636066 0.0835109 -0.1378434 0.2132778 +VERTEX_SE3:QUAT 1915 9.533057 4.770271 -3.911411 -0.3392996 0.6753723 -0.6526509 0.0528665 +VERTEX_SE3:QUAT 1916 9.588186 4.603853 -4.035650 0.1889873 0.9397266 0.1253326 0.2559093 +VERTEX_SE3:QUAT 1917 9.574568 4.635798 -4.152622 0.2343431 -0.9614719 -0.1187954 0.0808870 +VERTEX_SE3:QUAT 1918 9.561237 4.641638 -4.044841 0.5325000 -0.1274617 0.1756361 0.8181376 +VERTEX_SE3:QUAT 1919 9.207403 4.535860 -4.116979 0.2132555 0.2350493 0.3735169 0.8716415 +VERTEX_SE3:QUAT 1920 9.198057 4.579893 -4.104624 -0.6636824 0.3378582 -0.3463374 0.5704629 +VERTEX_SE3:QUAT 1921 9.390352 4.632156 -4.148168 0.7300763 0.5738005 -0.2912741 0.2300023 +VERTEX_SE3:QUAT 1922 9.347813 4.458549 -4.224120 -0.3676466 0.8636743 0.0663826 0.3383725 +VERTEX_SE3:QUAT 1923 9.452897 4.496706 -4.188085 0.4461415 0.6761393 -0.1168459 0.5745784 +VERTEX_SE3:QUAT 1924 9.522189 4.327969 -4.130707 0.2756227 0.8423593 -0.3925902 0.2456337 +VERTEX_SE3:QUAT 1925 9.480833 4.275339 -4.076418 0.8894554 0.0566014 -0.4027227 0.2085181 +VERTEX_SE3:QUAT 1926 9.468157 4.084416 -3.979662 -0.6591783 0.6341674 -0.1605807 0.3708497 +VERTEX_SE3:QUAT 1927 9.351370 3.913928 -4.019680 0.2074509 0.9380935 0.1064736 0.2561409 +VERTEX_SE3:QUAT 1928 9.295644 4.007837 -3.927998 0.1484424 0.4086571 -0.8999301 0.0330146 +VERTEX_SE3:QUAT 1929 9.132885 3.749226 -3.746069 0.0547992 -0.9342613 0.1333022 0.3261646 +VERTEX_SE3:QUAT 1930 9.103330 3.658026 -3.759256 0.5318409 -0.5466304 0.5143201 0.3921930 +VERTEX_SE3:QUAT 1931 9.170434 3.492443 -3.629839 0.4565467 0.8111453 0.1199466 0.3452841 +VERTEX_SE3:QUAT 1932 9.289830 3.502462 -3.552840 0.5720529 -0.2589958 0.0583445 0.7760623 +VERTEX_SE3:QUAT 1933 9.230917 3.527549 -3.378317 -0.6706588 0.7303998 0.0967335 0.0858810 +VERTEX_SE3:QUAT 1934 9.328311 3.291847 -3.442538 0.9686183 0.1409990 0.0651199 0.1940548 +VERTEX_SE3:QUAT 1935 9.323495 3.391861 -3.305257 0.8818077 -0.3718235 0.2646329 0.1188780 +VERTEX_SE3:QUAT 1936 9.293347 3.400393 -3.307022 0.4247434 0.8996695 0.0548063 0.0847595 +VERTEX_SE3:QUAT 1937 9.258415 3.480813 -3.370635 0.0445602 -0.9603625 0.1599115 0.2239344 +VERTEX_SE3:QUAT 1938 9.231941 3.619999 -3.441922 0.3337676 0.2770529 -0.1015993 0.8952756 +VERTEX_SE3:QUAT 1939 9.284738 3.755917 -3.486826 -0.1904484 -0.7900187 0.5331823 0.2351947 +VERTEX_SE3:QUAT 1940 9.202309 3.733099 -3.627571 0.9405811 0.1223255 0.2859302 0.1363360 +VERTEX_SE3:QUAT 1941 9.214814 3.638738 -3.705361 0.7694443 0.5370286 -0.0623632 0.3400978 +VERTEX_SE3:QUAT 1942 9.219205 3.554529 -3.652287 0.0703363 0.9559641 -0.2815078 0.0440314 +VERTEX_SE3:QUAT 1943 9.148059 3.530957 -3.707330 0.3175559 -0.8052764 0.4842247 0.1273370 +VERTEX_SE3:QUAT 1944 8.961682 3.582278 -3.645590 0.2739126 0.7106590 -0.3872645 0.5195785 +VERTEX_SE3:QUAT 1945 8.944858 3.647128 -3.655920 -0.2734303 0.8496167 -0.4265171 0.1465280 +VERTEX_SE3:QUAT 1946 8.817090 3.715062 -3.565912 0.2334504 -0.8728978 0.4233053 0.0660526 +VERTEX_SE3:QUAT 1947 8.760564 3.907264 -3.458304 -0.1723045 0.5485094 -0.4403133 0.6896178 +VERTEX_SE3:QUAT 1948 8.708300 3.963886 -3.328044 0.3481112 0.7473672 -0.5508992 0.1295026 +VERTEX_SE3:QUAT 1949 8.613415 4.113916 -3.335550 -0.8772748 -0.4793485 -0.0034218 0.0245408 +VERTEX_SE3:QUAT 1950 8.683259 4.096220 -3.250545 -0.6199289 -0.0118103 -0.7041709 0.3459652 +VERTEX_SE3:QUAT 1951 8.536611 4.065020 -3.158666 0.4757299 -0.6536976 0.5674765 0.1559841 +VERTEX_SE3:QUAT 1952 8.410071 3.863360 -3.150224 0.7941014 0.3521677 -0.3622235 0.3378979 +VERTEX_SE3:QUAT 1953 8.074863 3.861195 -3.005242 0.4945671 0.7138529 0.1223796 0.4804587 +VERTEX_SE3:QUAT 1954 8.047630 3.908555 -3.159656 -0.5525254 0.5846548 -0.1955129 0.5609539 +VERTEX_SE3:QUAT 1955 8.100313 3.958891 -3.105897 -0.0764493 0.8993326 -0.4304583 0.0078721 +VERTEX_SE3:QUAT 1956 8.063095 3.998908 -2.989145 0.5721517 0.5489157 0.5557352 0.2499849 +VERTEX_SE3:QUAT 1957 8.009777 4.070424 -3.129038 -0.6303702 -0.7228291 0.2826781 0.0156414 +VERTEX_SE3:QUAT 1958 8.149524 4.078402 -3.003421 -0.1783479 0.7058956 -0.6659484 0.1625305 +VERTEX_SE3:QUAT 1959 8.168668 3.965569 -2.929079 0.4553363 0.5726788 0.6582463 0.1772561 +VERTEX_SE3:QUAT 1960 8.285859 4.093448 -2.817664 0.2819011 0.8080268 -0.5042195 0.1157030 +VERTEX_SE3:QUAT 1961 8.156381 4.289837 -2.792101 0.5046810 0.6783090 -0.2304699 0.4817444 +VERTEX_SE3:QUAT 1962 8.301406 4.464864 -2.801799 0.5276862 0.5706722 -0.3096252 0.5477342 +VERTEX_SE3:QUAT 1963 8.453446 4.510030 -2.811228 0.4499541 0.1937120 0.3877340 0.7808196 +VERTEX_SE3:QUAT 1964 8.233492 4.394860 -2.847743 0.5397826 0.4406562 0.5561115 0.4529867 +VERTEX_SE3:QUAT 1965 8.233692 4.409213 -2.912320 -0.0470637 0.8567339 0.3484809 0.3772971 +VERTEX_SE3:QUAT 1966 8.319167 4.603336 -2.740740 0.3300102 -0.3327494 0.6009189 0.6475088 +VERTEX_SE3:QUAT 1967 8.357574 4.420944 -2.588315 -0.3070405 0.5861021 -0.7086157 0.2451005 +VERTEX_SE3:QUAT 1968 8.435142 4.386920 -2.393416 0.3504319 0.9247109 -0.1479811 0.0144493 +VERTEX_SE3:QUAT 1969 8.395856 4.499832 -2.368493 0.2310013 -0.9297516 0.2807787 0.0579975 +VERTEX_SE3:QUAT 1970 8.438108 4.623909 -2.425956 0.4067217 0.5172033 -0.6096620 0.4420299 +VERTEX_SE3:QUAT 1971 8.471982 4.606890 -2.406237 -0.5988122 -0.1153408 -0.7452400 0.2696997 +VERTEX_SE3:QUAT 1972 8.615768 4.814631 -2.401340 0.6894588 -0.5844760 0.3720314 0.2112509 +VERTEX_SE3:QUAT 1973 8.397150 4.902711 -2.391573 0.2979867 0.3659336 0.1302458 0.8719705 +VERTEX_SE3:QUAT 1974 8.245636 4.998017 -2.473128 0.7112902 0.6584087 0.2250671 0.0995437 +VERTEX_SE3:QUAT 1975 8.320870 5.077191 -2.340469 0.6933489 -0.0330170 0.7065873 0.1375192 +VERTEX_SE3:QUAT 1976 8.375420 5.006752 -2.146377 0.4435727 -0.3718072 0.7531803 0.3126054 +VERTEX_SE3:QUAT 1977 8.377876 5.022145 -2.192122 0.1736644 0.9451848 0.2612252 0.0907069 +VERTEX_SE3:QUAT 1978 8.312902 5.270708 -2.128581 0.9064499 0.3074288 -0.0862349 0.2764050 +VERTEX_SE3:QUAT 1979 8.212882 5.084445 -1.988059 0.6894943 -0.1589066 -0.0249151 0.7062050 +VERTEX_SE3:QUAT 1980 8.340893 5.202728 -1.922326 0.8878928 0.2811486 0.1292979 0.3404173 +VERTEX_SE3:QUAT 1981 8.250191 5.204536 -1.985463 0.2654870 0.4729027 -0.5377258 0.6455468 +VERTEX_SE3:QUAT 1982 8.404447 5.175156 -1.974772 0.3102149 0.4211147 -0.1018836 0.8461967 +VERTEX_SE3:QUAT 1983 8.538386 5.111558 -2.140068 0.2417136 -0.9619664 0.0226859 0.1252221 +VERTEX_SE3:QUAT 1984 8.632858 5.031396 -2.130575 0.6634708 0.2650452 0.1962692 0.6715921 +VERTEX_SE3:QUAT 1985 8.721702 4.973258 -2.235205 0.4956369 0.5888262 -0.1956075 0.6077544 +VERTEX_SE3:QUAT 1986 8.838629 5.263570 -2.270306 0.9219882 -0.1841758 0.0777224 0.3316267 +VERTEX_SE3:QUAT 1987 8.937963 5.191505 -2.314717 0.8651688 0.3068416 -0.1287151 0.3751847 +VERTEX_SE3:QUAT 1988 9.050295 5.207045 -2.189738 0.5219499 0.2075262 0.8229100 0.0855588 +VERTEX_SE3:QUAT 1989 9.008570 5.346400 -2.123561 -0.6560918 0.4787766 0.1313581 0.5683850 +VERTEX_SE3:QUAT 1990 9.066286 5.304781 -2.097265 0.6377410 -0.7410279 0.2101500 0.0010149 +VERTEX_SE3:QUAT 1991 9.210628 5.481117 -1.987545 -0.4160087 0.4930114 -0.1878470 0.7406686 +VERTEX_SE3:QUAT 1992 9.350804 5.554790 -2.193133 -0.2110809 0.6751140 0.4865017 0.5128177 +VERTEX_SE3:QUAT 1993 9.289392 5.403496 -2.014564 0.6499286 0.5507332 -0.2585831 0.4554344 +VERTEX_SE3:QUAT 1994 9.259952 5.286309 -1.998744 0.6999624 -0.3756822 0.5689727 0.2125692 +VERTEX_SE3:QUAT 1995 9.208658 5.243268 -2.014184 0.0077218 0.4622783 -0.7890087 0.4046040 +VERTEX_SE3:QUAT 1996 9.242603 5.222458 -2.140826 0.7244744 -0.2927253 0.5426667 0.3081582 +VERTEX_SE3:QUAT 1997 9.315652 5.252195 -2.260879 -0.1559122 0.5649573 -0.3924922 0.7088473 +VERTEX_SE3:QUAT 1998 9.269993 5.338163 -2.285941 0.1285902 0.4598166 0.0867430 0.8743620 +VERTEX_SE3:QUAT 1999 9.433583 5.110806 -2.143819 -0.0621014 0.4857247 -0.8438281 0.2194744 +VERTEX_SE3:QUAT 2000 9.649809 5.039968 -2.071640 0.5363711 -0.1755305 0.4858916 0.6673863 +VERTEX_SE3:QUAT 2001 9.677142 5.104581 -2.153024 0.6296597 0.2668504 0.5357220 0.4952994 +VERTEX_SE3:QUAT 2002 9.681130 4.909014 -2.202138 0.5785694 0.7648753 0.0536370 0.2781121 +VERTEX_SE3:QUAT 2003 9.644597 4.925264 -2.386067 0.8523146 -0.0531861 0.4560070 0.2505766 +VERTEX_SE3:QUAT 2004 9.744585 4.925445 -2.570768 0.4948043 -0.2635748 0.8063649 0.1883419 +VERTEX_SE3:QUAT 2005 9.720236 4.893279 -2.595503 0.1978324 0.8008020 -0.1694729 0.5393120 +VERTEX_SE3:QUAT 2006 9.864436 4.723011 -2.700619 -0.5060748 0.0327815 -0.3846340 0.7712784 +VERTEX_SE3:QUAT 2007 9.883671 4.563189 -2.744282 0.5264797 0.4063208 0.7127938 0.2228173 +VERTEX_SE3:QUAT 2008 9.772734 4.634262 -2.576396 -0.8018238 0.5325345 0.0604212 0.2642629 +VERTEX_SE3:QUAT 2009 10.013793 4.686496 -2.603942 -0.0953269 0.7970234 -0.0864782 0.5900746 +VERTEX_SE3:QUAT 2010 9.958172 4.673621 -2.661724 -0.3896157 -0.3765969 -0.8400462 0.0263970 +VERTEX_SE3:QUAT 2011 10.155032 4.598417 -2.790433 0.7296269 0.5952943 -0.1675594 0.2918786 +VERTEX_SE3:QUAT 2012 10.102038 4.641898 -2.757715 -0.5255547 -0.2279146 -0.8187240 0.0392211 +VERTEX_SE3:QUAT 2013 10.129749 4.494403 -2.742084 -0.4149686 -0.6616299 -0.5403005 0.3132448 +VERTEX_SE3:QUAT 2014 9.879683 4.512650 -2.763120 -0.4044335 0.0538518 -0.1748317 0.8960845 +VERTEX_SE3:QUAT 2015 9.983724 4.354632 -2.971587 -0.1319626 0.4121749 0.7985872 0.4182777 +VERTEX_SE3:QUAT 2016 10.239863 4.351380 -3.178727 0.8187173 0.2654149 0.3203335 0.3957818 +VERTEX_SE3:QUAT 2017 10.248688 4.383987 -3.283196 0.3291888 0.4706409 -0.3037540 0.7601746 +VERTEX_SE3:QUAT 2018 10.379052 4.472822 -3.258541 -0.7459394 -0.5570837 -0.3274743 0.1612227 +VERTEX_SE3:QUAT 2019 10.281583 4.473598 -3.435759 -0.0620302 0.5963102 -0.0673617 0.7975141 +VERTEX_SE3:QUAT 2020 10.304431 4.423411 -3.478170 -0.4086586 -0.6042096 -0.6739028 0.1174050 +VERTEX_SE3:QUAT 2021 10.330766 4.509441 -3.533915 -0.1733608 0.2095277 -0.5884621 0.7614174 +VERTEX_SE3:QUAT 2022 10.334942 4.567708 -3.569863 0.8215819 0.5653141 0.0735372 0.0039196 +VERTEX_SE3:QUAT 2023 10.573231 4.637643 -3.534197 -0.7165431 -0.2741054 -0.2067258 0.6072040 +VERTEX_SE3:QUAT 2024 10.512844 4.789818 -3.592567 0.7007698 -0.1902462 0.6100584 0.3171070 +VERTEX_SE3:QUAT 2025 10.469175 4.816979 -3.770113 -0.4824676 0.8347716 -0.0138472 0.2649333 +VERTEX_SE3:QUAT 2026 10.624552 4.897507 -3.823206 0.6352272 -0.0670270 0.7341255 0.2303335 +VERTEX_SE3:QUAT 2027 10.632630 4.708853 -3.986130 -0.6301055 0.2091813 0.0161603 0.7476290 +VERTEX_SE3:QUAT 2028 10.505001 4.834007 -3.972394 -0.7931917 -0.5855470 0.0097243 0.1669941 +VERTEX_SE3:QUAT 2029 10.420359 4.542037 -3.928142 0.1729464 0.3896764 0.8733863 0.2354533 +VERTEX_SE3:QUAT 2030 10.481426 4.553766 -3.759971 0.7525018 0.5321244 0.3488875 0.1698885 +VERTEX_SE3:QUAT 2031 10.480150 4.479264 -3.669465 0.0398039 0.9613747 0.1189184 0.2450160 +VERTEX_SE3:QUAT 2032 10.494141 4.545693 -3.665891 0.4828949 -0.7695853 0.3918039 0.1450541 +VERTEX_SE3:QUAT 2033 10.594718 4.573521 -3.656258 -0.4675799 0.3243751 0.3836672 0.7272890 +VERTEX_SE3:QUAT 2034 10.536552 4.559638 -3.512729 -0.0287521 0.1812626 -0.6470780 0.7400049 +VERTEX_SE3:QUAT 2035 10.485519 4.577532 -3.533133 0.5039810 0.4136957 0.4058026 0.6404555 +VERTEX_SE3:QUAT 2036 10.494097 4.402563 -3.618502 0.3574975 0.4396012 0.1507570 0.8100733 +VERTEX_SE3:QUAT 2037 10.470388 4.406029 -3.811625 -0.7380108 0.0488178 -0.6596711 0.1333829 +VERTEX_SE3:QUAT 2038 10.234859 4.460031 -3.664344 -0.1798609 0.4825468 -0.1356673 0.8464000 +VERTEX_SE3:QUAT 2039 10.281544 4.396216 -3.748138 0.7374173 -0.6245387 0.2572005 0.0038669 +VERTEX_SE3:QUAT 2040 10.189049 4.416180 -3.755613 -0.7716450 -0.5560859 -0.1824947 0.2490543 +VERTEX_SE3:QUAT 2041 10.031175 4.227951 -3.902105 0.3536705 0.1082548 0.5318420 0.7618019 +VERTEX_SE3:QUAT 2042 9.870178 4.295469 -3.852421 -0.3120858 -0.3269156 -0.7968680 0.4009115 +VERTEX_SE3:QUAT 2043 9.796528 4.335475 -3.941247 -0.5363572 -0.7981290 -0.2218331 0.1615585 +VERTEX_SE3:QUAT 2044 9.854991 4.118830 -3.721173 -0.0628734 0.7819989 0.3110646 0.5364359 +VERTEX_SE3:QUAT 2045 9.732789 4.037390 -3.900876 0.6280938 0.7453957 -0.1381995 0.1754546 +VERTEX_SE3:QUAT 2046 9.739578 4.005080 -3.913394 -0.5244208 0.0074016 -0.7720270 0.3590298 +VERTEX_SE3:QUAT 2047 9.642610 3.973134 -3.943957 -0.4033053 0.2338585 -0.1983170 0.8621632 +VERTEX_SE3:QUAT 2048 9.616410 3.951138 -4.090177 -0.7794646 0.1792164 -0.1890524 0.5697154 +VERTEX_SE3:QUAT 2049 9.437722 3.963185 -4.025356 0.7545174 0.2705616 0.5064768 0.3177754 +VERTEX_SE3:QUAT 2050 9.459016 3.770445 -4.123348 -0.6755645 -0.7346325 0.0585419 0.0223745 +VERTEX_SE3:QUAT 2051 9.394052 3.821811 -3.943703 -0.2322620 0.0317434 -0.5800783 0.7801000 +VERTEX_SE3:QUAT 2052 9.235655 3.987307 -3.941552 -0.5492780 -0.2299590 -0.7735043 0.2170338 +VERTEX_SE3:QUAT 2053 9.148005 3.894309 -3.789354 0.6015010 0.3898515 0.5552455 0.4217995 +VERTEX_SE3:QUAT 2054 9.092012 3.731480 -3.718048 0.7943270 0.3388652 0.4889863 0.1229119 +VERTEX_SE3:QUAT 2055 9.030950 3.974744 -3.639950 -0.2114055 0.6339571 0.7311225 0.1373536 +VERTEX_SE3:QUAT 2056 9.067456 4.038941 -3.709434 0.7937218 -0.0441563 0.2655368 0.5454780 +VERTEX_SE3:QUAT 2057 8.872808 4.029745 -3.699488 -0.1648824 0.5989922 0.5639233 0.5440705 +VERTEX_SE3:QUAT 2058 8.830310 3.995755 -3.631029 0.0160832 0.6570862 -0.6989461 0.2818748 +VERTEX_SE3:QUAT 2059 8.658554 4.066754 -3.581172 -0.0509489 0.9559942 -0.1903824 0.2173333 +VERTEX_SE3:QUAT 2060 8.519463 4.011337 -3.406188 0.8444551 -0.4465980 0.2704223 0.1196560 +VERTEX_SE3:QUAT 2061 8.387987 4.060306 -3.313582 0.3029376 0.5122484 0.4124855 0.6897000 +VERTEX_SE3:QUAT 2062 8.368719 3.979234 -3.274784 0.0222801 0.6629322 0.0868523 0.7432908 +VERTEX_SE3:QUAT 2063 8.385486 4.014969 -3.288699 -0.1385151 -0.1131847 -0.8818495 0.4362845 +VERTEX_SE3:QUAT 2064 8.469223 3.888566 -3.209973 -0.3880569 0.5388906 -0.6221374 0.4146732 +VERTEX_SE3:QUAT 2065 8.512649 3.922467 -3.179602 0.4703911 0.8559592 -0.1565459 0.1468315 +VERTEX_SE3:QUAT 2066 8.371435 3.737588 -3.231792 0.6018659 -0.6075958 0.4599609 0.2387902 +VERTEX_SE3:QUAT 2067 8.267983 3.766665 -2.924002 0.4374453 0.7117851 0.3104169 0.4534810 +VERTEX_SE3:QUAT 2068 8.418151 3.660475 -2.729645 -0.3563438 0.8093718 -0.1530892 0.4410217 +VERTEX_SE3:QUAT 2069 8.369592 3.631489 -2.666456 -0.4354478 -0.8398676 -0.3101083 0.0940237 +VERTEX_SE3:QUAT 2070 8.513390 3.744686 -2.654939 0.1182499 0.7070777 0.6652300 0.2086316 +VERTEX_SE3:QUAT 2071 8.522595 3.672809 -2.569770 -0.7012723 0.1418091 -0.6051576 0.3491298 +VERTEX_SE3:QUAT 2072 8.475561 3.610802 -2.470557 -0.5936835 0.2610548 0.2145296 0.7303200 +VERTEX_SE3:QUAT 2073 8.534573 3.587242 -2.488341 -0.6116734 -0.1982250 -0.4818080 0.5953349 +VERTEX_SE3:QUAT 2074 8.530649 3.531129 -2.597229 0.7343459 0.1128147 0.6350410 0.2114991 +VERTEX_SE3:QUAT 2075 8.707820 3.479178 -2.671439 0.4016792 0.5707085 0.6359667 0.3293811 +VERTEX_SE3:QUAT 2076 8.698287 3.299648 -2.493724 0.5142407 0.0091931 0.5921090 0.6203861 +VERTEX_SE3:QUAT 2077 8.611792 3.214347 -2.420992 -0.7113932 0.6961968 0.0113575 0.0953980 +VERTEX_SE3:QUAT 2078 8.533285 3.176493 -2.461628 0.0309121 0.7730176 0.1972150 0.6021582 +VERTEX_SE3:QUAT 2079 8.434888 3.102240 -2.501129 -0.1763131 0.6981864 -0.4739730 0.5067535 +VERTEX_SE3:QUAT 2080 8.326157 3.131024 -2.440640 -0.1646312 0.5613236 -0.5257243 0.6175972 +VERTEX_SE3:QUAT 2081 8.376281 3.098844 -2.440614 -0.0480241 0.7092663 -0.5259286 0.4669412 +VERTEX_SE3:QUAT 2082 8.706115 3.185139 -2.631129 0.1519998 0.2226207 -0.1361063 0.9533159 +VERTEX_SE3:QUAT 2083 8.750522 3.099132 -2.706681 0.4778014 -0.1211244 0.7850992 0.3750385 +VERTEX_SE3:QUAT 2084 8.569256 3.123420 -2.745707 -0.2043779 -0.2857651 -0.6957885 0.6264554 +VERTEX_SE3:QUAT 2085 8.483930 3.019809 -2.550682 -0.9133984 0.2848683 -0.2815188 0.0728046 +VERTEX_SE3:QUAT 2086 8.456529 2.842440 -2.687409 0.6542541 -0.4353977 0.4862807 0.3819837 +VERTEX_SE3:QUAT 2087 8.647545 2.856656 -2.688367 -0.1105486 -0.3882012 -0.8884399 0.2185253 +VERTEX_SE3:QUAT 2088 8.846697 2.904623 -2.615184 0.7013347 -0.2741165 0.6358740 0.1692752 +VERTEX_SE3:QUAT 2089 9.012552 2.815308 -2.674850 -0.0201345 -0.2656008 0.9544774 0.1342526 +VERTEX_SE3:QUAT 2090 9.044091 2.769156 -2.857603 -0.4316587 0.3235756 -0.3433615 0.7688124 +VERTEX_SE3:QUAT 2091 9.153814 2.970941 -2.870053 0.8201900 0.4918768 0.2486166 0.1534122 +VERTEX_SE3:QUAT 2092 9.320881 3.065091 -2.910359 -0.7510562 0.4903172 -0.4172777 0.1462289 +VERTEX_SE3:QUAT 2093 9.559620 3.043487 -2.836746 -0.4866449 0.0736446 -0.0834429 0.8664817 +VERTEX_SE3:QUAT 2094 9.583125 3.039692 -2.811916 -0.6496601 -0.0869313 -0.2561323 0.7104794 +VERTEX_SE3:QUAT 2095 9.523043 3.064440 -2.929736 -0.2781633 0.2060076 0.8185960 0.4583520 +VERTEX_SE3:QUAT 2096 9.543283 3.104317 -2.857970 0.0494397 0.5558438 0.4589946 0.6913156 +VERTEX_SE3:QUAT 2097 9.436792 3.178818 -2.774088 0.2035392 0.2590676 0.3306728 0.8843705 +VERTEX_SE3:QUAT 2098 9.418940 3.136716 -2.726929 -0.4378263 0.8240872 0.1452674 0.3287640 +VERTEX_SE3:QUAT 2099 9.381825 3.230349 -2.990035 -0.7003595 -0.4747613 -0.5281407 0.0718728 +VERTEX_SE3:QUAT 2100 9.578515 3.252102 -3.127358 -0.7725476 0.3420544 -0.2675321 0.4632446 +VERTEX_SE3:QUAT 2101 9.593400 3.210817 -2.956667 0.3156756 0.4921544 0.1368341 0.7996308 +VERTEX_SE3:QUAT 2102 9.704895 3.134315 -3.103631 0.1231292 -0.2033674 0.9680037 0.0803107 +VERTEX_SE3:QUAT 2103 9.585204 3.061971 -3.086726 0.4831534 0.4335232 0.7564709 0.0798258 +VERTEX_SE3:QUAT 2104 9.584781 3.100859 -3.064691 0.7946415 0.4011385 0.2157673 0.4013443 +VERTEX_SE3:QUAT 2105 9.682018 3.205543 -3.186304 -0.6042300 0.6638865 0.2756691 0.3437548 +VERTEX_SE3:QUAT 2106 9.634280 3.342269 -3.195892 -0.4370920 0.0493500 0.2454826 0.8638596 +VERTEX_SE3:QUAT 2107 9.631435 3.430036 -3.289699 -0.6101659 -0.0700202 -0.7799160 0.1205229 +VERTEX_SE3:QUAT 2108 9.875139 3.351913 -3.265590 -0.3159375 0.5107164 0.7243140 0.3387056 +VERTEX_SE3:QUAT 2109 9.993375 3.254473 -3.386992 -0.0105566 0.2441413 -0.6567131 0.7134504 +VERTEX_SE3:QUAT 2110 10.054789 3.244483 -3.298267 -0.1628760 0.3781726 -0.7563234 0.5083619 +VERTEX_SE3:QUAT 2111 10.199733 3.281723 -3.366997 -0.0106588 -0.0646475 -0.5496571 0.8328170 +VERTEX_SE3:QUAT 2112 10.271673 3.236085 -3.539156 0.0548474 -0.1770437 -0.5777843 0.7948664 +VERTEX_SE3:QUAT 2113 10.088820 3.178049 -3.399294 0.0904014 0.5944580 -0.0431557 0.7978627 +VERTEX_SE3:QUAT 2114 10.137147 3.175245 -3.432078 0.8591228 0.2990764 0.3783002 0.1713195 +VERTEX_SE3:QUAT 2115 10.498373 3.192939 -3.628533 -0.4805614 -0.1160852 -0.6444632 0.5833114 +VERTEX_SE3:QUAT 2116 10.616785 3.207439 -3.900932 -0.3069018 0.8533798 -0.3682526 0.2048029 +VERTEX_SE3:QUAT 2117 10.570161 3.008771 -3.872398 -0.0476020 -0.0159709 0.9157457 0.3986085 +VERTEX_SE3:QUAT 2118 10.647543 3.259707 -3.987757 0.3432286 -0.2170397 0.6142269 0.6766190 +VERTEX_SE3:QUAT 2119 10.785107 3.393271 -4.019881 0.1685965 -0.4335315 0.7001844 0.5416340 +VERTEX_SE3:QUAT 2120 10.711862 3.413344 -4.151566 0.0343415 0.5295934 0.7278623 0.4342441 +VERTEX_SE3:QUAT 2121 10.787228 3.449851 -4.207664 0.1168625 0.0232089 0.0063287 0.9928567 +VERTEX_SE3:QUAT 2122 10.764108 3.646589 -4.368174 0.1005413 -0.3476044 0.6590880 0.6592917 +VERTEX_SE3:QUAT 2123 10.803632 3.753834 -4.354370 0.0297604 -0.0839879 -0.6402185 0.7630076 +VERTEX_SE3:QUAT 2124 10.927076 3.932417 -4.419584 -0.4064755 0.6605906 0.4859450 0.4028091 +VERTEX_SE3:QUAT 2125 10.809300 3.645332 -4.610926 -0.2482578 0.1231775 -0.8871404 0.3690220 +VERTEX_SE3:QUAT 2126 10.970595 3.779526 -4.695395 0.1989856 0.5165924 0.4768079 0.6827820 +VERTEX_SE3:QUAT 2127 10.926323 3.685886 -4.885275 0.5046095 0.6889969 0.4997282 0.1446522 +VERTEX_SE3:QUAT 2128 10.921708 3.790733 -4.947009 -0.2203382 -0.0327351 -0.3700027 0.9019299 +VERTEX_SE3:QUAT 2129 10.754466 3.845331 -5.006764 0.0526792 0.0400742 0.2317404 0.9705232 +VERTEX_SE3:QUAT 2130 10.743509 3.787183 -4.909363 -0.5187233 -0.3851996 -0.7514320 0.1337810 +VERTEX_SE3:QUAT 2131 10.600461 3.807001 -4.940942 -0.4439316 -0.0351238 -0.6119771 0.6535864 +VERTEX_SE3:QUAT 2132 10.568279 3.729844 -4.916578 -0.3589525 0.5016995 0.2454884 0.7477875 +VERTEX_SE3:QUAT 2133 10.809409 3.923531 -4.767197 0.6096342 -0.5989958 0.4514208 0.2564554 +VERTEX_SE3:QUAT 2134 10.909898 4.021408 -4.769740 0.6407611 0.6226796 0.4481642 0.0290536 +VERTEX_SE3:QUAT 2135 10.975643 4.100054 -4.703569 -0.1287589 0.5160154 -0.3665239 0.7634195 +VERTEX_SE3:QUAT 2136 10.861577 4.277212 -4.810854 0.2047596 -0.1730781 -0.9219812 0.2794066 +VERTEX_SE3:QUAT 2137 10.801357 4.329568 -4.785060 0.0991224 0.5535296 0.6540636 0.5059452 +VERTEX_SE3:QUAT 2138 10.794620 4.401551 -4.792420 0.1942676 -0.0073925 0.7033175 0.6837762 +VERTEX_SE3:QUAT 2139 10.701034 4.508826 -4.813635 0.7923586 0.1306108 0.4455868 0.3956781 +VERTEX_SE3:QUAT 2140 10.717254 4.550317 -4.768189 0.4754763 0.6892090 0.1931168 0.5114872 +VERTEX_SE3:QUAT 2141 10.628905 4.621147 -4.806826 -0.0618968 -0.2074314 -0.8510465 0.4783940 +VERTEX_SE3:QUAT 2142 10.635810 4.482131 -4.909437 0.2915059 0.1645239 -0.4824154 0.8094638 +VERTEX_SE3:QUAT 2143 10.621822 4.570754 -4.901026 0.3449146 -0.0100150 -0.5536759 0.7578764 +VERTEX_SE3:QUAT 2144 10.671500 4.577721 -5.008064 0.3403647 0.2853208 0.3969653 0.8032200 +VERTEX_SE3:QUAT 2145 10.717156 4.474628 -5.048037 0.1024119 0.0625288 -0.0969746 0.9880273 +VERTEX_SE3:QUAT 2146 10.590035 4.440554 -5.037443 0.7772532 0.3832748 -0.2545364 0.4291725 +VERTEX_SE3:QUAT 2147 10.573981 4.485959 -5.148012 -0.0876839 0.3516381 0.5445914 0.7563613 +VERTEX_SE3:QUAT 2148 10.367559 4.588132 -5.037869 0.3890486 -0.0751378 -0.5878020 0.7053257 +VERTEX_SE3:QUAT 2149 10.300932 4.660123 -5.155186 -0.6513253 0.4424309 -0.4774528 0.3899604 +VERTEX_SE3:QUAT 2150 10.271252 4.710582 -5.165545 -0.6391911 -0.0969633 -0.5498859 0.5288273 +VERTEX_SE3:QUAT 2151 10.275134 4.697486 -5.178825 0.2636008 0.5996969 -0.3593821 0.6646223 +VERTEX_SE3:QUAT 2152 10.246313 4.624788 -5.215039 -0.1891422 0.3938265 -0.7530443 0.4919860 +VERTEX_SE3:QUAT 2153 10.274767 4.711133 -5.199730 0.5963532 0.6487810 -0.4143991 0.2274191 +VERTEX_SE3:QUAT 2154 10.092728 4.669630 -5.243383 0.7371502 -0.5143432 0.3834147 0.2122587 +VERTEX_SE3:QUAT 2155 9.969470 4.699711 -5.151217 0.8937738 -0.0995689 -0.1597938 0.4070876 +VERTEX_SE3:QUAT 2156 9.916498 4.882535 -5.210558 0.5581548 -0.2434881 0.7685763 0.1961307 +VERTEX_SE3:QUAT 2157 9.959119 4.994905 -5.214288 0.3041698 0.3715998 0.7334718 0.4810546 +VERTEX_SE3:QUAT 2158 10.126988 5.181590 -5.365591 0.0271558 0.1275340 -0.4465465 0.8852084 +VERTEX_SE3:QUAT 2159 9.910326 5.146705 -5.343194 -0.3237231 0.3071539 -0.1002761 0.8892719 +VERTEX_SE3:QUAT 2160 9.645355 5.106613 -5.302870 0.4866113 -0.2603567 0.1453835 0.8211501 +VERTEX_SE3:QUAT 2161 9.481753 5.173002 -5.462394 0.8002570 0.2542576 -0.0602592 0.5397320 +VERTEX_SE3:QUAT 2162 9.230924 4.991504 -5.693106 0.5926352 0.3300096 -0.7328619 0.0528269 +VERTEX_SE3:QUAT 2163 9.191283 4.767058 -5.671759 0.2147713 0.4689262 0.3590257 0.7778702 +VERTEX_SE3:QUAT 2164 9.238865 4.771013 -5.648709 -0.2336337 0.4022729 0.1293191 0.8757102 +VERTEX_SE3:QUAT 2165 9.077958 4.819524 -5.614806 0.6459071 -0.2018578 0.5175702 0.5236206 +VERTEX_SE3:QUAT 2166 9.069212 4.786299 -5.631546 0.2061288 0.2969183 0.2469284 0.8990977 +VERTEX_SE3:QUAT 2167 8.914656 4.893178 -5.592485 0.2717201 -0.6102595 0.6940573 0.2683950 +VERTEX_SE3:QUAT 2168 8.823264 5.050013 -5.646806 0.8442092 0.1767112 0.4967669 0.0964709 +VERTEX_SE3:QUAT 2169 8.684260 4.924131 -5.711758 0.7357554 0.4572854 -0.0567285 0.4963224 +VERTEX_SE3:QUAT 2170 8.676241 4.963659 -5.772150 -0.0419822 0.9040724 -0.2036991 0.3733594 +VERTEX_SE3:QUAT 2171 8.708469 5.073467 -5.671868 0.2397751 0.8605383 -0.2508634 0.3728930 +VERTEX_SE3:QUAT 2172 8.650471 5.076308 -5.723129 0.3601530 0.2670749 0.2623773 0.8544700 +VERTEX_SE3:QUAT 2173 8.755465 4.959023 -5.598974 -0.5618457 0.5499562 -0.6021076 0.1390828 +VERTEX_SE3:QUAT 2174 8.552369 4.799557 -5.682544 -0.6251532 0.6713437 -0.3593131 0.1713917 +VERTEX_SE3:QUAT 2175 8.663605 4.777124 -5.897513 0.4082487 0.4343408 -0.6016315 0.5317148 +VERTEX_SE3:QUAT 2176 8.654726 4.626861 -5.912502 0.3106363 0.2161920 0.6796636 0.6283499 +VERTEX_SE3:QUAT 2177 8.611413 4.714753 -5.948295 0.4007509 -0.0407807 -0.5897640 0.6999386 +VERTEX_SE3:QUAT 2178 8.599437 4.624085 -5.891086 0.3824994 0.2914612 0.7222735 0.4970569 +VERTEX_SE3:QUAT 2179 8.683803 4.682221 -5.858592 0.1994001 0.5669145 -0.1456209 0.7859021 +VERTEX_SE3:QUAT 2180 8.439184 4.731580 -5.897229 0.2347859 0.7524629 0.1397193 0.5992943 +VERTEX_SE3:QUAT 2181 8.306965 4.583874 -5.898361 0.5613858 0.2914828 0.6090220 0.4785144 +VERTEX_SE3:QUAT 2182 8.433447 4.426516 -5.981566 -0.0684597 -0.5122448 0.8238776 0.2326890 +VERTEX_SE3:QUAT 2183 8.246206 4.441934 -5.958862 0.4659653 -0.7050060 0.1852413 0.5015262 +VERTEX_SE3:QUAT 2184 8.098434 4.499937 -6.153557 0.5543608 0.4347792 0.1095157 0.7011829 +VERTEX_SE3:QUAT 2185 8.010462 4.501350 -6.224759 0.0994379 0.2250561 -0.5263432 0.8138948 +VERTEX_SE3:QUAT 2186 8.002930 4.442066 -6.276834 0.8913584 0.3036884 0.2850649 0.1788620 +VERTEX_SE3:QUAT 2187 7.938695 4.440207 -6.415220 0.8224119 0.0813351 -0.3979966 0.3982737 +VERTEX_SE3:QUAT 2188 7.902761 4.202491 -6.467536 0.1551857 -0.9008372 0.3958646 0.0877548 +VERTEX_SE3:QUAT 2189 7.714183 4.193142 -6.457525 0.4980805 0.2870805 -0.2680095 0.7730922 +VERTEX_SE3:QUAT 2190 7.670413 4.150775 -6.442340 0.6479675 0.4412748 0.5313136 0.3211238 +VERTEX_SE3:QUAT 2191 7.689868 3.958109 -6.394687 0.0581760 0.7098486 -0.0531993 0.6999288 +VERTEX_SE3:QUAT 2192 7.745238 3.997368 -6.327989 0.1918572 -0.6034238 0.7730164 0.0389370 +VERTEX_SE3:QUAT 2193 7.590426 3.857188 -6.486718 0.1796286 0.8832856 -0.3439690 0.2631073 +VERTEX_SE3:QUAT 2194 7.642478 3.757838 -6.599319 0.7883495 0.1160719 -0.4429738 0.4108608 +VERTEX_SE3:QUAT 2195 7.741989 3.653391 -6.547325 -0.2552907 0.8764416 -0.0765348 0.4010226 +VERTEX_SE3:QUAT 2196 7.615571 3.469185 -6.637328 0.7073060 0.4368884 -0.4381161 0.3419080 +VERTEX_SE3:QUAT 2197 7.621825 3.414674 -6.467300 0.2080810 0.2521125 -0.7288861 0.6015536 +VERTEX_SE3:QUAT 2198 7.847756 3.475154 -6.377328 0.2766087 0.5591103 -0.2072710 0.7536060 +VERTEX_SE3:QUAT 2199 7.930569 3.417937 -6.295944 0.3658819 0.1031087 0.4460715 0.8102588 +VERTEX_SE3:QUAT 2200 7.901294 3.464728 -6.086222 0.4382971 -0.3391812 0.5279361 0.6435334 +VERTEX_SE3:QUAT 2201 7.933711 3.357448 -6.037518 -0.0403466 0.8815571 0.0340228 0.4691179 +VERTEX_SE3:QUAT 2202 8.148314 3.417554 -5.909800 0.1409212 -0.3844554 0.8878171 0.2100380 +VERTEX_SE3:QUAT 2203 8.113042 3.476630 -5.963214 0.8071656 0.3555227 0.0731560 0.4655486 +VERTEX_SE3:QUAT 2204 8.255498 3.486498 -5.969032 0.6548451 0.4083208 -0.5957303 0.2226151 +VERTEX_SE3:QUAT 2205 8.295421 3.479936 -5.951417 0.4137224 0.2182431 -0.2757289 0.8397484 +VERTEX_SE3:QUAT 2206 8.549683 3.560476 -5.924824 0.3587705 -0.1265891 0.8503404 0.3635659 +VERTEX_SE3:QUAT 2207 8.814643 3.560233 -6.001577 0.2506919 0.1258484 0.8497670 0.4463315 +VERTEX_SE3:QUAT 2208 8.737080 3.504959 -5.905535 -0.5505463 0.0486648 -0.7201079 0.4194938 +VERTEX_SE3:QUAT 2209 8.830370 3.505045 -6.010453 0.6479078 0.5606610 0.3660068 0.3631994 +VERTEX_SE3:QUAT 2210 8.798954 3.348631 -6.076636 -0.0331345 0.9222768 -0.2518060 0.2913783 +VERTEX_SE3:QUAT 2211 8.880533 3.237781 -6.034407 0.7628288 -0.3521312 0.3630084 0.4028905 +VERTEX_SE3:QUAT 2212 8.921091 3.171022 -6.013580 -0.5930617 0.2118109 -0.7500559 0.2020645 +VERTEX_SE3:QUAT 2213 8.901905 3.255559 -5.880587 0.6004508 -0.3057209 0.1704905 0.7189761 +VERTEX_SE3:QUAT 2214 8.905921 3.210310 -5.849074 0.7491811 0.2253501 0.0162602 0.6226400 +VERTEX_SE3:QUAT 2215 9.118597 3.147136 -5.906486 0.5062372 0.5264771 -0.3271787 0.5995831 +VERTEX_SE3:QUAT 2216 9.186378 3.046648 -5.807401 0.2258001 0.9513708 -0.1438146 0.1523984 +VERTEX_SE3:QUAT 2217 9.290258 2.993844 -5.801970 0.2022853 0.4031035 -0.8301502 0.3277786 +VERTEX_SE3:QUAT 2218 9.423326 3.027962 -5.929851 0.7786299 0.2314802 0.4568747 0.3625160 +VERTEX_SE3:QUAT 2219 9.369281 2.758750 -5.838422 -0.8397586 0.0364804 -0.5111184 0.1795345 +VERTEX_SE3:QUAT 2220 9.591239 2.848678 -5.859860 -0.6231218 0.7061766 -0.3203362 0.1020717 +VERTEX_SE3:QUAT 2221 9.564275 3.045316 -5.827171 -0.3458788 0.6653023 -0.5079704 0.4239182 +VERTEX_SE3:QUAT 2222 9.618494 3.118199 -5.756652 0.2597419 -0.1194340 0.6900083 0.6649498 +VERTEX_SE3:QUAT 2223 9.881239 3.016606 -5.609987 0.1969978 -0.7020686 0.6750718 0.1121143 +VERTEX_SE3:QUAT 2224 9.926675 3.073834 -5.562224 -0.3959894 0.0287461 -0.8247393 0.4027047 +VERTEX_SE3:QUAT 2225 9.923616 3.051641 -5.578747 -0.1411843 0.6274986 0.0225745 0.7653776 +VERTEX_SE3:QUAT 2226 10.014923 3.093361 -5.568655 0.1362876 0.4146902 -0.6994806 0.5658486 +VERTEX_SE3:QUAT 2227 9.939115 3.165613 -5.419547 -0.1639070 0.4102264 0.1875179 0.8773174 +VERTEX_SE3:QUAT 2228 9.922703 3.201389 -5.399860 0.1302136 -0.2406734 0.8826099 0.3822571 +VERTEX_SE3:QUAT 2229 9.757804 3.295911 -5.390127 0.5036648 -0.5654094 -0.0167154 0.6529583 +VERTEX_SE3:QUAT 2230 9.610597 3.347481 -5.562149 0.0606491 0.8076268 -0.1982796 0.5520380 +VERTEX_SE3:QUAT 2231 9.456496 3.372042 -5.692866 0.1140708 0.1847483 -0.4805538 0.8496611 +VERTEX_SE3:QUAT 2232 9.481682 3.629882 -5.875907 0.5416120 -0.0255322 0.6752921 0.4999851 +VERTEX_SE3:QUAT 2233 9.494575 3.524275 -5.873823 0.4566512 -0.8391193 0.0928434 0.2805862 +VERTEX_SE3:QUAT 2234 9.344892 3.506901 -6.035290 0.5373725 0.0987077 0.7577706 0.3567511 +VERTEX_SE3:QUAT 2235 9.566462 3.534750 -6.138717 -0.0560076 0.2850918 -0.6502500 0.7019692 +VERTEX_SE3:QUAT 2236 9.379677 3.507234 -6.096236 0.4664527 -0.3261769 0.1718951 0.8040414 +VERTEX_SE3:QUAT 2237 9.374631 3.726657 -6.280962 0.2334145 0.4426086 0.5929076 0.6309326 +VERTEX_SE3:QUAT 2238 9.374685 3.852936 -6.290097 0.1841912 0.4426099 -0.3746626 0.7935981 +VERTEX_SE3:QUAT 2239 9.276633 3.869803 -6.166671 0.9335808 0.1799138 0.3098670 0.0063466 +VERTEX_SE3:QUAT 2240 9.204256 4.026704 -6.231657 0.5046079 0.5087416 0.4503151 0.5326999 +VERTEX_SE3:QUAT 2241 9.145451 4.272447 -6.222892 -0.6360856 0.6512185 -0.3496654 0.2214578 +VERTEX_SE3:QUAT 2242 8.972004 4.352667 -6.311349 0.8922400 0.2350793 0.3844047 0.0296409 +VERTEX_SE3:QUAT 2243 8.988633 4.469577 -6.372775 0.6433040 0.2927033 0.3307541 0.6253691 +VERTEX_SE3:QUAT 2244 8.847083 4.476196 -6.420570 -0.1997330 0.7723056 -0.5638778 0.2137583 +VERTEX_SE3:QUAT 2245 8.745938 4.660998 -6.361192 0.6913842 0.0978607 -0.4575432 0.5505137 +VERTEX_SE3:QUAT 2246 8.628605 4.786891 -6.333148 0.0441180 0.7448383 -0.2005451 0.6348631 +VERTEX_SE3:QUAT 2247 8.645435 4.835651 -6.198341 0.5627417 -0.2261381 0.6932115 0.3894112 +VERTEX_SE3:QUAT 2248 8.676073 4.928337 -6.306739 0.2648898 -0.1758744 -0.0031879 0.9480988 +VERTEX_SE3:QUAT 2249 8.634825 4.832417 -6.425776 -0.2310547 0.7183744 -0.6087197 0.2449740 +VERTEX_SE3:QUAT 2250 8.709589 4.819597 -6.427802 0.4872410 0.4603868 -0.3919384 0.6300988 +VERTEX_SE3:QUAT 2251 8.584635 4.729814 -6.195893 0.0032418 -0.2171822 -0.9487310 0.2296320 +VERTEX_SE3:QUAT 2252 8.564979 4.853386 -6.242908 0.0928260 0.5757091 0.3974266 0.7085157 +VERTEX_SE3:QUAT 2253 8.765332 4.898845 -6.093857 0.4712752 -0.2399037 0.5516375 0.6450132 +VERTEX_SE3:QUAT 2254 8.680449 4.928204 -6.151199 0.2964113 -0.4730943 -0.0270315 0.8292113 +VERTEX_SE3:QUAT 2255 8.843671 4.849502 -6.215828 0.1370108 0.8871969 -0.2012910 0.3919076 +VERTEX_SE3:QUAT 2256 8.757505 5.038388 -6.352961 0.8621160 0.3096579 0.3116483 0.2524743 +VERTEX_SE3:QUAT 2257 8.711882 5.136940 -6.358869 0.4763666 -0.5062109 0.7111533 0.1052919 +VERTEX_SE3:QUAT 2258 8.334931 5.147760 -6.502193 0.2944822 0.2998994 0.8209773 0.3864414 +VERTEX_SE3:QUAT 2259 8.277919 5.197740 -6.796150 0.1652046 -0.1704029 -0.6161298 0.7510355 +VERTEX_SE3:QUAT 2260 8.049479 5.355947 -6.702235 -0.0657306 -0.1425185 -0.9797417 0.1243956 +VERTEX_SE3:QUAT 2261 7.975108 5.338957 -6.846162 -0.2732343 -0.4477387 0.6861285 0.5040840 +VERTEX_SE3:QUAT 2262 7.920678 5.422636 -6.936286 0.5553370 0.0017943 0.5223454 0.6471112 +VERTEX_SE3:QUAT 2263 7.834923 5.418246 -7.001397 0.1440739 0.3973271 0.5785921 0.6975708 +VERTEX_SE3:QUAT 2264 7.657944 5.273559 -6.908418 0.3683241 -0.0388690 0.6005909 0.7086022 +VERTEX_SE3:QUAT 2265 7.627041 5.477418 -6.923802 0.3729513 -0.0402644 0.1592358 0.9131977 +VERTEX_SE3:QUAT 2266 7.640753 5.519011 -6.775403 0.2436813 -0.8180511 0.3897976 0.3456438 +VERTEX_SE3:QUAT 2267 7.540558 5.614993 -6.931484 0.5808350 0.4236406 0.5414140 0.4359245 +VERTEX_SE3:QUAT 2268 7.595295 5.655275 -6.767758 0.0184142 0.7167650 -0.6966619 0.0238943 +VERTEX_SE3:QUAT 2269 7.610679 5.664324 -6.701999 -0.0489554 -0.0439816 0.2499029 0.9660318 +VERTEX_SE3:QUAT 2270 7.343495 5.718042 -6.876696 -0.2286008 0.4265250 -0.7864083 0.3839011 +VERTEX_SE3:QUAT 2271 7.316123 5.791190 -6.821376 0.6565981 -0.2430524 0.7132716 0.0323733 +VERTEX_SE3:QUAT 2272 7.415852 5.766351 -6.781527 0.6960089 -0.3685864 0.5961044 0.1561257 +VERTEX_SE3:QUAT 2273 7.361610 5.742299 -6.822997 -0.1407839 0.2050112 -0.8869545 0.3891811 +VERTEX_SE3:QUAT 2274 7.452703 5.623041 -6.803745 0.4849338 0.1348948 0.3986326 0.7666386 +VERTEX_SE3:QUAT 2275 7.420748 5.719470 -6.887703 0.1605429 -0.3724380 0.1953771 0.8929411 +VERTEX_SE3:QUAT 2276 7.669599 5.786222 -6.766012 0.0901142 -0.1827205 -0.7247390 0.6582143 +VERTEX_SE3:QUAT 2277 7.611765 5.832971 -6.794539 0.0122420 -0.2814443 0.3640013 0.8877738 +VERTEX_SE3:QUAT 2278 7.504279 5.733888 -6.834947 0.6920550 -0.0352581 -0.6008643 0.3984706 +VERTEX_SE3:QUAT 2279 7.562955 5.519256 -6.839309 0.8142442 0.0571611 -0.1589801 0.5553956 +VERTEX_SE3:QUAT 2280 7.486033 5.645190 -6.784523 -0.1171333 -0.3691233 0.8335703 0.3939395 +VERTEX_SE3:QUAT 2281 7.482651 5.603055 -6.916023 0.5018383 -0.4407057 0.5563726 0.4943545 +VERTEX_SE3:QUAT 2282 7.408794 5.572325 -6.809035 -0.3658463 -0.3327723 -0.8528530 0.1675136 +VERTEX_SE3:QUAT 2283 7.345256 5.408303 -6.608115 -0.1211803 0.1265358 -0.8017225 0.5714412 +VERTEX_SE3:QUAT 2284 7.492376 5.175354 -6.662449 0.3861247 0.1809140 -0.9039866 0.0314034 +VERTEX_SE3:QUAT 2285 7.400435 5.160756 -6.415326 0.1574460 0.5870956 0.1580513 0.7781705 +VERTEX_SE3:QUAT 2286 7.411018 5.189689 -6.441023 -0.0644459 0.3103434 0.1090870 0.9421431 +VERTEX_SE3:QUAT 2287 7.419527 4.951530 -6.468902 0.2112915 0.6013003 -0.4992200 0.5870037 +VERTEX_SE3:QUAT 2288 7.283062 4.833094 -6.418639 0.4719941 -0.2965517 -0.0153327 0.8300864 +VERTEX_SE3:QUAT 2289 7.175069 4.754475 -6.273501 0.2830810 0.0979158 -0.9448406 0.1324914 +VERTEX_SE3:QUAT 2290 7.236716 4.851773 -6.385045 -0.6915952 0.0084757 -0.6690491 0.2720248 +VERTEX_SE3:QUAT 2291 7.092455 4.770545 -6.448134 0.4496665 0.0759922 0.6315053 0.6270775 +VERTEX_SE3:QUAT 2292 7.126839 4.705027 -6.463913 0.7096516 0.5564234 0.2287239 0.3667055 +VERTEX_SE3:QUAT 2293 7.019808 4.555033 -6.463086 0.2724832 0.0831899 0.3742117 0.8824953 +VERTEX_SE3:QUAT 2294 7.005902 4.615150 -6.379765 0.0513659 0.7454804 0.1440077 0.6487544 +VERTEX_SE3:QUAT 2295 7.046304 4.370779 -6.539886 0.3658463 -0.8262671 0.3456849 0.2528658 +VERTEX_SE3:QUAT 2296 7.312006 4.314700 -6.514141 0.4500312 0.1920742 -0.6022525 0.6307704 +VERTEX_SE3:QUAT 2297 7.352099 4.196214 -6.548327 0.7434035 0.2271308 -0.0693839 0.6252589 +VERTEX_SE3:QUAT 2298 7.404020 4.348002 -6.520226 -0.0806594 -0.0401460 -0.8543433 0.5118397 +VERTEX_SE3:QUAT 2299 7.344027 4.285978 -6.233257 -0.1637339 -0.0425497 -0.0469150 0.9844693 +VERTEX_SE3:QUAT 2300 7.263156 4.079804 -6.239332 0.7487023 0.3107288 0.3422556 0.4751354 +VERTEX_SE3:QUAT 2301 7.370964 4.123456 -5.966298 0.0825959 0.2926181 -0.5293542 0.7920459 +VERTEX_SE3:QUAT 2302 7.480227 4.103597 -5.968165 0.0150669 0.7384620 0.0256968 0.6736368 +VERTEX_SE3:QUAT 2303 7.527820 3.998775 -5.942029 0.7057718 0.3925710 -0.3207296 0.4948804 +VERTEX_SE3:QUAT 2304 7.602948 3.858989 -5.940226 -0.1605775 0.0414818 -0.9144900 0.3690558 +VERTEX_SE3:QUAT 2305 7.591458 3.877061 -5.824742 0.8823868 -0.1285899 0.2490513 0.3779306 +VERTEX_SE3:QUAT 2306 7.582966 3.797770 -5.636793 0.2918953 0.3139054 -0.8117763 0.3965851 +VERTEX_SE3:QUAT 2307 7.751832 3.894116 -5.272386 0.3662827 0.4059286 -0.3014035 0.7811625 +VERTEX_SE3:QUAT 2308 7.871139 3.811065 -5.130139 0.5241122 -0.0847443 -0.2842722 0.7983196 +VERTEX_SE3:QUAT 2309 7.814720 3.861050 -4.915724 -0.0844700 -0.5831531 0.7387256 0.3272335 +VERTEX_SE3:QUAT 2310 7.645364 3.929079 -4.686758 -0.2300064 0.6042248 -0.5148390 0.5629833 +VERTEX_SE3:QUAT 2311 7.556360 3.851537 -4.665793 0.8090690 -0.3481762 0.3362553 0.3333364 +VERTEX_SE3:QUAT 2312 7.498263 3.946533 -4.643732 -0.2751739 0.0198833 0.5668889 0.7762222 +VERTEX_SE3:QUAT 2313 7.507664 3.913689 -4.727985 0.2097403 0.0797677 -0.5623561 0.7958654 +VERTEX_SE3:QUAT 2314 7.433645 3.924871 -4.717820 0.7460951 0.2177035 0.1230221 0.6171003 +VERTEX_SE3:QUAT 2315 7.533349 3.987909 -4.564836 0.2136003 -0.2856756 0.4256916 0.8315954 +VERTEX_SE3:QUAT 2316 7.518223 4.014550 -4.546831 0.0375564 0.5425343 -0.2029906 0.8142732 +VERTEX_SE3:QUAT 2317 7.409679 4.044868 -4.537276 0.4704889 0.6730328 -0.1837600 0.5402771 +VERTEX_SE3:QUAT 2318 7.427948 4.081834 -4.606446 0.2969978 -0.7307743 0.4363705 0.4328301 +VERTEX_SE3:QUAT 2319 7.426950 4.101622 -4.493916 0.2533924 0.4567080 -0.1735599 0.8349174 +VERTEX_SE3:QUAT 2320 7.307275 4.168958 -4.433277 0.5358734 0.5384070 -0.6214524 0.1917146 +VERTEX_SE3:QUAT 2321 7.184767 4.106371 -4.269315 -0.3786506 0.8020240 -0.3844021 0.2561566 +VERTEX_SE3:QUAT 2322 7.215157 4.108260 -4.203080 0.4260075 -0.4681157 0.7285329 0.2619639 +VERTEX_SE3:QUAT 2323 7.173364 4.118996 -4.196536 0.8253425 0.1739224 0.4741582 0.2524576 +VERTEX_SE3:QUAT 2324 7.079807 4.201398 -4.215418 0.2381896 0.2787424 0.8686256 0.3332537 +VERTEX_SE3:QUAT 2325 7.088378 4.354173 -4.116011 0.7639215 -0.1562219 0.6136523 0.1242960 +VERTEX_SE3:QUAT 2326 7.305332 4.354645 -3.953605 -0.1461135 0.4224970 -0.3840300 0.8078787 +VERTEX_SE3:QUAT 2327 7.328970 4.538730 -3.950081 0.5265966 0.2167721 -0.3950233 0.7208762 +VERTEX_SE3:QUAT 2328 7.255940 4.606498 -3.867486 0.2169000 -0.7041220 0.3871620 0.5543214 +VERTEX_SE3:QUAT 2329 7.397438 4.693222 -3.915188 0.3115632 0.8107277 0.1431442 0.4745089 +VERTEX_SE3:QUAT 2330 7.297262 4.747381 -3.852656 0.1080333 0.7467074 -0.5639644 0.3357097 +VERTEX_SE3:QUAT 2331 7.561114 4.948818 -4.006015 0.3668729 0.4268727 0.0573685 0.8245561 +VERTEX_SE3:QUAT 2332 7.622376 4.897754 -4.017383 0.6071647 0.3311857 0.0573085 0.7199881 +VERTEX_SE3:QUAT 2333 7.580162 5.006416 -4.289541 0.7209933 0.0045581 0.0963072 0.6862017 +VERTEX_SE3:QUAT 2334 7.748172 5.114632 -4.423341 -0.3964321 0.7066996 -0.4974885 0.3097134 +VERTEX_SE3:QUAT 2335 7.799716 5.129264 -4.544454 0.1547787 -0.0810632 0.9763423 0.1273890 +VERTEX_SE3:QUAT 2336 7.725228 5.267549 -4.509087 0.3619450 -0.9022559 0.1971525 0.1267324 +VERTEX_SE3:QUAT 2337 7.832405 5.232614 -4.332354 -0.3819756 0.4674534 -0.7619114 0.2346762 +VERTEX_SE3:QUAT 2338 7.912111 5.384886 -4.394838 0.2038472 0.1258879 0.4388094 0.8660513 +VERTEX_SE3:QUAT 2339 7.839050 5.245683 -4.327664 0.3380284 0.8424822 -0.4150196 0.0609854 +VERTEX_SE3:QUAT 2340 7.926650 5.115814 -4.242982 0.5118398 -0.7724359 0.0355388 0.3742991 +VERTEX_SE3:QUAT 2341 7.883021 5.143855 -4.249494 0.6914657 -0.0440293 -0.0252141 0.7206254 +VERTEX_SE3:QUAT 2342 8.073624 5.032796 -4.332239 0.4049831 0.6036827 -0.0079580 0.6866531 +VERTEX_SE3:QUAT 2343 8.145365 5.216920 -4.389439 -0.2042748 0.9472014 -0.1322936 0.2087576 +VERTEX_SE3:QUAT 2344 8.082744 5.393181 -4.280390 0.5829633 0.3646483 -0.2725900 0.6729637 +VERTEX_SE3:QUAT 2345 8.155980 5.500236 -4.229887 0.8814890 0.0605405 -0.3398502 0.3222017 +VERTEX_SE3:QUAT 2346 8.121822 5.601121 -4.227538 0.6042519 0.5523010 -0.4556166 0.3496522 +VERTEX_SE3:QUAT 2347 8.224671 5.630051 -4.162368 0.7675016 -0.2065819 0.3096869 0.5218805 +VERTEX_SE3:QUAT 2348 8.019366 5.618470 -4.231120 0.4813905 0.1086683 0.5175005 0.6990333 +VERTEX_SE3:QUAT 2349 7.923783 5.819619 -4.303132 0.2607620 0.9047347 -0.1584946 0.2972166 +VERTEX_SE3:QUAT 2350 7.910690 5.934633 -4.328605 0.4415648 -0.7576713 0.1889376 0.4418792 +VERTEX_SE3:QUAT 2351 7.859277 5.885135 -4.257965 -0.7347742 -0.0037220 -0.6771741 0.0390925 +VERTEX_SE3:QUAT 2352 7.802564 6.052370 -4.085861 0.3171865 -0.7004350 0.5096600 0.3860443 +VERTEX_SE3:QUAT 2353 7.839152 6.072521 -4.023285 0.5974898 -0.1487079 0.7874350 0.0289486 +VERTEX_SE3:QUAT 2354 7.625580 6.272805 -4.033357 0.4122105 0.0384157 0.7203264 0.5565398 +VERTEX_SE3:QUAT 2355 7.629913 6.369824 -4.138050 0.8246797 -0.4242712 0.2198803 0.3025721 +VERTEX_SE3:QUAT 2356 7.810972 6.526794 -4.177228 0.4106903 0.0838102 0.8150379 0.4000281 +VERTEX_SE3:QUAT 2357 7.916800 6.517934 -4.309942 0.4251108 0.5863832 0.2751932 0.6322216 +VERTEX_SE3:QUAT 2358 7.880514 6.431261 -4.364697 0.5910788 -0.5380768 0.2941056 0.5240239 +VERTEX_SE3:QUAT 2359 7.931976 6.399190 -4.325101 0.5220013 -0.1029597 0.1079739 0.8397950 +VERTEX_SE3:QUAT 2360 7.934548 6.240918 -4.383889 -0.0900477 0.5846923 -0.4827010 0.6457755 +VERTEX_SE3:QUAT 2361 7.715877 6.290634 -4.434494 -0.6906704 0.2105461 -0.6446238 0.2512069 +VERTEX_SE3:QUAT 2362 7.673464 6.322594 -4.410877 0.3535347 0.7047567 -0.1003769 0.6068408 +VERTEX_SE3:QUAT 2363 7.409539 6.278123 -4.404177 0.5438883 0.2671788 0.2776026 0.7454782 +VERTEX_SE3:QUAT 2364 7.395371 6.354092 -4.247594 0.6923018 0.6180697 0.0379262 0.3704993 +VERTEX_SE3:QUAT 2365 7.250150 6.449366 -4.379150 0.4735009 0.7299804 -0.1444609 0.4712288 +VERTEX_SE3:QUAT 2366 7.288245 6.486592 -4.430434 0.5548704 0.5843322 -0.4879082 0.3355895 +VERTEX_SE3:QUAT 2367 7.290627 6.499110 -4.460199 -0.0006094 0.0396340 0.4077481 0.9122337 +VERTEX_SE3:QUAT 2368 7.309135 6.395566 -4.560450 -0.1423100 0.1173736 -0.9809360 0.0611210 +VERTEX_SE3:QUAT 2369 7.323110 6.321302 -4.587573 0.0896210 0.2198927 0.4223006 0.8748014 +VERTEX_SE3:QUAT 2370 7.197736 6.273864 -4.483715 0.0873054 -0.3068185 0.8043478 0.5012631 +VERTEX_SE3:QUAT 2371 7.029685 6.103439 -4.485993 0.3815648 0.8866844 -0.2611476 0.0009492 +VERTEX_SE3:QUAT 2372 6.935562 5.935826 -4.509595 0.5512550 0.0627376 0.2459097 0.7948021 +VERTEX_SE3:QUAT 2373 6.994251 5.805809 -4.564871 0.4495903 -0.0627514 -0.8251610 0.3362145 +VERTEX_SE3:QUAT 2374 6.984406 5.858985 -4.731486 0.4509695 0.5795121 -0.1712745 0.6568541 +VERTEX_SE3:QUAT 2375 6.842560 5.900051 -4.642919 -0.2469775 -0.9205319 0.3008816 0.0330662 +VERTEX_SE3:QUAT 2376 6.592244 5.868622 -4.647196 -0.1385464 0.6915528 -0.1580686 0.6910673 +VERTEX_SE3:QUAT 2377 6.653814 5.798155 -4.579783 0.2310927 -0.6190209 0.2595277 0.7043115 +VERTEX_SE3:QUAT 2378 6.683431 5.555787 -4.726646 0.3785628 0.1664035 0.3754075 0.8294994 +VERTEX_SE3:QUAT 2379 6.623356 5.376118 -4.566333 0.1973978 -0.3482359 0.2798470 0.8726119 +VERTEX_SE3:QUAT 2380 6.604490 5.405965 -4.591734 0.7885772 -0.0558288 -0.4677527 0.3952677 +VERTEX_SE3:QUAT 2381 6.586985 5.461399 -4.613998 -0.2060210 0.4409267 -0.8466679 0.2151568 +VERTEX_SE3:QUAT 2382 6.441712 5.637401 -4.629067 0.7012370 0.4494182 -0.3136760 0.4559576 +VERTEX_SE3:QUAT 2383 6.380071 5.466338 -4.587486 0.1661801 0.8630581 -0.4699187 0.0818008 +VERTEX_SE3:QUAT 2384 6.393867 5.514972 -4.580573 -0.4092805 0.7757763 -0.4710416 0.0937042 +VERTEX_SE3:QUAT 2385 6.311886 5.536363 -4.529577 0.2295267 0.5772295 0.0140231 0.7835349 +VERTEX_SE3:QUAT 2386 6.159197 5.562595 -4.478987 0.8122098 0.5070042 0.2501305 0.1438635 +VERTEX_SE3:QUAT 2387 5.998520 5.556086 -4.665539 0.1243177 -0.5044602 0.3236713 0.7907603 +VERTEX_SE3:QUAT 2388 6.070992 5.453672 -4.741727 -0.5563841 -0.4751800 0.6780003 0.0704008 +VERTEX_SE3:QUAT 2389 6.053714 5.444296 -4.775919 0.1158059 -0.7530748 0.6252751 0.1688145 +VERTEX_SE3:QUAT 2390 6.141633 5.252787 -4.755590 0.2479881 0.1625970 -0.1068594 0.9490233 +VERTEX_SE3:QUAT 2391 6.194366 5.249905 -4.657890 0.0342700 -0.1780355 0.9419281 0.2826664 +VERTEX_SE3:QUAT 2392 6.172751 5.148323 -4.773112 -0.0520043 0.8800293 -0.3533240 0.3130592 +VERTEX_SE3:QUAT 2393 6.302824 5.086161 -4.800443 -0.5099210 0.4533321 -0.6444682 0.3451541 +VERTEX_SE3:QUAT 2394 6.307783 5.014917 -4.851601 -0.2224810 0.7139142 -0.6285935 0.2137731 +VERTEX_SE3:QUAT 2395 6.404259 5.142033 -4.978511 -0.4549469 0.7733602 -0.2424840 0.3689699 +VERTEX_SE3:QUAT 2396 6.530161 5.314599 -5.090267 0.3640562 0.4441174 -0.7934911 0.2014813 +VERTEX_SE3:QUAT 2397 6.750279 5.236807 -5.031991 0.7168902 0.3869737 -0.4283706 0.3909200 +VERTEX_SE3:QUAT 2398 6.790658 5.113352 -5.043176 0.5336522 0.0726759 0.1366994 0.8314126 +VERTEX_SE3:QUAT 2399 6.766291 5.218926 -5.052747 -0.4498867 0.3773503 -0.6864773 0.4289028 +VERTEX_SE3:QUAT 2400 6.764624 5.068278 -5.060306 0.6725021 0.4420883 -0.5928940 0.0278504 +VERTEX_SE3:QUAT 2401 6.646131 4.895360 -4.985393 0.1417361 0.0693593 0.5122345 0.8442251 +VERTEX_SE3:QUAT 2402 6.671481 4.948982 -5.181769 0.6898755 0.1110265 0.7136523 0.0494506 +VERTEX_SE3:QUAT 2403 6.764652 5.045189 -5.053944 0.5549745 0.1351553 0.5110875 0.6422818 +VERTEX_SE3:QUAT 2404 6.891451 4.850899 -5.191696 0.4021049 -0.8575315 0.2529584 0.1973916 +VERTEX_SE3:QUAT 2405 6.959798 4.886491 -5.125751 0.2835878 -0.3558309 0.5305398 0.7151852 +VERTEX_SE3:QUAT 2406 7.088739 4.785293 -5.119469 0.4102555 -0.8081692 0.4193929 0.0516004 +VERTEX_SE3:QUAT 2407 7.195220 4.636967 -4.992824 -0.1655082 -0.5381450 0.8213893 0.0912499 +VERTEX_SE3:QUAT 2408 7.342113 4.669367 -4.736724 0.5104863 -0.1072515 0.7213404 0.4555973 +VERTEX_SE3:QUAT 2409 7.346518 4.651916 -4.608116 -0.4849479 0.7607961 -0.4294954 0.0393520 +VERTEX_SE3:QUAT 2410 7.476545 4.720554 -4.455744 0.1306411 -0.6366930 0.7015047 0.2923117 +VERTEX_SE3:QUAT 2411 7.515225 4.689839 -4.441117 0.1363813 0.8238655 -0.5318441 0.1406684 +VERTEX_SE3:QUAT 2412 7.573626 4.734926 -4.478295 0.4580281 0.7759086 -0.3075179 0.3059555 +VERTEX_SE3:QUAT 2413 7.509575 4.692742 -4.455132 0.0513095 0.1365669 -0.3821793 0.9124998 +VERTEX_SE3:QUAT 2414 7.347469 4.799238 -4.555696 0.2402652 0.8793146 -0.2579457 0.3202225 +VERTEX_SE3:QUAT 2415 7.346614 4.828163 -4.474565 0.2131501 0.4852998 -0.3334359 0.7796612 +VERTEX_SE3:QUAT 2416 7.272217 4.833369 -4.461825 0.4443431 0.1607751 -0.8744079 0.1100973 +VERTEX_SE3:QUAT 2417 7.424189 4.840037 -4.396493 0.6167926 -0.1907275 0.6004031 0.4719174 +VERTEX_SE3:QUAT 2418 7.493052 4.769364 -4.333277 0.2564322 0.3061512 -0.8029611 0.4424561 +VERTEX_SE3:QUAT 2419 7.604575 4.833944 -4.245243 0.2634891 -0.2729934 0.6574035 0.6510520 +VERTEX_SE3:QUAT 2420 7.723843 4.954941 -4.218335 -0.3615040 0.9033117 -0.1353298 0.1871596 +VERTEX_SE3:QUAT 2421 7.810498 5.166455 -4.038114 0.1300248 -0.2993339 0.6924014 0.6434851 +VERTEX_SE3:QUAT 2422 7.751435 5.312359 -4.036175 0.3095960 0.7066227 0.2390096 0.5896685 +VERTEX_SE3:QUAT 2423 7.790890 5.443053 -3.916862 -0.2485037 0.2924265 -0.3377805 0.8594399 +VERTEX_SE3:QUAT 2424 7.914838 5.373710 -3.887289 -0.0676391 0.0001458 0.5471145 0.8343204 +VERTEX_SE3:QUAT 2425 8.073681 5.454426 -3.954451 -0.0897093 -0.8651694 0.4344008 0.2339445 +VERTEX_SE3:QUAT 2426 8.283550 5.386213 -4.018437 -0.7793196 -0.1088364 -0.6051317 0.1209594 +VERTEX_SE3:QUAT 2427 8.399156 5.405337 -3.934972 -0.5292427 0.5736795 -0.6091056 0.1406568 +VERTEX_SE3:QUAT 2428 8.316669 5.454086 -4.057806 -0.5126264 0.7329980 -0.2349004 0.3804601 +VERTEX_SE3:QUAT 2429 8.424085 5.685145 -4.179770 0.7859587 -0.2792280 -0.1228757 0.5377753 +VERTEX_SE3:QUAT 2430 8.411686 5.739318 -4.150328 -0.4895679 0.2020872 -0.7573842 0.3819073 +VERTEX_SE3:QUAT 2431 8.298930 5.774542 -4.084001 -0.0686854 0.3808425 -0.6303558 0.6729732 +VERTEX_SE3:QUAT 2432 8.336400 6.000585 -4.054031 0.0215440 -0.0078797 -0.9532959 0.3011654 +VERTEX_SE3:QUAT 2433 8.480006 6.106436 -4.134144 -0.0541661 -0.0459758 -0.9603700 0.2695212 +VERTEX_SE3:QUAT 2434 8.512099 5.993158 -4.307830 -0.1344933 0.2865545 -0.7942908 0.5185559 +VERTEX_SE3:QUAT 2435 8.678155 6.024490 -4.357332 -0.1603889 0.6222113 -0.6620822 0.3857145 +VERTEX_SE3:QUAT 2436 8.911745 6.174749 -4.295107 -0.4450505 0.6159021 -0.4293027 0.4881535 +VERTEX_SE3:QUAT 2437 8.908835 6.231041 -4.213240 0.5688337 -0.2049477 0.7899555 0.1019555 +VERTEX_SE3:QUAT 2438 8.993199 6.446231 -4.336313 -0.3792155 0.0031393 -0.7934071 0.4761206 +VERTEX_SE3:QUAT 2439 8.991726 6.490628 -4.291318 0.0755306 -0.5903729 0.2454460 0.7651871 +VERTEX_SE3:QUAT 2440 8.963115 6.575076 -4.248688 -0.3932896 0.4530176 -0.5456787 0.5850925 +VERTEX_SE3:QUAT 2441 8.919971 6.635837 -4.237820 -0.0641449 0.0893896 -0.9396674 0.3239137 +VERTEX_SE3:QUAT 2442 8.950888 6.766675 -4.157217 -0.1441057 -0.0261470 0.2424450 0.9590466 +VERTEX_SE3:QUAT 2443 8.917636 6.591846 -4.214480 0.0494474 -0.6111890 0.7221420 0.3201779 +VERTEX_SE3:QUAT 2444 8.887330 6.784125 -4.294532 -0.6918842 0.2249432 -0.6434922 0.2379382 +VERTEX_SE3:QUAT 2445 8.910682 6.880371 -4.271595 0.5099574 0.6776453 -0.2334844 0.4756315 +VERTEX_SE3:QUAT 2446 8.878666 6.897937 -4.277897 0.2426866 0.1262864 -0.7084769 0.6505500 +VERTEX_SE3:QUAT 2447 8.889882 6.954637 -4.351559 0.6100008 0.0005520 -0.0741151 0.7889269 +VERTEX_SE3:QUAT 2448 8.891080 7.137963 -4.359210 0.7141004 0.5826358 -0.2520660 0.2950575 +VERTEX_SE3:QUAT 2449 8.996690 7.198119 -4.360768 -0.4864685 0.0976574 -0.7808056 0.3796762 +VERTEX_SE3:QUAT 2450 8.866713 7.198062 -4.509283 0.5774083 0.4145142 -0.3929393 0.5834178 +VERTEX_SE3:QUAT 2451 8.763118 7.293415 -4.646763 0.4338570 -0.7793045 0.3357184 0.3028956 +VERTEX_SE3:QUAT 2452 8.893767 7.256159 -4.712480 -0.0570077 -0.0039829 -0.2206748 0.9736719 +VERTEX_SE3:QUAT 2453 8.904151 7.262331 -4.597375 0.5743192 -0.7211827 0.3681332 0.1205445 +VERTEX_SE3:QUAT 2454 8.875193 7.051312 -4.727357 -0.0685674 -0.5478871 0.7530329 0.3578542 +VERTEX_SE3:QUAT 2455 8.914744 7.047436 -4.819581 0.3013849 -0.6731975 0.2279916 0.6356038 +VERTEX_SE3:QUAT 2456 8.685663 7.083732 -4.915435 0.4056520 -0.3517028 0.8435958 0.0098839 +VERTEX_SE3:QUAT 2457 8.732806 7.020588 -4.939240 0.2440709 0.4581256 -0.7304199 0.4438886 +VERTEX_SE3:QUAT 2458 8.633484 6.832543 -5.186646 0.1303711 -0.1847094 -0.6671559 0.7097808 +VERTEX_SE3:QUAT 2459 8.502221 6.796522 -5.233005 0.1376283 0.0886197 0.7479778 0.6432217 +VERTEX_SE3:QUAT 2460 8.377765 7.045914 -5.183836 0.6751840 -0.5250983 0.4763691 0.2036440 +VERTEX_SE3:QUAT 2461 8.359568 6.902482 -5.126311 -0.5937909 -0.0725118 -0.6909905 0.4058159 +VERTEX_SE3:QUAT 2462 8.578166 6.845659 -4.959570 0.8247743 0.2618419 0.2537880 0.4321781 +VERTEX_SE3:QUAT 2463 8.410512 6.703792 -5.129948 0.1786177 -0.7026294 0.6375873 0.2605574 +VERTEX_SE3:QUAT 2464 8.330000 6.664041 -5.267708 -0.6321552 0.2635464 -0.7087352 0.1691673 +VERTEX_SE3:QUAT 2465 8.405516 6.694905 -5.283079 -0.0712441 -0.5740913 0.5419515 0.6096163 +VERTEX_SE3:QUAT 2466 8.402752 6.715773 -5.355037 0.2528270 0.0087176 -0.8023421 0.5406011 +VERTEX_SE3:QUAT 2467 8.415312 6.460610 -5.455829 0.2774520 -0.0964981 0.5669306 0.7696092 +VERTEX_SE3:QUAT 2468 8.461093 6.552859 -5.475664 0.0365751 -0.5250510 0.8493189 0.0405096 +VERTEX_SE3:QUAT 2469 8.290856 6.700570 -5.538868 0.3033342 0.7807446 -0.5037286 0.2113853 +VERTEX_SE3:QUAT 2470 8.323820 6.649355 -5.585793 0.3997842 0.4465966 -0.1596581 0.7843681 +VERTEX_SE3:QUAT 2471 8.179363 6.698697 -5.726485 0.2720760 0.2746172 0.9127032 0.1324121 +VERTEX_SE3:QUAT 2472 8.154089 6.648234 -5.601517 0.9347781 -0.2020482 0.2848908 0.0648356 +VERTEX_SE3:QUAT 2473 8.308581 6.703069 -5.677370 0.5942342 0.5700130 -0.0510264 0.5651258 +VERTEX_SE3:QUAT 2474 8.423432 6.585504 -5.717870 0.7427755 -0.1108152 0.2491882 0.6114817 +VERTEX_SE3:QUAT 2475 8.458205 6.572972 -5.842999 -0.1687247 -0.2323984 -0.9458076 0.1515614 +VERTEX_SE3:QUAT 2476 8.432099 6.414002 -5.866218 0.9587525 0.1274286 0.2386618 0.0871564 +VERTEX_SE3:QUAT 2477 8.517221 6.413729 -5.836930 -0.5374358 0.6252533 -0.1303745 0.5506574 +VERTEX_SE3:QUAT 2478 8.631936 6.375885 -5.806424 -0.3955808 -0.3103854 -0.8366167 0.2173689 +VERTEX_SE3:QUAT 2479 8.634749 6.168897 -5.700837 0.4169554 -0.0170631 0.7454907 0.5197120 +VERTEX_SE3:QUAT 2480 8.673087 6.121530 -5.615388 -0.5265683 0.5189793 -0.1653566 0.6527201 +VERTEX_SE3:QUAT 2481 8.699950 6.090933 -5.517432 0.7958167 0.1935822 0.2442976 0.5191535 +VERTEX_SE3:QUAT 2482 8.572839 6.073352 -5.545493 0.7246351 0.0964460 0.6169880 0.2914239 +VERTEX_SE3:QUAT 2483 8.473946 6.142196 -5.461548 -0.2549539 0.5526370 -0.6723353 0.4213740 +VERTEX_SE3:QUAT 2484 8.661860 6.053869 -5.400463 -0.3365727 -0.1698442 -0.9170004 0.1303150 +VERTEX_SE3:QUAT 2485 8.764258 5.828616 -5.351125 -0.0307608 0.6772899 -0.6938232 0.2427786 +VERTEX_SE3:QUAT 2486 8.706022 5.719518 -5.302052 0.7876412 0.0913248 -0.0817317 0.6038220 +VERTEX_SE3:QUAT 2487 8.789239 5.638749 -5.431778 0.0888926 0.4083889 -0.6984841 0.5808929 +VERTEX_SE3:QUAT 2488 8.961447 5.455159 -5.354530 -0.5768047 0.7434305 -0.2629949 0.2131691 +VERTEX_SE3:QUAT 2489 9.062637 5.418388 -5.280269 0.0270295 -0.9508880 0.3018849 0.0628240 +VERTEX_SE3:QUAT 2490 8.963788 5.302381 -5.360434 0.7030154 0.4761978 -0.4480466 0.2797485 +VERTEX_SE3:QUAT 2491 8.883617 5.410286 -5.387368 0.7335199 -0.6436607 0.0766838 0.2043750 +VERTEX_SE3:QUAT 2492 8.851723 5.366965 -5.324979 0.0732614 0.6118987 -0.7866580 0.0371751 +VERTEX_SE3:QUAT 2493 8.861737 5.366582 -5.182913 -0.0947963 0.7595654 -0.5850598 0.2679162 +VERTEX_SE3:QUAT 2494 9.053134 5.394760 -5.225558 0.0307242 0.1007409 -0.9817715 0.1582153 +VERTEX_SE3:QUAT 2495 9.122957 5.295790 -5.273126 0.1345189 0.7446881 -0.2364438 0.6094577 +VERTEX_SE3:QUAT 2496 9.192192 5.279936 -5.259167 0.6443526 0.0290130 -0.5920329 0.4831821 +VERTEX_SE3:QUAT 2497 9.364356 5.183382 -5.172055 0.6228524 -0.6092267 0.1963039 0.4498472 +VERTEX_SE3:QUAT 2498 9.374341 5.031045 -5.187926 0.6721625 0.1796000 -0.6372493 0.3314436 +VERTEX_SE3:QUAT 2499 9.464701 5.067896 -5.315490 -0.1079157 0.9239522 -0.3162707 0.1861167 +VERTEX_SE3:QUAT 2500 9.557204 5.057778 -5.381760 0.1945060 0.1124880 0.9689018 0.1036498 +VERTEX_SE3:QUAT 2501 9.646528 5.070605 -5.378673 0.5907704 0.4313772 0.2691318 0.6264759 +VERTEX_SE3:QUAT 2502 9.659997 4.995316 -5.399239 0.4538591 0.6935491 -0.2642448 0.4931291 +VERTEX_SE3:QUAT 2503 9.870923 4.936566 -5.442142 0.1517783 0.6931873 0.0575450 0.7022417 +VERTEX_SE3:QUAT 2504 9.839485 4.829911 -5.384543 0.2152111 0.5564753 -0.7910543 0.1351015 +VERTEX_SE3:QUAT 2505 10.041968 4.849486 -5.281118 0.5698272 -0.1375127 0.8032830 0.1054686 +VERTEX_SE3:QUAT 2506 10.198004 4.803126 -5.158193 0.8306516 0.1818031 0.4672619 0.2421403 +VERTEX_SE3:QUAT 2507 10.172993 4.764604 -5.154648 0.3480504 -0.1229358 0.8478122 0.3807390 +VERTEX_SE3:QUAT 2508 10.141430 4.895865 -5.140721 0.1369002 0.4991604 -0.7473176 0.4166697 +VERTEX_SE3:QUAT 2509 10.003391 5.004884 -4.989087 0.0384896 -0.1754758 0.1094156 0.9776272 +VERTEX_SE3:QUAT 2510 10.230607 4.867795 -4.938993 0.1677042 0.1097038 0.9233213 0.3275945 +VERTEX_SE3:QUAT 2511 10.316346 4.795866 -4.987224 -0.3109076 0.1231615 -0.2646231 0.9045122 +VERTEX_SE3:QUAT 2512 10.098146 4.789772 -5.040245 0.0553261 -0.4585838 0.8868988 0.0071078 +VERTEX_SE3:QUAT 2513 10.020495 4.697538 -5.057190 0.2243965 0.3441459 -0.3351746 0.8478607 +VERTEX_SE3:QUAT 2514 10.111651 4.715308 -5.046333 0.0036883 -0.5017688 0.7165258 0.4845671 +VERTEX_SE3:QUAT 2515 10.013643 4.796405 -5.048656 -0.1074081 0.4037855 -0.7165432 0.5585576 +VERTEX_SE3:QUAT 2516 10.249622 4.882257 -5.079679 0.1489554 -0.0322103 -0.4615272 0.8739379 +VERTEX_SE3:QUAT 2517 10.412341 4.903798 -5.054408 -0.4651843 0.6600013 -0.2350305 0.5410753 +VERTEX_SE3:QUAT 2518 10.573949 5.005900 -4.841460 0.4520049 -0.1284234 -0.4838727 0.7382860 +VERTEX_SE3:QUAT 2519 10.718430 4.964169 -4.856252 0.0848180 0.7238181 -0.6831760 0.0465158 +VERTEX_SE3:QUAT 2520 10.771081 4.951707 -4.711649 -0.0699938 0.5143563 0.0117490 0.8546347 +VERTEX_SE3:QUAT 2521 10.846969 5.013554 -4.646414 0.5106559 -0.2874534 0.3970865 0.7063451 +VERTEX_SE3:QUAT 2522 10.923765 5.045315 -4.556599 -0.0291530 0.0881246 -0.5066604 0.8571344 +VERTEX_SE3:QUAT 2523 10.948544 5.235392 -4.679131 -0.5650304 0.6766496 -0.4534089 0.1315534 +VERTEX_SE3:QUAT 2524 10.919901 5.353989 -4.646409 0.4056214 0.5157565 0.2210023 0.7215431 +VERTEX_SE3:QUAT 2525 10.858973 5.542522 -4.563268 -0.2393502 0.0876296 -0.6525156 0.7136217 +VERTEX_SE3:QUAT 2526 11.035526 5.597081 -4.424766 0.6017975 0.2997170 0.1850523 0.7167741 +VERTEX_SE3:QUAT 2527 10.999814 5.696969 -4.538802 0.4725169 0.3912617 0.4038762 0.6786207 +VERTEX_SE3:QUAT 2528 11.040995 5.777332 -4.706482 -0.5538095 0.5941457 -0.4577537 0.3615902 +VERTEX_SE3:QUAT 2529 10.989861 5.927289 -4.869213 0.6796687 0.4739565 0.3109083 0.4655660 +VERTEX_SE3:QUAT 2530 10.854515 6.025072 -4.977682 -0.6160892 -0.2251139 -0.7522796 0.0619136 +VERTEX_SE3:QUAT 2531 10.630848 6.112744 -5.054597 0.4067093 -0.1089265 -0.3467552 0.8381428 +VERTEX_SE3:QUAT 2532 10.508362 6.368572 -5.126997 0.2953535 -0.5678832 0.7007189 0.3150682 +VERTEX_SE3:QUAT 2533 10.299797 6.401448 -5.060726 -0.1325220 0.7205675 0.1424313 0.6655327 +VERTEX_SE3:QUAT 2534 10.261361 6.488166 -4.965415 0.1661439 0.0197749 -0.3543682 0.9200154 +VERTEX_SE3:QUAT 2535 10.101803 6.472107 -5.091078 0.0886513 0.2140982 -0.9727685 0.0049396 +VERTEX_SE3:QUAT 2536 10.041023 6.515479 -5.183349 0.5202406 -0.5051292 0.2603791 0.6374927 +VERTEX_SE3:QUAT 2537 10.068165 6.678923 -5.242273 0.0926492 0.4642990 -0.5664697 0.6745032 +VERTEX_SE3:QUAT 2538 10.050159 6.676607 -5.224416 0.2889959 0.1472717 0.8582311 0.3977837 +VERTEX_SE3:QUAT 2539 9.930881 6.864268 -5.092416 0.5745475 0.6272912 -0.3440797 0.3975047 +VERTEX_SE3:QUAT 2540 9.726891 6.891557 -5.056038 -0.0107132 0.4926127 -0.0585309 0.8682120 +VERTEX_SE3:QUAT 2541 9.670266 6.989450 -5.123304 -0.0961943 0.4838847 -0.1431169 0.8579742 +VERTEX_SE3:QUAT 2542 9.704075 6.957034 -5.168833 -0.1431323 -0.0205240 0.5812204 0.8007964 +VERTEX_SE3:QUAT 2543 9.628317 7.052685 -5.205814 0.8630157 0.2080011 0.0173692 0.4600410 +VERTEX_SE3:QUAT 2544 9.611392 7.012541 -5.310153 -0.0036744 0.4239660 0.0875976 0.9014244 +VERTEX_SE3:QUAT 2545 9.665003 7.115668 -5.406738 0.2330029 0.1677920 -0.5580433 0.7785519 +VERTEX_SE3:QUAT 2546 9.585523 7.101197 -5.359038 -0.5923329 0.7411541 -0.2117094 0.2345452 +VERTEX_SE3:QUAT 2547 9.626169 7.061891 -5.492164 0.2643149 0.2444298 0.6717732 0.6473890 +VERTEX_SE3:QUAT 2548 9.513655 7.057765 -5.816444 0.3958829 -0.2180366 0.8920406 0.0005039 +VERTEX_SE3:QUAT 2549 9.539393 7.237853 -5.895211 -0.6705741 0.6624346 -0.3127371 0.1170737 +VERTEX_SE3:QUAT 2550 9.366385 7.298365 -5.805158 0.5892625 0.6402734 0.1161154 0.4788913 +VERTEX_SE3:QUAT 2551 9.266192 7.196688 -5.836035 0.3628606 -0.5394107 0.6874759 0.3236434 +VERTEX_SE3:QUAT 2552 9.215520 7.200488 -5.843429 0.6615451 0.0165626 -0.4129682 0.6257324 +VERTEX_SE3:QUAT 2553 9.132312 7.294245 -5.806911 -0.0320821 0.3260258 0.0586655 0.9429932 +VERTEX_SE3:QUAT 2554 8.966214 7.321891 -5.760219 0.5611477 0.5107045 0.5939902 0.2673385 +VERTEX_SE3:QUAT 2555 8.871054 7.299737 -5.645026 -0.1539261 0.7937152 -0.2647727 0.5255648 +VERTEX_SE3:QUAT 2556 8.777057 7.289239 -5.730348 0.7648350 -0.1988391 0.4741283 0.3881917 +VERTEX_SE3:QUAT 2557 8.678009 7.170022 -5.663629 0.8149720 0.0021020 -0.1543741 0.5585560 +VERTEX_SE3:QUAT 2558 8.588673 7.135783 -5.800699 0.8062423 -0.1499750 0.5722371 0.0050513 +VERTEX_SE3:QUAT 2559 8.666978 7.308031 -6.008231 0.1466751 0.1237478 -0.1629655 0.9677888 +VERTEX_SE3:QUAT 2560 8.535981 7.426903 -5.985174 0.4180898 -0.7590729 0.3478625 0.3577721 +VERTEX_SE3:QUAT 2561 8.461316 7.557008 -6.015043 0.0624965 0.8063019 -0.1314224 0.5733232 +VERTEX_SE3:QUAT 2562 8.420135 7.367274 -6.113512 0.5475089 -0.4154560 0.6709799 0.2782379 +VERTEX_SE3:QUAT 2563 8.419587 7.359098 -6.101843 0.2632753 -0.6887957 0.1862193 0.6492834 +VERTEX_SE3:QUAT 2564 8.374186 7.269083 -6.328180 0.6101991 -0.6927823 0.3700322 0.1038550 +VERTEX_SE3:QUAT 2565 8.419319 7.295365 -6.433032 0.3714235 -0.4580583 0.7955089 0.1392582 +VERTEX_SE3:QUAT 2566 8.442261 7.397174 -6.600982 0.6262973 0.3850388 -0.0053571 0.6778408 +VERTEX_SE3:QUAT 2567 8.311020 7.289237 -6.719163 0.1614778 0.1368727 0.5173979 0.8291503 +VERTEX_SE3:QUAT 2568 8.254830 7.121539 -6.884479 0.4174695 -0.6829905 0.5937215 0.0820854 +VERTEX_SE3:QUAT 2569 8.057713 7.002607 -7.053333 0.5122125 -0.5548737 0.6098963 0.2403747 +VERTEX_SE3:QUAT 2570 7.983529 6.954428 -7.139451 -0.3023453 0.2658180 -0.8992386 0.1711669 +VERTEX_SE3:QUAT 2571 7.915186 6.880892 -7.322910 -0.0122445 -0.6742587 0.6805550 0.2864789 +VERTEX_SE3:QUAT 2572 7.823651 6.709591 -7.256989 0.5531543 0.4185993 -0.5605981 0.4522442 +VERTEX_SE3:QUAT 2573 7.789284 6.640099 -7.164994 0.1559907 -0.0097662 -0.6203519 0.7685929 +VERTEX_SE3:QUAT 2574 7.821085 6.582478 -7.190633 -0.0289725 -0.3667057 0.9257480 0.0876252 +VERTEX_SE3:QUAT 2575 7.640137 6.606415 -7.316769 -0.4818039 0.0740774 -0.6916838 0.5328706 +VERTEX_SE3:QUAT 2576 7.529872 6.562623 -7.295817 -0.0450357 0.8269617 -0.3537907 0.4346702 +VERTEX_SE3:QUAT 2577 7.598542 6.607205 -7.224310 0.3335235 0.8367197 0.0314941 0.4332093 +VERTEX_SE3:QUAT 2578 7.609047 6.633712 -7.368690 -0.4187806 0.4904006 -0.5322184 0.5485195 +VERTEX_SE3:QUAT 2579 7.745155 6.608260 -7.506333 0.3605654 0.0927761 0.5537891 0.7447838 +VERTEX_SE3:QUAT 2580 7.817345 6.669361 -7.559205 -0.0299370 0.1530064 -0.2360717 0.9591470 +VERTEX_SE3:QUAT 2581 7.767074 6.503958 -7.590107 -0.0946290 0.8805078 -0.1758528 0.4299153 +VERTEX_SE3:QUAT 2582 7.839739 6.451079 -7.663669 -0.0111360 0.7000370 -0.3105291 0.6429587 +VERTEX_SE3:QUAT 2583 7.647462 6.524784 -7.659519 -0.5333602 0.2964555 -0.7041004 0.3631579 +VERTEX_SE3:QUAT 2584 7.786258 6.599302 -7.579546 -0.0544403 -0.8142857 0.5766273 0.0384201 +VERTEX_SE3:QUAT 2585 7.896979 6.569456 -7.713302 -0.3501253 0.1334365 -0.7558168 0.5369804 +VERTEX_SE3:QUAT 2586 8.037070 6.439475 -7.724339 0.6612095 -0.1732996 0.7192790 0.1241245 +VERTEX_SE3:QUAT 2587 7.917050 6.497795 -7.835668 0.8169522 -0.1229348 -0.0452221 0.5616325 +VERTEX_SE3:QUAT 2588 8.038761 6.545994 -7.826831 0.4465806 -0.5319473 0.2943582 0.6564686 +VERTEX_SE3:QUAT 2589 7.994956 6.490648 -7.681272 0.0985971 -0.8294592 0.5190577 0.1812598 +VERTEX_SE3:QUAT 2590 7.919322 6.587152 -7.702798 0.3239617 -0.3100733 -0.1135740 0.8865688 +VERTEX_SE3:QUAT 2591 7.915367 6.495397 -7.581706 0.5882157 0.0887748 -0.2747979 0.7553856 +VERTEX_SE3:QUAT 2592 7.830778 6.274056 -7.583222 0.0473816 -0.1141190 0.0897058 0.9882736 +VERTEX_SE3:QUAT 2593 7.897683 6.419238 -7.506974 0.1646511 -0.0429689 0.8754522 0.4523573 +VERTEX_SE3:QUAT 2594 7.887735 6.455320 -7.489357 0.0828796 -0.5928983 0.6328968 0.4909626 +VERTEX_SE3:QUAT 2595 7.927531 6.339005 -7.453875 0.1645232 -0.0946864 0.1111309 0.9755084 +VERTEX_SE3:QUAT 2596 8.029185 6.320438 -7.512765 0.2240927 0.1675141 -0.9595018 0.0328295 +VERTEX_SE3:QUAT 2597 7.824663 6.240724 -7.519668 0.5226959 -0.7715845 0.3329272 0.1435471 +VERTEX_SE3:QUAT 2598 7.995667 6.065228 -7.483453 0.5706591 0.6840952 0.1056564 0.4418128 +VERTEX_SE3:QUAT 2599 7.929341 6.066762 -7.431613 0.8150601 -0.1840228 0.3599858 0.4149975 +VERTEX_SE3:QUAT 2600 8.039434 6.063308 -7.452314 0.3643533 -0.0330166 -0.6472081 0.6687887 +VERTEX_SE3:QUAT 2601 8.168865 5.906514 -7.356991 0.8306480 0.2976772 0.1746878 0.4369169 +VERTEX_SE3:QUAT 2602 8.308652 6.037163 -7.421827 0.2746673 0.2540548 -0.7628113 0.5273831 +VERTEX_SE3:QUAT 2603 8.298213 6.078211 -7.425665 0.2815922 0.4698914 -0.8178883 0.1759736 +VERTEX_SE3:QUAT 2604 8.357348 6.069035 -7.361761 -0.5554096 0.0237021 -0.6443444 0.5251463 +VERTEX_SE3:QUAT 2605 8.574992 6.146699 -7.377488 0.2051540 0.1616435 0.8635616 0.4313288 +VERTEX_SE3:QUAT 2606 8.558848 6.269886 -7.340224 -0.2064819 0.3164986 -0.8543035 0.3568744 +VERTEX_SE3:QUAT 2607 8.619890 6.173789 -7.220249 0.4571651 -0.1849679 0.4092685 0.7676498 +VERTEX_SE3:QUAT 2608 8.644527 6.158718 -7.118348 -0.1970264 0.0899013 0.2795267 0.9353947 +VERTEX_SE3:QUAT 2609 8.721137 6.060827 -7.030962 0.7131824 -0.1453967 0.0037775 0.6857233 +VERTEX_SE3:QUAT 2610 8.619732 6.249443 -6.918643 0.4726439 0.4095714 -0.6456657 0.4381492 +VERTEX_SE3:QUAT 2611 8.700196 6.226614 -6.853211 0.6224618 -0.2340918 0.6485339 0.3703324 +VERTEX_SE3:QUAT 2612 8.838754 6.213318 -6.641043 0.8366338 0.2869413 0.2761424 0.3761037 +VERTEX_SE3:QUAT 2613 8.797000 6.323279 -6.829633 -0.1107289 0.2167368 -0.8252006 0.5097139 +VERTEX_SE3:QUAT 2614 9.036746 6.503965 -6.807470 0.3340919 0.0841228 -0.7796089 0.5229875 +VERTEX_SE3:QUAT 2615 8.821853 6.655289 -6.810944 -0.5290534 0.3576470 -0.5595759 0.5282669 +VERTEX_SE3:QUAT 2616 8.884423 6.634402 -6.737463 0.4674390 -0.6569716 0.3925274 0.4425057 +VERTEX_SE3:QUAT 2617 9.190762 6.588915 -6.699753 -0.4910536 -0.2458985 -0.8350398 0.0332986 +VERTEX_SE3:QUAT 2618 9.291428 6.698152 -6.661223 0.1585145 -0.1073443 0.5424133 0.8180086 +VERTEX_SE3:QUAT 2619 9.187310 6.672442 -6.631493 0.0543668 0.8113212 -0.3924845 0.4298350 +VERTEX_SE3:QUAT 2620 9.253856 6.800634 -6.762520 -0.7933907 0.3200390 -0.5169438 0.0295865 +VERTEX_SE3:QUAT 2621 9.229412 6.753930 -6.860324 0.4989197 -0.5574971 0.5928725 0.2979568 +VERTEX_SE3:QUAT 2622 9.160399 6.782104 -6.648316 -0.7620806 0.0979368 -0.6087211 0.1977376 +VERTEX_SE3:QUAT 2623 9.104567 6.762492 -6.595229 0.6945845 0.2969339 0.4842329 0.4414761 +VERTEX_SE3:QUAT 2624 9.089145 6.780489 -6.320462 -0.1474787 0.4769964 0.0427641 0.8653876 +VERTEX_SE3:QUAT 2625 9.030232 6.822619 -6.103368 0.1027970 0.3292368 -0.9147745 0.2102940 +VERTEX_SE3:QUAT 2626 8.840239 6.782994 -6.036636 -0.2649892 0.6150956 -0.3957121 0.6283710 +VERTEX_SE3:QUAT 2627 8.834592 6.882201 -6.000278 0.6356224 -0.5078648 0.5666395 0.1302968 +VERTEX_SE3:QUAT 2628 8.771088 6.907478 -5.852139 0.6657374 0.1703254 0.6724314 0.2749890 +VERTEX_SE3:QUAT 2629 8.760314 6.922061 -5.811405 0.6735956 -0.2281842 0.6685835 0.2172485 +VERTEX_SE3:QUAT 2630 8.806814 7.036319 -5.726356 -0.1905473 -0.0594397 -0.9346759 0.2941761 +VERTEX_SE3:QUAT 2631 8.854647 6.953838 -5.689395 0.6398198 0.4727690 0.4985601 0.3443223 +VERTEX_SE3:QUAT 2632 8.712257 7.160764 -5.593126 -0.5112970 -0.3548129 0.7768123 0.0961555 +VERTEX_SE3:QUAT 2633 8.731228 7.256853 -5.594412 -0.0472505 0.4174158 -0.6912219 0.5879997 +VERTEX_SE3:QUAT 2634 8.858320 7.303106 -5.425855 0.6952343 0.5495933 -0.4436085 0.1334466 +VERTEX_SE3:QUAT 2635 8.897763 7.375729 -5.414283 0.9531286 -0.0413153 0.0177209 0.2992072 +VERTEX_SE3:QUAT 2636 8.945430 7.543967 -5.386535 0.0150739 0.7268781 0.1552899 0.6688094 +VERTEX_SE3:QUAT 2637 8.959036 7.665103 -5.312703 0.4479211 -0.7670659 0.4402728 0.1309063 +VERTEX_SE3:QUAT 2638 9.041683 7.720867 -5.114942 0.0898512 -0.1557604 0.6560293 0.7330014 +VERTEX_SE3:QUAT 2639 8.979381 7.849392 -4.944674 0.6897111 0.0749784 0.4158632 0.5879921 +VERTEX_SE3:QUAT 2640 8.989617 8.049296 -5.090367 0.4823707 -0.5328030 0.3174076 0.6186210 +VERTEX_SE3:QUAT 2641 8.762565 8.112055 -5.099644 -0.1692368 -0.3428699 0.8478646 0.3673210 +VERTEX_SE3:QUAT 2642 8.755430 8.312600 -4.985698 0.7587462 0.3320531 -0.2122097 0.5186637 +VERTEX_SE3:QUAT 2643 8.796899 8.552163 -5.125317 -0.1996127 -0.4697269 0.4339757 0.7424126 +VERTEX_SE3:QUAT 2644 8.815860 8.779148 -5.216823 0.0682525 -0.4483744 0.7864246 0.4193309 +VERTEX_SE3:QUAT 2645 8.640177 8.684830 -5.147666 -0.6313149 -0.1098772 0.7673197 0.0242692 +VERTEX_SE3:QUAT 2646 8.603457 8.864673 -5.005474 0.8468605 0.2680731 0.2736405 0.3688971 +VERTEX_SE3:QUAT 2647 8.529693 9.058336 -5.084227 0.0832299 -0.3776280 0.8830862 0.2657606 +VERTEX_SE3:QUAT 2648 8.633218 9.147352 -4.757935 0.4210557 0.3236607 -0.1679397 0.8305131 +VERTEX_SE3:QUAT 2649 8.664956 9.115980 -4.745309 -0.9019623 0.3496794 -0.2283217 0.1098066 +VERTEX_SE3:QUAT 2650 8.609863 8.935389 -4.847714 0.2577829 0.1882916 0.8715491 0.3721510 +VERTEX_SE3:QUAT 2651 8.662275 8.966484 -4.954956 0.4165783 -0.8723633 0.0760840 0.2442459 +VERTEX_SE3:QUAT 2652 8.514642 8.989321 -4.986568 0.4572728 -0.8875825 -0.0095837 0.0548358 +VERTEX_SE3:QUAT 2653 8.549015 9.114088 -5.021488 0.6889402 -0.6223032 0.0796192 0.3629889 +VERTEX_SE3:QUAT 2654 8.670256 9.147332 -5.115391 0.3447869 0.7835899 -0.2171741 0.4689821 +VERTEX_SE3:QUAT 2655 8.656194 9.244491 -5.054702 0.6127356 0.6923826 -0.0186223 0.3805452 +VERTEX_SE3:QUAT 2656 8.714326 9.362482 -5.171666 0.3080923 -0.6035107 -0.1490807 0.7201589 +VERTEX_SE3:QUAT 2657 8.849030 9.390785 -5.085727 0.9715734 -0.0324349 0.1627663 0.1688203 +VERTEX_SE3:QUAT 2658 8.925513 9.438292 -5.067607 0.4162902 0.0862765 0.4570677 0.7812477 +VERTEX_SE3:QUAT 2659 8.940972 9.393293 -5.203859 0.5766926 -0.7209515 0.3454809 0.1682187 +VERTEX_SE3:QUAT 2660 8.800477 9.505521 -5.298216 0.3012189 -0.6070723 -0.3437098 0.6500722 +VERTEX_SE3:QUAT 2661 8.793697 9.577707 -5.297028 0.7733989 -0.4026700 0.0848424 0.4821957 +VERTEX_SE3:QUAT 2662 9.018672 9.598012 -5.122691 0.7191801 -0.0321737 -0.4125121 0.5581923 +VERTEX_SE3:QUAT 2663 9.100934 9.792501 -5.367992 -0.0746217 0.6007945 -0.6336871 0.4815788 +VERTEX_SE3:QUAT 2664 9.243458 9.860537 -5.562673 -0.8407201 0.4353456 -0.3202466 0.0332582 +VERTEX_SE3:QUAT 2665 9.189981 9.897881 -5.730153 0.1755257 0.2919210 -0.6700211 0.6595792 +VERTEX_SE3:QUAT 2666 9.163061 9.834276 -5.862019 0.4998139 -0.0418645 0.2503481 0.8281058 +VERTEX_SE3:QUAT 2667 9.243156 9.908245 -6.022669 0.1256202 -0.5653409 -0.1090635 0.8079074 +VERTEX_SE3:QUAT 2668 9.399574 9.969484 -6.118050 0.0764337 -0.8286833 -0.0581540 0.5514164 +VERTEX_SE3:QUAT 2669 9.499713 9.919821 -6.080696 -0.3271801 0.0342972 -0.9261330 0.1845390 +VERTEX_SE3:QUAT 2670 9.711672 10.015732 -6.120695 -0.0324625 -0.7033784 0.2603350 0.6606290 +VERTEX_SE3:QUAT 2671 9.766292 10.035096 -6.176955 0.8397766 -0.5288119 0.0840799 0.0897990 +VERTEX_SE3:QUAT 2672 9.883499 10.087146 -6.192544 0.7751785 0.4929788 -0.3737550 0.1279744 +VERTEX_SE3:QUAT 2673 9.966304 10.165953 -6.311919 0.9107470 -0.1724713 0.1493913 0.3442030 +VERTEX_SE3:QUAT 2674 9.914023 10.089881 -6.352914 -0.0360146 -0.5149426 0.2395931 0.8222726 +VERTEX_SE3:QUAT 2675 9.954089 10.065156 -6.410644 -0.3429633 0.7138683 -0.5734709 0.2095217 +VERTEX_SE3:QUAT 2676 10.026750 9.917262 -6.584746 0.1217393 -0.8359549 0.5304586 0.0705169 +VERTEX_SE3:QUAT 2677 10.035717 9.729913 -6.729286 -0.0111286 -0.6623926 -0.1716493 0.7291424 +VERTEX_SE3:QUAT 2678 10.160397 9.730631 -6.711867 0.2325677 -0.1086089 0.3744802 0.8910000 +VERTEX_SE3:QUAT 2679 10.167032 9.722824 -6.698646 0.2555329 -0.5018867 0.0785039 0.8225873 +VERTEX_SE3:QUAT 2680 10.246801 9.642459 -6.912309 0.2590121 -0.3319849 0.4166420 0.8056725 +VERTEX_SE3:QUAT 2681 10.203063 9.727000 -7.079946 0.2643904 0.3953658 -0.3415787 0.8106217 +VERTEX_SE3:QUAT 2682 10.222085 9.580545 -7.135441 0.3936518 -0.1274947 0.5416134 0.7317365 +VERTEX_SE3:QUAT 2683 10.304405 9.438632 -7.160455 0.4742560 -0.2645547 -0.4158492 0.7294940 +VERTEX_SE3:QUAT 2684 10.362377 9.477839 -7.227642 0.7116927 0.3838061 -0.2737447 0.5208169 +VERTEX_SE3:QUAT 2685 10.316759 9.341931 -7.245488 0.0982486 -0.7643238 0.6277163 0.1101303 +VERTEX_SE3:QUAT 2686 10.316547 9.237901 -7.315549 0.5778818 -0.0324989 0.2029029 0.7898271 +VERTEX_SE3:QUAT 2687 10.256231 9.421410 -7.222839 0.5469686 0.3838773 0.2564382 0.6983574 +VERTEX_SE3:QUAT 2688 10.229161 9.372868 -7.162304 0.6986379 0.4582314 -0.2664723 0.4805431 +VERTEX_SE3:QUAT 2689 10.226391 9.294482 -7.263586 0.7928636 0.1742389 0.1580893 0.5621529 +VERTEX_SE3:QUAT 2690 10.082361 9.401565 -7.198269 0.7122007 -0.2526041 0.2836640 0.5903356 +VERTEX_SE3:QUAT 2691 10.209077 9.302265 -7.307839 0.1804617 0.1866509 -0.9303662 0.2588701 +VERTEX_SE3:QUAT 2692 10.346750 9.189049 -7.372497 -0.6932848 0.5141667 -0.4671377 0.1917580 +VERTEX_SE3:QUAT 2693 10.353037 9.134853 -7.402039 0.0792852 0.6837495 -0.5882182 0.4244996 +VERTEX_SE3:QUAT 2694 10.459196 9.070619 -7.561878 0.7208304 0.3623454 0.1819409 0.5621448 +VERTEX_SE3:QUAT 2695 10.512677 8.865490 -7.662066 0.3225977 -0.2991334 -0.0525126 0.8964889 +VERTEX_SE3:QUAT 2696 10.617936 8.902982 -7.798110 0.3915649 0.4290068 -0.2915842 0.7600058 +VERTEX_SE3:QUAT 2697 10.697543 8.948522 -7.759977 -0.4147534 0.4131750 -0.8051193 0.0951261 +VERTEX_SE3:QUAT 2698 10.731887 8.981850 -7.920294 0.2680691 0.9512901 -0.1270409 0.0839442 +VERTEX_SE3:QUAT 2699 10.849544 9.044870 -7.953861 0.2882044 -0.8226294 0.4364905 0.2229242 +VERTEX_SE3:QUAT 2700 10.754480 8.982586 -8.021943 0.7359335 0.0012720 -0.6218509 0.2677716 +VERTEX_SE3:QUAT 2701 10.689392 8.926920 -8.044313 0.7204640 -0.6293224 0.2485095 0.1520786 +VERTEX_SE3:QUAT 2702 10.583303 8.837156 -8.172890 0.6568853 0.3361266 0.0844988 0.6696123 +VERTEX_SE3:QUAT 2703 10.614137 8.614829 -8.276784 0.0515987 -0.5516975 -0.0494962 0.8309739 +VERTEX_SE3:QUAT 2704 10.520260 8.454120 -8.308968 0.1725680 -0.6105580 -0.2798806 0.7204901 +VERTEX_SE3:QUAT 2705 10.500452 8.392196 -8.345785 0.1009553 -0.2165293 0.7122214 0.6600483 +VERTEX_SE3:QUAT 2706 10.391895 8.299184 -8.347779 0.4950822 -0.7817310 0.3280160 0.1902521 +VERTEX_SE3:QUAT 2707 10.539884 8.255892 -8.237436 0.1199737 -0.8040271 0.4622942 0.3541620 +VERTEX_SE3:QUAT 2708 10.518138 8.212250 -8.153388 0.4056165 -0.6382078 0.6515400 0.0605115 +VERTEX_SE3:QUAT 2709 10.496447 8.033626 -8.210001 0.1876351 0.9319354 -0.2578018 0.1727067 +VERTEX_SE3:QUAT 2710 10.404995 8.272538 -8.139917 0.0988725 0.5875736 -0.7400325 0.3119830 +VERTEX_SE3:QUAT 2711 10.339733 8.141914 -8.111800 -0.4168412 -0.8322836 0.1749979 0.3208164 +VERTEX_SE3:QUAT 2712 10.253963 8.077787 -7.969156 -0.3714769 -0.7177746 0.5223033 0.2720364 +VERTEX_SE3:QUAT 2713 10.261059 8.027150 -7.888007 0.2024812 0.5000077 -0.1892779 0.8204679 +VERTEX_SE3:QUAT 2714 10.151094 7.894388 -7.641249 0.3668807 -0.9252257 0.0711111 0.0655686 +VERTEX_SE3:QUAT 2715 10.197346 7.818722 -7.582317 0.7752019 0.3170832 -0.5460712 0.0180675 +VERTEX_SE3:QUAT 2716 10.231014 7.917942 -7.418261 0.2411996 -0.0278866 0.4387411 0.8651886 +VERTEX_SE3:QUAT 2717 10.238883 7.990887 -7.244720 -0.0072549 0.7591981 -0.3282715 0.5619639 +VERTEX_SE3:QUAT 2718 10.193679 7.974950 -7.261858 0.1496534 -0.0883711 0.7637233 0.6217082 +VERTEX_SE3:QUAT 2719 10.077222 7.777093 -7.242669 0.0162225 -0.9186954 0.0472035 0.3918003 +VERTEX_SE3:QUAT 2720 10.118187 7.860708 -7.032995 0.8451775 -0.3718231 -0.0431186 0.3815276 +VERTEX_SE3:QUAT 2721 10.072259 7.885193 -7.021542 0.5766763 -0.3708979 0.4665863 0.5587275 +VERTEX_SE3:QUAT 2722 10.008464 8.000993 -6.866235 -0.1454201 0.5336940 -0.6411735 0.5319025 +VERTEX_SE3:QUAT 2723 9.885005 7.830037 -6.850090 0.4729817 -0.0359993 0.8521609 0.2209392 +VERTEX_SE3:QUAT 2724 9.894259 7.894169 -6.667209 -0.1129474 0.7284339 -0.6755701 0.0152286 +VERTEX_SE3:QUAT 2725 9.855531 7.767056 -6.638524 -0.3694269 -0.3883455 0.7968550 0.2788075 +VERTEX_SE3:QUAT 2726 9.821646 7.734459 -6.570097 0.8763153 -0.3694318 0.2929985 0.0987089 +VERTEX_SE3:QUAT 2727 9.741353 7.577465 -6.643174 -0.3517302 0.7729532 -0.3497152 0.3956368 +VERTEX_SE3:QUAT 2728 9.630532 7.552131 -6.392089 0.5486376 0.3668573 -0.7479146 0.0709666 +VERTEX_SE3:QUAT 2729 9.736270 7.558615 -6.127633 0.8934401 -0.0981261 -0.0143223 0.4380993 +VERTEX_SE3:QUAT 2730 9.734788 7.666743 -5.986276 -0.4462339 -0.4635449 0.7627685 0.0646967 +VERTEX_SE3:QUAT 2731 9.670861 7.615979 -5.882265 -0.3199109 -0.4277841 0.7758660 0.3356930 +VERTEX_SE3:QUAT 2732 9.744748 7.666659 -5.774393 0.0262251 -0.4107218 0.0252886 0.9110326 +VERTEX_SE3:QUAT 2733 9.803729 7.639143 -5.788282 0.3615042 0.0044466 -0.0273088 0.9319599 +VERTEX_SE3:QUAT 2734 9.828683 7.718158 -5.752482 -0.3423205 0.5769809 -0.7341864 0.1043074 +VERTEX_SE3:QUAT 2735 9.845956 7.744003 -5.643877 0.3763191 0.6939243 0.1824659 0.5861392 +VERTEX_SE3:QUAT 2736 9.814109 7.845040 -5.535431 -0.3602030 0.7086059 -0.5774956 0.1860922 +VERTEX_SE3:QUAT 2737 9.783528 7.902642 -5.556838 0.3544389 -0.6993593 0.1550932 0.6010122 +VERTEX_SE3:QUAT 2738 9.752351 7.990698 -5.352635 0.5492155 0.0929872 0.2299621 0.7980182 +VERTEX_SE3:QUAT 2739 9.762959 8.210622 -5.174926 -0.0068204 -0.1986058 0.8222338 0.5333299 +VERTEX_SE3:QUAT 2740 9.609809 8.337819 -5.037789 0.3113566 -0.6714830 -0.0593624 0.6698088 +VERTEX_SE3:QUAT 2741 9.617492 8.368455 -4.986660 0.4661026 0.3317224 -0.7129121 0.4055427 +VERTEX_SE3:QUAT 2742 9.621994 8.708684 -4.976443 0.6618357 0.1470114 0.3958404 0.6194123 +VERTEX_SE3:QUAT 2743 9.644078 8.733034 -5.053761 -0.2458490 0.6846241 -0.6494087 0.2216224 +VERTEX_SE3:QUAT 2744 9.590974 8.812060 -5.048273 0.7032574 -0.2650827 0.6456337 0.1353416 +VERTEX_SE3:QUAT 2745 9.696970 8.868291 -5.016075 0.0912176 0.5160815 -0.6395043 0.5624709 +VERTEX_SE3:QUAT 2746 9.535057 8.948795 -5.004757 -0.3358848 0.6495452 -0.6565148 0.1850965 +VERTEX_SE3:QUAT 2747 9.733817 9.165691 -4.956407 0.6378513 -0.0991542 0.4706779 0.6014785 +VERTEX_SE3:QUAT 2748 9.663999 9.109285 -4.930572 0.6765876 -0.0879357 0.5899021 0.4318705 +VERTEX_SE3:QUAT 2749 9.696056 9.124456 -4.928028 0.3998645 -0.6569044 0.6253913 0.1321772 +VERTEX_SE3:QUAT 2750 9.670093 9.040852 -5.044721 0.4406798 0.2398354 -0.7224189 0.4758058 +VERTEX_SE3:QUAT 2751 9.562686 8.934385 -4.850922 0.7607060 -0.6026690 -0.0008870 0.2410719 +VERTEX_SE3:QUAT 2752 9.770488 8.897476 -4.830796 0.7292341 -0.2452843 0.6229828 0.1412292 +VERTEX_SE3:QUAT 2753 9.912328 8.851563 -4.895861 0.2323097 0.1870391 -0.4352407 0.8494788 +VERTEX_SE3:QUAT 2754 9.882949 8.953867 -5.014670 0.1819501 0.7193181 -0.2848437 0.6069100 +VERTEX_SE3:QUAT 2755 9.725704 9.020013 -5.174148 0.9179672 0.1930395 -0.0118343 0.3463119 +VERTEX_SE3:QUAT 2756 9.698783 8.917507 -5.209906 0.1588065 -0.0743165 -0.2627455 0.9488005 +VERTEX_SE3:QUAT 2757 9.859297 8.820282 -5.259442 -0.4032430 -0.8961460 0.1623892 0.0891467 +VERTEX_SE3:QUAT 2758 9.733723 8.816921 -5.184527 -0.7207231 -0.1886826 0.6534198 0.1341629 +VERTEX_SE3:QUAT 2759 9.750618 8.786877 -5.331028 0.8038736 -0.5587498 0.0921778 0.1819042 +VERTEX_SE3:QUAT 2760 9.983187 8.722519 -5.416772 0.2416647 0.6938692 -0.1837427 0.6529796 +VERTEX_SE3:QUAT 2761 10.048179 8.819701 -5.528033 -0.1423043 -0.8499514 0.3903917 0.3239234 +VERTEX_SE3:QUAT 2762 10.066024 8.961033 -5.624754 0.1654598 -0.9005652 0.3575291 0.1837887 +VERTEX_SE3:QUAT 2763 10.110174 8.886900 -5.862862 0.5079959 0.0371696 -0.8431537 0.1721929 +VERTEX_SE3:QUAT 2764 10.042005 8.941035 -5.889058 0.9614894 0.2016226 -0.1816333 0.0435414 +VERTEX_SE3:QUAT 2765 9.993399 9.053891 -5.867665 0.2106838 0.2467455 0.1209444 0.9381372 +VERTEX_SE3:QUAT 2766 10.038875 8.998354 -5.977730 -0.0426429 -0.0213146 -0.5907870 0.8054179 +VERTEX_SE3:QUAT 2767 10.122320 8.911151 -5.816154 0.2037762 -0.5856679 0.7739612 0.1282668 +VERTEX_SE3:QUAT 2768 10.111142 8.988306 -6.047520 0.0714959 0.0139373 -0.5035232 0.8609056 +VERTEX_SE3:QUAT 2769 10.085654 8.962241 -5.905054 0.1316050 -0.2872659 -0.3459096 0.8834619 +VERTEX_SE3:QUAT 2770 9.756652 9.030055 -5.803129 0.0426657 0.4883864 -0.5321746 0.6902526 +VERTEX_SE3:QUAT 2771 9.643441 9.129025 -5.861786 0.1313018 0.4060787 0.1370552 0.8939104 +VERTEX_SE3:QUAT 2772 9.695457 9.231467 -5.908497 0.3629642 0.7075232 -0.4936825 0.3520589 +VERTEX_SE3:QUAT 2773 9.733472 9.310087 -5.836276 -0.3484727 0.7236879 -0.4204393 0.4219874 +VERTEX_SE3:QUAT 2774 9.742798 9.137983 -5.874440 0.5393264 -0.4170356 -0.1079811 0.7235665 +VERTEX_SE3:QUAT 2775 9.591012 9.308106 -6.032500 0.3158732 -0.6138489 0.7227216 0.0329715 +VERTEX_SE3:QUAT 2776 9.688851 9.234452 -6.169278 0.7746769 -0.1004176 -0.5721339 0.2499096 +VERTEX_SE3:QUAT 2777 9.673748 9.119484 -6.447992 0.0428875 0.2869036 -0.9375096 0.1921528 +VERTEX_SE3:QUAT 2778 9.531287 9.084157 -6.435595 0.2840781 0.6968976 0.0549284 0.6562135 +VERTEX_SE3:QUAT 2779 9.540010 9.251157 -6.389474 0.6728709 0.2018825 -0.6850711 0.1927844 +VERTEX_SE3:QUAT 2780 9.373787 9.078482 -6.553941 0.1763729 -0.4490403 -0.2543243 0.8381972 +VERTEX_SE3:QUAT 2781 9.177026 8.978941 -6.576398 -0.2485911 -0.1977199 0.8535612 0.4129681 +VERTEX_SE3:QUAT 2782 9.163812 8.804362 -6.782856 0.2596321 0.4897955 -0.0684554 0.8294609 +VERTEX_SE3:QUAT 2783 9.368581 8.813222 -6.831823 0.3241453 0.6215970 -0.2307111 0.6747736 +VERTEX_SE3:QUAT 2784 9.387899 8.785029 -6.915334 -0.0853625 -0.6207139 0.2641373 0.7332523 +VERTEX_SE3:QUAT 2785 9.289927 8.803594 -6.945070 0.2540450 0.9203240 -0.2724291 0.1193621 +VERTEX_SE3:QUAT 2786 9.211126 8.662033 -7.019407 0.2273702 -0.3773366 0.0317625 0.8971684 +VERTEX_SE3:QUAT 2787 9.576580 8.693748 -7.154230 0.2507550 -0.9456152 0.1030275 0.1797755 +VERTEX_SE3:QUAT 2788 9.557192 8.532736 -7.339810 0.3824821 0.3204634 -0.8543989 0.1449595 +VERTEX_SE3:QUAT 2789 9.526507 8.523922 -7.444748 0.3687135 -0.8362791 0.3822590 0.1362559 +VERTEX_SE3:QUAT 2790 9.553852 8.550834 -7.633892 0.3508968 0.3058548 -0.6535129 0.5968628 +VERTEX_SE3:QUAT 2791 9.558786 8.392139 -7.878282 0.2000053 0.8255703 0.0279864 0.5269234 +VERTEX_SE3:QUAT 2792 9.427327 8.446062 -7.879363 0.2402149 0.7561889 0.0790814 0.6035075 +VERTEX_SE3:QUAT 2793 9.551041 8.558147 -7.812862 0.5941038 0.4691609 0.2077923 0.6194764 +VERTEX_SE3:QUAT 2794 9.661057 8.504132 -7.861795 0.4072896 0.1936733 -0.4401966 0.7764231 +VERTEX_SE3:QUAT 2795 9.546187 8.297999 -7.721593 -0.7297721 -0.5589763 0.3877072 0.0682740 +VERTEX_SE3:QUAT 2796 9.554850 8.207060 -7.563800 -0.0118173 -0.4440173 0.8182958 0.3648300 +VERTEX_SE3:QUAT 2797 9.624329 8.145102 -7.531091 -0.5960692 -0.6405979 0.4596388 0.1518820 +VERTEX_SE3:QUAT 2798 9.548036 8.013178 -7.614422 -0.1807747 0.7059914 -0.4850050 0.4833909 +VERTEX_SE3:QUAT 2799 9.523379 8.170570 -7.648380 0.1963254 0.7808400 -0.5278440 0.2704182 +VERTEX_SE3:QUAT 2800 9.499515 8.157974 -7.383114 0.2530421 0.3574696 -0.7306643 0.5237508 +VERTEX_SE3:QUAT 2801 9.659198 8.142566 -7.164437 0.3387575 0.2021741 -0.8084675 0.4367485 +VERTEX_SE3:QUAT 2802 9.789305 8.122448 -7.110513 0.6807976 0.2522790 -0.6783773 0.1125794 +VERTEX_SE3:QUAT 2803 9.803050 8.038539 -7.036569 0.5407084 0.2698884 -0.5013972 0.6191894 +VERTEX_SE3:QUAT 2804 9.821067 8.002963 -7.045454 -0.4138303 0.4241113 -0.6792099 0.4330681 +VERTEX_SE3:QUAT 2805 9.917370 8.049185 -7.034513 0.8510054 -0.0708928 0.0881037 0.5128369 +VERTEX_SE3:QUAT 2806 9.873142 7.877645 -6.791028 0.8883879 -0.1739765 0.2253461 0.3601641 +VERTEX_SE3:QUAT 2807 10.199229 7.862777 -6.789901 0.9280474 -0.0216223 0.2397417 0.2842259 +VERTEX_SE3:QUAT 2808 10.264250 7.748105 -6.723372 -0.0968031 -0.6634829 0.7372439 0.0830123 +VERTEX_SE3:QUAT 2809 10.371221 7.842322 -6.697455 0.4638359 -0.1638179 0.4613860 0.7383380 +VERTEX_SE3:QUAT 2810 10.602949 7.839299 -6.632579 0.1261712 0.4469185 -0.4408719 0.7680994 +VERTEX_SE3:QUAT 2811 10.542316 7.656203 -6.595820 0.8530914 0.2624627 -0.4082288 0.1915662 +VERTEX_SE3:QUAT 2812 10.565922 7.669855 -6.486284 0.6919755 0.5444944 0.1093610 0.4612332 +VERTEX_SE3:QUAT 2813 10.761418 7.633609 -6.584288 -0.2731012 0.2185237 -0.9200801 0.1763965 +VERTEX_SE3:QUAT 2814 10.806346 7.730514 -6.688357 -0.5314974 0.6273193 -0.5615718 0.0928339 +VERTEX_SE3:QUAT 2815 10.752818 7.752539 -6.488457 0.4131014 0.4485882 -0.4077580 0.6795949 +VERTEX_SE3:QUAT 2816 10.854031 7.924308 -6.502045 0.4776383 -0.3016338 0.3903409 0.7269888 +VERTEX_SE3:QUAT 2817 10.952590 7.920860 -6.475032 0.6714916 -0.5860620 0.4240090 0.1607692 +VERTEX_SE3:QUAT 2818 10.947118 7.992466 -6.546337 0.4383513 -0.0830177 -0.2106111 0.8698271 +VERTEX_SE3:QUAT 2819 11.054585 8.238092 -6.388024 -0.3829338 0.2345508 -0.8375751 0.3111519 +VERTEX_SE3:QUAT 2820 11.093715 8.202241 -6.438729 0.6797475 -0.4599638 0.2110476 0.5308818 +VERTEX_SE3:QUAT 2821 11.126624 8.115498 -6.247549 0.0544846 0.7409583 -0.2475298 0.6218853 +VERTEX_SE3:QUAT 2822 11.233865 8.297747 -6.286493 -0.0637266 -0.7303867 0.3690658 0.5711958 +VERTEX_SE3:QUAT 2823 11.307274 8.384715 -6.147023 0.5293520 0.0812489 -0.2405644 0.8095146 +VERTEX_SE3:QUAT 2824 11.332927 8.450814 -6.019732 0.6135378 0.1473675 0.5317841 0.5648539 +VERTEX_SE3:QUAT 2825 11.416428 8.278698 -5.989876 0.5077052 0.7834227 -0.0494592 0.3550185 +VERTEX_SE3:QUAT 2826 11.451867 8.376945 -5.911109 -0.3213624 -0.3855270 0.8570524 0.1164319 +VERTEX_SE3:QUAT 2827 11.460263 8.420715 -5.917936 -0.0456157 -0.3126197 0.6009312 0.7342137 +VERTEX_SE3:QUAT 2828 11.567943 8.264541 -6.004113 0.3269112 0.1058585 -0.7001234 0.6258996 +VERTEX_SE3:QUAT 2829 11.317331 8.097632 -5.917681 0.2162563 -0.0169889 -0.7927609 0.5696268 +VERTEX_SE3:QUAT 2830 11.254142 8.071006 -5.693674 -0.2209886 -0.0535069 0.9717894 0.0626606 +VERTEX_SE3:QUAT 2831 11.467534 7.959801 -5.666542 0.9774051 -0.0236361 0.1788955 0.1100770 +VERTEX_SE3:QUAT 2832 11.473535 8.105195 -5.754991 0.8836606 0.3152275 -0.0082823 0.3459870 +VERTEX_SE3:QUAT 2833 11.471380 8.078156 -5.779423 0.8171165 0.3386916 -0.1612604 0.4377257 +VERTEX_SE3:QUAT 2834 11.616405 8.126507 -5.824967 0.0646889 -0.6475124 0.1361267 0.7470023 +VERTEX_SE3:QUAT 2835 11.594644 8.230201 -5.827694 0.0413317 -0.2977703 0.2764599 0.9127949 +VERTEX_SE3:QUAT 2836 11.650182 8.446953 -5.756455 -0.0021197 -0.1388494 -0.5630762 0.8146542 +VERTEX_SE3:QUAT 2837 11.793094 8.600466 -5.811658 -0.0427239 0.0194405 0.7682760 0.6383955 +VERTEX_SE3:QUAT 2838 11.801785 8.749834 -5.848897 0.3701815 -0.3858879 -0.7969380 0.2809735 +VERTEX_SE3:QUAT 2839 11.772383 8.905777 -5.917421 0.1609121 0.3252923 -0.5803841 0.7290038 +VERTEX_SE3:QUAT 2840 11.661113 9.000336 -5.891368 0.7569596 0.3666560 -0.2998886 0.4501581 +VERTEX_SE3:QUAT 2841 11.585002 8.974942 -5.857008 0.1744024 -0.0848801 -0.9092455 0.3683093 +VERTEX_SE3:QUAT 2842 11.608040 9.072820 -5.836799 0.2376308 -0.8142588 0.5294832 0.0127199 +VERTEX_SE3:QUAT 2843 11.593263 9.055308 -5.876292 0.2895241 -0.5186077 -0.1771608 0.7847521 +VERTEX_SE3:QUAT 2844 11.561599 9.151962 -5.920907 0.6254518 0.3084011 -0.4284846 0.5745431 +VERTEX_SE3:QUAT 2845 11.636130 9.253858 -5.948747 -0.4979341 0.0405980 0.8401452 0.2111149 +VERTEX_SE3:QUAT 2846 11.683153 9.218487 -6.012764 -0.6040081 -0.6837721 0.3508225 0.2110773 +VERTEX_SE3:QUAT 2847 11.690181 9.391178 -6.026598 0.3017603 0.5701521 -0.7389911 0.1943179 +VERTEX_SE3:QUAT 2848 11.779122 9.378934 -6.257221 0.6420065 -0.4673959 0.4227132 0.4366719 +VERTEX_SE3:QUAT 2849 11.796522 9.410754 -6.434328 0.1137430 -0.0112393 -0.1821346 0.9766080 +VERTEX_SE3:QUAT 2850 11.684150 9.601616 -6.477604 -0.2602524 -0.4339420 0.4098649 0.7589294 +VERTEX_SE3:QUAT 2851 11.703013 9.930208 -6.386999 0.3701181 -0.2248937 -0.8827118 0.1823606 +VERTEX_SE3:QUAT 2852 11.859189 9.981190 -6.468763 0.0397071 -0.2895541 -0.9374889 0.1889346 +VERTEX_SE3:QUAT 2853 11.786956 10.051454 -6.497044 0.2623412 -0.5257141 0.3617423 0.7238399 +VERTEX_SE3:QUAT 2854 11.770923 10.387146 -6.451763 0.4774595 0.4553518 -0.3657669 0.6564311 +VERTEX_SE3:QUAT 2855 11.882120 10.384966 -6.426212 0.6448138 -0.5584953 -0.3063947 0.4223985 +VERTEX_SE3:QUAT 2856 11.771226 10.480107 -6.636870 0.8509156 0.2688835 -0.0197041 0.4508392 +VERTEX_SE3:QUAT 2857 11.677635 10.475298 -6.517084 -0.7471064 -0.1022698 0.6231929 0.2073730 +VERTEX_SE3:QUAT 2858 11.683251 10.496531 -6.539997 0.3595923 -0.4783742 -0.0788925 0.7972625 +VERTEX_SE3:QUAT 2859 11.805568 10.602531 -6.581092 0.2826796 0.1973262 -0.4842252 0.8041645 +VERTEX_SE3:QUAT 2860 11.732739 10.627973 -6.491909 -0.3186351 -0.6755720 0.3055712 0.5905086 +VERTEX_SE3:QUAT 2861 11.828025 10.680946 -6.574080 0.1553796 0.2467104 0.7840845 0.5479075 +VERTEX_SE3:QUAT 2862 12.085464 10.738113 -6.634197 0.3743596 -0.7326741 0.3834515 0.4195337 +VERTEX_SE3:QUAT 2863 12.131597 10.613356 -6.879684 -0.0470257 -0.6931000 0.7180940 0.0417355 +VERTEX_SE3:QUAT 2864 12.014223 10.530331 -6.777173 0.8184489 0.2371439 -0.0081287 0.5232955 +VERTEX_SE3:QUAT 2865 11.974336 10.510363 -6.864345 0.1199633 -0.8309382 0.4502995 0.3039423 +VERTEX_SE3:QUAT 2866 11.991199 10.377364 -6.787549 0.0667582 -0.2364380 0.8694874 0.4285230 +VERTEX_SE3:QUAT 2867 11.880717 10.390677 -6.940240 0.0713032 -0.3318897 0.4026118 0.8500993 +VERTEX_SE3:QUAT 2868 11.803104 10.392824 -7.108792 0.9436180 -0.1063612 -0.2267678 0.2164458 +VERTEX_SE3:QUAT 2869 11.601366 10.242550 -7.038981 0.4242108 -0.2490692 0.6300556 0.6008658 +VERTEX_SE3:QUAT 2870 11.733109 10.356717 -7.092915 0.0170572 -0.5582706 0.7093353 0.4299841 +VERTEX_SE3:QUAT 2871 11.785033 10.246075 -7.146809 0.6311543 0.1927720 -0.4393639 0.6094609 +VERTEX_SE3:QUAT 2872 11.827003 10.163735 -7.176248 -0.3265653 -0.1414154 0.9103546 0.2112139 +VERTEX_SE3:QUAT 2873 11.886213 10.261782 -7.325974 0.5200116 0.2142960 -0.4715382 0.6792032 +VERTEX_SE3:QUAT 2874 11.927880 10.266044 -7.314020 0.7151485 -0.3147446 -0.5013984 0.3716155 +VERTEX_SE3:QUAT 2875 12.043501 10.295760 -7.453982 0.5692863 -0.1738509 0.1655821 0.7863025 +VERTEX_SE3:QUAT 2876 12.000389 10.279233 -7.529558 0.0890243 -0.0766490 -0.1769862 0.9771773 +VERTEX_SE3:QUAT 2877 12.139660 10.088972 -7.666693 0.7312003 -0.2964456 0.5498522 0.2740960 +VERTEX_SE3:QUAT 2878 12.201594 10.049493 -7.729689 0.4005142 0.2615021 -0.8177427 0.3201593 +VERTEX_SE3:QUAT 2879 12.244914 9.969732 -7.806918 -0.0915424 -0.8914823 0.4348378 0.0882916 +VERTEX_SE3:QUAT 2880 12.296353 9.832043 -7.861393 -0.5315960 -0.1966675 0.7289316 0.3839093 +VERTEX_SE3:QUAT 2881 12.237749 9.676649 -7.872470 0.3807075 -0.1085627 -0.7742819 0.4937241 +VERTEX_SE3:QUAT 2882 12.427814 9.484774 -7.655433 -0.1897791 -0.2711970 0.2729169 0.9033009 +VERTEX_SE3:QUAT 2883 12.176845 9.610019 -7.656724 0.0921590 -0.2827021 -0.4377298 0.8485157 +VERTEX_SE3:QUAT 2884 12.006139 9.547613 -7.625165 -0.4778691 -0.6682350 0.4633114 0.3323337 +VERTEX_SE3:QUAT 2885 12.012643 9.264226 -7.613562 0.2995473 0.1706906 -0.6627848 0.6647199 +VERTEX_SE3:QUAT 2886 12.061900 9.236957 -7.681953 0.7842584 0.1814311 0.3600329 0.4715908 +VERTEX_SE3:QUAT 2887 12.000200 9.199995 -7.725117 0.1811161 -0.7657451 0.0136509 0.6169644 +VERTEX_SE3:QUAT 2888 11.831762 9.174659 -7.748443 -0.7587320 -0.1026145 0.6039126 0.2215525 +VERTEX_SE3:QUAT 2889 11.625887 9.023224 -7.996710 0.1872740 -0.6186354 0.6478726 0.4030878 +VERTEX_SE3:QUAT 2890 11.676561 9.153895 -7.937705 0.3928636 0.1351531 -0.1772286 0.8921781 +VERTEX_SE3:QUAT 2891 11.703309 9.067896 -8.056311 0.6568386 -0.3271671 -0.4916129 0.4688725 +VERTEX_SE3:QUAT 2892 11.626827 9.079001 -8.272567 0.6860340 -0.4819692 0.0978621 0.5361773 +VERTEX_SE3:QUAT 2893 11.472776 9.018065 -8.224848 -0.3608868 0.2293702 -0.9039027 0.0104885 +VERTEX_SE3:QUAT 2894 11.636102 8.990543 -8.231335 -0.0012745 0.7434956 -0.6454627 0.1749017 +VERTEX_SE3:QUAT 2895 11.531747 8.783776 -8.376998 -0.0529747 -0.6736419 -0.2284062 0.7008786 +VERTEX_SE3:QUAT 2896 11.560213 8.729771 -8.350929 0.7613712 0.1812235 -0.6153880 0.0936461 +VERTEX_SE3:QUAT 2897 11.609538 8.739180 -8.348288 -0.2169287 -0.5222041 0.7880288 0.2434246 +VERTEX_SE3:QUAT 2898 11.589634 8.719323 -8.279635 0.5990654 0.4900733 -0.3786505 0.5075161 +VERTEX_SE3:QUAT 2899 11.582992 8.688927 -8.187900 0.1882336 -0.7550009 0.6071826 0.1608444 +VERTEX_SE3:QUAT 2900 11.571554 8.586970 -8.271030 -0.8714428 -0.1414426 0.4123648 0.2248035 +VERTEX_SE3:QUAT 2901 11.459868 8.343471 -8.128401 -0.8344235 -0.3951442 0.3609736 0.1315167 +VERTEX_SE3:QUAT 2902 11.488618 8.267682 -7.905516 -0.5577565 -0.7140015 0.1169376 0.4067371 +VERTEX_SE3:QUAT 2903 11.641330 8.251453 -8.067247 -0.6843086 -0.6870064 0.0778745 0.2316886 +VERTEX_SE3:QUAT 2904 11.555918 8.310942 -7.999495 0.0392828 0.8031134 -0.4403525 0.3994438 +VERTEX_SE3:QUAT 2905 11.566932 8.314530 -7.832286 0.7410703 0.0196859 -0.6324845 0.2244784 +VERTEX_SE3:QUAT 2906 11.427178 8.345075 -7.812193 -0.0846391 -0.4825454 0.5927505 0.6392441 +VERTEX_SE3:QUAT 2907 11.188159 8.329413 -7.659752 0.5037978 -0.5701913 0.0010694 0.6488980 +VERTEX_SE3:QUAT 2908 11.059206 8.473221 -7.589778 0.4987964 -0.3880042 -0.7488385 0.1997392 +VERTEX_SE3:QUAT 2909 11.034601 8.284678 -7.507701 0.7375913 0.1597992 0.0167854 0.6558518 +VERTEX_SE3:QUAT 2910 11.034265 8.129575 -7.336361 0.6216644 0.3438356 -0.2820277 0.6448030 +VERTEX_SE3:QUAT 2911 10.899381 8.041684 -7.245542 -0.1472112 -0.2160795 0.6297459 0.7314770 +VERTEX_SE3:QUAT 2912 10.775293 8.061249 -7.097169 -0.9767050 -0.1281098 0.1519249 0.0809573 +VERTEX_SE3:QUAT 2913 10.687438 8.101426 -7.165460 -0.2007592 0.4879304 -0.8494734 0.0038272 +VERTEX_SE3:QUAT 2914 10.575212 8.014183 -7.049948 0.4185477 -0.0847463 0.4107119 0.8055753 +VERTEX_SE3:QUAT 2915 10.594894 7.974874 -7.045171 -0.4174297 -0.0435144 0.8320730 0.3626478 +VERTEX_SE3:QUAT 2916 10.408124 7.786279 -7.027738 0.5843358 -0.7480433 -0.1949690 0.2469208 +VERTEX_SE3:QUAT 2917 10.354272 7.826401 -7.045077 0.0541375 -0.6968378 0.4032877 0.5906311 +VERTEX_SE3:QUAT 2918 10.290880 7.897486 -7.059623 0.5576346 -0.1718899 0.2115878 0.7840460 +VERTEX_SE3:QUAT 2919 10.195581 7.802875 -6.985736 0.9088244 -0.3332474 -0.0322827 0.2488821 +VERTEX_SE3:QUAT 2920 10.205860 7.783556 -6.844220 -0.4911153 -0.4011004 0.7731341 0.0137114 +VERTEX_SE3:QUAT 2921 10.244394 7.740275 -6.712622 0.0688879 0.6582309 -0.7291940 0.1739618 +VERTEX_SE3:QUAT 2922 10.275682 7.696082 -6.661647 0.0752415 -0.9786172 0.1910248 0.0125138 +VERTEX_SE3:QUAT 2923 10.070142 7.589902 -6.542804 0.0713899 0.9926607 -0.0687742 0.0692704 +VERTEX_SE3:QUAT 2924 10.156316 7.585959 -6.504409 0.2945033 -0.5762152 0.1966589 0.7365929 +VERTEX_SE3:QUAT 2925 10.175016 7.589691 -6.588085 0.4414364 -0.0297969 -0.7885170 0.4271849 +VERTEX_SE3:QUAT 2926 10.070386 7.608708 -6.472758 0.0786787 -0.3585208 0.9285860 0.0547762 +VERTEX_SE3:QUAT 2927 10.062472 7.635405 -6.443845 0.2987211 -0.9388529 0.1355608 0.1046145 +VERTEX_SE3:QUAT 2928 10.206778 7.652355 -6.444514 0.7083277 0.1850986 -0.6643283 0.1505929 +VERTEX_SE3:QUAT 2929 10.066772 7.542755 -6.556080 0.5422833 0.1581963 -0.5508046 0.6144242 +VERTEX_SE3:QUAT 2930 9.944644 7.536029 -6.579437 0.6037782 -0.0373867 -0.7603242 0.2365614 +VERTEX_SE3:QUAT 2931 10.083086 7.708819 -6.641083 -0.0128892 -0.2436967 0.6601654 0.7103714 +VERTEX_SE3:QUAT 2932 10.125724 7.759855 -6.670271 0.5019452 -0.3547213 -0.5894854 0.5241477 +VERTEX_SE3:QUAT 2933 10.061120 7.717828 -6.628241 0.0482231 -0.5601957 0.2956354 0.7723050 +VERTEX_SE3:QUAT 2934 10.169302 7.668808 -6.484769 0.3746633 0.2090906 0.0801780 0.8997111 +VERTEX_SE3:QUAT 2935 10.095760 7.876833 -6.591201 0.2853913 -0.8545156 -0.0761423 0.4272671 +VERTEX_SE3:QUAT 2936 10.280045 7.994799 -6.694017 -0.8518619 -0.1696088 0.4937092 0.0426075 +VERTEX_SE3:QUAT 2937 10.222785 8.012341 -6.626860 -0.4129741 -0.6112965 0.0189003 0.6748420 +VERTEX_SE3:QUAT 2938 10.131139 8.100481 -6.494054 0.8137720 0.1806280 -0.2284561 0.5029478 +VERTEX_SE3:QUAT 2939 10.369778 8.142548 -6.416574 -0.0805062 -0.9187053 0.3770298 0.0857190 +VERTEX_SE3:QUAT 2940 10.483704 8.229803 -6.431701 -0.6686752 -0.6604154 0.1991487 0.2776053 +VERTEX_SE3:QUAT 2941 10.405150 8.350609 -6.290733 -0.4760420 -0.2434021 0.7484438 0.3923916 +VERTEX_SE3:QUAT 2942 10.298149 8.344644 -6.314268 0.5733311 0.7949561 -0.0536653 0.1909352 +VERTEX_SE3:QUAT 2943 10.284436 8.526934 -6.276691 -0.4456937 -0.6952027 0.4825853 0.2918249 +VERTEX_SE3:QUAT 2944 10.382202 8.559174 -6.327916 0.0950057 -0.9530526 0.2203759 0.1846593 +VERTEX_SE3:QUAT 2945 10.460160 8.769446 -6.582323 0.2187947 -0.9497983 -0.0562278 0.2164499 +VERTEX_SE3:QUAT 2946 10.560910 8.888768 -6.630708 0.0615815 -0.9792954 -0.0571905 0.1841669 +VERTEX_SE3:QUAT 2947 10.514444 8.974931 -6.542882 -0.5949034 0.1524675 0.7615599 0.2070509 +VERTEX_SE3:QUAT 2948 10.537559 8.895339 -6.610222 0.3983893 0.3290596 -0.8556066 0.0307103 +VERTEX_SE3:QUAT 2949 10.506251 8.923175 -6.394801 0.8279227 0.1295806 0.0886717 0.5384145 +VERTEX_SE3:QUAT 2950 10.374490 9.164751 -6.439782 0.7229005 0.3235089 0.0134992 0.6103889 +VERTEX_SE3:QUAT 2951 10.449538 9.200618 -6.305646 -0.2815470 -0.2710914 0.8137988 0.4300840 +VERTEX_SE3:QUAT 2952 10.510733 9.246100 -6.384314 -0.0553607 -0.4186772 0.2140549 0.8808093 +VERTEX_SE3:QUAT 2953 10.536644 9.221703 -6.500465 0.2703338 0.9127502 -0.2433097 0.1860300 +VERTEX_SE3:QUAT 2954 10.556670 9.087502 -6.506924 0.1380251 0.1743157 -0.9748816 0.0130002 +VERTEX_SE3:QUAT 2955 10.659565 9.036519 -6.641328 0.9881043 0.0597244 -0.0984028 0.1019794 +VERTEX_SE3:QUAT 2956 10.775019 9.277184 -6.721978 0.9426739 0.1366291 -0.0609285 0.2983054 +VERTEX_SE3:QUAT 2957 10.785760 9.371053 -6.737410 0.7241622 -0.2628437 -0.0736948 0.6333019 +VERTEX_SE3:QUAT 2958 10.920983 9.405423 -6.713919 0.4014437 -0.6329349 -0.0007302 0.6619938 +VERTEX_SE3:QUAT 2959 10.769285 9.206007 -6.636116 0.3881356 -0.2007792 -0.8913681 0.1204215 +VERTEX_SE3:QUAT 2960 10.688624 9.323558 -6.538045 0.8587255 0.2502692 -0.3239186 0.3082736 +VERTEX_SE3:QUAT 2961 10.822368 9.456038 -6.563011 0.1517193 -0.5370954 0.0874130 0.8251477 +VERTEX_SE3:QUAT 2962 10.956814 9.570345 -6.483527 0.2392197 -0.1629444 -0.4012081 0.8690542 +VERTEX_SE3:QUAT 2963 11.029577 9.689777 -6.630945 0.2629077 -0.6455146 -0.5492931 0.4609420 +VERTEX_SE3:QUAT 2964 11.106210 9.675259 -6.430140 0.1927813 -0.3988723 -0.0941205 0.8915591 +VERTEX_SE3:QUAT 2965 11.061294 9.773424 -6.427409 0.8754976 0.2109399 -0.0200473 0.4342884 +VERTEX_SE3:QUAT 2966 11.030562 9.883302 -6.458575 0.4534421 -0.5358105 0.6804569 0.2104182 +VERTEX_SE3:QUAT 2967 11.120932 9.981523 -6.495604 0.0346420 -0.7578390 0.0651846 0.6482523 +VERTEX_SE3:QUAT 2968 11.139608 9.980782 -6.643360 -0.4504602 -0.6238869 0.5342109 0.3499564 +VERTEX_SE3:QUAT 2969 11.128847 9.863290 -6.806011 -0.6431776 -0.3769006 0.6648126 0.0478830 +VERTEX_SE3:QUAT 2970 11.250181 9.757911 -6.873109 0.7263003 -0.2227864 -0.2018126 0.6181632 +VERTEX_SE3:QUAT 2971 11.252990 9.843349 -6.781540 -0.1751169 -0.2311037 0.6088582 0.7383880 +VERTEX_SE3:QUAT 2972 11.428893 9.664605 -6.842497 0.1608945 -0.5303430 0.0661071 0.8297464 +VERTEX_SE3:QUAT 2973 11.366611 9.530878 -6.987369 0.6000159 0.1458259 -0.7773000 0.1205007 +VERTEX_SE3:QUAT 2974 11.510155 9.558137 -7.006599 -0.0618170 -0.4631200 0.6944511 0.5472076 +VERTEX_SE3:QUAT 2975 11.678436 9.369863 -7.015130 0.3681112 0.1445052 -0.4289759 0.8121528 +VERTEX_SE3:QUAT 2976 11.781980 9.197862 -7.104552 0.4473797 0.2255252 -0.6114683 0.6124511 +VERTEX_SE3:QUAT 2977 11.846752 8.991749 -7.156318 0.5318008 0.5171205 -0.6098800 0.2789637 +VERTEX_SE3:QUAT 2978 11.892694 8.939224 -7.152815 0.2251125 -0.8541428 0.1584540 0.4411993 +VERTEX_SE3:QUAT 2979 11.861966 9.050022 -7.291269 0.2574643 -0.1660756 0.6018753 0.7374803 +VERTEX_SE3:QUAT 2980 11.761204 9.099391 -7.298397 0.3797612 -0.7716730 -0.1411801 0.4902758 +VERTEX_SE3:QUAT 2981 11.821432 9.036173 -7.231993 -0.5569812 -0.4910953 0.3575569 0.5663483 +VERTEX_SE3:QUAT 2982 11.834726 8.984124 -7.192751 0.1366169 -0.1327492 -0.7648424 0.6154101 +VERTEX_SE3:QUAT 2983 11.741971 8.869371 -7.102508 0.5523660 -0.7513955 0.0514988 0.3572737 +VERTEX_SE3:QUAT 2984 11.846629 8.826440 -7.282815 -0.3212914 -0.4175515 0.6349357 0.5650479 +VERTEX_SE3:QUAT 2985 11.583889 8.686477 -7.275715 -0.1916912 -0.6550984 0.7297042 0.0404032 +VERTEX_SE3:QUAT 2986 11.659342 8.677818 -7.360714 0.6172885 0.0625502 -0.7742611 0.1247484 +VERTEX_SE3:QUAT 2987 11.487433 8.729269 -7.450645 0.1174012 -0.8953338 0.3725713 0.2139741 +VERTEX_SE3:QUAT 2988 11.324689 8.668459 -7.533746 0.1391528 -0.4174099 0.7120592 0.5471537 +VERTEX_SE3:QUAT 2989 11.234406 8.545573 -7.454312 -0.0031552 -0.1863424 -0.1410189 0.9723067 +VERTEX_SE3:QUAT 2990 11.116539 8.387878 -7.400414 0.5876308 -0.6144822 -0.2416331 0.4676699 +VERTEX_SE3:QUAT 2991 11.006971 8.309478 -7.309939 0.6569511 -0.3751801 -0.2704400 0.5954136 +VERTEX_SE3:QUAT 2992 10.983055 8.299562 -7.243106 -0.0952911 -0.8665318 0.3476349 0.3452424 +VERTEX_SE3:QUAT 2993 10.880549 8.112682 -7.258072 0.1131745 0.2866365 -0.9067868 0.2876955 +VERTEX_SE3:QUAT 2994 10.804007 8.150970 -7.209678 -0.2056845 -0.8517651 0.4818539 0.0026383 +VERTEX_SE3:QUAT 2995 10.651163 8.092012 -7.150312 0.4463148 0.2781552 -0.8352275 0.1607104 +VERTEX_SE3:QUAT 2996 10.620208 8.219353 -7.139518 -0.4454800 -0.5923989 0.5705394 0.3536891 +VERTEX_SE3:QUAT 2997 10.775437 8.172022 -7.111742 -0.3309328 -0.6133285 0.2300231 0.6792651 +VERTEX_SE3:QUAT 2998 10.729115 8.237925 -7.159762 0.7929514 -0.0420161 -0.5979201 0.1093358 +VERTEX_SE3:QUAT 2999 10.680268 8.195565 -7.102384 0.0658560 -0.0606273 -0.6302851 0.7711861 +VERTEX_SE3:QUAT 3000 10.659935 8.140991 -7.020371 0.6973310 -0.3394659 -0.6126012 0.1523553 +VERTEX_SE3:QUAT 3001 10.512833 8.235813 -6.882886 0.0646031 -0.5098233 -0.5401020 0.6664807 +VERTEX_SE3:QUAT 3002 10.506743 8.265653 -6.915641 -0.0564069 0.0161038 0.5540533 0.8304119 +VERTEX_SE3:QUAT 3003 10.313183 8.209107 -7.026531 -0.4097921 -0.2131244 0.8457741 0.2670481 +VERTEX_SE3:QUAT 3004 10.129466 8.234536 -6.913621 -0.4935365 -0.4135193 -0.0332442 0.7644072 +VERTEX_SE3:QUAT 3005 10.117146 8.199473 -6.921056 0.5739193 -0.3354680 -0.5873033 0.4616847 +VERTEX_SE3:QUAT 3006 10.153400 8.259106 -6.812238 0.5029574 -0.7967877 0.2612577 0.2095417 +VERTEX_SE3:QUAT 3007 10.229857 8.250402 -6.673762 0.2925336 -0.7873725 0.1634448 0.5174499 +VERTEX_SE3:QUAT 3008 10.163190 8.430235 -6.683796 -0.1608419 -0.9550739 0.1803442 0.1715799 +VERTEX_SE3:QUAT 3009 10.161655 8.378951 -6.794317 0.2320054 0.3035607 -0.8207063 0.4248124 +VERTEX_SE3:QUAT 3010 10.130024 8.325484 -6.826998 -0.1352451 -0.9363251 0.1003891 0.3081008 +VERTEX_SE3:QUAT 3011 9.991496 8.271369 -6.941409 0.3848392 0.0565362 -0.3882813 0.8354281 +VERTEX_SE3:QUAT 3012 9.842367 8.248210 -6.853451 -0.3231556 -0.2849694 0.4728313 0.7686309 +VERTEX_SE3:QUAT 3013 9.767032 8.439930 -6.862000 -0.3616929 -0.5155352 0.7726566 0.0800221 +VERTEX_SE3:QUAT 3014 9.985689 8.381806 -6.937519 0.5126189 0.0452888 -0.0926702 0.8523984 +VERTEX_SE3:QUAT 3015 10.024694 8.486687 -6.876018 0.5862752 -0.4316227 0.0306431 0.6848680 +VERTEX_SE3:QUAT 3016 9.933109 8.302424 -6.909228 -0.0807169 0.1349239 -0.7443713 0.6489929 +VERTEX_SE3:QUAT 3017 9.815480 8.303554 -6.724379 -0.0361131 0.2445345 0.9684131 0.0327853 +VERTEX_SE3:QUAT 3018 9.729451 8.401317 -6.637967 0.1501322 -0.3297498 -0.6032946 0.7104654 +VERTEX_SE3:QUAT 3019 9.599537 8.547128 -6.634287 0.4705777 -0.6158797 0.5755869 0.2606695 +VERTEX_SE3:QUAT 3020 9.569059 8.522446 -6.467492 -0.3264122 -0.5863167 0.2284847 0.7053244 +VERTEX_SE3:QUAT 3021 9.725898 8.570683 -6.422986 -0.3681316 -0.5916609 0.5866874 0.4125706 +VERTEX_SE3:QUAT 3022 9.740419 8.615797 -6.455812 -0.0838349 -0.1003980 -0.8765746 0.4631510 +VERTEX_SE3:QUAT 3023 9.815647 8.752852 -6.306866 0.1059136 0.5258165 -0.7274376 0.4279415 +VERTEX_SE3:QUAT 3024 9.707584 8.899683 -6.256093 0.5914937 0.1387328 -0.2538801 0.7526176 +VERTEX_SE3:QUAT 3025 9.714396 8.806275 -6.025302 -0.0948699 -0.4312362 -0.5784493 0.6858801 +VERTEX_SE3:QUAT 3026 9.614492 8.883236 -5.948105 0.3170802 0.4527635 -0.8057958 0.2125052 +VERTEX_SE3:QUAT 3027 9.613508 8.744227 -6.115185 0.1439211 -0.6455443 0.7047311 0.2567359 +VERTEX_SE3:QUAT 3028 9.761229 8.993049 -6.128901 0.0439202 0.5347107 -0.6122860 0.5807420 +VERTEX_SE3:QUAT 3029 9.767237 8.798480 -6.169978 0.0482251 -0.2921849 -0.6968365 0.6532390 +VERTEX_SE3:QUAT 3030 9.762896 8.862886 -6.062305 0.2930599 -0.3889443 -0.6386966 0.5957390 +VERTEX_SE3:QUAT 3031 9.853661 8.779552 -6.010622 0.4651107 -0.5440871 0.6627695 0.2199497 +VERTEX_SE3:QUAT 3032 9.922671 8.780218 -6.031226 0.2345464 -0.0074312 0.9017026 0.3631325 +VERTEX_SE3:QUAT 3033 9.910889 8.819503 -6.043606 -0.0320568 0.0736297 -0.0200863 0.9965679 +VERTEX_SE3:QUAT 3034 9.872452 8.836071 -6.041634 -0.3606167 -0.7824357 0.4983885 0.0967411 +VERTEX_SE3:QUAT 3035 9.800446 8.852085 -5.900119 0.5446171 -0.3859454 -0.4578697 0.5871913 +VERTEX_SE3:QUAT 3036 9.718818 8.838297 -6.040606 0.2440608 -0.2450258 -0.5728980 0.7430912 +VERTEX_SE3:QUAT 3037 9.788780 8.695275 -6.034225 0.2337199 0.1740562 -0.7156761 0.6347340 +VERTEX_SE3:QUAT 3038 9.703687 8.641312 -6.133213 0.7279797 -0.1165547 0.0929108 0.6691997 +VERTEX_SE3:QUAT 3039 9.850211 8.519500 -6.090393 0.5735852 -0.5824832 -0.4838679 0.3123862 +VERTEX_SE3:QUAT 3040 9.758394 8.622025 -5.909375 -0.0504640 -0.5084697 -0.5935830 0.6217484 +VERTEX_SE3:QUAT 3041 9.733273 8.775051 -5.840653 -0.1485776 -0.0588838 -0.7498624 0.6419999 +VERTEX_SE3:QUAT 3042 9.809678 8.864873 -5.884745 0.3809961 0.1157347 0.3921129 0.8292737 +VERTEX_SE3:QUAT 3043 9.826788 8.891335 -5.881776 0.2292267 -0.2966308 0.1707514 0.9112130 +VERTEX_SE3:QUAT 3044 9.865760 8.795089 -5.876010 0.6415044 -0.4280877 0.5057497 0.3865621 +VERTEX_SE3:QUAT 3045 9.874385 8.640879 -5.948826 0.0712562 0.8448554 -0.5279222 0.0493957 +VERTEX_SE3:QUAT 3046 9.824138 8.638343 -5.790187 0.8265892 -0.4176747 -0.3301805 0.1824253 +VERTEX_SE3:QUAT 3047 9.636291 8.589288 -5.943548 -0.0079463 0.5996100 -0.7398485 0.3050064 +VERTEX_SE3:QUAT 3048 9.627026 8.631709 -5.899196 0.7274169 -0.6052308 0.1989364 0.2549210 +VERTEX_SE3:QUAT 3049 9.676223 8.587322 -5.998713 0.4683585 0.3419266 -0.8135883 0.0424325 +VERTEX_SE3:QUAT 3050 9.598949 8.709996 -6.108378 -0.1831143 -0.4645762 0.2359885 0.8336351 +VERTEX_SE3:QUAT 3051 9.615076 8.815371 -6.063214 0.2838125 -0.2576481 -0.9123679 0.1437109 +VERTEX_SE3:QUAT 3052 9.668222 9.025881 -6.124497 0.1132053 -0.7509131 -0.3101453 0.5719475 +VERTEX_SE3:QUAT 3053 9.704769 9.090295 -6.130585 0.0691675 -0.5750880 0.0750296 0.8117021 +VERTEX_SE3:QUAT 3054 9.776135 9.125109 -6.161189 0.7615433 0.1091814 -0.2474591 0.5889781 +VERTEX_SE3:QUAT 3055 9.782758 9.086109 -6.210525 0.9318051 -0.0545022 0.1119436 0.3409360 +VERTEX_SE3:QUAT 3056 9.871778 8.779530 -6.175664 -0.0928382 -0.2947451 0.5819134 0.7522521 +VERTEX_SE3:QUAT 3057 9.860383 8.781047 -6.141238 0.7966346 -0.1415517 0.3610698 0.4636432 +VERTEX_SE3:QUAT 3058 10.082371 8.713703 -6.141253 0.2904946 -0.4050711 -0.6393396 0.5854700 +VERTEX_SE3:QUAT 3059 10.121720 8.589181 -6.342408 -0.3910281 0.0429825 0.6385207 0.6614687 +VERTEX_SE3:QUAT 3060 10.119640 8.657393 -6.224151 0.4223511 -0.5550308 -0.6841035 0.2134541 +VERTEX_SE3:QUAT 3061 10.055309 8.801788 -6.293223 -0.7446534 -0.4950092 0.4316392 0.1189321 +VERTEX_SE3:QUAT 3062 9.964115 8.832323 -6.382810 0.7095271 -0.1324183 0.4595980 0.5175001 +VERTEX_SE3:QUAT 3063 10.033720 8.921280 -6.465403 -0.7529027 0.0595684 0.5686921 0.3258503 +VERTEX_SE3:QUAT 3064 10.029568 8.847417 -6.565931 -0.3458379 -0.4824772 -0.3359956 0.7312448 +VERTEX_SE3:QUAT 3065 10.001153 8.743325 -6.645890 0.4625220 0.2051654 -0.5183141 0.6894426 +VERTEX_SE3:QUAT 3066 10.156451 8.763889 -6.739046 0.8198630 -0.3543314 -0.4494939 0.0151411 +VERTEX_SE3:QUAT 3067 10.286606 8.838647 -6.784260 0.2479176 -0.2064987 -0.9417628 0.0947523 +VERTEX_SE3:QUAT 3068 10.295148 8.858908 -6.829610 0.7859030 0.0020558 -0.4177281 0.4559118 +VERTEX_SE3:QUAT 3069 10.261259 8.824511 -6.821910 0.1403973 -0.7781751 0.3346304 0.5125960 +VERTEX_SE3:QUAT 3070 10.518166 8.950590 -6.897610 -0.6840985 -0.6197149 0.3780318 0.0710959 +VERTEX_SE3:QUAT 3071 10.464023 8.877391 -6.748500 0.0336340 -0.6891608 0.6665008 0.2823168 +VERTEX_SE3:QUAT 3072 10.459514 8.936129 -6.907752 -0.0182553 0.1757854 0.9282068 0.3274117 +VERTEX_SE3:QUAT 3073 10.540061 8.749864 -7.091034 0.3323823 0.5553743 -0.6310991 0.4275456 +VERTEX_SE3:QUAT 3074 10.620433 8.739156 -7.018517 0.4988875 0.7532047 -0.4122994 0.1174866 +VERTEX_SE3:QUAT 3075 10.681462 8.540118 -6.923763 0.5848950 0.2101159 -0.6114792 0.4897370 +VERTEX_SE3:QUAT 3076 10.709969 8.376629 -6.916429 0.0325809 -0.6783177 0.1784442 0.7120262 +VERTEX_SE3:QUAT 3077 10.575896 8.319082 -6.852335 0.0929756 -0.2832855 -0.3231604 0.8981493 +VERTEX_SE3:QUAT 3078 10.552427 8.296266 -6.793096 -0.0518319 -0.1144096 0.7458530 0.6541614 +VERTEX_SE3:QUAT 3079 10.324085 8.262039 -6.934236 0.4882378 -0.3548286 0.6649214 0.4400000 +VERTEX_SE3:QUAT 3080 10.293884 8.267707 -7.104392 0.3200211 0.6701904 -0.4918138 0.4544783 +VERTEX_SE3:QUAT 3081 10.355815 8.168682 -7.014105 -0.3168026 0.1475517 -0.6006012 0.7191265 +VERTEX_SE3:QUAT 3082 10.453572 8.067745 -7.165781 0.6495870 -0.0281953 -0.5228911 0.5512047 +VERTEX_SE3:QUAT 3083 10.434469 8.087144 -7.086397 -0.1771328 -0.4915889 -0.1088828 0.8456411 +VERTEX_SE3:QUAT 3084 10.352729 8.131980 -7.165319 0.4102850 -0.0785423 0.9024744 0.1050581 +VERTEX_SE3:QUAT 3085 10.344527 8.107544 -7.275606 0.7555827 0.0705867 -0.6475942 0.0688046 +VERTEX_SE3:QUAT 3086 10.177290 8.150925 -6.975410 0.3466992 0.0599040 -0.8249017 0.4424346 +VERTEX_SE3:QUAT 3087 10.163708 8.071844 -6.951444 0.2519718 0.2019361 0.9347213 0.1484186 +VERTEX_SE3:QUAT 3088 10.265695 8.005233 -6.747561 0.5934606 -0.4166478 0.5319844 0.4372662 +VERTEX_SE3:QUAT 3089 10.184706 8.007070 -6.752321 -0.0199687 -0.5716885 0.8148632 0.0936556 +VERTEX_SE3:QUAT 3090 10.013146 8.016724 -6.725743 -0.1978678 0.1044845 -0.1007623 0.9694216 +VERTEX_SE3:QUAT 3091 9.983304 7.864363 -6.481083 0.1686332 0.2281132 0.5753405 0.7671444 +VERTEX_SE3:QUAT 3092 10.030854 7.820982 -6.522201 0.3042672 -0.2837598 0.5257906 0.7419206 +VERTEX_SE3:QUAT 3093 9.790471 7.745796 -6.488305 0.7928022 -0.2750092 -0.5426265 0.0372981 +VERTEX_SE3:QUAT 3094 9.811756 7.611931 -6.421460 -0.0471915 -0.3374671 -0.8734612 0.3477852 +VERTEX_SE3:QUAT 3095 9.884387 7.755478 -6.318618 0.0252528 -0.2915338 0.5383055 0.7903148 +VERTEX_SE3:QUAT 3096 9.967670 7.749411 -6.168396 -0.3514138 -0.2393051 -0.5887315 0.6874857 +VERTEX_SE3:QUAT 3097 9.847898 7.745512 -6.167523 0.4332082 -0.0950333 -0.0929635 0.8914354 +VERTEX_SE3:QUAT 3098 9.740381 7.762385 -6.083646 0.0476836 0.1093461 0.9251298 0.3604227 +VERTEX_SE3:QUAT 3099 9.920992 7.728527 -6.227426 0.3177877 -0.2221528 0.6528522 0.6507251 +VERTEX_SE3:QUAT 3100 9.897128 7.663061 -6.161090 -0.6799604 -0.3382355 0.4425931 0.4768248 +VERTEX_SE3:QUAT 3101 9.992861 7.707976 -6.170110 -0.1479288 -0.7313439 0.6609786 0.0797531 +VERTEX_SE3:QUAT 3102 10.156580 7.731937 -6.301837 -0.2632738 -0.2713778 -0.6792209 0.6290469 +VERTEX_SE3:QUAT 3103 10.182776 7.774702 -6.074673 0.5609932 -0.0472365 -0.1373484 0.8149790 +VERTEX_SE3:QUAT 3104 10.149868 7.670104 -5.972520 0.2737521 -0.7221555 0.2535881 0.5824469 +VERTEX_SE3:QUAT 3105 10.097863 7.760823 -5.957934 -0.2407625 -0.0680700 -0.7315479 0.6342220 +VERTEX_SE3:QUAT 3106 9.868386 7.845208 -5.845772 0.7365351 -0.0916746 0.1892414 0.6428838 +VERTEX_SE3:QUAT 3107 9.991778 7.937611 -5.748557 -0.5650105 -0.0305147 0.8245192 0.0003029 +VERTEX_SE3:QUAT 3108 10.052488 7.956078 -5.457974 0.2965280 0.1606332 0.3027515 0.8914088 +VERTEX_SE3:QUAT 3109 10.127199 7.991545 -5.527240 -0.0452690 -0.3742111 -0.4821615 0.7908458 +VERTEX_SE3:QUAT 3110 10.279307 7.997477 -5.381013 0.3117198 -0.5114795 0.6150301 0.5127937 +VERTEX_SE3:QUAT 3111 10.161455 8.029426 -5.188580 0.0047426 0.0036510 -0.5954733 0.8033528 +VERTEX_SE3:QUAT 3112 10.172093 8.086436 -5.066075 -0.0900880 0.7270402 -0.6054484 0.3110127 +VERTEX_SE3:QUAT 3113 10.178247 8.169771 -4.825398 0.5690813 -0.0359097 0.1826487 0.8009348 +VERTEX_SE3:QUAT 3114 10.229169 8.221580 -4.806058 0.2853592 0.5765966 -0.7213420 0.2564608 +VERTEX_SE3:QUAT 3115 10.380771 8.136509 -4.651282 -0.4576698 -0.0319054 0.1806673 0.8699883 +VERTEX_SE3:QUAT 3116 10.483011 8.224345 -4.563893 0.3112406 -0.6647200 0.6152239 0.2877085 +VERTEX_SE3:QUAT 3117 10.573417 8.222185 -4.612480 -0.0106567 -0.1059686 -0.9938226 0.0312040 +VERTEX_SE3:QUAT 3118 10.622039 8.179386 -4.598201 0.5419045 -0.0075832 0.7192032 0.4347743 +VERTEX_SE3:QUAT 3119 10.709885 8.204328 -4.462045 0.7707975 0.1628113 -0.4776955 0.3888068 +VERTEX_SE3:QUAT 3120 10.672095 8.243044 -4.577221 -0.1034076 -0.0011002 0.8219111 0.5601499 +VERTEX_SE3:QUAT 3121 10.645117 8.268471 -4.601818 -0.4877816 -0.0743260 0.8093825 0.3185040 +VERTEX_SE3:QUAT 3122 10.562859 8.418857 -4.519737 0.8293732 -0.1321505 -0.0730096 0.5379089 +VERTEX_SE3:QUAT 3123 10.525831 8.597182 -4.340105 0.4142018 0.6837737 -0.5671968 0.1979350 +VERTEX_SE3:QUAT 3124 10.535684 8.902835 -4.379219 0.4142228 0.7605606 -0.1866148 0.4638340 +VERTEX_SE3:QUAT 3125 10.496226 8.990123 -4.207767 -0.0319254 0.6886076 -0.4525266 0.5657031 +VERTEX_SE3:QUAT 3126 10.680434 9.048031 -4.031668 0.6275601 -0.4078563 -0.4125152 0.5192810 +VERTEX_SE3:QUAT 3127 10.779384 9.215930 -4.099519 0.0600842 -0.3413654 0.9377778 0.0207908 +VERTEX_SE3:QUAT 3128 10.645028 9.203707 -4.025126 0.4742382 -0.2590484 0.8404089 0.0412893 +VERTEX_SE3:QUAT 3129 10.686094 9.199933 -4.095681 0.1048951 0.3002684 -0.8818326 0.3481482 +VERTEX_SE3:QUAT 3130 10.572722 9.256019 -4.173654 0.2459884 -0.1395566 0.7875361 0.5475404 +VERTEX_SE3:QUAT 3131 10.713107 9.340684 -4.273439 0.7868585 0.1919809 -0.4086641 0.4207026 +VERTEX_SE3:QUAT 3132 11.077700 9.437073 -4.211919 -0.0719354 -0.8142668 -0.1697685 0.5504304 +VERTEX_SE3:QUAT 3133 11.059254 9.555162 -4.189045 0.4778859 0.3038795 -0.8090713 0.1571175 +VERTEX_SE3:QUAT 3134 10.850074 9.659988 -4.125295 -0.4359537 -0.1959022 0.8777475 0.0335570 +VERTEX_SE3:QUAT 3135 10.990889 9.644346 -4.144705 0.5970063 0.7506302 -0.0356719 0.2808296 +VERTEX_SE3:QUAT 3136 10.994491 9.803815 -4.332107 0.4032451 0.4640770 0.0770187 0.7849166 +VERTEX_SE3:QUAT 3137 10.962522 9.849097 -4.548359 0.6893891 0.0915914 0.4328626 0.5735709 +VERTEX_SE3:QUAT 3138 11.175483 9.851024 -4.520847 -0.5693410 -0.7119745 0.3804517 0.1555622 +VERTEX_SE3:QUAT 3139 11.236001 9.888373 -4.564119 0.1692591 -0.7784977 -0.2322348 0.5579961 +VERTEX_SE3:QUAT 3140 11.213911 9.970296 -4.369305 0.7037426 -0.1819848 -0.2998171 0.6178492 +VERTEX_SE3:QUAT 3141 11.370025 10.011387 -4.269596 0.3051385 -0.0989397 0.4343889 0.8416696 +VERTEX_SE3:QUAT 3142 11.470567 10.186428 -4.203693 0.4336834 0.0853389 0.6659164 0.6009919 +VERTEX_SE3:QUAT 3143 11.365204 10.309941 -4.362767 0.6317275 -0.3743117 0.4974066 0.4619500 +VERTEX_SE3:QUAT 3144 11.258072 10.217293 -4.087516 0.0178767 -0.5854432 -0.2157023 0.7812869 +VERTEX_SE3:QUAT 3145 11.045091 10.328719 -4.197108 -0.0691931 -0.5990110 -0.0238175 0.7973900 +VERTEX_SE3:QUAT 3146 10.997463 10.445415 -4.258189 -0.8202116 -0.0366629 0.5426821 0.1772141 +VERTEX_SE3:QUAT 3147 10.833297 10.516669 -4.345917 -0.1822653 -0.1731158 0.9137900 0.3190581 +VERTEX_SE3:QUAT 3148 10.754094 10.647863 -4.224024 0.5897741 0.4728379 -0.5583094 0.3418794 +VERTEX_SE3:QUAT 3149 10.887386 10.810652 -4.168179 0.8617977 0.2431365 0.0854102 0.4369148 +VERTEX_SE3:QUAT 3150 10.942225 10.954764 -4.301766 0.5258458 0.7309759 -0.4196369 0.1143031 +VERTEX_SE3:QUAT 3151 11.123175 11.126496 -4.348905 0.6356676 -0.2641248 0.1799291 0.7027021 +VERTEX_SE3:QUAT 3152 11.332483 11.070134 -4.297351 0.2150456 -0.6506121 -0.1235523 0.7177702 +VERTEX_SE3:QUAT 3153 11.230445 11.184565 -4.296671 0.1677824 -0.0404958 -0.0680042 0.9826416 +VERTEX_SE3:QUAT 3154 11.222021 11.259899 -4.250064 -0.1915542 -0.2138821 -0.4530878 0.8439626 +VERTEX_SE3:QUAT 3155 11.365586 11.606082 -4.279369 0.3793534 0.6898558 -0.1148451 0.6058057 +VERTEX_SE3:QUAT 3156 11.599167 11.853149 -4.185122 0.0467968 -0.1183215 0.7051653 0.6975328 +VERTEX_SE3:QUAT 3157 11.619686 11.976160 -4.241301 0.4537642 -0.6561016 0.3728680 0.4739180 +VERTEX_SE3:QUAT 3158 11.872463 11.997416 -4.489336 0.0166094 -0.7402486 -0.1277509 0.6598756 +VERTEX_SE3:QUAT 3159 11.837469 11.947245 -4.511648 -0.0360507 0.5252052 -0.8149833 0.2422024 +VERTEX_SE3:QUAT 3160 11.774337 11.993509 -4.569966 0.2402606 -0.2253413 0.9092795 0.2543757 +VERTEX_SE3:QUAT 3161 11.803628 12.109956 -4.592828 0.7598403 -0.2438240 0.3760978 0.4708959 +VERTEX_SE3:QUAT 3162 11.883415 12.214687 -4.574632 0.2517090 0.3614493 0.1896262 0.8775186 +VERTEX_SE3:QUAT 3163 12.074142 12.261673 -4.614641 0.1968096 -0.1822736 0.9570439 0.1100425 +VERTEX_SE3:QUAT 3164 12.083086 12.282830 -4.689630 -0.2419558 -0.7632133 0.1873935 0.5690752 +VERTEX_SE3:QUAT 3165 12.227466 12.235176 -4.772304 0.8336984 0.2466357 0.2178868 0.4434446 +VERTEX_SE3:QUAT 3166 12.145449 12.221806 -4.882247 0.7616531 0.2964801 -0.3982919 0.4163505 +VERTEX_SE3:QUAT 3167 12.263565 12.130317 -4.977436 0.4928682 -0.5210799 0.6896915 0.0994099 +VERTEX_SE3:QUAT 3168 12.207786 12.130599 -5.066842 -0.2006537 -0.4428304 0.6213846 0.6144270 +VERTEX_SE3:QUAT 3169 12.193192 12.175576 -5.109081 -0.8985232 -0.0069893 0.4315681 0.0797251 +VERTEX_SE3:QUAT 3170 12.197100 12.080993 -5.181639 0.6596940 -0.0539825 0.4288193 0.6148201 +VERTEX_SE3:QUAT 3171 12.378853 12.121260 -5.176695 -0.5969381 -0.6587314 0.4327295 0.1499436 +VERTEX_SE3:QUAT 3172 12.303151 11.947987 -5.319359 0.6226587 -0.1954394 -0.7575099 0.0166830 +VERTEX_SE3:QUAT 3173 12.356431 11.959124 -5.555254 0.0185961 0.6565296 -0.6748611 0.3364307 +VERTEX_SE3:QUAT 3174 12.415366 11.921502 -5.483733 0.2900036 -0.2251360 0.8074357 0.4618000 +VERTEX_SE3:QUAT 3175 12.313545 11.901557 -5.643462 0.7342425 0.5600398 -0.3516681 0.1535348 +VERTEX_SE3:QUAT 3176 12.188550 11.938376 -5.787972 0.8170016 -0.5354214 0.1831065 0.1109245 +VERTEX_SE3:QUAT 3177 12.281355 12.014354 -5.842650 -0.0733127 -0.4886756 -0.1047655 0.8630444 +VERTEX_SE3:QUAT 3178 12.303969 11.868008 -5.848512 0.4305941 0.2875861 -0.4748446 0.7116218 +VERTEX_SE3:QUAT 3179 12.399707 11.754380 -5.939062 0.6632821 0.0127242 -0.7440460 0.0793133 +VERTEX_SE3:QUAT 3180 12.389038 11.789297 -6.120947 0.0498239 -0.0017070 0.7607051 0.6471804 +VERTEX_SE3:QUAT 3181 12.589406 11.766616 -5.985826 -0.4902367 -0.0492657 0.8032031 0.3348218 +VERTEX_SE3:QUAT 3182 12.410676 11.677754 -6.080838 0.3608968 -0.1578639 0.7847652 0.4785144 +VERTEX_SE3:QUAT 3183 12.425892 11.487308 -6.107130 0.4727722 0.0121769 0.1901236 0.8603437 +VERTEX_SE3:QUAT 3184 12.545457 11.496745 -6.184540 0.4168983 -0.5775816 0.6598326 0.2391992 +VERTEX_SE3:QUAT 3185 12.579975 11.535863 -6.260190 0.1933035 0.1030113 0.1321279 0.9667288 +VERTEX_SE3:QUAT 3186 12.767475 11.371448 -6.447023 0.0053224 0.2883918 -0.9208872 0.2622377 +VERTEX_SE3:QUAT 3187 12.893525 11.231148 -6.370527 -0.0270372 0.1162823 -0.5406083 0.8327605 +VERTEX_SE3:QUAT 3188 12.964376 11.169207 -6.501528 0.2115604 0.3303020 -0.3598721 0.8465429 +VERTEX_SE3:QUAT 3189 12.662482 11.201113 -6.641748 0.2378324 0.3058567 -0.3204997 0.8643884 +VERTEX_SE3:QUAT 3190 12.600267 11.204007 -6.417974 0.5786451 -0.0084420 0.0822762 0.8113749 +VERTEX_SE3:QUAT 3191 12.614978 11.015219 -6.435859 0.6261196 0.5771236 -0.4336439 0.2947127 +VERTEX_SE3:QUAT 3192 12.574999 11.053924 -6.531734 -0.3307972 -0.4633513 0.7996198 0.1910155 +VERTEX_SE3:QUAT 3193 12.547242 11.049483 -6.619659 0.3825664 -0.6061448 -0.1614418 0.6783568 +VERTEX_SE3:QUAT 3194 12.484866 11.052884 -6.557931 0.8526018 -0.0021562 -0.2456487 0.4612181 +VERTEX_SE3:QUAT 3195 12.566010 11.023479 -6.573538 0.6484866 -0.6589869 -0.3339397 0.1835365 +VERTEX_SE3:QUAT 3196 12.754076 10.857335 -6.535136 -0.5139218 -0.7452899 0.1162798 0.4085418 +VERTEX_SE3:QUAT 3197 12.826427 10.772415 -6.351347 0.4472470 0.5904476 0.0028680 0.6718136 +VERTEX_SE3:QUAT 3198 12.729830 10.613587 -6.496126 0.2024283 -0.0758038 0.1768580 0.9602072 +VERTEX_SE3:QUAT 3199 12.691471 10.460447 -6.635829 0.7853257 -0.4937115 -0.1205534 0.3535243 +VERTEX_SE3:QUAT 3200 12.623613 10.509863 -6.553700 -0.0338657 0.1068624 0.6483573 0.7530381 +VERTEX_SE3:QUAT 3201 12.481407 10.696694 -6.659132 -0.0808978 0.7974600 -0.4495351 0.3942476 +VERTEX_SE3:QUAT 3202 12.276986 10.612730 -6.637678 0.0519569 0.4625200 -0.7407992 0.4843473 +VERTEX_SE3:QUAT 3203 12.075818 10.629287 -6.552995 0.9506209 -0.0002257 -0.1694529 0.2600108 +VERTEX_SE3:QUAT 3204 12.114530 10.425576 -6.435930 -0.0926757 -0.5929364 0.5928047 0.5370476 +VERTEX_SE3:QUAT 3205 12.255151 10.394718 -6.363063 0.1611436 0.1484116 0.9171374 0.3329650 +VERTEX_SE3:QUAT 3206 12.357364 10.372738 -6.457323 0.2896800 -0.7618607 0.0878610 0.5726555 +VERTEX_SE3:QUAT 3207 12.285354 10.278127 -6.205843 0.9511668 0.1761821 -0.2248534 0.1169724 +VERTEX_SE3:QUAT 3208 12.280703 10.106335 -6.039880 0.2274355 -0.8912277 0.2924485 0.2616491 +VERTEX_SE3:QUAT 3209 12.432318 10.075490 -6.093402 -0.1932154 -0.5994667 -0.0670922 0.7738257 +VERTEX_SE3:QUAT 3210 12.356767 10.022149 -6.061432 0.4242164 0.2224257 0.2355004 0.8456399 +VERTEX_SE3:QUAT 3211 12.371984 10.046756 -6.017687 -0.1208256 0.3329164 -0.8791490 0.3188494 +VERTEX_SE3:QUAT 3212 12.342224 9.925478 -5.940778 0.7836011 -0.0432478 -0.0265109 0.6191899 +VERTEX_SE3:QUAT 3213 12.293354 9.797498 -6.002081 0.4349913 -0.2767229 0.7434762 0.4259697 +VERTEX_SE3:QUAT 3214 12.395618 9.879422 -6.058103 -0.1930903 -0.6973955 0.0911076 0.6841455 +VERTEX_SE3:QUAT 3215 12.419459 9.815448 -6.043609 -0.0816832 -0.8629659 0.4321592 0.2487088 +VERTEX_SE3:QUAT 3216 12.547309 9.714284 -5.909403 0.2072582 0.1472105 -0.7202972 0.6454031 +VERTEX_SE3:QUAT 3217 12.600663 9.596830 -5.892918 0.1281758 -0.5483425 0.4154402 0.7143535 +VERTEX_SE3:QUAT 3218 12.550173 9.482831 -5.722215 0.8105763 -0.5154484 0.0735174 0.2680937 +VERTEX_SE3:QUAT 3219 12.265433 9.606892 -5.591106 0.0274204 0.2272041 -0.1267430 0.9651749 +VERTEX_SE3:QUAT 3220 12.177412 9.785475 -5.647994 0.3490333 0.8442388 -0.3398968 0.2233982 +VERTEX_SE3:QUAT 3221 12.090218 9.875147 -5.525724 0.6732259 0.0643531 -0.4559022 0.5786006 +VERTEX_SE3:QUAT 3222 12.064219 9.984670 -5.504873 0.0598298 -0.3385439 0.6369749 0.6899793 +VERTEX_SE3:QUAT 3223 12.027204 10.139315 -5.548159 0.1147374 -0.0618152 0.1633817 0.9779165 +VERTEX_SE3:QUAT 3224 11.887661 10.090562 -5.620623 0.4789826 -0.5188929 -0.2510351 0.6620478 +VERTEX_SE3:QUAT 3225 11.848156 10.064717 -5.547897 -0.2972571 -0.4104536 0.2372521 0.8287807 +VERTEX_SE3:QUAT 3226 11.780466 9.976846 -5.453464 -0.0269424 -0.0811297 -0.1681014 0.9820560 +VERTEX_SE3:QUAT 3227 11.932070 10.044162 -5.279169 0.5668697 -0.5441471 -0.1377929 0.6029725 +VERTEX_SE3:QUAT 3228 12.033275 10.090956 -5.144614 0.0239232 -0.5424214 0.7965310 0.2659795 +VERTEX_SE3:QUAT 3229 11.975851 10.163214 -5.009770 0.1113463 0.3533463 0.0133228 0.9287470 +VERTEX_SE3:QUAT 3230 12.054221 10.169796 -5.080772 -0.3199878 -0.1358426 -0.4059449 0.8452002 +VERTEX_SE3:QUAT 3231 12.011158 10.196374 -5.234972 0.0319060 0.2750936 0.1308136 0.9519419 +VERTEX_SE3:QUAT 3232 12.081101 10.368096 -5.262644 0.2773453 -0.4974907 0.5117374 0.6432010 +VERTEX_SE3:QUAT 3233 11.954838 10.497578 -5.136453 0.0290864 -0.3062415 0.1162967 0.9443756 +VERTEX_SE3:QUAT 3234 11.913073 10.435307 -5.127082 -0.0942158 -0.6745065 0.7058596 0.1947474 +VERTEX_SE3:QUAT 3235 11.957298 10.615540 -5.382076 0.4090127 0.5882617 -0.5108169 0.4751030 +VERTEX_SE3:QUAT 3236 11.820084 10.547168 -5.371522 0.2040528 -0.2968890 0.9284915 0.0901272 +VERTEX_SE3:QUAT 3237 11.738229 10.542329 -5.352370 0.0429572 0.7508440 -0.4972171 0.4326235 +VERTEX_SE3:QUAT 3238 11.755721 10.358570 -5.473137 0.4127184 0.3731375 0.0824737 0.8268192 +VERTEX_SE3:QUAT 3239 11.600938 10.398408 -5.455493 -0.0430478 0.1610816 -0.9508464 0.2609421 +VERTEX_SE3:QUAT 3240 11.671313 10.542116 -5.540423 -0.2000272 -0.1824962 0.7689549 0.5791308 +VERTEX_SE3:QUAT 3241 11.681267 10.779720 -5.471462 0.3109078 0.5693299 0.0387087 0.7600667 +VERTEX_SE3:QUAT 3242 11.894177 10.698580 -5.514214 0.4395232 -0.6512758 0.2651459 0.5588890 +VERTEX_SE3:QUAT 3243 12.071707 10.675833 -5.531991 0.3150701 0.2693849 0.6409552 0.6460178 +VERTEX_SE3:QUAT 3244 12.212648 10.871859 -5.365874 0.5292920 -0.1598019 -0.1650822 0.8167382 +VERTEX_SE3:QUAT 3245 12.186732 10.806592 -5.410505 0.2394063 0.4626216 -0.6701174 0.5287802 +VERTEX_SE3:QUAT 3246 12.327060 10.892649 -5.288473 0.6249543 0.2168499 -0.4271978 0.6163686 +VERTEX_SE3:QUAT 3247 12.176651 11.012697 -5.381446 0.2738570 -0.4009415 0.0337922 0.8735596 +VERTEX_SE3:QUAT 3248 12.085507 11.082616 -5.417024 0.1579099 -0.1730473 0.8274624 0.5103186 +VERTEX_SE3:QUAT 3249 12.129996 11.132165 -5.503764 0.4652724 0.1520194 0.0991708 0.8663584 +VERTEX_SE3:QUAT 3250 12.045414 10.985422 -5.458371 0.3161454 -0.2635790 -0.3252425 0.8513492 +VERTEX_SE3:QUAT 3251 11.964136 11.148629 -5.479852 -0.1637906 0.3031498 -0.5914569 0.7290073 +VERTEX_SE3:QUAT 3252 12.088340 11.289442 -5.456709 0.1840447 -0.4350353 -0.0824268 0.8775407 +VERTEX_SE3:QUAT 3253 12.003477 11.391614 -5.516901 0.4962702 -0.5030417 0.0979566 0.7007635 +VERTEX_SE3:QUAT 3254 11.924642 11.454120 -5.648253 0.4732839 0.3501848 0.0395403 0.8073472 +VERTEX_SE3:QUAT 3255 11.945792 11.469172 -5.730786 -0.3493814 0.6538956 -0.6705875 0.0257984 +VERTEX_SE3:QUAT 3256 11.826553 11.461967 -5.705092 0.0388969 -0.1133276 0.9254492 0.3594270 +VERTEX_SE3:QUAT 3257 11.846969 11.502970 -5.760140 -0.5087424 0.5183949 -0.6582048 0.1980263 +VERTEX_SE3:QUAT 3258 11.897351 11.473324 -5.620447 0.4156693 0.0568859 0.3987998 0.8154396 +VERTEX_SE3:QUAT 3259 11.622039 11.432384 -5.488573 0.2917013 -0.4375683 0.4399362 0.7279426 +VERTEX_SE3:QUAT 3260 11.629727 11.597032 -5.630783 0.9166353 0.2541326 -0.0727229 0.2998462 +VERTEX_SE3:QUAT 3261 11.679609 11.585629 -5.520472 0.2683515 -0.1647299 -0.4446157 0.8385514 +VERTEX_SE3:QUAT 3262 11.677305 11.767141 -5.690455 0.4006604 -0.5416597 0.6894043 0.2660783 +VERTEX_SE3:QUAT 3263 11.783684 11.727111 -5.651769 0.8528921 -0.3388356 0.3672863 0.1512159 +VERTEX_SE3:QUAT 3264 11.740007 11.714426 -5.843806 0.2720700 -0.0569135 0.9152669 0.2915909 +VERTEX_SE3:QUAT 3265 11.731807 11.700070 -5.765817 0.0210788 -0.6223433 0.7622238 0.1768033 +VERTEX_SE3:QUAT 3266 11.708647 11.687545 -5.789534 0.5989585 -0.2939391 0.2140387 0.7134675 +VERTEX_SE3:QUAT 3267 11.710187 11.713973 -5.688792 -0.0244120 0.6130399 -0.5628164 0.5539169 +VERTEX_SE3:QUAT 3268 11.787534 11.731311 -5.749066 0.2688792 0.6958733 -0.4080680 0.5262555 +VERTEX_SE3:QUAT 3269 11.723281 11.701140 -5.883506 0.7605150 0.2565069 -0.1672353 0.5725849 +VERTEX_SE3:QUAT 3270 11.583734 11.705117 -5.916308 0.2371029 -0.0753369 -0.6046864 0.7566115 +VERTEX_SE3:QUAT 3271 11.394109 11.687540 -5.805865 -0.2062268 0.5793859 -0.7190807 0.3235821 +VERTEX_SE3:QUAT 3272 11.464064 11.778434 -5.914573 -0.2336224 0.4679701 -0.5873838 0.6175798 +VERTEX_SE3:QUAT 3273 11.540415 11.887771 -6.008707 0.3767109 -0.0948226 -0.2682672 0.8815499 +VERTEX_SE3:QUAT 3274 11.560715 11.917246 -6.171965 0.0658699 0.9280629 -0.3430745 0.1290748 +VERTEX_SE3:QUAT 3275 11.532662 11.742632 -6.140452 0.8001387 -0.5075378 -0.1502885 0.2821291 +VERTEX_SE3:QUAT 3276 11.570541 11.681387 -6.102730 0.2934930 0.0845159 -0.8713291 0.3840632 +VERTEX_SE3:QUAT 3277 11.398677 11.677377 -6.148758 0.0450412 -0.4538046 0.3564225 0.8154727 +VERTEX_SE3:QUAT 3278 11.467624 11.709989 -6.091620 0.2781410 -0.9374683 0.1797708 0.1071129 +VERTEX_SE3:QUAT 3279 11.354680 11.544838 -6.156335 0.3886196 0.1477272 0.6923559 0.5897412 +VERTEX_SE3:QUAT 3280 11.375564 11.443535 -6.095560 0.8789766 -0.0373065 -0.4146707 0.2325007 +VERTEX_SE3:QUAT 3281 11.365578 11.449978 -6.005949 -0.1092662 0.6998057 -0.5796524 0.4029094 +VERTEX_SE3:QUAT 3282 11.286453 11.410707 -5.957269 0.7834348 0.4648550 0.0161807 0.4121626 +VERTEX_SE3:QUAT 3283 11.420524 11.379898 -5.848839 0.1837017 -0.8433391 -0.0108382 0.5048914 +VERTEX_SE3:QUAT 3284 11.254212 11.438457 -5.986155 -0.4331807 0.7417592 -0.3969470 0.3233898 +VERTEX_SE3:QUAT 3285 11.324722 11.438418 -6.149593 -0.5665710 0.3096570 -0.7507649 0.1395056 +VERTEX_SE3:QUAT 3286 11.418245 11.254084 -6.157259 0.1369480 -0.5029054 0.2495222 0.8161312 +VERTEX_SE3:QUAT 3287 11.464365 11.255261 -6.212741 0.3821370 0.4019850 0.0128200 0.8319946 +VERTEX_SE3:QUAT 3288 11.472326 11.025410 -6.048348 0.4796874 -0.7254067 0.4119810 0.2719501 +VERTEX_SE3:QUAT 3289 11.207476 10.983755 -6.215606 0.0693439 -0.8971668 0.4304268 0.0708232 +VERTEX_SE3:QUAT 3290 11.282125 10.803447 -6.062032 0.0007312 -0.0823544 -0.8255273 0.5583205 +VERTEX_SE3:QUAT 3291 11.322343 10.742841 -5.985760 0.1035318 0.0021890 -0.9303757 0.3516780 +VERTEX_SE3:QUAT 3292 11.219046 10.680144 -6.157699 0.6049796 -0.3715776 0.6998621 0.0782484 +VERTEX_SE3:QUAT 3293 11.312252 10.619893 -6.180978 0.0544404 -0.1884424 0.3769863 0.9052110 +VERTEX_SE3:QUAT 3294 11.255778 10.589607 -6.195681 -0.2851674 -0.0918515 0.8926195 0.3368579 +VERTEX_SE3:QUAT 3295 11.165732 10.470514 -6.085379 -0.2705175 -0.9108003 0.3116430 0.0119067 +VERTEX_SE3:QUAT 3296 11.035034 10.329229 -6.107575 -0.0971442 0.1826003 -0.9444889 0.2552662 +VERTEX_SE3:QUAT 3297 10.929941 10.375378 -5.960192 0.1092020 0.1808483 0.3743124 0.9029170 +VERTEX_SE3:QUAT 3298 10.957231 10.378470 -5.827942 0.2460856 -0.5482279 -0.0324732 0.7986448 +VERTEX_SE3:QUAT 3299 11.059951 10.340293 -5.803833 0.2637501 0.6147372 0.0723538 0.7397966 +VERTEX_SE3:QUAT 3300 11.028965 10.167297 -5.729471 0.4421754 -0.3177085 0.4367261 0.7161093 +VERTEX_SE3:QUAT 3301 11.112538 10.160689 -5.680078 0.5967237 -0.1764625 -0.6696190 0.4054531 +VERTEX_SE3:QUAT 3302 11.018231 10.089186 -5.550441 0.1384845 -0.1145176 0.9363999 0.3014348 +VERTEX_SE3:QUAT 3303 11.161146 9.871559 -5.501387 0.2246623 0.2385146 0.7716992 0.5450853 +VERTEX_SE3:QUAT 3304 11.001834 9.712689 -5.400476 0.4986339 0.0336980 0.2735338 0.8218321 +VERTEX_SE3:QUAT 3305 10.917050 9.778750 -5.423670 -0.3699942 -0.5273573 0.7111996 0.2814136 +VERTEX_SE3:QUAT 3306 10.860973 9.938944 -5.471433 0.0961274 -0.6872177 0.4656779 0.5492135 +VERTEX_SE3:QUAT 3307 10.875595 10.019735 -5.423812 0.1791835 0.1303566 -0.7118922 0.6664157 +VERTEX_SE3:QUAT 3308 10.767449 9.883661 -5.463651 -0.2782574 -0.3776919 0.8070971 0.3584912 +VERTEX_SE3:QUAT 3309 10.738775 9.776816 -5.409570 -0.1324315 0.1579937 -0.0278648 0.9781224 +VERTEX_SE3:QUAT 3310 10.606363 9.579331 -5.201547 0.7095610 -0.3069415 0.6342442 0.0066650 +VERTEX_SE3:QUAT 3311 10.694683 9.577916 -5.192176 0.6811138 -0.4224795 0.4511055 0.3925544 +VERTEX_SE3:QUAT 3312 10.785491 9.465501 -4.994750 0.1230174 0.7884175 -0.3060093 0.5192523 +VERTEX_SE3:QUAT 3313 10.887141 9.428932 -5.044183 0.0793456 -0.5895278 0.1619268 0.7873633 +VERTEX_SE3:QUAT 3314 10.969779 9.373058 -4.916773 0.3433429 0.4508463 -0.7698243 0.2936389 +VERTEX_SE3:QUAT 3315 10.913797 9.392424 -4.876164 0.6917429 0.2949129 -0.5959321 0.2817498 +VERTEX_SE3:QUAT 3316 10.890069 9.287808 -4.547729 0.4891966 0.0793369 0.0257461 0.8681760 +VERTEX_SE3:QUAT 3317 11.005474 9.463718 -4.369616 0.4429742 0.2500210 -0.0850939 0.8567511 +VERTEX_SE3:QUAT 3318 11.193887 9.475296 -4.438544 0.5384263 0.6648412 -0.2852816 0.4320854 +VERTEX_SE3:QUAT 3319 11.146684 9.260382 -4.481758 -0.0309260 -0.7371169 -0.0060312 0.6750303 +VERTEX_SE3:QUAT 3320 10.971111 9.432123 -4.447515 0.2196715 0.9372102 -0.2696073 0.0263329 +VERTEX_SE3:QUAT 3321 10.949849 9.475032 -4.367802 0.1513602 0.7726904 -0.5511358 0.2762047 +VERTEX_SE3:QUAT 3322 10.992904 9.454639 -4.337717 0.0637400 0.0556466 0.4527771 0.8875999 +VERTEX_SE3:QUAT 3323 10.897833 9.509081 -4.159582 0.2048263 0.6988495 -0.6018150 0.3278328 +VERTEX_SE3:QUAT 3324 10.825850 9.660416 -4.089170 0.7609717 -0.3522534 0.5363434 0.0957882 +VERTEX_SE3:QUAT 3325 10.695278 9.753951 -4.134962 0.9116387 0.0444680 -0.1705004 0.3713045 +VERTEX_SE3:QUAT 3326 10.762576 9.856833 -3.922044 -0.0327949 -0.1581706 0.4794921 0.8625508 +VERTEX_SE3:QUAT 3327 10.655990 9.959666 -3.747601 -0.3001937 0.8009047 -0.4637857 0.2309508 +VERTEX_SE3:QUAT 3328 10.543131 9.999725 -3.634850 -0.0746645 0.2775666 -0.7502465 0.5954092 +VERTEX_SE3:QUAT 3329 10.575329 10.045152 -3.723060 0.7827851 0.3414092 -0.0622125 0.5165432 +VERTEX_SE3:QUAT 3330 10.681979 9.904731 -3.470556 0.1424637 -0.3728851 -0.2325455 0.8868954 +VERTEX_SE3:QUAT 3331 10.737286 9.967783 -3.438159 0.7974416 -0.1177611 0.5588810 0.1946052 +VERTEX_SE3:QUAT 3332 10.787343 9.942181 -3.469929 0.5649533 0.0930262 -0.4016023 0.7147653 +VERTEX_SE3:QUAT 3333 10.806278 9.958848 -3.429791 0.6903465 -0.1439513 -0.6910591 0.1585468 +VERTEX_SE3:QUAT 3334 10.799729 10.047040 -3.601487 0.2095163 -0.3617253 -0.7138215 0.5618866 +VERTEX_SE3:QUAT 3335 10.932468 10.149505 -3.564402 0.4008958 0.0084979 -0.4859308 0.7765833 +VERTEX_SE3:QUAT 3336 10.980598 10.363612 -3.654351 0.0765311 -0.9153260 0.3831282 0.0976430 +VERTEX_SE3:QUAT 3337 11.063116 10.202687 -3.862305 -0.0184565 -0.8698580 0.4412628 0.2197581 +VERTEX_SE3:QUAT 3338 11.086046 10.413176 -4.057986 0.2447714 -0.3680076 0.4699098 0.7640956 +VERTEX_SE3:QUAT 3339 10.925824 10.377846 -3.954680 0.7097839 -0.5443557 -0.1902091 0.4046036 +VERTEX_SE3:QUAT 3340 10.962044 10.362372 -3.928007 -0.1558406 0.6581458 -0.7071618 0.2061067 +VERTEX_SE3:QUAT 3341 10.998881 10.367156 -3.710763 0.4188016 0.2070986 0.3374457 0.8172183 +VERTEX_SE3:QUAT 3342 10.988769 10.304081 -3.733987 0.4555802 -0.1671113 0.6348861 0.6011989 +VERTEX_SE3:QUAT 3343 10.831937 10.279165 -3.733565 0.6922061 0.1542205 0.2020305 0.6754631 +VERTEX_SE3:QUAT 3344 10.831236 10.328962 -3.823039 0.2743767 0.4725885 -0.8367945 0.0339484 +VERTEX_SE3:QUAT 3345 10.768838 10.402436 -3.775307 0.2181220 -0.0782378 -0.3490711 0.9079929 +VERTEX_SE3:QUAT 3346 10.865519 10.477523 -3.802780 0.5983356 0.6964761 -0.2822037 0.2779868 +VERTEX_SE3:QUAT 3347 11.034565 10.590558 -3.845960 0.1048345 -0.1431050 0.5812656 0.7941417 +VERTEX_SE3:QUAT 3348 11.120400 10.596995 -3.893368 0.4317467 0.1842718 0.2051923 0.8587985 +VERTEX_SE3:QUAT 3349 11.019004 10.619039 -3.802618 0.1461524 0.0666929 -0.7462297 0.6460130 +VERTEX_SE3:QUAT 3350 10.941430 10.749477 -3.835052 0.3210269 0.6865317 -0.3524839 0.5489727 +VERTEX_SE3:QUAT 3351 10.955129 10.598031 -3.951054 0.4001375 0.5612767 -0.5106650 0.5138869 +VERTEX_SE3:QUAT 3352 10.972446 10.567067 -3.930547 0.5117733 0.2145361 0.7178082 0.4204924 +VERTEX_SE3:QUAT 3353 10.892881 10.699346 -3.880608 0.4842044 0.3518714 -0.7402044 0.3063170 +VERTEX_SE3:QUAT 3354 10.976235 10.713981 -3.856177 -0.0453939 0.1406667 0.3539397 0.9235145 +VERTEX_SE3:QUAT 3355 11.090099 10.612107 -3.882211 -0.1642954 -0.0364572 0.4435916 0.8802866 +VERTEX_SE3:QUAT 3356 11.124882 10.644365 -3.943810 -0.0647232 0.1315890 -0.2342910 0.9610426 +VERTEX_SE3:QUAT 3357 10.879529 10.664701 -4.116655 -0.2668792 0.2591123 -0.9217317 0.1097592 +VERTEX_SE3:QUAT 3358 10.894541 10.836752 -4.331486 0.1785061 -0.0494815 0.2261064 0.9563279 +VERTEX_SE3:QUAT 3359 10.895136 10.934264 -4.386937 -0.1313919 -0.4273163 0.8910930 0.0780398 +VERTEX_SE3:QUAT 3360 11.003434 10.903833 -4.468102 0.0683203 -0.1009693 -0.9900612 0.0701168 +VERTEX_SE3:QUAT 3361 10.979165 11.152869 -4.274124 0.4142761 -0.5006442 0.7585120 0.0488895 +VERTEX_SE3:QUAT 3362 11.024620 11.024982 -4.386927 0.0198884 0.6169759 -0.7347673 0.2811799 +VERTEX_SE3:QUAT 3363 11.214022 11.048817 -4.521913 0.0532254 0.8193537 -0.3872974 0.4193177 +VERTEX_SE3:QUAT 3364 11.104761 11.009241 -4.604894 0.0533917 -0.1734513 -0.9832700 0.0156229 +VERTEX_SE3:QUAT 3365 11.140838 11.047590 -4.650351 -0.1912681 -0.5611454 -0.0963311 0.7995328 +VERTEX_SE3:QUAT 3366 11.147839 11.155909 -4.761813 0.1652258 0.4136890 -0.6519439 0.6136212 +VERTEX_SE3:QUAT 3367 11.044724 11.214747 -4.878790 0.2057972 -0.6979272 -0.1312693 0.6732856 +VERTEX_SE3:QUAT 3368 11.235753 11.274690 -4.866617 0.2441506 -0.6728650 -0.2302679 0.6592571 +VERTEX_SE3:QUAT 3369 11.379969 11.317906 -4.961630 0.3171293 -0.8469356 0.2964438 0.3070020 +VERTEX_SE3:QUAT 3370 11.337451 11.173304 -5.149281 -0.2148133 -0.1364687 0.3367912 0.9065336 +VERTEX_SE3:QUAT 3371 11.395123 11.271389 -5.023804 -0.3682223 -0.3794560 0.7470565 0.4029044 +VERTEX_SE3:QUAT 3372 11.316563 11.111960 -5.140555 0.0966012 0.4335887 -0.6990625 0.5603398 +VERTEX_SE3:QUAT 3373 11.291989 11.041109 -5.051795 -0.2941196 -0.1561997 0.9108391 0.2438594 +VERTEX_SE3:QUAT 3374 11.416783 11.093915 -5.099932 0.4686085 0.8020982 -0.3258676 0.1756554 +VERTEX_SE3:QUAT 3375 11.426412 11.021549 -5.013454 -0.1268431 -0.6608914 -0.0862761 0.7346358 +VERTEX_SE3:QUAT 3376 11.705940 10.974786 -5.041653 0.1363048 -0.0880667 -0.6544296 0.7385033 +VERTEX_SE3:QUAT 3377 11.702800 10.608201 -5.087320 0.0680498 -0.7586534 0.5456518 0.3493970 +VERTEX_SE3:QUAT 3378 11.546386 10.708654 -5.219983 -0.4603253 -0.4602392 0.2869893 0.7027927 +VERTEX_SE3:QUAT 3379 11.396121 10.622158 -5.223612 0.5669937 -0.4854960 0.6255564 0.2269162 +VERTEX_SE3:QUAT 3380 11.349859 10.453432 -5.299307 0.2817859 0.3486023 -0.2716457 0.8516348 +VERTEX_SE3:QUAT 3381 11.311477 10.220002 -5.308181 -0.0569700 -0.7179185 0.1497811 0.6774312 +VERTEX_SE3:QUAT 3382 11.430020 10.116234 -5.236591 0.3489251 -0.0575258 -0.8756026 0.3290322 +VERTEX_SE3:QUAT 3383 11.478441 10.248368 -5.210077 -0.0740576 0.1044592 0.8829428 0.4516810 +VERTEX_SE3:QUAT 3384 11.552106 10.198586 -5.161584 0.1817619 -0.5751462 0.3630023 0.7102104 +VERTEX_SE3:QUAT 3385 11.679086 10.082891 -5.254541 -0.0740515 0.6546074 -0.6685196 0.3450899 +VERTEX_SE3:QUAT 3386 11.501701 10.133362 -5.305282 0.4317262 -0.4295850 0.4010892 0.6842490 +VERTEX_SE3:QUAT 3387 11.612239 10.121648 -5.481459 0.3986208 -0.5637792 -0.0076719 0.7233226 +VERTEX_SE3:QUAT 3388 11.468472 10.069158 -5.514325 0.4061304 -0.4814660 -0.2580630 0.7325654 +VERTEX_SE3:QUAT 3389 11.559899 9.978994 -5.402635 0.5529599 -0.0779569 0.6430212 0.5241010 +VERTEX_SE3:QUAT 3390 11.304627 9.886092 -5.289479 0.5187371 -0.1532724 -0.6938749 0.4753493 +VERTEX_SE3:QUAT 3391 11.346718 10.041149 -5.336625 0.4546562 0.2773384 -0.7832440 0.3207802 +VERTEX_SE3:QUAT 3392 11.460369 9.751330 -5.493634 -0.0043347 0.5605026 -0.7982519 0.2204812 +VERTEX_SE3:QUAT 3393 11.517200 9.737926 -5.510954 0.0548849 0.6877919 -0.5940773 0.4135241 +VERTEX_SE3:QUAT 3394 11.475317 9.681163 -5.396710 0.7151580 -0.5038619 0.4810535 0.0570949 +VERTEX_SE3:QUAT 3395 11.518989 9.531573 -5.237769 0.1826764 -0.6231560 -0.2452645 0.7198273 +VERTEX_SE3:QUAT 3396 11.362300 9.380560 -5.147830 -0.4651927 -0.1896535 0.8105002 0.3011922 +VERTEX_SE3:QUAT 3397 11.460971 9.307498 -5.121471 -0.0633902 -0.2191129 0.3162449 0.9208476 +VERTEX_SE3:QUAT 3398 11.540939 9.254505 -5.126189 0.6130926 0.1343687 -0.3628891 0.6887481 +VERTEX_SE3:QUAT 3399 11.512455 9.242630 -5.173081 -0.1100247 0.4782597 -0.7781099 0.3920551 +VERTEX_SE3:QUAT 3400 11.499980 9.312326 -4.967762 -0.1832006 0.8830055 -0.3618551 0.2362196 +VERTEX_SE3:QUAT 3401 11.449064 9.138735 -4.891368 0.9314826 0.1239386 -0.3286808 0.0945954 +VERTEX_SE3:QUAT 3402 11.313034 9.138611 -4.972556 0.6458961 -0.5839006 0.1186582 0.4772824 +VERTEX_SE3:QUAT 3403 11.268036 9.053408 -4.850293 -0.2994356 -0.5443423 0.3793613 0.6856491 +VERTEX_SE3:QUAT 3404 11.229370 8.900763 -4.775782 0.6424696 -0.1559694 -0.6405588 0.3906287 +VERTEX_SE3:QUAT 3405 11.173079 8.907729 -4.710613 0.0843287 -0.7191356 0.6579902 0.2068372 +VERTEX_SE3:QUAT 3406 11.049802 8.828345 -4.611949 0.3302958 -0.0879023 0.2886401 0.8943516 +VERTEX_SE3:QUAT 3407 10.973371 8.768358 -4.701717 0.3533059 -0.8916945 0.1903404 0.2093474 +VERTEX_SE3:QUAT 3408 11.017606 8.895151 -4.800031 0.5579322 -0.0019459 0.8164768 0.1485717 +VERTEX_SE3:QUAT 3409 10.833537 8.923801 -4.660008 0.0279294 -0.5016158 0.8404066 0.2032692 +VERTEX_SE3:QUAT 3410 10.752309 8.801910 -4.825173 0.1672088 0.7329674 -0.5598200 0.3484274 +VERTEX_SE3:QUAT 3411 10.639498 8.842882 -4.897070 -0.0396009 0.5613291 -0.0821857 0.8225491 +VERTEX_SE3:QUAT 3412 10.646555 8.795380 -4.961710 0.0551476 -0.0191471 0.3685114 0.9277885 +VERTEX_SE3:QUAT 3413 10.615070 8.598026 -5.059058 0.7933288 -0.0920566 -0.3353746 0.4996788 +VERTEX_SE3:QUAT 3414 10.619834 8.459501 -4.989572 0.0890797 -0.6147691 -0.0633161 0.7810985 +VERTEX_SE3:QUAT 3415 10.441872 8.493559 -4.857234 -0.2272069 -0.7689250 0.2728439 0.5316837 +VERTEX_SE3:QUAT 3416 10.441761 8.614499 -4.872703 0.3135408 -0.1810904 0.9318484 0.0236001 +VERTEX_SE3:QUAT 3417 10.283213 8.355893 -4.810420 0.1494773 -0.0968858 -0.9835428 0.0302209 +VERTEX_SE3:QUAT 3418 10.291237 8.399851 -4.726265 0.8613323 0.2826536 -0.1181122 0.4052939 +VERTEX_SE3:QUAT 3419 10.200292 8.581909 -4.622603 -0.2534676 0.4655678 -0.7891468 0.3102389 +VERTEX_SE3:QUAT 3420 10.215414 8.493054 -4.539736 -0.4123353 0.5387713 -0.7251861 0.1175169 +VERTEX_SE3:QUAT 3421 10.210774 8.420643 -4.544081 0.9170895 0.3646045 -0.1604736 0.0160831 +VERTEX_SE3:QUAT 3422 10.176504 8.486150 -4.481579 0.2711916 0.3433033 -0.4638312 0.7703626 +VERTEX_SE3:QUAT 3423 10.132791 8.593667 -4.550099 0.8452588 0.1877838 -0.1336943 0.4820795 +VERTEX_SE3:QUAT 3424 10.085996 8.697744 -4.555645 0.0591648 0.0420912 -0.9931971 0.0910352 +VERTEX_SE3:QUAT 3425 10.101267 8.566265 -4.619008 0.5437483 -0.0609199 0.6349521 0.5454011 +VERTEX_SE3:QUAT 3426 10.211708 8.561418 -4.831519 0.4766933 0.3587556 0.3323589 0.7304762 +VERTEX_SE3:QUAT 3427 10.251329 8.534162 -4.739138 -0.7602348 0.5088381 -0.3926965 0.0944259 +VERTEX_SE3:QUAT 3428 10.241725 8.587823 -4.706084 0.2324414 0.1317540 0.3351202 0.9034967 +VERTEX_SE3:QUAT 3429 10.220314 8.787430 -4.831250 0.9679615 -0.1530534 -0.1005928 0.1717740 +VERTEX_SE3:QUAT 3430 10.219463 8.826355 -4.588052 0.5836168 -0.1183903 -0.0677910 0.8004871 +VERTEX_SE3:QUAT 3431 10.317700 8.852862 -4.627528 -0.2797595 0.9097417 -0.2750332 0.1358728 +VERTEX_SE3:QUAT 3432 10.529109 8.835323 -4.478609 0.4846922 0.2099562 -0.3435320 0.7765163 +VERTEX_SE3:QUAT 3433 10.587959 8.948459 -4.428095 -0.7583628 0.5291634 -0.3518635 0.1451345 +VERTEX_SE3:QUAT 3434 10.468859 8.874952 -4.540242 -0.1528739 -0.5036122 0.7470518 0.4061009 +VERTEX_SE3:QUAT 3435 10.323751 9.008611 -4.663442 0.0837525 0.6850079 -0.5259813 0.4970849 +VERTEX_SE3:QUAT 3436 10.329040 9.080954 -4.698093 0.8559818 -0.0679756 -0.2773733 0.4309739 +VERTEX_SE3:QUAT 3437 10.280854 9.030263 -4.620501 0.3750931 0.4308732 -0.6542782 0.4955536 +VERTEX_SE3:QUAT 3438 10.418710 9.174415 -4.676525 0.0040902 0.3344693 -0.4848978 0.8080765 +VERTEX_SE3:QUAT 3439 10.508559 9.152473 -4.669459 0.6131423 0.0962808 -0.7613751 0.1873351 +VERTEX_SE3:QUAT 3440 10.399351 9.173004 -4.696890 -0.3070442 0.8693973 -0.1384201 0.3615412 +VERTEX_SE3:QUAT 3441 10.291208 9.202413 -4.733333 0.6469544 -0.3498732 -0.1570075 0.6590808 +VERTEX_SE3:QUAT 3442 10.243073 9.226276 -4.509545 0.8652912 -0.3077626 0.0181464 0.3952518 +VERTEX_SE3:QUAT 3443 10.285159 9.235471 -4.531301 -0.7528114 0.5884444 -0.2634241 0.1327253 +VERTEX_SE3:QUAT 3444 10.274288 9.320586 -4.381687 0.1292274 -0.2791313 0.5267117 0.7924397 +VERTEX_SE3:QUAT 3445 10.234436 9.423111 -4.338687 0.0287433 -0.2654987 -0.0907441 0.9594007 +VERTEX_SE3:QUAT 3446 10.255471 9.512277 -4.390316 0.0861086 0.2272374 -0.8763991 0.4157802 +VERTEX_SE3:QUAT 3447 10.166509 9.707916 -4.499023 -0.0728218 -0.6071665 0.4160695 0.6730023 +VERTEX_SE3:QUAT 3448 10.241836 9.669693 -4.541431 0.1936618 -0.5212511 0.8242494 0.1067957 +VERTEX_SE3:QUAT 3449 10.240645 9.660664 -4.555183 0.7298259 0.0019474 0.2881024 0.6199576 +VERTEX_SE3:QUAT 3450 10.201902 9.701851 -4.465117 0.6921872 -0.3058781 -0.3816523 0.5307137 +VERTEX_SE3:QUAT 3451 10.364611 9.610702 -4.376401 0.2561175 0.8056310 -0.4836554 0.2268040 +VERTEX_SE3:QUAT 3452 10.150569 9.713327 -4.252636 -0.8203146 -0.3339525 0.3511961 0.3036792 +VERTEX_SE3:QUAT 3453 10.147533 9.639477 -4.024526 0.1716344 -0.2325999 -0.2372446 0.9274448 +VERTEX_SE3:QUAT 3454 10.170402 9.449324 -3.953680 0.6906667 0.0023891 0.4138596 0.5930380 +VERTEX_SE3:QUAT 3455 10.242837 9.621387 -3.865629 0.1307232 -0.4478209 0.8594622 0.2090278 +VERTEX_SE3:QUAT 3456 10.014056 9.662125 -3.930894 0.1875182 0.2396348 -0.9497222 0.0737548 +VERTEX_SE3:QUAT 3457 9.989810 9.626547 -3.885573 0.3591639 -0.0191956 0.2509595 0.8986947 +VERTEX_SE3:QUAT 3458 10.100222 9.710507 -3.978142 0.5238347 -0.1310943 -0.7217773 0.4329538 +VERTEX_SE3:QUAT 3459 10.012699 9.632244 -3.903159 0.4002445 0.3924591 -0.5883892 0.5827335 +VERTEX_SE3:QUAT 3460 10.034504 9.789360 -3.948515 0.3646820 0.5891173 -0.6265119 0.3569744 +VERTEX_SE3:QUAT 3461 10.060161 9.796569 -3.961607 0.9260909 -0.3626804 -0.0167926 0.1026473 +VERTEX_SE3:QUAT 3462 10.312350 9.815185 -3.860879 0.8950944 0.4199722 0.0521833 0.1403786 +VERTEX_SE3:QUAT 3463 10.316007 9.882352 -3.831934 -0.0845610 0.5979453 -0.5997063 0.5250363 +VERTEX_SE3:QUAT 3464 10.476185 10.088902 -3.970404 -0.5747363 0.4777048 -0.6352015 0.1949237 +VERTEX_SE3:QUAT 3465 10.449341 10.317427 -3.823871 0.8195533 0.2929786 0.4163683 0.2629324 +VERTEX_SE3:QUAT 3466 10.533239 10.216964 -3.692155 0.3837781 -0.7093383 0.1107447 0.5807660 +VERTEX_SE3:QUAT 3467 10.469352 10.054058 -3.548355 0.4772628 0.7140564 0.1044004 0.5014423 +VERTEX_SE3:QUAT 3468 10.566536 10.070337 -3.319428 -0.5172880 -0.3247602 0.7906954 0.0417689 +VERTEX_SE3:QUAT 3469 10.759233 10.039305 -3.270141 0.2588849 -0.4247760 0.6850894 0.5321621 +VERTEX_SE3:QUAT 3470 10.844770 10.052247 -3.261878 0.4314458 -0.4988342 -0.1421074 0.7381222 +VERTEX_SE3:QUAT 3471 10.821966 10.165958 -3.335764 0.7136768 0.2104572 0.3840383 0.5467063 +VERTEX_SE3:QUAT 3472 11.137670 10.288000 -3.265497 0.5213005 0.6557571 -0.1323310 0.5298273 +VERTEX_SE3:QUAT 3473 11.251539 10.191252 -3.296809 0.2770866 0.2229872 -0.7472830 0.5613090 +VERTEX_SE3:QUAT 3474 11.374496 10.109426 -3.188690 0.8816724 -0.1231167 0.0579764 0.4518127 +VERTEX_SE3:QUAT 3475 11.258268 10.084500 -3.163448 0.4391387 0.2766033 0.3708052 0.7701631 +VERTEX_SE3:QUAT 3476 11.334288 10.090766 -3.059146 0.1478853 -0.6548930 0.1844213 0.7177980 +VERTEX_SE3:QUAT 3477 11.360260 10.105704 -2.759798 0.0644445 -0.5399222 0.7950837 0.2686501 +VERTEX_SE3:QUAT 3478 11.196427 10.039435 -2.750857 -0.1070962 0.3572920 -0.4234394 0.8255737 +VERTEX_SE3:QUAT 3479 11.217049 9.878188 -2.689516 0.3573285 0.9192144 0.0874359 0.1404143 +VERTEX_SE3:QUAT 3480 11.149947 9.734101 -2.647142 0.3919541 0.6181024 -0.3091160 0.6072634 +VERTEX_SE3:QUAT 3481 11.173391 9.663467 -2.441116 -0.5331283 -0.6677540 0.5180192 0.0391786 +VERTEX_SE3:QUAT 3482 11.288227 9.648139 -2.399767 -0.9509421 0.2448745 -0.1431484 0.1235080 +VERTEX_SE3:QUAT 3483 11.306010 9.676697 -2.579541 0.5567238 0.3667465 -0.5920869 0.4527569 +VERTEX_SE3:QUAT 3484 11.151404 9.557141 -2.615420 0.5423447 -0.0295662 -0.5276547 0.6531222 +VERTEX_SE3:QUAT 3485 11.144607 9.638080 -2.521729 0.2922780 0.3319650 -0.4217319 0.7915270 +VERTEX_SE3:QUAT 3486 11.187376 9.539854 -2.697212 -0.2303876 -0.9186129 0.1562075 0.2804839 +VERTEX_SE3:QUAT 3487 10.992994 9.395155 -2.915275 -0.5819992 0.3954898 -0.6979455 0.1331798 +VERTEX_SE3:QUAT 3488 11.179602 9.498904 -2.834432 0.1266655 -0.5659170 0.6361866 0.5088815 +VERTEX_SE3:QUAT 3489 11.249569 9.366031 -2.803826 0.7857089 -0.1968750 -0.5628070 0.1647726 +VERTEX_SE3:QUAT 3490 11.387401 9.338727 -2.664018 0.5003962 0.4356052 -0.7479812 0.0193900 +VERTEX_SE3:QUAT 3491 11.492801 9.277093 -2.668010 -0.3480767 -0.9370207 0.0226380 0.0179537 +VERTEX_SE3:QUAT 3492 11.562305 9.123421 -2.729693 0.7136385 -0.6610044 0.0337237 0.2294691 +VERTEX_SE3:QUAT 3493 11.549846 9.075522 -2.696056 0.3404286 0.8236427 -0.1713713 0.4199440 +VERTEX_SE3:QUAT 3494 11.613748 9.111935 -2.720996 0.2175919 -0.5577090 0.2575453 0.7584754 +VERTEX_SE3:QUAT 3495 11.668672 9.045225 -2.624668 0.1114608 0.3667148 -0.9204346 0.0767909 +VERTEX_SE3:QUAT 3496 11.618602 9.055388 -2.661067 0.8534414 -0.3684947 -0.3657138 0.0458559 +VERTEX_SE3:QUAT 3497 11.579133 8.766829 -2.633449 0.7816714 -0.0499134 0.4748448 0.4012740 +VERTEX_SE3:QUAT 3498 11.393830 8.840034 -2.708537 0.7586492 0.4897636 0.2732972 0.3314990 +VERTEX_SE3:QUAT 3499 11.338552 8.844707 -2.480394 0.7525438 0.0366131 0.5937588 0.2824674 +VERTEX_SE3:QUAT 3500 11.293414 8.832192 -2.528024 0.6931668 -0.6917516 0.0414088 0.1982039 +VERTEX_SE3:QUAT 3501 11.190384 8.859768 -2.535567 0.3977953 0.4099618 -0.7168375 0.3997927 +VERTEX_SE3:QUAT 3502 11.233069 8.778565 -2.595017 -0.3823637 0.2783679 -0.8787566 0.0640015 +VERTEX_SE3:QUAT 3503 11.194724 8.742948 -2.567627 0.0178502 -0.9863874 -0.1064229 0.1240786 +VERTEX_SE3:QUAT 3504 11.190281 8.496849 -2.522122 -0.7685498 -0.4890366 0.2675781 0.3139688 +VERTEX_SE3:QUAT 3505 11.207590 8.539496 -2.518474 0.7675286 -0.6247777 0.1429651 0.0106619 +VERTEX_SE3:QUAT 3506 11.223397 8.399178 -2.584497 0.5289559 -0.4864730 0.6061713 0.3407434 +VERTEX_SE3:QUAT 3507 11.177674 8.323914 -2.793203 -0.1138968 -0.9400823 -0.0895837 0.3086220 +VERTEX_SE3:QUAT 3508 11.068344 8.226563 -2.923153 0.4682374 0.7798887 -0.1637084 0.3817418 +VERTEX_SE3:QUAT 3509 10.936481 8.215492 -2.941102 -0.1308949 -0.7608250 0.2193240 0.5965809 +VERTEX_SE3:QUAT 3510 11.037615 8.002989 -3.032315 0.8521824 0.0743919 -0.1799587 0.4856602 +VERTEX_SE3:QUAT 3511 11.221208 7.944687 -2.995506 0.4338424 0.3380161 -0.4985851 0.6700289 +VERTEX_SE3:QUAT 3512 11.196447 7.976641 -3.026742 -0.1395547 -0.7820956 0.1211068 0.5951336 +VERTEX_SE3:QUAT 3513 11.249100 7.846614 -3.190993 0.4960089 -0.8080214 -0.0124693 0.3176809 +VERTEX_SE3:QUAT 3514 11.275762 7.854895 -3.131021 0.3989246 0.8215575 -0.1767077 0.3669834 +VERTEX_SE3:QUAT 3515 11.189863 7.886664 -2.989175 0.7783716 -0.4092352 -0.0185797 0.4757299 +VERTEX_SE3:QUAT 3516 11.187521 8.005068 -3.281597 0.4090029 0.8260417 -0.3694065 0.1179434 +VERTEX_SE3:QUAT 3517 11.185216 7.841329 -3.194621 0.5412528 -0.3917092 -0.4761390 0.5717526 +VERTEX_SE3:QUAT 3518 11.276571 7.795262 -3.130855 0.2295036 0.6225564 -0.4175642 0.6207993 +VERTEX_SE3:QUAT 3519 11.221647 7.969691 -3.092035 0.3629798 0.3544936 -0.1363941 0.8508681 +VERTEX_SE3:QUAT 3520 11.279974 7.929215 -3.189855 0.2872342 0.6566985 -0.2564342 0.6484482 +VERTEX_SE3:QUAT 3521 11.120387 7.883261 -3.090506 0.5800775 0.2780048 -0.7312716 0.2268594 +VERTEX_SE3:QUAT 3522 11.112682 7.749252 -2.975038 0.8866441 0.1998580 0.4112546 0.0691995 +VERTEX_SE3:QUAT 3523 11.082879 7.669125 -3.074127 0.5055207 -0.3693371 0.7763009 0.0734563 +VERTEX_SE3:QUAT 3524 11.156436 7.627721 -3.156383 0.1433635 -0.6210116 0.7378430 0.2222144 +VERTEX_SE3:QUAT 3525 11.184937 7.720260 -2.962068 -0.0844944 0.9349386 -0.0923737 0.3319904 +VERTEX_SE3:QUAT 3526 11.188249 7.835509 -2.961201 0.6433519 -0.5655660 0.1971015 0.4768484 +VERTEX_SE3:QUAT 3527 11.210755 7.867285 -3.112033 0.4841217 -0.5534476 0.5843968 0.3432235 +VERTEX_SE3:QUAT 3528 11.206087 7.959788 -2.961005 0.3398756 0.6605234 0.0301978 0.6687911 +VERTEX_SE3:QUAT 3529 11.204386 8.090005 -2.944937 0.9486177 0.0423570 -0.2948007 0.1068784 +VERTEX_SE3:QUAT 3530 11.186687 8.277332 -3.046646 0.3870009 -0.7047380 0.4525386 0.3857246 +VERTEX_SE3:QUAT 3531 11.271370 8.344022 -2.869541 -0.6011664 -0.1381487 0.7790306 0.1123623 +VERTEX_SE3:QUAT 3532 11.147104 8.508850 -2.812929 0.1061885 0.8296625 -0.2772447 0.4727786 +VERTEX_SE3:QUAT 3533 11.178944 8.464225 -2.853861 0.4269751 -0.7925152 -0.1007021 0.4236402 +VERTEX_SE3:QUAT 3534 11.105716 8.443760 -2.815084 0.3531630 0.1338118 -0.5636715 0.7346052 +VERTEX_SE3:QUAT 3535 11.130860 8.682591 -2.767228 0.5118784 0.6720445 0.0361716 0.5338804 +VERTEX_SE3:QUAT 3536 11.008823 8.779707 -2.614432 0.3402604 0.1881741 -0.7646127 0.5139852 +VERTEX_SE3:QUAT 3537 11.040025 8.728189 -2.867424 -0.6075314 -0.3842138 0.6874815 0.1032209 +VERTEX_SE3:QUAT 3538 11.059886 8.843897 -2.744388 0.5105607 -0.0967271 0.7093299 0.4762591 +VERTEX_SE3:QUAT 3539 11.021696 8.879922 -2.691428 -0.1206815 -0.9110786 0.1202823 0.3753718 +VERTEX_SE3:QUAT 3540 11.195078 9.054089 -2.616077 -0.2093682 -0.2856621 0.3189152 0.8791218 +VERTEX_SE3:QUAT 3541 11.257467 9.210911 -2.557862 -0.0447173 -0.1700298 0.9105381 0.3741798 +VERTEX_SE3:QUAT 3542 11.083942 9.247958 -2.461555 0.8948006 0.1074078 -0.3349770 0.2749288 +VERTEX_SE3:QUAT 3543 11.142476 9.327266 -2.476766 -0.2183127 0.8239288 -0.2876705 0.4367224 +VERTEX_SE3:QUAT 3544 11.064110 9.234990 -2.503761 0.7435157 0.2402463 -0.1639254 0.6021582 +VERTEX_SE3:QUAT 3545 11.062295 9.161627 -2.489934 0.5454967 -0.2058851 -0.6774229 0.4484896 +VERTEX_SE3:QUAT 3546 11.212422 9.251873 -2.524365 0.9156742 0.1379759 0.3649031 0.0966913 +VERTEX_SE3:QUAT 3547 11.460039 9.286827 -2.364860 0.4516611 0.5212449 -0.5122050 0.5118125 +VERTEX_SE3:QUAT 3548 11.503920 9.246928 -2.236154 0.5831305 -0.0779998 0.4726514 0.6561063 +VERTEX_SE3:QUAT 3549 11.503368 9.305266 -2.303531 -0.4259133 0.7837533 -0.2294201 0.3894806 +VERTEX_SE3:QUAT 3550 11.539366 9.249803 -2.148064 0.8208454 0.5277106 0.1471735 0.1614752 +VERTEX_SE3:QUAT 3551 11.530715 9.176953 -2.096403 0.1076880 -0.2382805 0.4518994 0.8528849 +VERTEX_SE3:QUAT 3552 11.436188 9.385172 -2.053962 0.6413640 0.4314816 0.5848237 0.2458803 +VERTEX_SE3:QUAT 3553 11.335296 9.452293 -2.255373 0.8404668 -0.4794026 0.1739197 0.1831412 +VERTEX_SE3:QUAT 3554 11.448682 9.542424 -2.162294 -0.2037165 -0.8706746 0.3156975 0.3174279 +VERTEX_SE3:QUAT 3555 11.385453 9.640744 -2.149096 0.0979076 0.2980417 0.2692165 0.9105535 +VERTEX_SE3:QUAT 3556 11.151092 9.936528 -2.064973 0.7578384 0.3221557 -0.5611747 0.0835442 +VERTEX_SE3:QUAT 3557 11.374998 9.958835 -2.045461 -0.0246696 -0.8503439 0.4628410 0.2491684 +VERTEX_SE3:QUAT 3558 11.461054 10.027608 -1.975938 0.0815558 0.3781148 -0.4279181 0.8168623 +VERTEX_SE3:QUAT 3559 11.537959 10.233561 -2.039102 -0.5311898 0.8438501 -0.0749326 0.0118100 +VERTEX_SE3:QUAT 3560 11.397076 10.290836 -2.032033 0.1539162 0.5605985 -0.1015216 0.8072995 +VERTEX_SE3:QUAT 3561 11.605657 10.334522 -1.878206 0.0221302 -0.7845789 0.3600345 0.5043029 +VERTEX_SE3:QUAT 3562 11.677646 10.494832 -1.895789 -0.0681903 0.5540628 -0.4230134 0.7137396 +VERTEX_SE3:QUAT 3563 11.671804 10.619302 -2.005155 0.6718335 0.1495007 0.4964015 0.5290321 +VERTEX_SE3:QUAT 3564 11.659620 10.701668 -1.981386 0.6526509 0.1692051 -0.6974439 0.2428754 +VERTEX_SE3:QUAT 3565 11.711965 10.700585 -2.021352 0.8193321 0.0704546 0.5673059 0.0435325 +VERTEX_SE3:QUAT 3566 11.856889 10.690645 -2.010428 0.2582973 0.7164110 -0.3020979 0.5733888 +VERTEX_SE3:QUAT 3567 11.920261 10.878325 -1.928269 0.9677525 -0.0757267 -0.1150521 0.2109112 +VERTEX_SE3:QUAT 3568 12.031655 10.852080 -2.062924 0.6419461 0.5976673 0.1339223 0.4612633 +VERTEX_SE3:QUAT 3569 12.109710 10.839454 -2.062551 -0.4994711 0.5694837 -0.6500131 0.0608262 +VERTEX_SE3:QUAT 3570 12.439755 10.916488 -2.177156 0.5470453 0.0332920 0.5494401 0.6306732 +VERTEX_SE3:QUAT 3571 12.344828 11.002294 -2.176543 0.3710083 0.8818892 -0.1419530 0.2539166 +VERTEX_SE3:QUAT 3572 12.471585 11.135289 -2.201102 0.4162823 0.1818552 -0.6310030 0.6288664 +VERTEX_SE3:QUAT 3573 12.439469 11.189747 -2.157024 0.5908636 0.3697580 -0.4003796 0.5948575 +VERTEX_SE3:QUAT 3574 12.532050 11.262732 -2.237458 0.6741249 -0.0643697 0.7088625 0.1972971 +VERTEX_SE3:QUAT 3575 12.543921 11.231034 -2.109230 0.1092151 0.5838618 -0.7992397 0.0916159 +VERTEX_SE3:QUAT 3576 12.566608 11.241748 -2.259294 0.6276587 -0.0584088 -0.0526186 0.7745090 +VERTEX_SE3:QUAT 3577 12.539140 11.159895 -2.258758 0.1944951 -0.3548964 0.8145380 0.4156297 +VERTEX_SE3:QUAT 3578 12.594339 11.158035 -2.331838 0.6110640 0.2681466 -0.4038184 0.6258026 +VERTEX_SE3:QUAT 3579 12.686472 11.159653 -2.318884 0.4110603 0.7961702 -0.0953391 0.4336506 +VERTEX_SE3:QUAT 3580 12.804268 11.153426 -2.423202 0.8792368 -0.2761180 0.3620134 0.1401705 +VERTEX_SE3:QUAT 3581 12.829733 11.247137 -2.514133 0.9495726 -0.1690722 -0.2460914 0.0957362 +VERTEX_SE3:QUAT 3582 12.949028 11.306768 -2.379484 -0.0966741 0.6772804 -0.4081869 0.6044243 +VERTEX_SE3:QUAT 3583 12.993767 11.235491 -2.438154 0.5734191 -0.1225408 0.1559557 0.7948912 +VERTEX_SE3:QUAT 3584 12.977402 11.227953 -2.416579 0.8660466 0.1179372 -0.4287484 0.2285365 +VERTEX_SE3:QUAT 3585 13.037193 11.195451 -2.620502 0.6403165 0.4564220 -0.4482991 0.4250903 +VERTEX_SE3:QUAT 3586 12.945448 11.234648 -2.677881 0.4117627 -0.1421204 0.8168168 0.3782374 +VERTEX_SE3:QUAT 3587 12.918647 11.214948 -2.603437 0.4217097 -0.3212387 0.1298917 0.8379109 +VERTEX_SE3:QUAT 3588 13.125885 11.212533 -2.714206 -0.4451786 -0.4175586 0.7396356 0.2835489 +VERTEX_SE3:QUAT 3589 13.117726 11.123779 -2.772050 0.6121755 0.0720615 0.2270316 0.7539927 +VERTEX_SE3:QUAT 3590 13.205502 11.172634 -2.929363 0.4677970 -0.0287823 -0.0261575 0.8829798 +VERTEX_SE3:QUAT 3591 13.247045 11.165675 -2.854120 -0.9328739 0.3233528 0.1544468 0.0365427 +VERTEX_SE3:QUAT 3592 13.155446 11.078849 -2.851977 0.1467059 -0.2644839 0.9236648 0.2353062 +VERTEX_SE3:QUAT 3593 12.953309 11.087256 -2.730658 0.2400532 -0.2710572 0.0058103 0.9321313 +VERTEX_SE3:QUAT 3594 13.030374 10.955775 -2.742405 0.6227436 -0.0395515 -0.3061551 0.7189542 +VERTEX_SE3:QUAT 3595 13.040899 10.761574 -2.663504 0.8090676 0.4616739 0.2587207 0.2555981 +VERTEX_SE3:QUAT 3596 13.006535 10.756794 -2.498037 0.0462404 0.7195989 -0.2225292 0.6561402 +VERTEX_SE3:QUAT 3597 13.005447 10.604808 -2.618267 -0.4676619 0.8106947 -0.3377119 0.1000853 +VERTEX_SE3:QUAT 3598 12.996235 10.609922 -2.608305 -0.0162953 -0.2219345 0.9379842 0.2658291 +VERTEX_SE3:QUAT 3599 13.005993 10.547012 -2.448539 0.7010287 0.0708303 -0.4778443 0.5246014 +VERTEX_SE3:QUAT 3600 12.998401 10.444610 -2.436100 0.0305052 0.4331013 -0.8304814 0.3489892 +VERTEX_SE3:QUAT 3601 12.969476 10.442423 -2.484974 -0.7497567 -0.5118729 0.3959775 0.1380319 +VERTEX_SE3:QUAT 3602 13.108149 10.139086 -2.357878 0.9346620 0.2599993 -0.0263188 0.2410696 +VERTEX_SE3:QUAT 3603 13.211859 10.106633 -2.318201 0.4463332 0.7985615 -0.1555871 0.3726646 +VERTEX_SE3:QUAT 3604 13.311950 10.202534 -2.311008 0.7299159 -0.5336511 0.0417059 0.4250881 +VERTEX_SE3:QUAT 3605 13.355071 10.185222 -2.348427 -0.2384987 0.7736587 -0.4223267 0.4076896 +VERTEX_SE3:QUAT 3606 13.376881 10.308315 -2.342590 0.8386143 0.4813457 0.1865448 0.1738779 +VERTEX_SE3:QUAT 3607 13.285270 10.052360 -2.259223 -0.6234614 0.3200111 -0.7119389 0.0450750 +VERTEX_SE3:QUAT 3608 13.130880 10.103507 -2.209902 0.6577047 -0.6731648 0.0785557 0.3287897 +VERTEX_SE3:QUAT 3609 13.080338 10.028502 -2.076036 0.3170316 0.6267137 -0.5237224 0.4821159 +VERTEX_SE3:QUAT 3610 13.106776 10.086587 -2.240901 0.5787974 0.0707591 0.1847567 0.7911078 +VERTEX_SE3:QUAT 3611 13.144286 9.971911 -2.224555 0.9152887 0.1277481 -0.1454493 0.3532301 +VERTEX_SE3:QUAT 3612 13.030604 9.814077 -2.169977 -0.0345780 0.7543099 -0.6279587 0.1883847 +VERTEX_SE3:QUAT 3613 12.929129 9.734854 -2.289017 0.4731637 -0.0366402 0.8491379 0.2318153 +VERTEX_SE3:QUAT 3614 12.867332 9.667203 -2.298891 0.7979095 -0.5321709 0.1235417 0.2546999 +VERTEX_SE3:QUAT 3615 12.851848 9.706956 -2.393279 -0.1866501 0.5666133 -0.4864388 0.6383482 +VERTEX_SE3:QUAT 3616 12.841301 9.551356 -2.448821 0.1607113 -0.9476088 0.0185140 0.2754392 +VERTEX_SE3:QUAT 3617 12.796086 9.664630 -2.372352 0.3756655 0.3653069 -0.7061939 0.4761476 +VERTEX_SE3:QUAT 3618 12.843179 9.705776 -2.620438 0.6810006 -0.5918508 -0.0842026 0.4229193 +VERTEX_SE3:QUAT 3619 12.937389 9.681521 -2.547266 -0.1325057 0.2949766 -0.8707880 0.3703503 +VERTEX_SE3:QUAT 3620 12.940204 9.594794 -2.715872 0.0348009 -0.7940404 0.1640672 0.5842694 +VERTEX_SE3:QUAT 3621 12.794649 9.429629 -2.713218 -0.1927432 0.6223023 -0.7320071 0.1993879 +VERTEX_SE3:QUAT 3622 12.794635 9.517800 -2.788840 0.8442704 -0.1134843 0.1156047 0.5108467 +VERTEX_SE3:QUAT 3623 12.791480 9.232434 -2.619633 -0.0087466 0.7113560 0.1849924 0.6779926 +VERTEX_SE3:QUAT 3624 12.622603 9.271878 -2.702571 0.4022695 0.4743090 -0.7332316 0.2749211 +VERTEX_SE3:QUAT 3625 12.503334 9.213134 -2.770405 0.2423796 -0.2076326 0.0524919 0.9462481 +VERTEX_SE3:QUAT 3626 12.503838 9.367696 -2.611546 0.7037650 -0.5723709 -0.0716285 0.4146996 +VERTEX_SE3:QUAT 3627 12.352783 9.110322 -2.433929 0.5750996 0.0168199 0.5869774 0.5695920 +VERTEX_SE3:QUAT 3628 12.150465 8.976440 -2.339431 0.6761467 -0.3244995 0.3234447 0.5769828 +VERTEX_SE3:QUAT 3629 12.103623 9.237576 -2.356492 0.0184511 0.2404039 -0.6879277 0.6845590 +VERTEX_SE3:QUAT 3630 12.053498 9.137052 -2.244567 0.3549041 0.0589473 -0.6621430 0.6573697 +VERTEX_SE3:QUAT 3631 11.936015 9.052744 -2.268278 -0.2053747 0.3639851 -0.0878852 0.9042191 +VERTEX_SE3:QUAT 3632 12.001035 9.226154 -2.405709 0.2781410 0.6729452 -0.6813736 0.0742450 +VERTEX_SE3:QUAT 3633 12.156855 9.263658 -2.357368 0.2143427 0.5573463 -0.4780251 0.6441384 +VERTEX_SE3:QUAT 3634 12.223539 9.417290 -2.416989 0.3967237 -0.4273152 0.3875085 0.7140372 +VERTEX_SE3:QUAT 3635 12.089589 9.307288 -2.184476 -0.7244293 0.3831158 -0.5714132 0.0437191 +VERTEX_SE3:QUAT 3636 11.919710 9.150351 -2.221225 0.1512063 0.9550918 0.0291382 0.2531548 +VERTEX_SE3:QUAT 3637 11.743742 9.287423 -2.157551 0.8341728 -0.5475387 0.0575984 0.0322410 +VERTEX_SE3:QUAT 3638 11.546967 9.353939 -2.179341 0.1481183 0.1901313 -0.0023342 0.9705182 +VERTEX_SE3:QUAT 3639 11.482133 9.321715 -2.282268 0.1747575 -0.1989124 0.9540841 0.1400612 +VERTEX_SE3:QUAT 3640 11.511013 9.329930 -2.517184 0.8723891 -0.2233389 0.4001611 0.1700826 +VERTEX_SE3:QUAT 3641 11.483755 9.290141 -2.709636 0.3589432 0.3035399 0.3932828 0.7901595 +VERTEX_SE3:QUAT 3642 11.408415 9.364891 -2.404124 0.0491259 -0.5889627 0.7906842 0.1597749 +VERTEX_SE3:QUAT 3643 11.227722 9.500285 -2.239745 -0.6953127 -0.5598075 0.4300149 0.1350669 +VERTEX_SE3:QUAT 3644 11.055227 9.364851 -2.235976 -0.6881950 0.2768174 -0.4234392 0.5200567 +VERTEX_SE3:QUAT 3645 11.105279 9.383524 -2.325555 -0.0733579 0.4374325 -0.6032263 0.6628645 +VERTEX_SE3:QUAT 3646 11.079777 9.344962 -2.251654 0.9008674 0.0751297 0.1394668 0.4041564 +VERTEX_SE3:QUAT 3647 11.066312 9.452645 -2.197157 -0.8609359 0.4950866 -0.0910917 0.0733552 +VERTEX_SE3:QUAT 3648 11.063008 9.363425 -2.252455 0.0516595 -0.8947481 0.2563247 0.3620148 +VERTEX_SE3:QUAT 3649 10.995471 9.301153 -2.223492 0.2649354 0.8995418 0.0473013 0.3440878 +VERTEX_SE3:QUAT 3650 10.915537 9.393556 -2.134832 0.9444895 0.1200718 -0.0706095 0.2975510 +VERTEX_SE3:QUAT 3651 10.684863 9.210821 -2.022095 0.5445381 0.4592719 0.3630955 0.6005907 +VERTEX_SE3:QUAT 3652 10.808863 9.431353 -1.990403 -0.6122976 0.6906984 -0.2246240 0.3123642 +VERTEX_SE3:QUAT 3653 10.741223 9.671451 -1.767783 0.3179938 0.6679258 0.0540308 0.6706979 +VERTEX_SE3:QUAT 3654 10.904849 9.651739 -1.922027 0.1674027 0.5408086 0.0894327 0.8194536 +VERTEX_SE3:QUAT 3655 10.808882 9.735353 -1.966813 0.6846665 -0.2705938 0.4378808 0.5160147 +VERTEX_SE3:QUAT 3656 10.852821 9.727191 -1.826438 0.1998521 0.7076906 -0.6331830 0.2414798 +VERTEX_SE3:QUAT 3657 10.682715 9.875010 -1.890154 0.2431024 0.9544957 0.1308530 0.1127685 +VERTEX_SE3:QUAT 3658 10.647906 10.002682 -1.997879 0.1124114 -0.9845639 -0.1096222 0.0773343 +VERTEX_SE3:QUAT 3659 10.798411 10.049586 -2.038838 0.6271984 0.3061698 0.6157851 0.3656378 +VERTEX_SE3:QUAT 3660 10.663042 10.061207 -2.058709 0.2018769 0.6850462 0.1176729 0.6900077 +VERTEX_SE3:QUAT 3661 10.656235 10.010965 -2.027187 0.7646342 0.0907577 -0.5427883 0.3353781 +VERTEX_SE3:QUAT 3662 10.680137 10.041585 -1.946269 0.6265674 0.4722001 -0.5682013 0.2481684 +VERTEX_SE3:QUAT 3663 10.796435 9.987444 -1.836186 -0.4367995 0.7054524 -0.5566006 0.0416987 +VERTEX_SE3:QUAT 3664 10.811320 9.989119 -1.992713 -0.1764052 0.7771183 -0.2678661 0.5414944 +VERTEX_SE3:QUAT 3665 10.828099 9.978705 -2.051768 0.7954224 -0.4778038 0.3656505 0.0728459 +VERTEX_SE3:QUAT 3666 10.655239 10.152048 -1.931754 0.1588366 -0.8825780 0.4413215 0.0325948 +VERTEX_SE3:QUAT 3667 10.620761 10.184804 -2.021515 0.3040525 -0.5831110 -0.1035953 0.7461914 +VERTEX_SE3:QUAT 3668 10.686767 10.264435 -2.145566 0.5574668 -0.0658290 -0.0444526 0.8263905 +VERTEX_SE3:QUAT 3669 10.782764 10.383575 -2.175812 -0.5444229 0.3770125 -0.7013227 0.2638404 +VERTEX_SE3:QUAT 3670 10.767112 10.326219 -2.096580 0.7684460 -0.0093358 0.5774310 0.2756394 +VERTEX_SE3:QUAT 3671 10.929817 10.300707 -2.065624 0.6891350 0.0990513 0.6127531 0.3739190 +VERTEX_SE3:QUAT 3672 10.914460 10.354867 -2.199116 0.7792209 -0.3894272 0.1317981 0.4730650 +VERTEX_SE3:QUAT 3673 11.161826 10.333483 -2.326131 0.6390791 0.3751448 -0.6664800 0.0815401 +VERTEX_SE3:QUAT 3674 11.068713 10.315811 -2.347212 0.4569195 -0.7299360 0.3751833 0.3430096 +VERTEX_SE3:QUAT 3675 10.983153 10.401157 -2.348317 -0.4009356 -0.2371224 0.8844538 0.0276616 +VERTEX_SE3:QUAT 3676 11.056229 10.584683 -2.200353 -0.9481872 -0.0293368 -0.3153811 0.0248026 +VERTEX_SE3:QUAT 3677 11.145051 10.604547 -1.966038 0.8169078 0.3896535 0.2673730 0.3306711 +VERTEX_SE3:QUAT 3678 11.316874 10.489272 -1.952887 0.5747237 -0.0231263 0.6482133 0.4989763 +VERTEX_SE3:QUAT 3679 11.416915 10.509011 -1.928340 -0.7150291 -0.5073916 0.3449627 0.3350938 +VERTEX_SE3:QUAT 3680 11.384867 10.496724 -2.035692 -0.0344875 -0.9330395 0.1892276 0.3040410 +VERTEX_SE3:QUAT 3681 11.558652 10.525699 -2.103037 0.6598171 0.4553453 0.0240697 0.5972627 +VERTEX_SE3:QUAT 3682 11.624216 10.458505 -2.139606 0.3668636 -0.7908515 0.2746972 0.4055938 +VERTEX_SE3:QUAT 3683 11.679855 10.442990 -2.128235 0.9501615 0.2030855 0.2028126 0.1217229 +VERTEX_SE3:QUAT 3684 11.721037 10.423269 -2.279799 -0.0083541 -0.5408023 0.8206700 0.1842927 +VERTEX_SE3:QUAT 3685 11.811780 10.224262 -2.253454 0.1600522 0.3498650 -0.4266403 0.8185083 +VERTEX_SE3:QUAT 3686 11.926851 10.297747 -2.310425 -0.1336646 0.7368294 -0.6618402 0.0344057 +VERTEX_SE3:QUAT 3687 12.122215 10.148485 -2.235862 0.7227096 -0.4346538 0.2106900 0.4943446 +VERTEX_SE3:QUAT 3688 12.246457 10.084926 -2.248082 0.4754749 0.4719961 -0.4322270 0.6035918 +VERTEX_SE3:QUAT 3689 12.362581 9.985432 -2.027945 0.5770646 -0.2666013 0.7422131 0.2122262 +VERTEX_SE3:QUAT 3690 12.383957 10.005484 -2.002845 0.0664960 -0.5763580 0.5311977 0.6174292 +VERTEX_SE3:QUAT 3691 12.224953 9.814916 -2.028337 0.6614505 0.0388881 0.5247455 0.5344278 +VERTEX_SE3:QUAT 3692 12.312583 9.708903 -2.068743 0.7246146 -0.2434276 0.2777707 0.5818249 +VERTEX_SE3:QUAT 3693 12.297257 9.561316 -2.098843 -0.0938664 -0.8305850 0.3248728 0.4424650 +VERTEX_SE3:QUAT 3694 12.237438 9.498568 -2.329021 0.5100918 -0.5006112 0.2092780 0.6673811 +VERTEX_SE3:QUAT 3695 12.270662 9.330022 -2.293159 -0.3233547 -0.7623602 0.3815311 0.4107100 +VERTEX_SE3:QUAT 3696 12.286847 9.144713 -2.275954 0.0881903 -0.7587630 -0.0857389 0.6396484 +VERTEX_SE3:QUAT 3697 12.351856 9.191548 -2.367643 0.4502101 -0.8123018 0.2056066 0.3085491 +VERTEX_SE3:QUAT 3698 12.354030 9.091055 -2.369625 0.3875561 -0.0248078 -0.5614635 0.7307145 +VERTEX_SE3:QUAT 3699 12.445669 9.091005 -2.410322 0.8285606 -0.4499747 0.0640441 0.3269686 +VERTEX_SE3:QUAT 3700 12.426896 8.956383 -2.381733 0.2213657 0.2130905 -0.8636464 0.3996306 +VERTEX_SE3:QUAT 3701 12.416375 8.967115 -2.450043 0.2980860 -0.4009181 0.4106440 0.7627456 +VERTEX_SE3:QUAT 3702 12.415351 9.026389 -2.596144 0.0571198 -0.8909901 0.3951548 0.2161635 +VERTEX_SE3:QUAT 3703 12.294879 8.873719 -2.486273 0.3276098 -0.8553578 0.3964849 0.0619243 +VERTEX_SE3:QUAT 3704 12.104609 8.845737 -2.557198 -0.9657727 -0.2438864 0.0759955 0.0450253 +VERTEX_SE3:QUAT 3705 12.041890 8.834883 -2.601506 0.6834184 -0.3290807 0.1253147 0.6394852 +VERTEX_SE3:QUAT 3706 12.019876 8.895480 -2.534804 -0.0643821 -0.3881399 0.2327327 0.8894031 +VERTEX_SE3:QUAT 3707 11.964839 9.028451 -2.618987 0.2087412 -0.2724026 0.8741285 0.3436909 +VERTEX_SE3:QUAT 3708 11.782812 8.954091 -2.638559 0.8211876 -0.3642312 0.0692227 0.4338142 +VERTEX_SE3:QUAT 3709 11.630650 9.005716 -2.597719 0.3913648 0.0561371 -0.6039436 0.6920508 +VERTEX_SE3:QUAT 3710 11.531572 9.115661 -2.738187 0.7353071 0.3086964 -0.5971003 0.0866094 +VERTEX_SE3:QUAT 3711 11.590454 9.090593 -2.760581 0.1826384 0.4709294 -0.3295585 0.7976590 +VERTEX_SE3:QUAT 3712 11.417457 9.094829 -2.639150 0.1205849 0.8298196 -0.5445861 0.0168733 +VERTEX_SE3:QUAT 3713 11.309347 9.216959 -2.728397 0.8464390 -0.4472743 -0.2887666 0.0100288 +VERTEX_SE3:QUAT 3714 11.258740 9.197209 -2.787842 0.2966136 -0.9435993 0.1374811 0.0523420 +VERTEX_SE3:QUAT 3715 11.147300 9.214615 -2.628685 0.4129643 -0.3142953 0.8288602 0.2089732 +VERTEX_SE3:QUAT 3716 11.048020 9.158046 -2.585018 0.3821674 0.5466448 -0.0569904 0.7428860 +VERTEX_SE3:QUAT 3717 11.044535 9.061330 -2.705940 0.7631411 -0.2787534 -0.3113191 0.4929427 +VERTEX_SE3:QUAT 3718 11.007655 9.177212 -2.607546 0.7083746 0.4904456 0.0368108 0.5062741 +VERTEX_SE3:QUAT 3719 10.998280 9.300334 -2.617429 0.5606361 -0.0000677 0.5834791 0.5875706 +VERTEX_SE3:QUAT 3720 10.824661 9.279971 -2.547574 0.2070498 0.8104458 -0.5311413 0.1348960 +VERTEX_SE3:QUAT 3721 10.929281 9.097368 -2.580421 0.1455311 -0.5355955 0.3473137 0.7558646 +VERTEX_SE3:QUAT 3722 10.896785 9.083233 -2.587060 0.5019739 0.8608787 -0.0444212 0.0702621 +VERTEX_SE3:QUAT 3723 10.799619 9.157981 -2.624436 0.2861062 0.6979466 -0.1834891 0.6303535 +VERTEX_SE3:QUAT 3724 10.715808 9.090468 -2.643970 0.5340941 0.4410582 -0.3605426 0.6246761 +VERTEX_SE3:QUAT 3725 10.607289 9.058935 -2.783746 0.8097438 0.2052520 0.0400320 0.5482555 +VERTEX_SE3:QUAT 3726 10.439396 9.132172 -2.603240 0.0518611 0.1957945 -0.3130912 0.9278733 +VERTEX_SE3:QUAT 3727 10.467867 9.104494 -2.523097 0.6848415 -0.2259277 0.3597546 0.5920518 +VERTEX_SE3:QUAT 3728 10.511490 9.207389 -2.342499 -0.4634014 0.8018302 -0.3746394 0.0444150 +VERTEX_SE3:QUAT 3729 10.456117 9.168625 -2.312655 -0.2777586 -0.7141798 0.4143372 0.4910417 +VERTEX_SE3:QUAT 3730 10.456488 9.221780 -2.452456 0.1682825 -0.0130850 -0.3354254 0.9268223 +VERTEX_SE3:QUAT 3731 10.445040 9.163741 -2.460789 -0.9616185 0.1083421 0.2514110 0.0185559 +VERTEX_SE3:QUAT 3732 10.245218 9.175404 -2.336003 0.5739144 0.7989712 -0.1167311 0.1365322 +VERTEX_SE3:QUAT 3733 10.061593 9.317209 -2.398277 0.9015062 0.4173979 -0.0125611 0.1136123 +VERTEX_SE3:QUAT 3734 9.924345 9.162841 -2.276636 0.6934445 -0.4142918 -0.3587606 0.4677476 +VERTEX_SE3:QUAT 3735 10.037204 9.150533 -2.249199 0.9121742 -0.0454126 -0.0981900 0.3952653 +VERTEX_SE3:QUAT 3736 9.963372 9.178198 -2.201080 -0.2434997 -0.4442064 0.8565026 0.0989540 +VERTEX_SE3:QUAT 3737 9.982079 9.245943 -2.138472 0.5814420 0.3635373 -0.6422238 0.3425119 +VERTEX_SE3:QUAT 3738 10.080801 9.500143 -2.103592 0.6628104 -0.1790122 -0.0418385 0.7258695 +VERTEX_SE3:QUAT 3739 10.293869 9.557220 -2.127693 -0.0437861 -0.7435471 0.6564944 0.1193130 +VERTEX_SE3:QUAT 3740 10.217110 9.676043 -2.256852 0.7435374 -0.6537050 0.0960963 0.1028952 +VERTEX_SE3:QUAT 3741 10.303501 9.650136 -2.113776 0.2848528 0.1658828 -0.6057076 0.7241961 +VERTEX_SE3:QUAT 3742 10.294194 9.643621 -1.987067 0.0843973 0.5539866 -0.3112160 0.7675419 +VERTEX_SE3:QUAT 3743 10.314373 9.604082 -1.957237 0.7018979 0.6927097 0.1032322 0.1297526 +VERTEX_SE3:QUAT 3744 10.342934 9.758054 -2.048514 0.9083635 0.2565340 -0.0465881 0.3269489 +VERTEX_SE3:QUAT 3745 10.276400 9.781143 -2.071235 0.8764221 -0.2539739 -0.1982891 0.3578590 +VERTEX_SE3:QUAT 3746 10.261206 9.686158 -2.102112 -0.4173714 -0.7420108 -0.0923759 0.5164182 +VERTEX_SE3:QUAT 3747 10.286891 9.876614 -2.106802 0.7043616 0.0248165 -0.3154100 0.6354332 +VERTEX_SE3:QUAT 3748 10.266564 9.908921 -2.001050 0.2785041 -0.7740889 -0.3589346 0.4408943 +VERTEX_SE3:QUAT 3749 10.254763 9.815291 -1.824933 0.4676980 0.6586050 -0.4547871 0.3750557 +VERTEX_SE3:QUAT 3750 10.319178 9.844911 -1.812247 0.1365219 -0.5101772 0.5641580 0.6346706 +VERTEX_SE3:QUAT 3751 10.391820 10.149833 -1.899741 0.6706500 -0.5132551 -0.1522391 0.5134404 +VERTEX_SE3:QUAT 3752 10.362657 10.227053 -1.905558 -0.0965990 -0.7064357 0.6232887 0.3211361 +VERTEX_SE3:QUAT 3753 10.385046 10.429543 -1.890747 -0.3640345 0.9290691 0.0340746 0.0561111 +VERTEX_SE3:QUAT 3754 10.537546 10.419495 -1.851715 0.9151236 -0.2276595 0.0190523 0.3322000 +VERTEX_SE3:QUAT 3755 10.461369 10.649233 -1.756481 -0.5968186 0.2543912 -0.7586566 0.0594381 +VERTEX_SE3:QUAT 3756 10.587231 10.553072 -1.773210 -0.9356030 0.0209896 0.3425449 0.0828826 +VERTEX_SE3:QUAT 3757 10.602195 10.608350 -1.668347 0.0415749 0.5557562 -0.7617292 0.3304167 +VERTEX_SE3:QUAT 3758 10.501561 10.536838 -1.746254 0.8773278 -0.3270854 -0.3495186 0.0338800 +VERTEX_SE3:QUAT 3759 10.555780 10.498447 -1.493933 0.2611622 -0.6989056 -0.2341573 0.6232941 +VERTEX_SE3:QUAT 3760 10.513739 10.531437 -1.351019 0.3966740 0.4509994 -0.0717338 0.7963062 +VERTEX_SE3:QUAT 3761 10.649335 10.527425 -1.388218 -0.4486317 -0.4578793 0.6396208 0.4242186 +VERTEX_SE3:QUAT 3762 10.614035 10.465243 -1.233053 0.7723283 0.5496711 -0.2301134 0.2200422 +VERTEX_SE3:QUAT 3763 10.587009 10.446074 -1.244276 -0.3922242 -0.8608690 0.1917541 0.2613333 +VERTEX_SE3:QUAT 3764 10.620323 10.371769 -1.262111 0.2212956 -0.7505508 0.1712680 0.5986393 +VERTEX_SE3:QUAT 3765 10.744316 10.381548 -1.226620 0.4234012 -0.8445012 0.3123003 0.1000884 +VERTEX_SE3:QUAT 3766 10.856407 10.429090 -1.026954 0.2969273 0.6438458 0.0018014 0.7051904 +VERTEX_SE3:QUAT 3767 10.833849 10.481707 -1.113525 -0.4102267 0.7032202 -0.5623914 0.1446078 +VERTEX_SE3:QUAT 3768 10.841034 10.440769 -1.109508 0.9051887 -0.2533736 -0.0152386 0.3408858 +VERTEX_SE3:QUAT 3769 10.825914 10.451810 -1.056264 -0.3492182 -0.5979982 0.6930953 0.2001592 +VERTEX_SE3:QUAT 3770 11.007229 10.413144 -1.067779 0.2400480 0.3905369 -0.8236648 0.3338176 +VERTEX_SE3:QUAT 3771 10.954260 10.537014 -0.742534 0.4388744 -0.2672283 -0.4624819 0.7225572 +VERTEX_SE3:QUAT 3772 11.030299 10.390297 -0.774861 0.8709968 -0.2288686 -0.4334382 0.0333926 +VERTEX_SE3:QUAT 3773 11.116760 10.207650 -0.663561 0.2602771 -0.4760063 0.8356866 0.0854501 +VERTEX_SE3:QUAT 3774 10.920156 10.083988 -0.419276 0.5764504 0.4959601 -0.1931536 0.6200163 +VERTEX_SE3:QUAT 3775 11.018191 10.076860 -0.384253 -0.9006492 0.4165150 -0.0114958 0.1233458 +VERTEX_SE3:QUAT 3776 10.899022 10.100075 -0.433697 0.5370510 -0.3942927 0.7362645 0.1184233 +VERTEX_SE3:QUAT 3777 10.928590 9.918533 -0.434562 0.1757103 0.9264831 -0.0038933 0.3327760 +VERTEX_SE3:QUAT 3778 11.152212 9.988550 -0.429775 0.8106557 -0.1259254 -0.5132390 0.2521226 +VERTEX_SE3:QUAT 3779 11.176059 9.990852 -0.441926 0.0617834 -0.1998051 -0.1696858 0.9630511 +VERTEX_SE3:QUAT 3780 11.139960 10.084751 -0.378461 0.2349580 0.1489897 -0.9376995 0.2081260 +VERTEX_SE3:QUAT 3781 10.981052 9.981201 -0.251010 0.7452328 0.0409182 0.4913063 0.4489675 +VERTEX_SE3:QUAT 3782 10.888145 9.909541 -0.216899 0.9480517 -0.1641878 -0.1456267 0.2302895 +VERTEX_SE3:QUAT 3783 10.769113 9.948219 -0.163151 -0.2459038 -0.6177588 0.3772640 0.6446528 +VERTEX_SE3:QUAT 3784 10.764371 9.933248 -0.051730 0.3688375 0.2212493 -0.7306782 0.5302047 +VERTEX_SE3:QUAT 3785 10.843669 10.206055 -0.037462 -0.1211106 -0.7953852 0.1960157 0.5606001 +VERTEX_SE3:QUAT 3786 10.705694 10.175642 -0.089087 -0.1423523 0.6248318 -0.7340340 0.2247556 +VERTEX_SE3:QUAT 3787 10.695897 9.991580 -0.019529 -0.4056060 0.3240100 -0.8351755 0.1816125 +VERTEX_SE3:QUAT 3788 10.694451 9.874241 0.115397 -0.6370438 0.3184968 -0.6838677 0.1583032 +VERTEX_SE3:QUAT 3789 10.784589 9.868459 0.116614 0.4624653 0.6891729 -0.3953234 0.3935555 +VERTEX_SE3:QUAT 3790 10.654405 9.716641 0.076729 -0.5013275 -0.3791794 0.7757152 0.0562103 +VERTEX_SE3:QUAT 3791 10.552552 9.685459 -0.030010 -0.0929664 -0.5759077 0.6982954 0.4148145 +VERTEX_SE3:QUAT 3792 10.517730 9.490199 -0.163685 0.7727060 -0.5712166 0.0235486 0.2758306 +VERTEX_SE3:QUAT 3793 10.512417 9.313037 -0.124634 0.0809894 -0.5675227 0.6645389 0.4793191 +VERTEX_SE3:QUAT 3794 10.466415 9.232235 -0.341374 0.3371737 0.1141993 -0.3864247 0.8508515 +VERTEX_SE3:QUAT 3795 10.501435 9.070720 -0.442761 0.7150769 0.0789743 -0.6908170 0.0721107 +VERTEX_SE3:QUAT 3796 10.408658 8.998866 -0.554545 0.7604987 0.0349448 -0.6330839 0.1400903 +VERTEX_SE3:QUAT 3797 10.384892 8.857325 -0.619882 0.5884996 0.6449073 -0.2865753 0.3945090 +VERTEX_SE3:QUAT 3798 10.550196 8.872877 -0.747739 0.4390979 0.2295253 -0.8671837 0.0500360 +VERTEX_SE3:QUAT 3799 10.566548 8.807243 -0.719205 0.1635257 -0.3215893 -0.0054347 0.9326361 +VERTEX_SE3:QUAT 3800 10.506180 8.714470 -0.728461 0.7970352 0.1748663 0.3262283 0.4772125 +VERTEX_SE3:QUAT 3801 10.676477 8.620088 -0.688059 -0.1520885 0.1851941 -0.8972017 0.3709466 +VERTEX_SE3:QUAT 3802 10.589314 8.397753 -0.616042 0.6680982 0.3759681 -0.6418962 0.0161870 +VERTEX_SE3:QUAT 3803 10.512898 8.165308 -0.559740 0.8053593 0.3720995 0.4071433 0.2171930 +VERTEX_SE3:QUAT 3804 10.535573 8.111103 -0.331746 0.4192606 0.5341585 0.1846782 0.7104852 +VERTEX_SE3:QUAT 3805 10.667320 7.870054 -0.286754 0.5766898 0.5074812 -0.3817066 0.5139958 +VERTEX_SE3:QUAT 3806 10.608474 7.937481 -0.393002 0.6106261 0.0104109 0.4037995 0.6811559 +VERTEX_SE3:QUAT 3807 10.588686 7.904687 -0.394505 0.6757208 0.3966326 -0.6043135 0.1445305 +VERTEX_SE3:QUAT 3808 10.462899 7.870168 -0.526242 -0.0881376 -0.0888997 -0.8861056 0.4462572 +VERTEX_SE3:QUAT 3809 10.476506 7.701320 -0.430799 0.4871415 0.1825019 -0.7913223 0.3212403 +VERTEX_SE3:QUAT 3810 10.427968 7.609965 -0.436774 0.4625157 0.3702855 0.7191001 0.3631292 +VERTEX_SE3:QUAT 3811 10.455939 7.590716 -0.554201 -0.2047024 0.2536160 -0.6943352 0.6416186 +VERTEX_SE3:QUAT 3812 10.349751 7.457227 -0.632018 -0.3936225 -0.0345265 -0.8943413 0.2098163 +VERTEX_SE3:QUAT 3813 10.156905 7.495661 -0.497602 0.8312612 0.1559633 0.2902575 0.4476951 +VERTEX_SE3:QUAT 3814 9.912273 7.452799 -0.556961 0.2808528 0.5707662 -0.7666063 0.0875349 +VERTEX_SE3:QUAT 3815 9.927522 7.301872 -0.551421 0.4262580 -0.0784061 0.8578399 0.2761653 +VERTEX_SE3:QUAT 3816 9.856252 7.034162 -0.670890 0.9157927 -0.2922512 0.2214910 0.1638738 +VERTEX_SE3:QUAT 3817 9.791955 6.886417 -0.818209 -0.0348943 -0.0170311 0.4433857 0.8954895 +VERTEX_SE3:QUAT 3818 9.630836 6.684375 -0.910365 0.2008457 0.9272572 -0.0648378 0.3092752 +VERTEX_SE3:QUAT 3819 9.484848 6.490746 -0.950820 -0.6977126 0.1956525 -0.6169970 0.3069722 +VERTEX_SE3:QUAT 3820 9.537187 6.336190 -0.905356 -0.2378537 0.3289667 -0.8232276 0.3968664 +VERTEX_SE3:QUAT 3821 9.448916 6.365410 -0.896979 0.0677864 0.2498469 -0.5176851 0.8154653 +VERTEX_SE3:QUAT 3822 9.463599 6.336371 -1.051494 0.0478658 -0.3363774 0.7127571 0.6136256 +VERTEX_SE3:QUAT 3823 9.327777 6.189932 -1.019560 0.9690346 -0.0944856 0.0301095 0.2261369 +VERTEX_SE3:QUAT 3824 9.203690 6.293991 -0.982992 0.8164026 -0.2260218 0.2329101 0.4776545 +VERTEX_SE3:QUAT 3825 9.112932 6.137031 -0.947250 -0.0598431 -0.2464730 0.5077519 0.8233212 +VERTEX_SE3:QUAT 3826 8.939293 6.194327 -0.811966 0.4995244 0.2575895 -0.7253911 0.3974050 +VERTEX_SE3:QUAT 3827 8.963674 6.086826 -1.002592 0.5556791 0.3018105 0.5834222 0.5096565 +VERTEX_SE3:QUAT 3828 8.879758 6.267031 -1.161434 0.0743179 -0.1183831 -0.1136037 0.9836445 +VERTEX_SE3:QUAT 3829 8.844415 6.232076 -1.102019 0.5265768 -0.8358966 0.0673040 0.1395133 +VERTEX_SE3:QUAT 3830 8.796927 6.071810 -1.212645 0.6562694 -0.4311135 0.2191154 0.5791719 +VERTEX_SE3:QUAT 3831 8.625075 6.072649 -1.359189 0.3162935 0.7216511 -0.2490824 0.5631483 +VERTEX_SE3:QUAT 3832 8.573325 6.074084 -1.431505 -0.3286471 0.7029072 -0.3204906 0.5433216 +VERTEX_SE3:QUAT 3833 8.507545 6.025468 -1.382180 0.8495287 -0.2261281 0.0520228 0.4737728 +VERTEX_SE3:QUAT 3834 8.405242 6.008107 -1.440997 0.3441692 0.7904782 0.1742634 0.4757352 +VERTEX_SE3:QUAT 3835 8.358824 6.201949 -1.284379 0.7331887 -0.0064340 0.0865081 0.6744696 +VERTEX_SE3:QUAT 3836 8.162945 6.201658 -1.446163 0.4569802 0.5002383 -0.5188514 0.5212714 +VERTEX_SE3:QUAT 3837 8.098722 6.183412 -1.461358 0.2899271 -0.0610364 0.3316434 0.8956726 +VERTEX_SE3:QUAT 3838 8.179288 6.283376 -1.270856 -0.1624212 0.3885005 -0.9047342 0.0643635 +VERTEX_SE3:QUAT 3839 8.117212 6.550964 -1.252002 -0.2083918 -0.2609225 0.9202165 0.2041907 +VERTEX_SE3:QUAT 3840 7.889157 6.492314 -1.089581 0.0119706 0.0569960 -0.8407151 0.5383366 +VERTEX_SE3:QUAT 3841 7.971045 6.566338 -1.144406 0.1980660 0.0567031 -0.1690636 0.9638320 +VERTEX_SE3:QUAT 3842 7.896971 6.755598 -1.184544 0.3294564 -0.6730943 0.0015855 0.6621179 +VERTEX_SE3:QUAT 3843 7.764373 6.718037 -1.150034 0.5201107 0.1883205 -0.8289184 0.0831537 +VERTEX_SE3:QUAT 3844 7.773997 6.769859 -1.197482 -0.0780903 0.6878502 -0.0251628 0.7212010 +VERTEX_SE3:QUAT 3845 7.788016 6.709871 -1.311829 0.2883905 0.9213573 -0.0246155 0.2594720 +VERTEX_SE3:QUAT 3846 7.763334 6.828687 -1.313376 0.3076010 -0.5862197 0.4782505 0.5770655 +VERTEX_SE3:QUAT 3847 7.680210 6.962864 -1.288300 -0.2530207 -0.5683768 0.7733467 0.1219151 +VERTEX_SE3:QUAT 3848 7.543322 7.273771 -1.126165 0.7389964 0.0715343 0.5331870 0.4055597 +VERTEX_SE3:QUAT 3849 7.671076 7.329545 -1.144748 0.3042428 -0.1304807 -0.0430053 0.9426355 +VERTEX_SE3:QUAT 3850 7.532238 7.393064 -1.130961 0.6592377 -0.0284820 -0.1883494 0.7274056 +VERTEX_SE3:QUAT 3851 7.794749 7.342350 -0.986166 -0.4161337 0.5451825 -0.5317595 0.4968306 +VERTEX_SE3:QUAT 3852 7.926158 7.453376 -0.946115 0.0538963 0.2472192 -0.7529142 0.6075344 +VERTEX_SE3:QUAT 3853 7.864194 7.480897 -1.025382 -0.0525418 -0.6594468 0.7451514 0.0843730 +VERTEX_SE3:QUAT 3854 7.889026 7.391819 -1.041148 -0.3070187 -0.7066278 0.6139178 0.1718188 +VERTEX_SE3:QUAT 3855 8.047513 7.368208 -1.071529 0.1174836 0.8955067 -0.4209608 0.0840077 +VERTEX_SE3:QUAT 3856 7.997065 7.503440 -1.157662 0.3418730 0.5980062 -0.6879230 0.2286337 +VERTEX_SE3:QUAT 3857 8.092270 7.538667 -1.199847 -0.4172031 0.3410880 -0.7216267 0.4345750 +VERTEX_SE3:QUAT 3858 8.033463 7.674321 -1.293363 -0.2364891 -0.7918674 0.5349206 0.1757236 +VERTEX_SE3:QUAT 3859 8.025776 7.787735 -1.214687 0.6219334 0.2942191 -0.7169201 0.1125145 +VERTEX_SE3:QUAT 3860 8.060825 7.892948 -1.172828 -0.0529498 0.6699085 -0.1657800 0.7217589 +VERTEX_SE3:QUAT 3861 8.252025 7.957191 -1.211577 0.2059260 0.1027597 0.2706209 0.9347723 +VERTEX_SE3:QUAT 3862 8.298434 7.853926 -1.189141 0.8489989 0.1055652 -0.3678315 0.3643583 +VERTEX_SE3:QUAT 3863 8.587498 7.918837 -1.405529 0.9507030 0.1056284 0.2588453 0.1341850 +VERTEX_SE3:QUAT 3864 8.639201 7.892874 -1.498397 -0.2302465 -0.0663408 0.9542229 0.1790088 +VERTEX_SE3:QUAT 3865 8.629678 7.927043 -1.300957 0.4994558 0.2239321 0.2045773 0.8115087 +VERTEX_SE3:QUAT 3866 8.614277 8.180352 -1.249668 0.1974012 0.5406810 -0.7929938 0.1996438 +VERTEX_SE3:QUAT 3867 8.765381 8.404756 -1.284466 0.3906449 0.2280037 0.0362585 0.8911208 +VERTEX_SE3:QUAT 3868 8.825033 8.202878 -1.216723 -0.4791199 0.2637450 -0.3917992 0.7398487 +VERTEX_SE3:QUAT 3869 8.802813 8.363385 -1.085193 -0.0001188 0.6302961 -0.6347126 0.4470646 +VERTEX_SE3:QUAT 3870 8.611689 8.396329 -1.272280 0.7972041 0.4201824 -0.3385131 0.2707791 +VERTEX_SE3:QUAT 3871 8.649321 8.570105 -1.212901 0.6012478 0.1904533 -0.7750229 0.0395993 +VERTEX_SE3:QUAT 3872 8.755687 8.587654 -1.138445 -0.3740950 0.4570626 -0.2676000 0.7612732 +VERTEX_SE3:QUAT 3873 8.846397 8.694029 -1.261748 0.5567709 0.3813665 -0.0579929 0.7356648 +VERTEX_SE3:QUAT 3874 9.050379 8.735326 -1.312505 -0.6459085 0.6956567 -0.3092148 0.0570111 +VERTEX_SE3:QUAT 3875 9.058657 8.775815 -1.317467 0.5541237 0.3524171 0.3439418 0.6711581 +VERTEX_SE3:QUAT 3876 9.104405 8.947532 -1.174372 0.5374004 0.1790348 0.4459198 0.6930389 +VERTEX_SE3:QUAT 3877 9.236983 9.038335 -1.253432 0.8227991 -0.1712424 -0.1419502 0.5229989 +VERTEX_SE3:QUAT 3878 9.250699 9.124941 -1.390748 0.3369891 0.0527175 -0.8922083 0.2960128 +VERTEX_SE3:QUAT 3879 9.238535 9.032759 -1.359559 0.3265211 0.1236056 0.4632359 0.8145662 +VERTEX_SE3:QUAT 3880 9.467164 9.108788 -1.290955 0.1686643 -0.4510156 0.1765175 0.8584747 +VERTEX_SE3:QUAT 3881 9.547134 9.184543 -1.237041 0.0739245 0.2851558 -0.4936683 0.8182377 +VERTEX_SE3:QUAT 3882 9.588383 8.944615 -1.244050 0.6680893 -0.4423251 0.5905822 0.0960096 +VERTEX_SE3:QUAT 3883 9.612389 8.898981 -1.162016 -0.0935299 -0.3527938 0.7435153 0.5603335 +VERTEX_SE3:QUAT 3884 9.784974 8.792077 -1.261585 0.2076562 0.6236680 -0.6474885 0.3855849 +VERTEX_SE3:QUAT 3885 9.809774 8.762616 -1.096526 -0.4727362 0.8154444 -0.2807308 0.1810002 +VERTEX_SE3:QUAT 3886 9.948597 8.610972 -1.025470 0.4317948 -0.3977897 0.7155607 0.3785359 +VERTEX_SE3:QUAT 3887 9.998211 8.539305 -0.968685 0.5976510 0.4049852 0.6433584 0.2547355 +VERTEX_SE3:QUAT 3888 9.942340 8.539948 -0.893880 0.1764591 0.0695469 -0.9552269 0.2270836 +VERTEX_SE3:QUAT 3889 10.012887 8.430399 -0.806904 0.3067648 0.1809917 0.5327794 0.7676480 +VERTEX_SE3:QUAT 3890 10.102806 8.542602 -0.805154 0.2664590 0.0259613 0.5576721 0.7857019 +VERTEX_SE3:QUAT 3891 10.226750 8.370981 -0.775872 0.0412969 -0.9276334 0.3497546 0.1243485 +VERTEX_SE3:QUAT 3892 10.291518 8.530732 -0.795480 0.4031473 0.0520559 0.3034383 0.8617933 +VERTEX_SE3:QUAT 3893 10.231717 8.464669 -0.732656 -0.2498443 -0.6037346 0.7098871 0.2629499 +VERTEX_SE3:QUAT 3894 10.209227 8.376157 -0.677138 0.5129374 0.5228729 -0.2155161 0.6457956 +VERTEX_SE3:QUAT 3895 10.144844 8.261955 -0.746919 0.2136157 -0.7820994 0.4909098 0.3188989 +VERTEX_SE3:QUAT 3896 10.273691 8.447828 -0.764256 0.2599252 0.0458691 -0.0581001 0.9627873 +VERTEX_SE3:QUAT 3897 10.221502 8.301610 -0.799436 -0.2003720 0.1896184 -0.6801833 0.6791514 +VERTEX_SE3:QUAT 3898 10.099962 8.148177 -0.768039 0.7183990 -0.1297455 -0.2464704 0.6374333 +VERTEX_SE3:QUAT 3899 10.126789 8.123355 -0.772956 -0.1778400 -0.6017699 0.5785594 0.5210709 +VERTEX_SE3:QUAT 3900 10.121370 8.022932 -0.684099 0.4392339 0.0956756 -0.4333808 0.7810895 +VERTEX_SE3:QUAT 3901 10.218538 7.956542 -0.590777 0.1774626 0.6334124 -0.1953832 0.7274072 +VERTEX_SE3:QUAT 3902 10.133979 8.039595 -0.584189 -0.5173480 0.0892137 -0.7496061 0.4030913 +VERTEX_SE3:QUAT 3903 10.188303 8.052292 -0.532806 0.4295699 -0.1885891 -0.0361212 0.8823826 +VERTEX_SE3:QUAT 3904 9.998234 8.007705 -0.622818 -0.0470077 -0.5756559 0.7774928 0.2488282 +VERTEX_SE3:QUAT 3905 10.063130 8.153162 -0.504725 0.4592800 0.6580235 -0.5415583 0.2505626 +VERTEX_SE3:QUAT 3906 10.153849 8.162884 -0.516130 0.3002741 -0.2237718 0.3659855 0.8519485 +VERTEX_SE3:QUAT 3907 10.141829 8.166142 -0.595719 -0.0410368 0.9028527 -0.1837168 0.3865504 +VERTEX_SE3:QUAT 3908 10.239585 8.020081 -0.693240 -0.0514799 -0.4342373 0.7876062 0.4341248 +VERTEX_SE3:QUAT 3909 10.446419 8.057661 -0.697620 0.1950220 0.1155796 0.9402823 0.2539231 +VERTEX_SE3:QUAT 3910 10.408044 8.135075 -0.615872 0.4169762 -0.3664041 0.5949688 0.5812839 +VERTEX_SE3:QUAT 3911 10.361602 8.230792 -0.605362 0.1773232 0.8035065 -0.2077369 0.5289416 +VERTEX_SE3:QUAT 3912 10.266977 8.185357 -0.551201 0.5602889 0.2514865 -0.1357775 0.7774287 +VERTEX_SE3:QUAT 3913 10.283308 8.171757 -0.471927 0.3033501 0.6509871 -0.5016395 0.4822368 +VERTEX_SE3:QUAT 3914 10.267724 8.210928 -0.444717 0.0358982 0.1757651 0.9754035 0.1280860 +VERTEX_SE3:QUAT 3915 10.243160 8.313490 -0.489413 0.0806485 0.8613148 -0.1566972 0.4765277 +VERTEX_SE3:QUAT 3916 10.244922 8.259191 -0.381058 0.5172669 0.6486613 -0.0919549 0.5506522 +VERTEX_SE3:QUAT 3917 10.284207 8.194289 -0.426388 0.0776053 0.7756587 -0.6239792 0.0545982 +VERTEX_SE3:QUAT 3918 10.235775 8.078635 -0.250627 0.2473442 0.0339636 -0.4641202 0.8498587 +VERTEX_SE3:QUAT 3919 10.318833 7.725979 -0.306169 0.3716324 0.1206192 -0.7943595 0.4651165 +VERTEX_SE3:QUAT 3920 10.281706 7.642634 -0.352194 0.8308917 -0.0433677 0.3977656 0.3866792 +VERTEX_SE3:QUAT 3921 10.224529 7.511853 -0.210958 0.0530752 -0.2968266 0.8799675 0.3670616 +VERTEX_SE3:QUAT 3922 10.218083 7.472767 -0.244656 -0.1965402 0.6706350 -0.4876630 0.5232642 +VERTEX_SE3:QUAT 3923 10.069414 7.589054 -0.265130 -0.1510648 -0.0396808 -0.8964165 0.4147798 +VERTEX_SE3:QUAT 3924 10.138593 7.471289 -0.358296 -0.6526656 0.4537397 -0.5856903 0.1584761 +VERTEX_SE3:QUAT 3925 10.049699 7.593595 -0.444524 -0.1897512 0.5798649 -0.6326184 0.4770169 +VERTEX_SE3:QUAT 3926 9.944126 7.580246 -0.474700 0.1388685 0.2788179 0.9467339 0.0816768 +VERTEX_SE3:QUAT 3927 9.920342 7.604226 -0.519125 0.7008271 -0.4617118 0.2139912 0.4998714 +VERTEX_SE3:QUAT 3928 10.109326 7.488417 -0.474134 0.4058889 0.2038902 0.5193681 0.7238369 +VERTEX_SE3:QUAT 3929 10.044713 7.415137 -0.240909 0.6702918 -0.0681762 0.6117587 0.4145024 +VERTEX_SE3:QUAT 3930 10.211885 7.322205 -0.211342 0.0727082 0.0709924 -0.5770402 0.8103692 +VERTEX_SE3:QUAT 3931 10.049130 7.217495 -0.309871 -0.5523337 0.6199148 -0.1078122 0.5468178 +VERTEX_SE3:QUAT 3932 10.205766 7.160380 -0.331533 0.1304216 -0.1619245 0.9054634 0.3700090 +VERTEX_SE3:QUAT 3933 10.310629 7.144271 -0.374040 0.0129320 -0.3334634 0.9331893 0.1333888 +VERTEX_SE3:QUAT 3934 10.202591 7.223408 -0.449548 0.5406937 0.2629288 -0.2094558 0.7711336 +VERTEX_SE3:QUAT 3935 10.240960 7.234181 -0.670657 0.5409586 0.4699109 0.2525999 0.6501852 +VERTEX_SE3:QUAT 3936 10.129803 7.373431 -0.642686 -0.2851377 0.3749869 -0.6744056 0.5685582 +VERTEX_SE3:QUAT 3937 9.968286 7.441656 -0.752812 0.6296656 -0.7102884 0.3074832 0.0668266 +VERTEX_SE3:QUAT 3938 9.938098 7.428786 -0.783547 0.4567443 0.4620170 0.6646480 0.3690094 +VERTEX_SE3:QUAT 3939 9.926234 7.459360 -0.947816 0.1924179 -0.3022945 0.5700357 0.7393596 +VERTEX_SE3:QUAT 3940 9.940610 7.345107 -1.070275 0.1403265 0.7516389 0.2204798 0.6055874 +VERTEX_SE3:QUAT 3941 9.706340 7.518023 -1.119437 0.4372820 -0.3373736 0.8274368 0.1015479 +VERTEX_SE3:QUAT 3942 9.814661 7.518944 -1.069295 -0.6555151 -0.2590952 -0.5405936 0.4592692 +VERTEX_SE3:QUAT 3943 9.787773 7.484305 -1.262935 -0.1924835 0.8790221 -0.4330867 0.0520201 +VERTEX_SE3:QUAT 3944 9.559963 7.443082 -1.340457 0.3761190 -0.0210671 -0.5068639 0.7753577 +VERTEX_SE3:QUAT 3945 9.498626 7.428192 -1.344228 -0.1168795 -0.3944179 0.8040992 0.4291832 +VERTEX_SE3:QUAT 3946 9.498748 7.445779 -1.248483 0.6341985 0.0830170 0.5919975 0.4903462 +VERTEX_SE3:QUAT 3947 9.287289 7.602317 -1.356024 -0.6359612 -0.4192654 -0.6275231 0.1611975 +VERTEX_SE3:QUAT 3948 9.159694 7.469643 -1.444319 -0.0232728 -0.1096605 -0.5655157 0.8170832 +VERTEX_SE3:QUAT 3949 9.233493 7.569066 -1.543383 0.4689644 0.4100888 0.1327649 0.7708911 +VERTEX_SE3:QUAT 3950 9.129064 7.674501 -1.442132 0.7318609 -0.3017362 0.5751279 0.2063076 +VERTEX_SE3:QUAT 3951 9.075246 7.702310 -1.586544 0.2045746 -0.1092633 -0.8559055 0.4622084 +VERTEX_SE3:QUAT 3952 9.010034 7.817081 -1.683072 0.4657709 0.6853829 -0.3810817 0.4099810 +VERTEX_SE3:QUAT 3953 9.105631 7.749750 -1.703144 0.4867387 0.6162339 -0.3351741 0.5205761 +VERTEX_SE3:QUAT 3954 9.176464 7.670479 -1.703622 0.0126190 -0.6066966 0.6914783 0.3919410 +VERTEX_SE3:QUAT 3955 9.228338 7.747562 -1.777611 -0.3267872 0.0703231 -0.1643657 0.9280348 +VERTEX_SE3:QUAT 3956 9.330798 7.686878 -1.772867 -0.0240901 0.9143834 -0.1353686 0.3807862 +VERTEX_SE3:QUAT 3957 9.195055 7.698336 -1.730736 -0.5765565 0.6910392 -0.3989217 0.1758095 +VERTEX_SE3:QUAT 3958 9.119480 7.781781 -1.764652 -0.3602094 0.2527045 -0.8964519 0.0525696 +VERTEX_SE3:QUAT 3959 9.187678 7.887817 -1.724614 0.2185111 0.4010476 -0.8194185 0.3463626 +VERTEX_SE3:QUAT 3960 9.292972 8.037311 -1.696655 0.8078436 0.3888058 0.1432037 0.4191794 +VERTEX_SE3:QUAT 3961 9.331580 8.186818 -1.818044 -0.5641098 0.6941173 -0.3778546 0.2391801 +VERTEX_SE3:QUAT 3962 9.311502 8.206812 -2.045514 0.7473912 0.3323806 0.5750623 0.0152599 +VERTEX_SE3:QUAT 3963 9.234356 8.380411 -2.218992 0.7057033 -0.1363348 -0.3095477 0.6225560 +VERTEX_SE3:QUAT 3964 9.278438 8.345666 -2.127638 -0.0291803 0.6793348 -0.2078793 0.7031636 +VERTEX_SE3:QUAT 3965 9.184286 8.396763 -2.001044 -0.4540113 0.4418856 -0.6438991 0.4289577 +VERTEX_SE3:QUAT 3966 9.180262 8.443046 -2.140656 0.1321963 -0.1242605 -0.9741707 0.1344427 +VERTEX_SE3:QUAT 3967 9.299959 8.377826 -2.162942 0.5530318 0.2418373 0.7456096 0.2823770 +VERTEX_SE3:QUAT 3968 9.278840 8.319919 -2.146173 0.2601370 0.6609863 -0.2249050 0.6669659 +VERTEX_SE3:QUAT 3969 9.073131 8.315452 -2.296169 0.2678798 0.7395437 -0.0983571 0.6096240 +VERTEX_SE3:QUAT 3970 9.235895 8.426536 -2.396827 0.0331758 0.3200611 -0.7656434 0.5570012 +VERTEX_SE3:QUAT 3971 9.198027 8.438017 -2.222236 -0.7287019 0.2790795 -0.3129357 0.5414605 +VERTEX_SE3:QUAT 3972 9.191182 8.579062 -2.095507 0.3222028 0.2833048 -0.6845808 0.5892986 +VERTEX_SE3:QUAT 3973 9.420562 8.842783 -1.718861 0.4719311 0.0582521 0.1294839 0.8701274 +VERTEX_SE3:QUAT 3974 9.515948 8.767937 -1.614689 0.0713562 -0.0410735 -0.2114135 0.9739228 +VERTEX_SE3:QUAT 3975 9.636792 8.781141 -1.944055 -0.0110889 0.2644271 0.8013283 0.5364963 +VERTEX_SE3:QUAT 3976 9.538267 8.825112 -1.889964 -0.5006403 0.2640592 -0.7418940 0.3594792 +VERTEX_SE3:QUAT 3977 9.565877 8.719503 -1.894573 -0.0886374 0.7160348 -0.6606575 0.2072903 +VERTEX_SE3:QUAT 3978 9.488533 8.820722 -1.870669 -0.2130285 0.5303642 -0.6323614 0.5229261 +VERTEX_SE3:QUAT 3979 9.489293 8.691829 -2.001764 -0.2184683 -0.2759486 -0.8868899 0.2992496 +VERTEX_SE3:QUAT 3980 9.526960 8.821085 -1.920274 -0.2144943 0.3048642 0.2807746 0.8844295 +VERTEX_SE3:QUAT 3981 9.454504 8.863655 -1.792755 0.1546981 0.0158758 -0.4377239 0.8855587 +VERTEX_SE3:QUAT 3982 9.520277 8.755162 -1.809150 0.0566172 0.5810719 0.2860260 0.7598283 +VERTEX_SE3:QUAT 3983 9.437907 8.648718 -1.647864 0.4206929 -0.3685303 0.3586894 0.7473585 +VERTEX_SE3:QUAT 3984 9.434180 8.436825 -1.602191 0.0052542 0.2974331 0.5052485 0.8100802 +VERTEX_SE3:QUAT 3985 9.497785 8.384302 -1.537129 0.2211082 -0.1267924 -0.3307898 0.9086325 +VERTEX_SE3:QUAT 3986 9.448408 8.413055 -1.393114 -0.1486774 0.0302871 -0.9002065 0.4081740 +VERTEX_SE3:QUAT 3987 9.491986 8.299185 -1.306499 -0.3483559 0.1392797 -0.8143533 0.4428070 +VERTEX_SE3:QUAT 3988 9.531503 8.452977 -1.210427 0.0744960 0.6045529 -0.3439628 0.7146018 +VERTEX_SE3:QUAT 3989 9.584817 8.491175 -1.191526 0.5551843 -0.6475806 0.3415237 0.3946787 +VERTEX_SE3:QUAT 3990 9.486091 8.469355 -1.097539 0.1094781 0.8732961 -0.1596281 0.4470876 +VERTEX_SE3:QUAT 3991 9.521646 8.539536 -0.928144 0.5239819 0.5746042 0.2506069 0.5766014 +VERTEX_SE3:QUAT 3992 9.495977 8.597072 -0.733882 0.3713451 -0.1963643 -0.6009215 0.6800274 +VERTEX_SE3:QUAT 3993 9.476566 8.453984 -0.682614 0.1638861 0.3941365 -0.8065318 0.4090285 +VERTEX_SE3:QUAT 3994 9.565412 8.461424 -0.553772 -0.3234805 0.1359731 0.9210911 0.1687093 +VERTEX_SE3:QUAT 3995 9.537607 8.261254 -0.457367 -0.3232181 -0.1582937 0.0574752 0.9312195 +VERTEX_SE3:QUAT 3996 9.319307 8.148993 -0.477682 0.8120149 -0.0823376 -0.1683890 0.5527183 +VERTEX_SE3:QUAT 3997 9.279888 7.930994 -0.336747 0.3640196 -0.1858410 0.7524730 0.5164661 +VERTEX_SE3:QUAT 3998 9.027076 7.904633 -0.221805 0.1911407 0.6349766 -0.2514452 0.7050144 +VERTEX_SE3:QUAT 3999 8.949426 7.969662 -0.258641 0.5444670 0.5134030 -0.6236650 0.2258651 +VERTEX_SE3:QUAT 4000 8.766819 7.873447 -0.236880 0.0228287 -0.3286011 -0.8770088 0.3497939 +VERTEX_SE3:QUAT 4001 8.862851 7.788310 -0.329213 0.4972026 -0.0888163 0.8495615 0.1521400 +VERTEX_SE3:QUAT 4002 8.650524 7.744100 -0.299828 0.0317968 -0.0820559 -0.8546585 0.5116783 +VERTEX_SE3:QUAT 4003 8.741108 7.736005 -0.429456 0.1345873 0.2957439 -0.9445608 0.0471875 +VERTEX_SE3:QUAT 4004 8.708685 7.801191 -0.435472 0.5476835 -0.5205967 0.5025083 0.4201277 +VERTEX_SE3:QUAT 4005 8.604992 7.849605 -0.398195 0.4885983 0.4562642 -0.0971431 0.7373316 +VERTEX_SE3:QUAT 4006 8.632588 7.544845 -0.302123 -0.4818623 -0.0730424 0.8731085 0.0124535 +VERTEX_SE3:QUAT 4007 8.651575 7.496713 -0.449643 -0.7213724 0.1306407 -0.6760569 0.0741748 +VERTEX_SE3:QUAT 4008 8.567452 7.384996 -0.552157 0.3886973 -0.0078652 0.0590500 0.9194377 +VERTEX_SE3:QUAT 4009 8.324949 7.341030 -0.467273 0.3894695 -0.5008384 0.3851590 0.6701693 +VERTEX_SE3:QUAT 4010 8.309819 7.188696 -0.426011 0.1994218 -0.2234657 0.2036449 0.9321066 +VERTEX_SE3:QUAT 4011 8.275508 7.205473 -0.576212 -0.0523918 -0.2840325 -0.3327191 0.8977074 +VERTEX_SE3:QUAT 4012 8.257853 7.066862 -0.519761 0.5027744 -0.2882366 -0.6891313 0.4350122 +VERTEX_SE3:QUAT 4013 8.195540 7.261653 -0.685102 -0.1708058 0.3632242 0.4298024 0.8088037 +VERTEX_SE3:QUAT 4014 8.187478 7.080210 -0.740090 0.1453610 -0.4850186 -0.0131995 0.8622372 +VERTEX_SE3:QUAT 4015 8.260028 6.982145 -0.757858 0.1268079 -0.0528569 -0.9583017 0.2505667 +VERTEX_SE3:QUAT 4016 8.267004 6.759009 -0.904570 0.0807053 0.3568550 -0.2181158 0.9047468 +VERTEX_SE3:QUAT 4017 8.253681 6.733360 -0.814038 0.1599035 -0.6150115 0.5619654 0.5295155 +VERTEX_SE3:QUAT 4018 8.311063 6.777673 -0.690921 -0.3553843 0.1152299 -0.9271912 0.0272138 +VERTEX_SE3:QUAT 4019 8.191458 6.942743 -0.650439 0.5497355 -0.0646461 -0.8129984 0.1806805 +VERTEX_SE3:QUAT 4020 8.225545 6.979730 -0.648805 0.1603783 0.2364844 -0.3467351 0.8933805 +VERTEX_SE3:QUAT 4021 8.280867 6.840883 -0.720245 -0.2709944 -0.2578545 0.1997404 0.9056362 +VERTEX_SE3:QUAT 4022 8.281158 6.743778 -0.767642 0.3626607 0.3913606 -0.7365410 0.4157180 +VERTEX_SE3:QUAT 4023 8.332063 6.753557 -0.846129 -0.0143957 -0.1863331 -0.8729227 0.4506426 +VERTEX_SE3:QUAT 4024 8.309552 6.733313 -1.042522 0.0662390 -0.4267628 0.7922270 0.4311174 +VERTEX_SE3:QUAT 4025 8.286830 6.733828 -0.980066 0.2428657 0.3018672 0.1292856 0.9127857 +VERTEX_SE3:QUAT 4026 8.181126 6.592360 -1.028571 0.4898546 0.5399887 0.3962290 0.5580836 +VERTEX_SE3:QUAT 4027 8.240309 6.570158 -1.205543 -0.0512387 -0.6286201 0.6369074 0.4433513 +VERTEX_SE3:QUAT 4028 8.165263 6.439896 -1.238875 -0.0536038 0.7547695 -0.6417122 0.1251204 +VERTEX_SE3:QUAT 4029 7.975023 6.463796 -1.224275 -0.0892021 0.1337562 0.9809714 0.1088461 +VERTEX_SE3:QUAT 4030 8.073798 6.353370 -1.215367 -0.1609611 0.0062245 0.9483514 0.2732807 +VERTEX_SE3:QUAT 4031 8.252745 6.226928 -1.278853 0.1231575 -0.3445878 0.1835911 0.9123518 +VERTEX_SE3:QUAT 4032 8.239279 6.195421 -1.306668 0.4177325 0.2489282 0.0161276 0.8736556 +VERTEX_SE3:QUAT 4033 8.145189 6.068385 -1.415268 0.2361956 -0.2741763 0.9167334 0.1692303 +VERTEX_SE3:QUAT 4034 8.027801 6.069352 -1.462121 0.3708025 -0.3519558 -0.0221973 0.8591507 +VERTEX_SE3:QUAT 4035 7.966678 6.125400 -1.452992 0.2195647 -0.6885100 0.2339923 0.6503790 +VERTEX_SE3:QUAT 4036 7.771871 6.125485 -1.452571 -0.0623531 0.9442614 -0.3221053 0.0270297 +VERTEX_SE3:QUAT 4037 7.779521 5.972910 -1.438889 0.1398667 0.6003489 -0.1111481 0.7795285 +VERTEX_SE3:QUAT 4038 7.890702 5.891789 -1.481513 0.6887678 -0.1159871 -0.6187640 0.3595511 +VERTEX_SE3:QUAT 4039 7.850312 6.079496 -1.526598 0.5924386 0.4702785 0.1849936 0.6274010 +VERTEX_SE3:QUAT 4040 7.934410 6.040466 -1.637774 -0.0241179 0.7787013 -0.0581400 0.6242294 +VERTEX_SE3:QUAT 4041 7.981139 5.903518 -1.461879 0.4780604 0.1381254 -0.6980603 0.5148704 +VERTEX_SE3:QUAT 4042 8.191690 5.878776 -1.627440 -0.0740890 0.1515227 -0.2184250 0.9611671 +VERTEX_SE3:QUAT 4043 8.198202 5.917385 -1.741578 0.3174160 -0.1041135 0.9413750 0.0471238 +VERTEX_SE3:QUAT 4044 8.289830 5.748050 -1.899520 0.4095121 0.6651174 -0.3352861 0.5267845 +VERTEX_SE3:QUAT 4045 8.164002 5.909622 -1.934676 0.6023360 0.1949313 -0.6907483 0.3493707 +VERTEX_SE3:QUAT 4046 8.218019 5.903170 -2.093082 0.3573914 0.6758531 -0.6244187 0.1599853 +VERTEX_SE3:QUAT 4047 8.122891 5.801551 -2.104731 0.4963486 0.3579265 0.2356843 0.7549700 +VERTEX_SE3:QUAT 4048 7.923274 5.921666 -2.167289 0.0040265 0.1257588 0.9904175 0.0569357 +VERTEX_SE3:QUAT 4049 7.998019 6.010309 -2.223365 -0.1264426 0.2934808 0.4393819 0.8395385 +VERTEX_SE3:QUAT 4050 7.852936 6.103472 -2.271206 0.6630676 0.4653582 0.2872329 0.5111559 +VERTEX_SE3:QUAT 4051 7.685556 6.093237 -2.176447 0.0424543 -0.2540498 0.8504122 0.4587542 +VERTEX_SE3:QUAT 4052 7.852778 6.097650 -2.215096 0.2218568 0.4714393 0.0740889 0.8503149 +VERTEX_SE3:QUAT 4053 7.748596 6.213767 -2.044739 0.2433879 0.4797586 0.4095739 0.7367789 +VERTEX_SE3:QUAT 4054 7.665829 6.206324 -1.867365 0.3047276 0.6197255 -0.4763632 0.5442054 +VERTEX_SE3:QUAT 4055 7.762494 6.256423 -2.001643 -0.1997753 -0.4003904 0.7751800 0.4459521 +VERTEX_SE3:QUAT 4056 7.619613 6.285051 -1.880924 0.3566744 0.2681332 -0.4676004 0.7630451 +VERTEX_SE3:QUAT 4057 7.540704 6.296116 -2.085447 0.7926164 0.0953702 0.0177726 0.6019534 +VERTEX_SE3:QUAT 4058 7.487127 6.212780 -2.104168 0.3681213 -0.3885496 -0.0160234 0.8445467 +VERTEX_SE3:QUAT 4059 7.493887 6.126218 -2.076275 0.3524610 0.0393773 0.1462109 0.9234950 +VERTEX_SE3:QUAT 4060 7.448810 6.075572 -2.139549 -0.1291381 -0.2807266 0.7217560 0.6193418 +VERTEX_SE3:QUAT 4061 7.411114 6.011573 -2.054257 -0.3090426 0.5828316 -0.1948623 0.7258297 +VERTEX_SE3:QUAT 4062 7.412011 6.128954 -1.960135 0.6750932 0.1325301 0.3912497 0.6112353 +VERTEX_SE3:QUAT 4063 7.259379 5.989125 -1.851931 -0.4902717 0.5816960 -0.6207717 0.1894887 +VERTEX_SE3:QUAT 4064 7.364848 6.145191 -1.720089 -0.4646176 0.5406529 -0.3878621 0.5842841 +VERTEX_SE3:QUAT 4065 7.267301 6.174013 -1.655975 0.2821179 0.2282025 0.6869161 0.6296661 +VERTEX_SE3:QUAT 4066 7.120088 6.217816 -1.576196 0.7082439 -0.2890277 0.5966983 0.2424968 +VERTEX_SE3:QUAT 4067 7.127576 6.251427 -1.656966 0.2671290 0.1395824 -0.2742158 0.9132166 +VERTEX_SE3:QUAT 4068 7.324677 6.113666 -1.751844 0.1992607 -0.3863739 0.5588091 0.7062172 +VERTEX_SE3:QUAT 4069 7.355061 6.130856 -1.847382 -0.0131863 -0.5193768 0.8544433 0.0006885 +VERTEX_SE3:QUAT 4070 7.310300 6.218823 -1.984274 0.0701408 0.1875465 -0.0683263 0.9773628 +VERTEX_SE3:QUAT 4071 7.356642 6.404256 -1.959070 0.4401737 0.2909318 0.7614327 0.3765979 +VERTEX_SE3:QUAT 4072 7.481749 6.547600 -1.806925 -0.5369003 0.3942294 -0.6980695 0.2627172 +VERTEX_SE3:QUAT 4073 7.649649 6.752064 -1.724610 0.1750485 0.1112338 -0.3653699 0.9074635 +VERTEX_SE3:QUAT 4074 7.718975 6.723389 -1.837810 0.1456158 0.5565434 -0.7743973 0.2633711 +VERTEX_SE3:QUAT 4075 7.703645 6.691338 -1.706106 0.2703714 0.1940952 -0.9311591 0.1488928 +VERTEX_SE3:QUAT 4076 7.580598 6.690613 -1.666798 0.7732203 0.3034362 0.2609534 0.4918945 +VERTEX_SE3:QUAT 4077 7.532510 6.885676 -1.629625 0.2026350 0.3060780 -0.7707917 0.5207067 +VERTEX_SE3:QUAT 4078 7.488957 6.910460 -1.698868 -0.0031049 0.7680612 -0.5079905 0.3898950 +VERTEX_SE3:QUAT 4079 7.385997 7.032614 -1.610131 -0.5045420 -0.1374809 -0.8523282 0.0085430 +VERTEX_SE3:QUAT 4080 7.406212 7.240105 -1.430319 0.5226961 0.2536125 0.6097711 0.5391185 +VERTEX_SE3:QUAT 4081 7.479914 7.370641 -1.484700 -0.4864839 -0.0371846 -0.8051135 0.3372580 +VERTEX_SE3:QUAT 4082 7.456574 7.475942 -1.453558 0.1205498 0.3279932 0.9361661 0.0384876 +VERTEX_SE3:QUAT 4083 7.636843 7.544685 -1.459042 -0.0742983 0.6322260 -0.6474565 0.4190110 +VERTEX_SE3:QUAT 4084 7.732099 7.540668 -1.299858 0.3932617 -0.1924153 0.7216686 0.5362052 +VERTEX_SE3:QUAT 4085 7.639267 7.593146 -1.329361 -0.0766051 0.3431597 -0.2681748 0.8969144 +VERTEX_SE3:QUAT 4086 7.602895 7.707518 -1.168946 0.7915367 0.0111195 0.5344477 0.2961615 +VERTEX_SE3:QUAT 4087 7.638204 7.668375 -1.271077 -0.3020598 0.3103103 -0.8512773 0.2963011 +VERTEX_SE3:QUAT 4088 7.587713 7.656518 -1.357933 -0.2890641 0.1786832 -0.1412156 0.9298239 +VERTEX_SE3:QUAT 4089 7.531667 7.681218 -1.374506 -0.4079635 0.5877292 -0.5718436 0.4014162 +VERTEX_SE3:QUAT 4090 7.474716 7.716459 -1.452136 -0.2853679 0.1810021 0.3996155 0.8521214 +VERTEX_SE3:QUAT 4091 7.597226 7.763582 -1.356080 0.1994848 0.2639805 -0.7715901 0.5432944 +VERTEX_SE3:QUAT 4092 7.743946 7.615353 -1.370340 0.4881246 0.3329873 -0.6322383 0.5011272 +VERTEX_SE3:QUAT 4093 7.708563 7.617827 -1.250133 -0.0724746 0.0666021 -0.7038799 0.7034662 +VERTEX_SE3:QUAT 4094 7.855487 7.538153 -1.152170 0.1690824 -0.2629343 0.4053696 0.8590414 +VERTEX_SE3:QUAT 4095 7.740703 7.628789 -1.162196 -0.5816023 -0.0252682 -0.8129171 0.0163105 +VERTEX_SE3:QUAT 4096 7.770315 7.558655 -1.395665 0.2079132 -0.0184661 0.2387904 0.9483724 +VERTEX_SE3:QUAT 4097 7.778174 7.472826 -1.416280 0.4110290 0.7066439 0.0657590 0.5721759 +VERTEX_SE3:QUAT 4098 7.662853 7.443186 -1.502037 0.2539470 0.3823879 -0.8506402 0.2563235 +VERTEX_SE3:QUAT 4099 7.742928 7.395632 -1.475787 -0.2736538 0.2051231 -0.5071713 0.7910850 +VERTEX_SE3:QUAT 4100 7.653899 7.391537 -1.566409 0.2440045 -0.2445006 -0.9109834 0.2253673 +VERTEX_SE3:QUAT 4101 7.640591 7.188946 -1.377283 -0.6687653 0.4463510 -0.5896199 0.0766300 +VERTEX_SE3:QUAT 4102 7.667978 7.141283 -1.502182 0.6787584 -0.0182483 0.7271151 0.1012802 +VERTEX_SE3:QUAT 4103 7.728634 7.121223 -1.533222 0.0550800 0.6507569 -0.7217957 0.2291126 +VERTEX_SE3:QUAT 4104 7.623566 7.187041 -1.388939 0.1154624 0.5882336 -0.7790360 0.1837190 +VERTEX_SE3:QUAT 4105 7.729442 7.254153 -1.381310 0.0964352 0.6267538 -0.7694316 0.0765174 +VERTEX_SE3:QUAT 4106 7.837851 7.328085 -1.363889 0.5438593 -0.2102580 -0.5754142 0.5735043 +VERTEX_SE3:QUAT 4107 7.903808 7.083664 -1.453073 -0.2494170 0.4332693 -0.4599304 0.7338480 +VERTEX_SE3:QUAT 4108 7.875515 7.025896 -1.279046 0.3508576 0.4477036 -0.7728895 0.2812512 +VERTEX_SE3:QUAT 4109 7.901277 6.819138 -1.274294 -0.4175933 0.7812780 -0.3393419 0.3163347 +VERTEX_SE3:QUAT 4110 7.988161 6.858188 -1.335835 -0.3633828 -0.0815488 -0.9260611 0.0609392 +VERTEX_SE3:QUAT 4111 8.105168 6.820149 -1.289750 0.1521695 0.8217795 -0.3722095 0.4037114 +VERTEX_SE3:QUAT 4112 8.229231 6.779168 -1.297618 0.3269256 -0.4155788 0.1437449 0.8365114 +VERTEX_SE3:QUAT 4113 8.324887 6.865622 -1.297316 0.3192659 -0.6171489 0.2978385 0.6545905 +VERTEX_SE3:QUAT 4114 8.291085 6.859356 -1.232812 0.4382886 0.6126757 0.3283979 0.5698126 +VERTEX_SE3:QUAT 4115 8.156460 6.718261 -1.255750 0.4179478 0.6698173 -0.2690138 0.5516303 +VERTEX_SE3:QUAT 4116 8.260121 6.668096 -1.250779 -0.0863925 0.6390933 -0.1949957 0.7389674 +VERTEX_SE3:QUAT 4117 8.300816 6.652875 -1.239221 -0.2382739 0.8388133 -0.3607297 0.3308956 +VERTEX_SE3:QUAT 4118 8.421800 6.630609 -1.320443 0.3730431 0.5242778 0.7553386 0.1242386 +VERTEX_SE3:QUAT 4119 8.272520 6.562748 -1.424128 -0.0421750 -0.0511194 -0.7699789 0.6346185 +VERTEX_SE3:QUAT 4120 8.106126 6.481488 -1.493876 0.3516613 -0.4490312 0.8211148 0.0218102 +VERTEX_SE3:QUAT 4121 8.159038 6.419163 -1.377563 0.6959239 0.3637863 -0.4779949 0.3935356 +VERTEX_SE3:QUAT 4122 8.232509 6.316361 -1.528855 0.1595160 0.6791817 -0.6926605 0.1829980 +VERTEX_SE3:QUAT 4123 8.150155 6.181536 -1.476258 -0.3104654 0.0702222 -0.3618681 0.8762029 +VERTEX_SE3:QUAT 4124 8.222649 6.161814 -1.553478 0.2437748 0.3309436 0.7565205 0.5086520 +VERTEX_SE3:QUAT 4125 8.321800 6.053086 -1.766668 -0.1090408 0.0907766 0.0322427 0.9893584 +VERTEX_SE3:QUAT 4126 8.162003 6.099906 -1.564413 -0.5070616 0.4609813 -0.3040286 0.6617790 +VERTEX_SE3:QUAT 4127 8.178996 6.054548 -1.555191 0.4760426 0.1385143 -0.2893973 0.8188079 +VERTEX_SE3:QUAT 4128 8.023604 5.978826 -1.574748 0.6958647 0.3857858 -0.4803844 0.3690156 +VERTEX_SE3:QUAT 4129 7.816378 6.091284 -1.529370 -0.0823295 0.7525789 -0.0277360 0.6527462 +VERTEX_SE3:QUAT 4130 7.880101 6.126591 -1.473185 0.5676537 0.5086877 0.3035250 0.5717331 +VERTEX_SE3:QUAT 4131 7.762263 6.024509 -1.548944 0.7494485 -0.1259706 0.6498679 0.0114061 +VERTEX_SE3:QUAT 4132 7.792359 6.000383 -1.492061 -0.2595399 0.4702523 0.3847679 0.7506367 +VERTEX_SE3:QUAT 4133 7.812571 6.047143 -1.465868 0.1734780 0.4454839 -0.3987755 0.7825775 +VERTEX_SE3:QUAT 4134 7.909362 6.007733 -1.764968 -0.5396684 0.3898509 -0.7336036 0.1363820 +VERTEX_SE3:QUAT 4135 7.860723 5.986057 -1.738403 0.1761410 0.5269404 -0.7846514 0.2750096 +VERTEX_SE3:QUAT 4136 7.903807 6.010850 -1.720622 0.2936066 0.8042476 -0.4627792 0.2298182 +VERTEX_SE3:QUAT 4137 7.774469 6.083501 -1.781101 -0.0152364 -0.1352482 -0.4516694 0.8817429 +VERTEX_SE3:QUAT 4138 7.747869 6.109991 -1.823703 0.2282312 0.8671489 -0.4244850 0.1256017 +VERTEX_SE3:QUAT 4139 7.739901 6.075270 -1.817602 -0.1036158 -0.4006701 0.4296652 0.8025678 +VERTEX_SE3:QUAT 4140 7.692577 6.027566 -1.846834 -0.1120796 -0.6169125 0.7395776 0.2447082 +VERTEX_SE3:QUAT 4141 7.599173 6.085946 -1.755019 -0.3339379 0.1545193 -0.9294292 0.0277601 +VERTEX_SE3:QUAT 4142 7.498515 6.137485 -1.823875 0.6124722 0.0953476 -0.6763685 0.3978848 +VERTEX_SE3:QUAT 4143 7.472702 6.165330 -1.800020 -0.1634669 -0.7151425 0.6790060 0.0282939 +VERTEX_SE3:QUAT 4144 7.319342 6.220320 -1.848117 0.4824537 -0.1295667 0.3153477 0.8068499 +VERTEX_SE3:QUAT 4145 7.435721 6.412306 -1.990703 -0.1600933 0.8948617 -0.4162550 0.0180115 +VERTEX_SE3:QUAT 4146 7.532718 6.333023 -1.979451 -0.1965167 -0.2996360 -0.1702573 0.9179389 +VERTEX_SE3:QUAT 4147 7.501700 6.364701 -2.077542 0.0292262 -0.2409804 0.2534295 0.9364015 +VERTEX_SE3:QUAT 4148 7.581324 6.286925 -2.193079 0.4824660 -0.2527564 -0.4464702 0.7099332 +VERTEX_SE3:QUAT 4149 7.481616 6.329656 -2.085776 0.0540838 0.6645961 -0.6636884 0.3389759 +VERTEX_SE3:QUAT 4150 7.416526 6.510598 -2.072796 0.4387353 0.3730882 -0.3241827 0.7504812 +VERTEX_SE3:QUAT 4151 7.414198 6.550340 -2.157288 0.1769516 -0.4792564 0.2414774 0.8250394 +VERTEX_SE3:QUAT 4152 7.519860 6.452803 -2.259629 -0.3549036 0.3419095 -0.8381653 0.2337097 +VERTEX_SE3:QUAT 4153 7.722085 6.596888 -2.209272 0.2169853 0.2843403 -0.9199745 0.1603588 +VERTEX_SE3:QUAT 4154 7.618927 6.776399 -2.372198 0.1460871 0.7395241 -0.6351971 0.1681885 +VERTEX_SE3:QUAT 4155 7.563936 6.807679 -2.519058 0.8801759 -0.0839401 -0.1866325 0.4282670 +VERTEX_SE3:QUAT 4156 7.608300 6.854814 -2.545487 0.3580870 -0.1690855 0.7980071 0.4542779 +VERTEX_SE3:QUAT 4157 7.406306 7.030486 -2.549261 0.0978268 -0.5147200 0.0500025 0.8502899 +VERTEX_SE3:QUAT 4158 7.274142 7.149903 -2.688264 0.0058985 0.0668541 0.6876669 0.7229177 +VERTEX_SE3:QUAT 4159 7.479772 7.225464 -2.786166 0.1046478 -0.0338159 -0.9177102 0.3817240 +VERTEX_SE3:QUAT 4160 7.475760 7.361991 -2.738838 0.2497764 -0.6252543 0.1962924 0.7128380 +VERTEX_SE3:QUAT 4161 7.354036 7.439945 -2.924461 0.5604436 0.1284296 0.7047129 0.4156784 +VERTEX_SE3:QUAT 4162 7.351800 7.547026 -2.947415 0.2144870 0.2718836 0.9379383 0.0186117 +VERTEX_SE3:QUAT 4163 7.237284 7.554310 -3.045464 0.4415609 -0.6136594 0.3348288 0.5624373 +VERTEX_SE3:QUAT 4164 7.355550 7.439319 -2.954537 -0.2890063 -0.2773327 0.3000984 0.8657383 +VERTEX_SE3:QUAT 4165 7.294436 7.341481 -2.906710 0.5573542 -0.4421995 0.6009010 0.3643266 +VERTEX_SE3:QUAT 4166 7.300320 7.615050 -2.900282 0.3400676 0.3172117 0.8778785 0.1142811 +VERTEX_SE3:QUAT 4167 7.275407 7.714737 -2.867384 0.4476503 0.5905505 -0.1456013 0.6554842 +VERTEX_SE3:QUAT 4168 7.402270 7.634674 -2.773772 -0.0073624 0.0965632 -0.7179537 0.6893212 +VERTEX_SE3:QUAT 4169 7.327404 7.487715 -2.631251 0.5825398 -0.4689817 0.5383733 0.3884041 +VERTEX_SE3:QUAT 4170 7.237831 7.547127 -2.596345 0.4670353 -0.7113546 0.5202002 0.0724179 +VERTEX_SE3:QUAT 4171 7.240657 7.436182 -2.453525 -0.0410319 -0.1541244 0.9175600 0.3642056 +VERTEX_SE3:QUAT 4172 7.212109 7.298344 -2.332453 -0.0621276 0.4625165 -0.6683494 0.5792475 +VERTEX_SE3:QUAT 4173 7.234484 7.331309 -2.131936 0.8119660 -0.0547784 0.5387577 0.2178315 +VERTEX_SE3:QUAT 4174 7.150520 7.374034 -2.229021 0.6210186 -0.4375940 0.4129324 0.5023288 +VERTEX_SE3:QUAT 4175 7.082865 7.540668 -2.210162 0.6681258 0.4983263 -0.3343801 0.4398509 +VERTEX_SE3:QUAT 4176 7.056676 7.754115 -2.183906 0.7451603 0.3735955 0.4583472 0.3083509 +VERTEX_SE3:QUAT 4177 7.195199 7.565522 -2.168237 0.4548009 0.5933809 -0.4111709 0.5215302 +VERTEX_SE3:QUAT 4178 7.046881 7.714486 -2.048762 0.4497133 0.4992537 0.6108180 0.4188139 +VERTEX_SE3:QUAT 4179 7.040846 7.644421 -1.943921 -0.4001515 0.6475186 -0.6475261 0.0361715 +VERTEX_SE3:QUAT 4180 7.137609 7.872862 -1.822189 0.2460796 -0.0944102 0.9193090 0.2922369 +VERTEX_SE3:QUAT 4181 6.999047 7.945879 -1.858427 -0.0358575 0.2589123 -0.3289998 0.9074347 +VERTEX_SE3:QUAT 4182 6.871978 7.944730 -1.670537 0.0391436 -0.8476420 0.3801358 0.3680594 +VERTEX_SE3:QUAT 4183 6.810853 8.038342 -1.483826 0.0151839 -0.7125626 0.4045784 0.5730099 +VERTEX_SE3:QUAT 4184 6.668724 8.136471 -1.494183 0.3864174 0.0385215 -0.6238054 0.6782806 +VERTEX_SE3:QUAT 4185 6.803309 8.032905 -1.360837 0.6567332 -0.5330075 0.4742566 0.2443056 +VERTEX_SE3:QUAT 4186 7.066223 8.028048 -1.342330 -0.3830604 0.7775463 -0.4881401 0.1020085 +VERTEX_SE3:QUAT 4187 7.123512 8.079384 -1.257838 -0.2270341 -0.2762127 0.9215798 0.1511711 +VERTEX_SE3:QUAT 4188 7.045257 7.983515 -1.277757 0.7295330 -0.0896976 0.6454995 0.2075241 +VERTEX_SE3:QUAT 4189 7.088941 8.131786 -1.402074 0.3784173 0.3666220 -0.8498875 0.0089423 +VERTEX_SE3:QUAT 4190 7.109855 7.988176 -1.332605 0.3847984 0.5556238 -0.6571926 0.3336319 +VERTEX_SE3:QUAT 4191 7.316409 7.852394 -1.150101 0.1797405 0.6885136 0.1063975 0.6944940 +VERTEX_SE3:QUAT 4192 7.415828 7.816638 -0.942085 0.7446586 0.3668613 -0.1845600 0.5261501 +VERTEX_SE3:QUAT 4193 7.346517 7.661146 -0.991032 0.2031735 -0.5775430 0.7231496 0.3197175 +VERTEX_SE3:QUAT 4194 7.419303 7.757460 -0.929641 0.9129573 0.0927476 0.1044001 0.3834155 +VERTEX_SE3:QUAT 4195 7.507364 7.804996 -0.953176 0.2956221 -0.0163294 0.5326496 0.7928590 +VERTEX_SE3:QUAT 4196 7.624516 7.664264 -0.980760 0.2668697 0.4324572 -0.8599224 0.0479048 +VERTEX_SE3:QUAT 4197 7.654501 7.618722 -1.065605 0.0527525 0.0009401 0.9087329 0.4140299 +VERTEX_SE3:QUAT 4198 7.625265 7.422518 -1.181471 -0.2738690 0.5984013 -0.4321607 0.6165621 +VERTEX_SE3:QUAT 4199 7.766028 7.366265 -1.359872 0.5832868 -0.4251527 0.5240578 0.4520898 +VERTEX_SE3:QUAT 4200 7.780274 7.409518 -1.486152 0.4988301 -0.3465276 0.1141895 0.7861603 +VERTEX_SE3:QUAT 4201 7.868545 7.312996 -1.465128 0.3903673 0.0594388 -0.8560902 0.3334514 +VERTEX_SE3:QUAT 4202 7.777354 6.998815 -1.448713 0.1345882 -0.6445039 0.3578153 0.6621699 +VERTEX_SE3:QUAT 4203 7.578127 6.949903 -1.482741 0.4898023 0.2644384 -0.0430834 0.8296444 +VERTEX_SE3:QUAT 4204 7.556457 7.061543 -1.464753 0.1904549 0.2502436 -0.5990965 0.7363344 +VERTEX_SE3:QUAT 4205 7.575785 7.110310 -1.389901 -0.0967275 0.2187892 -0.7805315 0.5775341 +VERTEX_SE3:QUAT 4206 7.731023 7.021032 -1.464764 0.4300430 -0.3610107 0.5227677 0.6414423 +VERTEX_SE3:QUAT 4207 7.865918 6.992414 -1.409370 0.5775295 0.5365870 -0.0658133 0.6117210 +VERTEX_SE3:QUAT 4208 7.975862 6.976216 -1.166047 0.4914224 0.1191266 -0.5915946 0.6279560 +VERTEX_SE3:QUAT 4209 8.035708 6.769241 -1.267012 0.7739782 0.6053015 -0.0947166 0.1599896 +VERTEX_SE3:QUAT 4210 7.934379 6.791814 -1.407934 0.7734206 0.3678583 -0.5136326 0.0517929 +VERTEX_SE3:QUAT 4211 8.016292 6.719442 -1.506660 0.6010958 -0.0405693 -0.0394590 0.7971706 +VERTEX_SE3:QUAT 4212 8.060732 6.693089 -1.559093 0.0404730 -0.0297116 0.9703186 0.2365607 +VERTEX_SE3:QUAT 4213 8.100848 6.629523 -1.644151 -0.5738573 0.2087884 -0.7429484 0.2740855 +VERTEX_SE3:QUAT 4214 8.192694 6.511613 -1.628576 0.5463804 0.5072833 0.2963869 0.5968977 +VERTEX_SE3:QUAT 4215 8.066252 6.538997 -1.667580 0.1830321 -0.1486615 0.1569529 0.9590437 +VERTEX_SE3:QUAT 4216 8.106160 6.515671 -1.728553 -0.6296733 0.3234038 -0.7059314 0.0241317 +VERTEX_SE3:QUAT 4217 8.070203 6.304979 -1.838356 -0.4226070 0.0741136 -0.8740890 0.2277694 +VERTEX_SE3:QUAT 4218 8.221297 6.419387 -1.870510 0.3826729 0.3579218 -0.7300137 0.4387865 +VERTEX_SE3:QUAT 4219 8.073557 6.436309 -2.119276 0.2549573 -0.2222209 -0.8197090 0.4622681 +VERTEX_SE3:QUAT 4220 8.036389 6.435667 -1.943249 0.6599829 0.5032559 0.1835831 0.5267384 +VERTEX_SE3:QUAT 4221 7.971128 6.397690 -1.952475 0.3227983 0.4432364 0.5645830 0.6169188 +VERTEX_SE3:QUAT 4222 8.091743 6.346697 -2.084729 0.8940244 0.0948504 -0.1049511 0.4250988 +VERTEX_SE3:QUAT 4223 8.277541 6.226973 -2.079649 0.3577142 -0.8027718 0.3397193 0.3349460 +VERTEX_SE3:QUAT 4224 8.287765 6.024812 -2.075488 0.3587563 0.5503513 -0.7431613 0.1269590 +VERTEX_SE3:QUAT 4225 8.364310 5.781290 -1.876391 0.0048863 0.0704640 0.9170712 0.3924172 +VERTEX_SE3:QUAT 4226 8.090904 5.805188 -1.884117 0.3911255 -0.2711576 0.4205482 0.7724206 +VERTEX_SE3:QUAT 4227 8.168337 5.766725 -1.998977 0.0770240 -0.0980948 -0.3916230 0.9116338 +VERTEX_SE3:QUAT 4228 8.286088 5.811855 -2.053058 0.0436577 -0.5509359 0.7802968 0.2927464 +VERTEX_SE3:QUAT 4229 8.222533 5.788640 -2.048975 -0.2427583 0.7433149 -0.2833689 0.5552058 +VERTEX_SE3:QUAT 4230 8.188022 5.918989 -2.015024 0.3853875 0.1121730 0.8835223 0.2414167 +VERTEX_SE3:QUAT 4231 8.272380 5.973828 -2.137191 0.4389654 -0.3253003 0.1286835 0.8276047 +VERTEX_SE3:QUAT 4232 8.157516 5.782700 -1.987558 0.3836831 0.3258544 0.7403707 0.4454855 +VERTEX_SE3:QUAT 4233 8.168937 5.660389 -2.056682 -0.2399565 -0.0103325 -0.2027345 0.9493223 +VERTEX_SE3:QUAT 4234 8.208517 5.642646 -1.992619 0.0985795 0.3709865 -0.7155640 0.5836259 +VERTEX_SE3:QUAT 4235 8.271057 5.729344 -2.119058 0.1214697 0.7845402 -0.0250965 0.6075458 +VERTEX_SE3:QUAT 4236 8.317341 5.722479 -2.221626 -0.4030678 0.5733225 -0.5046801 0.5041186 +VERTEX_SE3:QUAT 4237 8.235836 5.688323 -2.240069 0.4512464 0.4816016 -0.3594261 0.6597344 +VERTEX_SE3:QUAT 4238 8.129901 5.768918 -2.299876 -0.2376432 0.0018111 0.3336332 0.9122562 +VERTEX_SE3:QUAT 4239 7.999131 5.659716 -2.277563 0.6780192 0.2210614 -0.6047068 0.3546145 +VERTEX_SE3:QUAT 4240 8.074635 5.558607 -2.463825 0.8350797 -0.1587921 0.0628796 0.5229466 +VERTEX_SE3:QUAT 4241 8.206521 5.422358 -2.413061 -0.0060857 0.7323604 -0.5710271 0.3708630 +VERTEX_SE3:QUAT 4242 8.089286 5.500068 -2.346165 0.3408488 0.6585178 -0.4824664 0.4662646 +VERTEX_SE3:QUAT 4243 8.002153 5.609650 -2.266748 -0.0881834 0.3697131 -0.1321441 0.9154637 +VERTEX_SE3:QUAT 4244 7.866040 5.866952 -2.219049 0.1901933 -0.7168765 0.5104075 0.4351997 +VERTEX_SE3:QUAT 4245 7.761595 5.863776 -2.217209 -0.5131711 0.2234521 -0.6684486 0.4897969 +VERTEX_SE3:QUAT 4246 7.638069 6.020155 -2.313366 0.6533533 0.6825453 -0.0906485 0.3147129 +VERTEX_SE3:QUAT 4247 7.537187 5.974564 -2.314686 -0.3232655 0.5795930 -0.5018965 0.5546813 +VERTEX_SE3:QUAT 4248 7.457921 5.932972 -2.242341 0.5156185 0.6910744 -0.3957545 0.3161206 +VERTEX_SE3:QUAT 4249 7.340965 5.880251 -2.064027 0.1482477 0.3350469 -0.0789727 0.9271081 +VERTEX_SE3:QUAT 4250 7.286529 5.916109 -2.060448 0.5499914 0.0552132 0.1104931 0.8259856 +VERTEX_SE3:QUAT 4251 7.390690 5.847255 -2.028780 -0.2248507 0.0302938 0.7587410 0.6106035 +VERTEX_SE3:QUAT 4252 7.221653 5.939338 -2.087367 0.7146826 0.0134709 -0.2388527 0.6572645 +VERTEX_SE3:QUAT 4253 7.205071 6.028551 -2.029228 -0.1434507 -0.1196852 -0.9816540 0.0381149 +VERTEX_SE3:QUAT 4254 7.325388 6.052224 -2.093163 0.6339066 0.6277854 -0.0527321 0.4486282 +VERTEX_SE3:QUAT 4255 7.339856 6.086282 -2.064723 0.1332093 0.6884001 -0.7034412 0.1163232 +VERTEX_SE3:QUAT 4256 7.280701 6.223098 -2.033085 0.4402290 0.0160404 -0.1612693 0.8831384 +VERTEX_SE3:QUAT 4257 7.273765 6.276668 -2.024445 -0.3320478 0.4793247 0.4924866 0.6461030 +VERTEX_SE3:QUAT 4258 7.288742 6.404951 -2.165795 -0.4197249 -0.0982521 -0.6016853 0.6724227 +VERTEX_SE3:QUAT 4259 7.339654 6.643144 -2.117924 -0.1138947 0.3067749 -0.9292064 0.1717341 +VERTEX_SE3:QUAT 4260 7.278122 6.781053 -2.187108 0.8330844 -0.0397304 0.5362724 0.1296294 +VERTEX_SE3:QUAT 4261 7.285786 6.807769 -1.970866 0.0302108 0.3602608 0.1416046 0.9215463 +VERTEX_SE3:QUAT 4262 7.268952 6.898400 -1.878111 -0.4813405 -0.1478445 -0.8458005 0.1762803 +VERTEX_SE3:QUAT 4263 7.218137 6.885797 -1.915458 -0.7969231 -0.0344461 -0.5939371 0.1047171 +VERTEX_SE3:QUAT 4264 7.344810 6.921048 -1.857669 -0.8272215 -0.3195495 -0.4529339 0.0918891 +VERTEX_SE3:QUAT 4265 7.376611 6.861794 -1.822682 -0.1414892 0.1474180 0.6754272 0.7085526 +VERTEX_SE3:QUAT 4266 7.379231 6.947935 -1.817176 -0.0492655 0.6976537 -0.6664910 0.2581510 +VERTEX_SE3:QUAT 4267 7.293115 7.170133 -1.955322 0.4390799 -0.4364796 0.3029019 0.7245308 +VERTEX_SE3:QUAT 4268 7.310771 7.188873 -1.978064 -0.1442579 0.1419653 -0.4314273 0.8791507 +VERTEX_SE3:QUAT 4269 7.102475 7.284915 -1.915892 -0.1521755 0.3360788 0.7088091 0.6012349 +VERTEX_SE3:QUAT 4270 7.127965 7.347570 -1.711882 -0.0870288 0.4308455 -0.8541703 0.2778331 +VERTEX_SE3:QUAT 4271 7.160332 7.342748 -1.470486 0.3927821 0.3279331 -0.2232735 0.8296572 +VERTEX_SE3:QUAT 4272 7.130933 7.164792 -1.487882 -0.2375139 -0.2530268 -0.7086562 0.6143052 +VERTEX_SE3:QUAT 4273 7.050028 7.069574 -1.481819 0.1390708 0.7620553 -0.3232911 0.5435199 +VERTEX_SE3:QUAT 4274 6.945315 7.274037 -1.417048 0.2765106 -0.3699653 0.3575568 0.8116777 +VERTEX_SE3:QUAT 4275 6.887246 7.258685 -1.199557 0.7790059 0.0029915 -0.1968516 0.5953069 +VERTEX_SE3:QUAT 4276 6.615153 7.196113 -1.080712 0.4921972 0.6042654 0.3316982 0.5315840 +VERTEX_SE3:QUAT 4277 6.525461 7.110251 -1.049485 -0.1118654 0.8375694 -0.3837260 0.3724487 +VERTEX_SE3:QUAT 4278 6.525019 7.076565 -0.876146 0.1681360 0.7021514 -0.1049253 0.6838892 +VERTEX_SE3:QUAT 4279 6.535266 7.164323 -0.913788 -0.3002722 -0.3564666 -0.8270227 0.3143274 +VERTEX_SE3:QUAT 4280 6.660720 7.292645 -0.770233 -0.0028243 0.0880388 0.0229097 0.9958496 +VERTEX_SE3:QUAT 4281 6.734657 7.393904 -0.644241 -0.2836421 0.1781070 0.6236066 0.7063568 +VERTEX_SE3:QUAT 4282 6.795830 7.488583 -0.584165 0.2122092 0.2868142 0.9076681 0.2210056 +VERTEX_SE3:QUAT 4283 6.626738 7.630741 -0.619323 -0.1381389 0.8310133 -0.4343714 0.3188355 +VERTEX_SE3:QUAT 4284 6.566217 7.693997 -0.600690 -0.0007608 0.0370819 -0.6275987 0.7776530 +VERTEX_SE3:QUAT 4285 6.770884 7.697646 -0.503753 -0.2596571 0.3096427 0.1338426 0.9048678 +VERTEX_SE3:QUAT 4286 6.843115 7.603864 -0.488644 0.5394631 -0.1740217 -0.1120350 0.8161766 +VERTEX_SE3:QUAT 4287 6.934497 7.626706 -0.456071 -0.0457584 0.0874774 0.9702465 0.2210782 +VERTEX_SE3:QUAT 4288 6.767144 7.596285 -0.572090 0.3805848 -0.5587897 0.5791090 0.4555679 +VERTEX_SE3:QUAT 4289 6.910907 7.419838 -0.569409 0.1642518 -0.2374187 -0.6908544 0.6628529 +VERTEX_SE3:QUAT 4290 7.076048 7.267799 -0.443317 0.7203392 -0.2135166 0.5183875 0.4084073 +VERTEX_SE3:QUAT 4291 7.024386 7.242160 -0.510927 0.4829250 0.6180654 0.6017170 0.1507158 +VERTEX_SE3:QUAT 4292 6.969703 7.236630 -0.360486 -0.2775624 0.2473005 -0.4688100 0.8012607 +VERTEX_SE3:QUAT 4293 7.011244 7.357181 -0.221785 0.0787799 0.0360570 0.3029477 0.9490607 +VERTEX_SE3:QUAT 4294 7.116025 7.458286 -0.234905 -0.0376432 0.6041186 0.3678937 0.7058881 +VERTEX_SE3:QUAT 4295 7.208059 7.535208 -0.361945 -0.1076764 -0.0506783 -0.2843315 0.9513113 +VERTEX_SE3:QUAT 4296 7.316262 7.452257 -0.201430 0.6039583 -0.1972192 0.3496629 0.6885309 +VERTEX_SE3:QUAT 4297 7.308528 7.603546 -0.314577 0.0321570 -0.1581164 0.8115528 0.5615577 +VERTEX_SE3:QUAT 4298 7.453311 7.656193 -0.357253 0.3854224 -0.2677690 0.8537545 0.2255054 +VERTEX_SE3:QUAT 4299 7.381808 7.641841 -0.299824 -0.1959451 -0.2382413 -0.8589670 0.4086836 +VERTEX_SE3:QUAT 4300 7.487311 7.733520 -0.287510 0.4626010 0.1195043 0.2571886 0.8399840 +VERTEX_SE3:QUAT 4301 7.447517 7.597922 -0.254044 -0.0607330 -0.5261698 0.8476945 0.0295097 +VERTEX_SE3:QUAT 4302 7.437432 7.570654 -0.296327 -0.6724961 0.6160549 -0.3517162 0.2110004 +VERTEX_SE3:QUAT 4303 7.512766 7.504917 -0.305678 -0.0341730 -0.0008408 0.9904766 0.1333703 +VERTEX_SE3:QUAT 4304 7.392126 7.533284 -0.248735 -0.1738371 0.5868862 -0.4161113 0.6724557 +VERTEX_SE3:QUAT 4305 7.535714 7.436879 -0.300624 0.7445484 -0.2373393 0.4909880 0.3850305 +VERTEX_SE3:QUAT 4306 7.492849 7.252612 -0.356301 -0.2434925 0.8752570 -0.0273058 0.4170023 +VERTEX_SE3:QUAT 4307 7.622941 7.207801 -0.419009 0.3489275 0.6666878 -0.4812478 0.4496415 +VERTEX_SE3:QUAT 4308 7.761351 7.096869 -0.575277 -0.1423275 0.7592348 -0.1156264 0.6244485 +VERTEX_SE3:QUAT 4309 7.649510 6.881374 -0.753528 -0.0162731 0.5942349 -0.4562446 0.6621639 +VERTEX_SE3:QUAT 4310 7.701613 6.614570 -0.765183 0.2200338 0.7348514 0.3788854 0.5177108 +VERTEX_SE3:QUAT 4311 7.826913 6.407347 -1.053447 0.4199300 0.8436514 0.1078431 0.3166717 +VERTEX_SE3:QUAT 4312 7.940246 6.651637 -1.049273 0.1060168 0.4792235 0.7158650 0.4966312 +VERTEX_SE3:QUAT 4313 8.088783 6.498378 -1.170539 -0.7122724 0.3738065 -0.5898721 0.0706231 +VERTEX_SE3:QUAT 4314 8.173346 6.414679 -1.219012 0.4778359 0.4017673 -0.0930853 0.7756230 +VERTEX_SE3:QUAT 4315 8.303266 6.352409 -1.310719 -0.2806289 0.3713763 0.3858042 0.7965439 +VERTEX_SE3:QUAT 4316 8.384829 6.237223 -1.065306 0.8257963 0.0310145 0.3740647 0.4209207 +VERTEX_SE3:QUAT 4317 8.488545 6.374972 -1.243640 0.0017665 0.5077086 0.0344180 0.8608393 +VERTEX_SE3:QUAT 4318 8.557331 6.277252 -1.400847 0.2264634 0.1124336 0.3084008 0.9170398 +VERTEX_SE3:QUAT 4319 8.511202 6.188695 -1.391725 -0.4015106 0.4127410 0.2538838 0.7771597 +VERTEX_SE3:QUAT 4320 8.629919 6.168152 -1.283166 -0.2882876 0.3305181 0.2201661 0.8713064 +VERTEX_SE3:QUAT 4321 8.749841 6.068910 -1.279101 0.4447046 -0.2223824 0.2650959 0.8261404 +VERTEX_SE3:QUAT 4322 8.867539 6.026334 -1.330808 -0.3643611 0.4251583 -0.1295605 0.8183492 +VERTEX_SE3:QUAT 4323 8.931205 5.905752 -1.263893 -0.1048726 0.7285066 -0.5874316 0.3364580 +VERTEX_SE3:QUAT 4324 9.066644 5.861702 -1.268449 -0.1836693 0.4382348 -0.3518847 0.8064695 +VERTEX_SE3:QUAT 4325 9.104613 5.701880 -1.276341 0.4495594 0.7053539 -0.4944066 0.2365045 +VERTEX_SE3:QUAT 4326 9.131294 5.789987 -1.304918 -0.5192001 -0.0970370 -0.8486635 0.0280249 +VERTEX_SE3:QUAT 4327 9.244838 5.738924 -1.436683 0.8288695 0.1140957 -0.0204755 0.5473010 +VERTEX_SE3:QUAT 4328 9.070873 5.699833 -1.360820 -0.8390224 -0.0481163 -0.5299075 0.1136856 +VERTEX_SE3:QUAT 4329 9.140685 5.692795 -1.365425 0.1487575 -0.7770016 0.6032354 0.1012257 +VERTEX_SE3:QUAT 4330 9.096806 5.534214 -1.323306 -0.2000681 0.8365097 0.3655111 0.3558454 +VERTEX_SE3:QUAT 4331 9.217818 5.374931 -1.452273 -0.1277431 0.4285518 -0.8526450 0.2702251 +VERTEX_SE3:QUAT 4332 9.292082 5.535125 -1.405253 -0.0667934 -0.0821520 0.8768506 0.4689592 +VERTEX_SE3:QUAT 4333 9.188763 5.551761 -1.435371 0.0165116 -0.4917706 0.7932999 0.3585586 +VERTEX_SE3:QUAT 4334 9.035800 5.564887 -1.572501 0.0945060 -0.5733847 0.7102149 0.3973581 +VERTEX_SE3:QUAT 4335 9.217275 5.753731 -1.665521 -0.3937768 0.3475659 -0.7865593 0.3247495 +VERTEX_SE3:QUAT 4336 9.086081 5.824466 -1.664899 -0.1799638 0.2066004 -0.4068246 0.8714488 +VERTEX_SE3:QUAT 4337 9.018983 5.873328 -1.742704 0.3587591 -0.6049657 0.5879096 0.3995882 +VERTEX_SE3:QUAT 4338 9.023375 5.796398 -1.896109 0.3554942 0.1413296 -0.0431289 0.9229246 +VERTEX_SE3:QUAT 4339 8.900237 5.966424 -1.872504 0.1837818 0.6329223 -0.0283243 0.7515527 +VERTEX_SE3:QUAT 4340 8.996394 5.832546 -1.908235 -0.2396924 0.0651213 -0.2688554 0.9306038 +VERTEX_SE3:QUAT 4341 8.861359 5.882766 -1.898280 0.3195026 0.4053900 -0.6734563 0.5291821 +VERTEX_SE3:QUAT 4342 8.725531 5.788093 -2.038000 0.3694163 -0.2258205 0.4067598 0.8044148 +VERTEX_SE3:QUAT 4343 8.768331 5.925579 -1.939367 -0.6349108 0.5477098 -0.5070914 0.1994007 +VERTEX_SE3:QUAT 4344 8.665949 5.897684 -1.956759 -0.5070420 -0.2730255 -0.7347806 0.3584173 +VERTEX_SE3:QUAT 4345 8.323067 5.911337 -1.962368 0.5940152 0.1731266 -0.5841964 0.5252502 +VERTEX_SE3:QUAT 4346 8.324405 5.961323 -1.926890 -0.2440459 0.5466600 -0.6850224 0.4151490 +VERTEX_SE3:QUAT 4347 8.231662 6.087386 -1.872336 -0.8057794 0.1769059 -0.2994864 0.4793035 +VERTEX_SE3:QUAT 4348 8.146291 6.032545 -2.123753 0.8330451 0.0961075 0.5407514 0.0662346 +VERTEX_SE3:QUAT 4349 8.065174 6.024731 -2.274461 0.0796797 0.6766868 0.3736425 0.6293945 +VERTEX_SE3:QUAT 4350 7.990973 5.974307 -2.377320 0.0809004 -0.0134491 0.9835915 0.1606925 +VERTEX_SE3:QUAT 4351 7.801318 5.805258 -2.502086 -0.1429630 0.2190163 -0.9485059 0.1786899 +VERTEX_SE3:QUAT 4352 7.754233 5.825615 -2.445726 0.5257388 -0.0744931 -0.0168285 0.8472109 +VERTEX_SE3:QUAT 4353 7.717833 5.791143 -2.485501 0.1033175 0.4462512 0.7200632 0.5212430 +VERTEX_SE3:QUAT 4354 7.662493 5.861950 -2.482980 0.3890297 0.6343093 0.6396132 0.1928797 +VERTEX_SE3:QUAT 4355 7.636115 5.888914 -2.489325 0.2147030 0.7026871 0.1305765 0.6656450 +VERTEX_SE3:QUAT 4356 7.583303 5.862613 -2.637355 0.2740288 -0.3292754 0.4110009 0.8047137 +VERTEX_SE3:QUAT 4357 7.653932 5.981135 -2.498886 -0.0892207 0.6786125 -0.0322791 0.7283425 +VERTEX_SE3:QUAT 4358 7.459379 6.129358 -2.518578 -0.4219957 0.7597391 -0.1458216 0.4727072 +VERTEX_SE3:QUAT 4359 7.245201 6.045689 -2.604470 -0.0950093 0.7304363 -0.0980714 0.6691921 +VERTEX_SE3:QUAT 4360 7.140190 6.178708 -2.416340 0.1498775 0.6562762 0.6736912 0.3049236 +VERTEX_SE3:QUAT 4361 7.042375 6.271972 -2.370659 0.2748694 -0.2661795 -0.6340915 0.6719548 +VERTEX_SE3:QUAT 4362 7.047313 6.197589 -2.150603 0.1918087 0.0046823 0.6242706 0.7572805 +VERTEX_SE3:QUAT 4363 6.976511 6.330639 -2.104582 0.0408618 0.7565614 -0.3892892 0.5238311 +VERTEX_SE3:QUAT 4364 6.987991 6.438182 -2.075978 -0.6033195 0.3984101 -0.5028114 0.4737676 +VERTEX_SE3:QUAT 4365 7.018180 6.431766 -2.126025 0.1569310 0.1772636 0.6178199 0.7498326 +VERTEX_SE3:QUAT 4366 7.100131 6.522959 -2.131768 0.1228160 -0.2318305 0.2919080 0.9197611 +VERTEX_SE3:QUAT 4367 6.978825 6.611719 -2.019560 0.0251559 -0.3341634 -0.8532118 0.3996644 +VERTEX_SE3:QUAT 4368 7.063052 6.720121 -2.062433 0.0800847 0.1289661 0.7093594 0.6883047 +VERTEX_SE3:QUAT 4369 7.024619 6.687557 -1.942810 0.1658528 0.5522796 -0.7209953 0.3842471 +VERTEX_SE3:QUAT 4370 7.029446 6.891940 -1.933667 0.6944270 0.4388553 0.2851876 0.4938069 +VERTEX_SE3:QUAT 4371 6.915821 6.969665 -1.743969 -0.2626335 -0.3645976 0.8576016 0.2502233 +VERTEX_SE3:QUAT 4372 6.854700 6.967698 -1.715873 -0.0370961 0.2704603 -0.4251261 0.8629849 +VERTEX_SE3:QUAT 4373 6.916265 7.076450 -1.646783 0.0033122 0.0089518 -0.6006986 0.7994186 +VERTEX_SE3:QUAT 4374 6.865676 6.969132 -1.687617 -0.2678835 -0.2381344 0.8716370 0.3343342 +VERTEX_SE3:QUAT 4375 6.819386 6.930326 -1.632394 -0.3862653 0.0869994 0.4466947 0.8023055 +VERTEX_SE3:QUAT 4376 6.864323 7.157051 -1.533564 0.4080743 0.0579284 0.9074730 0.0813171 +VERTEX_SE3:QUAT 4377 6.872733 7.315477 -1.489218 0.2296631 -0.0768207 0.1637374 0.9563177 +VERTEX_SE3:QUAT 4378 7.000417 7.365504 -1.395106 -0.5762164 -0.1484260 -0.6517710 0.4702541 +VERTEX_SE3:QUAT 4379 6.874959 7.370344 -1.241240 -0.3537899 -0.1432279 -0.6100500 0.6943756 +VERTEX_SE3:QUAT 4380 7.060787 7.296934 -1.053663 0.2544504 0.1219680 -0.9337794 0.2200790 +VERTEX_SE3:QUAT 4381 7.071582 7.436538 -0.883103 0.7339943 0.0902993 0.2402160 0.6288041 +VERTEX_SE3:QUAT 4382 7.068275 7.378336 -0.853418 0.3541998 -0.4284031 0.8307694 0.0289049 +VERTEX_SE3:QUAT 4383 7.121197 7.374248 -0.994701 -0.4030793 -0.1395286 -0.8301777 0.3589761 +VERTEX_SE3:QUAT 4384 7.065844 7.458756 -0.917660 -0.5153387 0.0281953 -0.1226717 0.8476925 +VERTEX_SE3:QUAT 4385 7.110812 7.561148 -0.888066 0.3295483 -0.1305457 0.3179612 0.8793500 +VERTEX_SE3:QUAT 4386 7.241676 7.578184 -0.774618 -0.0423504 0.3012597 0.6578277 0.6889933 +VERTEX_SE3:QUAT 4387 7.243340 7.752518 -0.742066 -0.1768839 -0.1882015 -0.9647757 0.0500016 +VERTEX_SE3:QUAT 4388 7.213231 7.569652 -0.601086 0.3716206 0.0880646 0.2591713 0.8871150 +VERTEX_SE3:QUAT 4389 7.172838 7.522744 -0.582380 0.3818358 -0.1956177 0.7458297 0.5095814 +VERTEX_SE3:QUAT 4390 7.151495 7.649139 -0.580193 -0.1685576 0.0093654 -0.8036019 0.5707229 +VERTEX_SE3:QUAT 4391 7.246738 7.536812 -0.617471 0.0399248 0.0195636 -0.9886580 0.1434524 +VERTEX_SE3:QUAT 4392 7.279159 7.493488 -0.539053 0.6111895 -0.1568736 0.7670616 0.1159936 +VERTEX_SE3:QUAT 4393 7.356214 7.513899 -0.615356 0.5519210 0.0050494 0.1265145 0.8242280 +VERTEX_SE3:QUAT 4394 7.316840 7.527357 -0.778616 -0.3805829 0.5985134 0.1099526 0.6963109 +VERTEX_SE3:QUAT 4395 7.529501 7.554752 -0.726058 0.4349770 0.6002855 -0.1308122 0.6582860 +VERTEX_SE3:QUAT 4396 7.703263 7.514196 -0.738886 0.2505371 -0.6920919 0.6720488 0.0811810 +VERTEX_SE3:QUAT 4397 7.792069 7.487066 -0.607734 0.8471734 0.2447094 0.2035039 0.4254417 +VERTEX_SE3:QUAT 4398 7.859005 7.542478 -0.602745 0.1741339 -0.2041886 -0.9273672 0.2607192 +VERTEX_SE3:QUAT 4399 7.836564 7.554148 -0.714861 0.2557751 0.2124804 -0.5965133 0.7304814 +VERTEX_SE3:QUAT 4400 7.887441 7.592638 -0.571821 -0.2538103 0.6119677 -0.7311443 0.1628004 +VERTEX_SE3:QUAT 4401 7.873134 7.678406 -0.473430 -0.1040825 0.8455151 -0.4786801 0.2124534 +VERTEX_SE3:QUAT 4402 7.923949 7.687867 -0.371220 0.1899652 0.7950926 0.1100587 0.5653566 +VERTEX_SE3:QUAT 4403 8.101649 7.700489 -0.464785 -0.0550856 0.4719829 0.1308874 0.8700955 +VERTEX_SE3:QUAT 4404 8.043491 7.741807 -0.513790 0.6916122 0.4970434 0.4469331 0.2736261 +VERTEX_SE3:QUAT 4405 7.967536 7.594665 -0.714903 -0.6856338 -0.0325767 -0.6635181 0.2976386 +VERTEX_SE3:QUAT 4406 7.992806 7.645678 -0.752300 0.0789023 0.3305394 0.9176950 0.2058009 +VERTEX_SE3:QUAT 4407 7.980713 7.563751 -0.673807 -0.8604176 -0.3095120 -0.4034326 0.0335550 +VERTEX_SE3:QUAT 4408 7.933503 7.567105 -0.800666 0.6401277 0.2025073 0.7037296 0.2323615 +VERTEX_SE3:QUAT 4409 7.777623 7.623446 -0.801829 -0.2813437 0.4314732 -0.7893933 0.3339682 +VERTEX_SE3:QUAT 4410 7.840736 7.359919 -0.659111 -0.4479177 0.4454400 -0.0557324 0.7732056 +VERTEX_SE3:QUAT 4411 7.813396 7.209777 -0.555223 0.2065976 0.5621077 0.6056967 0.5239121 +VERTEX_SE3:QUAT 4412 7.812939 7.070536 -0.530171 0.1776402 0.6694664 -0.0058244 0.7212661 +VERTEX_SE3:QUAT 4413 7.737785 6.954100 -0.491376 0.2637812 -0.2648012 0.7983337 0.4721897 +VERTEX_SE3:QUAT 4414 7.742332 7.057642 -0.512054 0.3643777 0.1384935 0.7541814 0.5284494 +VERTEX_SE3:QUAT 4415 7.749942 6.975830 -0.386962 -0.4391790 0.5861121 -0.5229005 0.4360843 +VERTEX_SE3:QUAT 4416 7.733061 6.839261 -0.352659 0.0759269 -0.0070952 -0.9119951 0.4030505 +VERTEX_SE3:QUAT 4417 7.739061 6.749986 -0.357186 0.1791815 0.5673514 0.6984685 0.3976785 +VERTEX_SE3:QUAT 4418 7.819433 6.675654 -0.337433 -0.8327782 0.0471089 -0.3055092 0.4592660 +VERTEX_SE3:QUAT 4419 7.946767 6.546145 -0.130115 0.2994850 -0.0850822 0.8759596 0.3684624 +VERTEX_SE3:QUAT 4420 7.940722 6.723643 0.091698 0.2134938 0.0045251 0.0747855 0.9740673 +VERTEX_SE3:QUAT 4421 8.037568 6.633212 0.078082 -0.6511498 0.3299801 -0.6453313 0.2250879 +VERTEX_SE3:QUAT 4422 7.957645 6.665314 0.002057 -0.0710159 0.3648464 -0.8624079 0.3436517 +VERTEX_SE3:QUAT 4423 7.919076 6.527701 0.116406 -0.1679358 -0.0660201 0.8929214 0.4124685 +VERTEX_SE3:QUAT 4424 8.035546 6.376448 0.045607 -0.5228345 -0.0012730 0.2820744 0.8044106 +VERTEX_SE3:QUAT 4425 7.971826 6.222166 -0.070539 -0.0845915 0.8007627 0.2145439 0.5528058 +VERTEX_SE3:QUAT 4426 8.060725 6.035252 -0.243203 0.2377503 0.5371499 0.5637299 0.5806491 +VERTEX_SE3:QUAT 4427 8.115212 6.014789 -0.331227 -0.2067808 0.4823831 0.5189823 0.6746892 +VERTEX_SE3:QUAT 4428 8.225425 5.975551 -0.297030 0.3394990 0.4362491 -0.6766909 0.4863297 +VERTEX_SE3:QUAT 4429 8.200696 6.045625 -0.271886 -0.5439008 0.4834618 0.1750266 0.6631759 +VERTEX_SE3:QUAT 4430 8.312847 5.839343 -0.289697 -0.7128698 0.1084515 -0.1149543 0.6832572 +VERTEX_SE3:QUAT 4431 8.260965 5.587703 -0.248182 -0.1927104 0.4920692 -0.8488480 0.0137034 +VERTEX_SE3:QUAT 4432 8.230213 5.569972 -0.387480 -0.2068181 -0.4637592 -0.5060326 0.6971977 +VERTEX_SE3:QUAT 4433 8.109874 5.579397 -0.402002 -0.5911790 0.5207946 -0.0843518 0.6100534 +VERTEX_SE3:QUAT 4434 8.097466 5.501555 -0.517227 -0.3398419 0.2638255 0.8486514 0.3077243 +VERTEX_SE3:QUAT 4435 8.005463 5.530571 -0.800154 -0.1508616 0.4900410 -0.6975933 0.5004640 +VERTEX_SE3:QUAT 4436 7.849228 5.367871 -0.850885 0.2258411 -0.1778452 -0.7687313 0.5713310 +VERTEX_SE3:QUAT 4437 7.891300 5.269054 -0.879257 0.1978721 0.1007256 0.6883066 0.6906048 +VERTEX_SE3:QUAT 4438 7.934842 5.255915 -1.095944 -0.7796869 0.2007594 -0.2986561 0.5124339 +VERTEX_SE3:QUAT 4439 8.064963 5.081544 -1.186287 0.4747749 0.4710438 0.0385316 0.7424432 +VERTEX_SE3:QUAT 4440 7.983129 5.085241 -1.094078 -0.0270695 0.3285148 -0.9321995 0.1494970 +VERTEX_SE3:QUAT 4441 7.865198 5.036817 -1.028426 0.5036488 0.6882625 0.4709176 0.2255421 +VERTEX_SE3:QUAT 4442 7.843703 4.989257 -1.046796 -0.5258749 0.2353426 -0.7896182 0.2111222 +VERTEX_SE3:QUAT 4443 7.673871 4.881918 -1.175759 -0.0417808 -0.3484465 -0.7065984 0.6144576 +VERTEX_SE3:QUAT 4444 7.630436 4.865759 -1.111733 0.5161143 0.5095579 0.1064392 0.6801819 +VERTEX_SE3:QUAT 4445 7.605769 4.801402 -1.237082 -0.7016963 0.4416781 -0.5124606 0.2234432 +VERTEX_SE3:QUAT 4446 7.505835 4.853168 -1.200474 -0.1469164 0.7937698 -0.0822049 0.5844549 +VERTEX_SE3:QUAT 4447 7.533924 4.836252 -1.120639 -0.5165335 0.1794852 0.4787625 0.6868513 +VERTEX_SE3:QUAT 4448 7.681535 4.765837 -1.023009 0.3574149 0.1612562 0.1650541 0.9049907 +VERTEX_SE3:QUAT 4449 7.879062 4.694660 -0.943598 -0.4387628 -0.3427392 -0.8286013 0.0586251 +VERTEX_SE3:QUAT 4450 7.752125 4.635558 -1.077727 0.3199836 0.6186251 0.3509693 0.6258866 +VERTEX_SE3:QUAT 4451 7.685841 4.678923 -0.972618 -0.3212494 0.3052436 0.7477698 0.4944346 +VERTEX_SE3:QUAT 4452 7.603265 4.560694 -1.093984 0.5580692 0.1977273 0.6188124 0.5162692 +VERTEX_SE3:QUAT 4453 7.599419 4.341424 -1.295970 -0.4347189 -0.0820986 0.5151641 0.7340881 +VERTEX_SE3:QUAT 4454 7.480591 4.248314 -1.248020 0.3756236 0.4397112 -0.0768673 0.8121899 +VERTEX_SE3:QUAT 4455 7.529395 4.292448 -1.239576 -0.3511662 -0.6493462 -0.6291482 0.2433195 +VERTEX_SE3:QUAT 4456 7.374468 4.270534 -1.281525 0.1458989 0.3207451 -0.8101342 0.4685282 +VERTEX_SE3:QUAT 4457 7.300165 4.296510 -1.262202 0.4765900 0.0859806 0.8557414 0.1821427 +VERTEX_SE3:QUAT 4458 7.258673 4.375450 -1.333642 -0.1098649 0.4962470 0.0110297 0.8611312 +VERTEX_SE3:QUAT 4459 7.232599 4.386149 -1.399017 -0.8668914 0.3196601 -0.3824604 0.0063908 +VERTEX_SE3:QUAT 4460 7.190440 4.543158 -1.560196 0.0970995 -0.3082069 0.6999006 0.6369610 +VERTEX_SE3:QUAT 4461 7.201449 4.584056 -1.424412 -0.1636644 0.3696236 -0.8300588 0.3841807 +VERTEX_SE3:QUAT 4462 7.063684 4.625693 -1.599335 -0.3578372 0.6718017 -0.4826644 0.4332090 +VERTEX_SE3:QUAT 4463 6.925954 4.715868 -1.586675 -0.7352941 0.2374640 -0.0747782 0.6303663 +VERTEX_SE3:QUAT 4464 6.984166 4.726398 -1.512291 -0.2223859 -0.0039218 0.1534256 0.9628031 +VERTEX_SE3:QUAT 4465 6.925166 4.824707 -1.546744 0.4134982 -0.5387978 0.7188073 0.1484323 +VERTEX_SE3:QUAT 4466 7.005674 4.705177 -1.581982 -0.8275798 0.3652701 -0.2680004 0.3314592 +VERTEX_SE3:QUAT 4467 7.141796 4.879058 -1.594979 0.2808765 0.5715102 0.4347928 0.6367415 +VERTEX_SE3:QUAT 4468 7.115357 4.913486 -1.694116 -0.4731443 0.4811044 0.6509992 0.3476679 +VERTEX_SE3:QUAT 4469 7.021796 4.923441 -1.531867 -0.2734392 -0.6782462 -0.6671218 0.1419913 +VERTEX_SE3:QUAT 4470 7.024968 4.934842 -1.510495 0.2384140 0.5771155 0.3577029 0.6943667 +VERTEX_SE3:QUAT 4471 7.103404 4.905429 -1.408345 0.4336248 0.1697131 0.3867300 0.7959943 +VERTEX_SE3:QUAT 4472 7.142014 4.996904 -1.317954 0.1858427 -0.3563790 0.8614896 0.3103097 +VERTEX_SE3:QUAT 4473 7.170283 4.950869 -1.592391 -0.8469189 -0.0316882 -0.3014411 0.4368724 +VERTEX_SE3:QUAT 4474 7.333701 5.129581 -1.490359 0.3562480 0.4097596 0.0813891 0.8357991 +VERTEX_SE3:QUAT 4475 7.250479 5.243404 -1.466297 0.0124830 0.7026925 0.3941652 0.5922004 +VERTEX_SE3:QUAT 4476 7.101000 5.228192 -1.549047 0.2307333 0.2746782 -0.4205767 0.8333242 +VERTEX_SE3:QUAT 4477 7.287658 5.327353 -1.496800 -0.8071407 0.0514342 -0.2355779 0.5388706 +VERTEX_SE3:QUAT 4478 7.180421 5.354577 -1.646005 -0.2924553 0.1753680 -0.9382273 0.0586981 +VERTEX_SE3:QUAT 4479 7.277878 5.428632 -1.585534 -0.5883532 -0.4823563 -0.5874357 0.2758483 +VERTEX_SE3:QUAT 4480 7.437313 5.602230 -1.576049 -0.4539404 0.0127264 0.4595168 0.7632958 +VERTEX_SE3:QUAT 4481 7.547123 5.683437 -1.500539 -0.9248887 0.0996311 -0.2722323 0.2460572 +VERTEX_SE3:QUAT 4482 7.620063 5.763292 -1.464184 0.1447750 0.2718401 -0.0982082 0.9463077 +VERTEX_SE3:QUAT 4483 7.773165 5.918134 -1.467121 -0.2921942 -0.0389838 -0.6093499 0.7360676 +VERTEX_SE3:QUAT 4484 7.740908 5.851633 -1.430434 0.2814286 0.6694455 0.0929437 0.6811770 +VERTEX_SE3:QUAT 4485 7.835312 5.693630 -1.503479 -0.3728498 0.0828827 0.7111723 0.5902096 +VERTEX_SE3:QUAT 4486 7.757876 5.694817 -1.445460 -0.6714863 0.3116740 0.2108935 0.6383489 +VERTEX_SE3:QUAT 4487 7.841286 5.730160 -1.355202 -0.2914458 0.7471033 -0.4029956 0.4410109 +VERTEX_SE3:QUAT 4488 7.738417 5.618118 -1.183775 -0.5595004 -0.5558327 -0.4514540 0.4173710 +VERTEX_SE3:QUAT 4489 7.667989 5.660567 -1.337390 -0.3644228 0.0806982 -0.1129980 0.9208232 +VERTEX_SE3:QUAT 4490 7.869638 5.528242 -1.285395 -0.5963792 0.3188332 -0.7311945 0.0896206 +VERTEX_SE3:QUAT 4491 8.022197 5.398947 -1.236849 -0.5833588 0.6916691 -0.2477250 0.3462929 +VERTEX_SE3:QUAT 4492 8.135196 5.333633 -1.257440 -0.3210439 -0.5825339 -0.6375155 0.3887918 +VERTEX_SE3:QUAT 4493 8.464976 5.333077 -1.154474 -0.8669108 -0.0766375 -0.4007308 0.2863690 +VERTEX_SE3:QUAT 4494 8.544132 5.368816 -1.009736 0.5967779 0.0808148 0.6059204 0.5197937 +VERTEX_SE3:QUAT 4495 8.374900 5.483744 -1.203787 0.5929955 0.6135018 0.3981183 0.3368587 +VERTEX_SE3:QUAT 4496 8.558224 5.519867 -1.161666 -0.4838309 0.4052174 0.7174536 0.2949015 +VERTEX_SE3:QUAT 4497 8.582825 5.528969 -1.094698 0.4025226 0.5883659 0.6936263 0.1033618 +VERTEX_SE3:QUAT 4498 8.556605 5.498308 -0.980151 -0.1861080 0.0474081 0.3164055 0.9289800 +VERTEX_SE3:QUAT 4499 8.543702 5.394936 -0.976298 -0.4254143 0.1833342 0.5765689 0.6730376 +VERTEX_SE3:QUAT 4500 8.659473 5.264587 -0.946335 0.2172281 0.2908706 -0.6715854 0.6458942 +VERTEX_SE3:QUAT 4501 8.572002 5.382727 -0.963562 0.0371948 0.2348818 -0.4346155 0.8686521 +VERTEX_SE3:QUAT 4502 8.732965 5.342152 -1.062425 -0.3563051 -0.1715837 -0.8803385 0.2619347 +VERTEX_SE3:QUAT 4503 8.610620 5.498523 -1.079500 0.2413320 0.2572045 0.6562424 0.6670461 +VERTEX_SE3:QUAT 4504 8.609190 5.402470 -1.139002 -0.6231248 0.1547268 -0.5245755 0.5591025 +VERTEX_SE3:QUAT 4505 8.615653 5.486756 -1.250601 -0.3173583 0.8754946 0.0029383 0.3643957 +VERTEX_SE3:QUAT 4506 8.788531 5.349819 -1.253768 -0.0682811 0.7576236 -0.0722851 0.6450729 +VERTEX_SE3:QUAT 4507 8.807425 5.338952 -1.240047 0.1579319 0.0738617 0.5294541 0.8302291 +VERTEX_SE3:QUAT 4508 8.810423 5.264247 -1.329896 0.3270590 0.5575026 0.6946439 0.3157421 +VERTEX_SE3:QUAT 4509 8.878034 5.329251 -1.119193 -0.0770777 0.3029477 -0.1039221 0.9441832 +VERTEX_SE3:QUAT 4510 9.058363 5.351347 -1.187867 0.0290728 0.4283998 0.2296520 0.8734348 +VERTEX_SE3:QUAT 4511 9.061094 5.225892 -1.274393 -0.4600710 0.2363229 -0.5443455 0.6604348 +VERTEX_SE3:QUAT 4512 9.180389 5.021174 -1.364851 0.5057005 0.3272819 -0.1272811 0.7880058 +VERTEX_SE3:QUAT 4513 9.030028 4.868876 -1.411470 -0.4329892 -0.3217624 -0.7135087 0.4470958 +VERTEX_SE3:QUAT 4514 8.814521 4.824295 -1.483706 -0.5786369 -0.3190041 -0.6823190 0.3128203 +VERTEX_SE3:QUAT 4515 8.765260 4.881449 -1.500627 -0.3655907 0.1653958 0.1379776 0.9055108 +VERTEX_SE3:QUAT 4516 8.681402 4.825141 -1.432730 0.1274734 0.3016242 0.9296785 0.1687346 +VERTEX_SE3:QUAT 4517 8.709287 4.774003 -1.302033 -0.6533098 -0.1238549 0.2039192 0.7185146 +VERTEX_SE3:QUAT 4518 8.696952 4.965230 -1.215892 -0.4515074 0.0685889 0.6712687 0.5838107 +VERTEX_SE3:QUAT 4519 8.708689 4.820026 -1.076863 -0.1261087 0.2819583 0.9510873 0.0053818 +VERTEX_SE3:QUAT 4520 8.775932 4.808126 -1.245780 -0.1017902 -0.1477618 0.9297291 0.3215727 +VERTEX_SE3:QUAT 4521 8.830891 4.739934 -1.288915 -0.1211456 0.6123668 0.7738907 0.1068821 +VERTEX_SE3:QUAT 4522 8.717879 4.606131 -1.216073 0.0590137 -0.2847036 -0.9491970 0.1203589 +VERTEX_SE3:QUAT 4523 8.776210 4.684055 -1.182096 0.2619942 -0.0049533 -0.0667765 0.9627437 +VERTEX_SE3:QUAT 4524 8.710963 4.545930 -1.168184 0.5377013 0.2652507 0.0426504 0.7991873 +VERTEX_SE3:QUAT 4525 8.698552 4.385341 -1.050199 -0.1605939 -0.1342781 -0.2138984 0.9541627 +VERTEX_SE3:QUAT 4526 8.856272 4.397874 -1.226685 0.4714004 0.3269371 0.4342692 0.6944811 +VERTEX_SE3:QUAT 4527 9.017659 4.316077 -1.231379 -0.5173407 0.3403112 0.7472186 0.2412699 +VERTEX_SE3:QUAT 4528 8.983316 4.313292 -1.400709 -0.1703105 -0.0682583 -0.3122668 0.9321076 +VERTEX_SE3:QUAT 4529 8.907365 4.295216 -1.276941 -0.0929928 -0.1063034 0.3604134 0.9220380 +VERTEX_SE3:QUAT 4530 9.006597 4.266296 -1.403898 -0.8294923 0.2304923 0.0992794 0.4989583 +VERTEX_SE3:QUAT 4531 8.866824 4.119359 -1.400432 0.2377092 -0.6256159 -0.7111506 0.2153228 +VERTEX_SE3:QUAT 4532 8.848329 4.120100 -1.658883 -0.7084283 -0.4544672 -0.5351276 0.0723012 +VERTEX_SE3:QUAT 4533 8.874581 4.068022 -1.436035 0.2904948 0.6274630 0.5960809 0.4081551 +VERTEX_SE3:QUAT 4534 8.759766 4.045626 -1.354154 0.3625615 0.5574637 0.7263839 0.1736367 +VERTEX_SE3:QUAT 4535 8.614231 3.949379 -1.257037 -0.6723459 -0.1586988 0.1920869 0.6970425 +VERTEX_SE3:QUAT 4536 8.703820 3.853409 -1.300809 0.6704973 0.5713182 0.4365258 0.1829594 +VERTEX_SE3:QUAT 4537 8.580674 3.951948 -1.329301 -0.4991379 -0.4676217 -0.7087888 0.1726550 +VERTEX_SE3:QUAT 4538 8.594326 3.880272 -1.330082 -0.1901119 0.1765317 -0.9278887 0.2677994 +VERTEX_SE3:QUAT 4539 8.490215 3.924210 -1.523744 0.4988651 0.6883951 0.4455804 0.2805422 +VERTEX_SE3:QUAT 4540 8.453959 3.850084 -1.418187 0.0566876 0.5434213 0.8065325 0.2257989 +VERTEX_SE3:QUAT 4541 8.379131 3.822107 -1.481258 -0.2926195 0.2869945 0.3315678 0.8497475 +VERTEX_SE3:QUAT 4542 8.327908 3.868234 -1.594599 -0.5135584 -0.4789570 -0.7088780 0.0659548 +VERTEX_SE3:QUAT 4543 8.238645 3.989955 -1.434855 0.0328405 0.0541418 -0.4174897 0.9064726 +VERTEX_SE3:QUAT 4544 8.170189 3.942888 -1.452524 0.0238308 0.1438744 -0.0606312 0.9874493 +VERTEX_SE3:QUAT 4545 8.195717 3.853002 -1.519136 -0.1640443 0.0912200 0.7936457 0.5787010 +VERTEX_SE3:QUAT 4546 8.286378 3.883549 -1.545441 0.1493594 -0.6953787 -0.6977515 0.0853409 +VERTEX_SE3:QUAT 4547 8.201131 3.825955 -1.438453 0.0908598 -0.5241194 -0.4939903 0.6877622 +VERTEX_SE3:QUAT 4548 8.151980 3.970976 -1.422665 0.1579220 0.5453408 -0.4778632 0.6703065 +VERTEX_SE3:QUAT 4549 8.058652 3.795287 -1.468534 -0.2408871 0.8064536 0.3327394 0.4253123 +VERTEX_SE3:QUAT 4550 7.900809 3.819704 -1.616253 0.2032545 -0.1108669 -0.9636156 0.1335705 +VERTEX_SE3:QUAT 4551 7.799328 3.910141 -1.565052 -0.1415157 0.1110949 -0.0358401 0.9830294 +VERTEX_SE3:QUAT 4552 7.713111 3.825988 -1.347695 -0.5602101 0.6568959 -0.2231233 0.4526239 +VERTEX_SE3:QUAT 4553 7.816849 3.834044 -1.327402 -0.1201818 0.5394089 0.4102017 0.7254853 +VERTEX_SE3:QUAT 4554 7.877022 3.934647 -1.571867 -0.1232499 -0.0780933 -0.6460713 0.7492015 +VERTEX_SE3:QUAT 4555 7.735097 4.083841 -1.638000 -0.5856280 -0.1334810 0.4008213 0.6917839 +VERTEX_SE3:QUAT 4556 7.685234 4.263153 -1.754746 -0.5615608 0.4967193 0.4987993 0.4348777 +VERTEX_SE3:QUAT 4557 7.634315 4.461054 -1.927748 -0.2775642 -0.0652413 -0.5884999 0.7565511 +VERTEX_SE3:QUAT 4558 7.580018 4.451308 -1.749185 -0.0923977 0.4001125 -0.9078059 0.0852116 +VERTEX_SE3:QUAT 4559 7.476542 4.362339 -1.806237 0.0701899 0.4130222 -0.2838625 0.8625011 +VERTEX_SE3:QUAT 4560 7.298608 4.514638 -1.864383 -0.3521593 -0.0212694 -0.8076047 0.4725528 +VERTEX_SE3:QUAT 4561 7.190270 4.701861 -2.027806 0.2651319 0.2626024 -0.0284222 0.9273280 +VERTEX_SE3:QUAT 4562 7.192270 4.632727 -2.113023 0.1291631 0.4381909 0.8427601 0.2847121 +VERTEX_SE3:QUAT 4563 7.257084 4.721487 -2.193873 0.1518716 -0.6222095 -0.7365290 0.2175210 +VERTEX_SE3:QUAT 4564 7.225892 4.813065 -2.328758 0.1396833 -0.6542450 -0.5961356 0.4439306 +VERTEX_SE3:QUAT 4565 6.909078 4.782084 -2.276327 -0.4356987 0.1341581 0.8846169 0.0980875 +VERTEX_SE3:QUAT 4566 6.788378 4.733733 -2.225700 -0.5730145 -0.5871723 -0.5626336 0.1016194 +VERTEX_SE3:QUAT 4567 6.529798 4.849099 -2.311042 -0.8212728 0.1334741 -0.3939793 0.3904816 +VERTEX_SE3:QUAT 4568 6.581569 4.804193 -2.341911 -0.4393712 -0.6157154 -0.6373171 0.1472223 +VERTEX_SE3:QUAT 4569 6.507448 4.622013 -2.405166 -0.2168332 0.2412684 0.2681182 0.9071304 +VERTEX_SE3:QUAT 4570 6.586050 4.788710 -2.292226 0.1310772 -0.4793438 -0.6161510 0.6110697 +VERTEX_SE3:QUAT 4571 6.613679 4.824144 -2.366323 0.2046772 0.1612730 -0.5082430 0.8208455 +VERTEX_SE3:QUAT 4572 6.718646 4.749741 -2.256750 -0.6853590 -0.0485835 -0.5045607 0.5228204 +VERTEX_SE3:QUAT 4573 6.762847 4.891162 -2.157334 0.1251681 0.7295183 0.4005314 0.5401024 +VERTEX_SE3:QUAT 4574 6.709714 4.957516 -2.275676 -0.2093164 -0.0511850 -0.6072059 0.7647665 +VERTEX_SE3:QUAT 4575 6.712073 5.024669 -2.588746 -0.3051091 0.8122228 0.0182842 0.4968584 +VERTEX_SE3:QUAT 4576 6.649123 5.183230 -2.488171 -0.2826334 -0.0454917 0.9538779 0.0903651 +VERTEX_SE3:QUAT 4577 6.650243 5.174287 -2.536922 0.2514922 0.5089041 0.7601630 0.3161022 +VERTEX_SE3:QUAT 4578 6.724175 5.225540 -2.644283 -0.2855287 -0.4333989 -0.3892149 0.7610194 +VERTEX_SE3:QUAT 4579 6.667226 5.556467 -2.809888 -0.6585857 0.3322798 -0.5288998 0.4196665 +VERTEX_SE3:QUAT 4580 6.850105 5.837179 -2.921684 -0.3034583 0.8011495 -0.0236094 0.5152816 +VERTEX_SE3:QUAT 4581 6.721611 5.669859 -3.009950 0.2386730 0.6101806 -0.0749069 0.7517339 +VERTEX_SE3:QUAT 4582 6.814011 5.869828 -2.980023 -0.6358881 0.5774443 -0.4327255 0.2737754 +VERTEX_SE3:QUAT 4583 6.869324 6.023419 -3.005536 0.1190266 -0.6542779 -0.7131390 0.2217788 +VERTEX_SE3:QUAT 4584 6.828166 6.050839 -3.058234 -0.0839974 0.8741975 -0.0747960 0.4723651 +VERTEX_SE3:QUAT 4585 6.963718 6.023293 -2.997263 -0.0858237 0.0038222 -0.7553838 0.6496268 +VERTEX_SE3:QUAT 4586 6.981173 6.206085 -2.934008 -0.7424694 0.1505594 0.3722496 0.5361915 +VERTEX_SE3:QUAT 4587 7.043635 6.191973 -3.054185 -0.6605723 0.3869669 0.2160707 0.6059821 +VERTEX_SE3:QUAT 4588 7.114908 6.220903 -2.897342 0.0412087 -0.3527311 -0.8862047 0.2975297 +VERTEX_SE3:QUAT 4589 7.009476 6.299985 -2.713317 -0.2552304 0.5787397 -0.1293599 0.7636647 +VERTEX_SE3:QUAT 4590 7.056822 6.675709 -2.702328 -0.0314316 0.6509734 0.7131761 0.2581193 +VERTEX_SE3:QUAT 4591 7.131601 6.682839 -2.665531 0.3182789 0.3439007 -0.1702941 0.8668511 +VERTEX_SE3:QUAT 4592 7.123482 6.857681 -2.753670 0.2052447 0.7935354 0.1499585 0.5528912 +VERTEX_SE3:QUAT 4593 7.192589 6.855995 -2.829182 0.4844069 0.3264040 0.5344444 0.6108842 +VERTEX_SE3:QUAT 4594 7.247227 6.850567 -2.741772 -0.5395750 0.6012875 -0.3848291 0.4463392 +VERTEX_SE3:QUAT 4595 7.213710 6.887144 -2.654980 0.0355854 0.2286887 -0.3787941 0.8960749 +VERTEX_SE3:QUAT 4596 7.207138 6.868940 -2.690120 -0.6934197 -0.5905758 -0.2388062 0.3366912 +VERTEX_SE3:QUAT 4597 7.053714 6.902315 -2.650512 -0.1528088 0.2431990 -0.4132331 0.8641424 +VERTEX_SE3:QUAT 4598 6.918677 6.928019 -2.424214 0.1530441 0.0463077 -0.0542440 0.9856423 +VERTEX_SE3:QUAT 4599 6.935712 6.791191 -2.508563 -0.0000857 -0.6908875 -0.6831099 0.2367177 +VERTEX_SE3:QUAT 4600 7.071148 6.984110 -2.507605 -0.2699707 0.3699545 0.3833688 0.8020460 +VERTEX_SE3:QUAT 4601 7.054948 6.879704 -2.445594 0.4233802 -0.0808270 0.7649491 0.4786116 +VERTEX_SE3:QUAT 4602 7.089968 6.987539 -2.445858 -0.0069710 0.1633957 0.9864204 0.0151043 +VERTEX_SE3:QUAT 4603 7.164150 7.144380 -2.470880 -0.2058902 -0.2266961 -0.6394554 0.7052056 +VERTEX_SE3:QUAT 4604 7.195282 7.078415 -2.319044 0.0697048 0.4829726 -0.5708114 0.6603431 +VERTEX_SE3:QUAT 4605 7.186435 7.198091 -2.508470 0.0977121 -0.6399659 -0.7620705 0.0120250 +VERTEX_SE3:QUAT 4606 7.265473 7.141607 -2.558742 -0.6741188 0.3230579 -0.5851151 0.3143849 +VERTEX_SE3:QUAT 4607 7.238542 7.141810 -2.823223 -0.2332520 0.4787658 -0.3907412 0.7507983 +VERTEX_SE3:QUAT 4608 7.315607 7.007482 -2.944566 -0.6190745 -0.5570298 -0.2676978 0.4845641 +VERTEX_SE3:QUAT 4609 7.248695 6.882883 -3.000284 0.0095677 0.2160245 0.9640388 0.1545030 +VERTEX_SE3:QUAT 4610 7.365559 7.024244 -2.912989 0.7025100 0.1181471 0.6986340 0.0665699 +VERTEX_SE3:QUAT 4611 7.315045 6.890734 -2.715945 -0.3720655 0.0040694 -0.2325793 0.8985864 +VERTEX_SE3:QUAT 4612 7.287695 6.955048 -2.787448 -0.1149798 0.2252654 0.9127862 0.3207126 +VERTEX_SE3:QUAT 4613 7.107295 6.956562 -2.867900 -0.4410181 0.5831764 -0.3007089 0.6123581 +VERTEX_SE3:QUAT 4614 7.049400 6.936622 -2.921090 0.0758127 0.1935003 0.0033748 0.9781609 +VERTEX_SE3:QUAT 4615 7.158067 6.941218 -2.831110 -0.5022243 0.0336608 -0.1091289 0.8571631 +VERTEX_SE3:QUAT 4616 7.323757 7.028865 -2.818039 -0.4023171 -0.6284544 -0.5095806 0.4283849 +VERTEX_SE3:QUAT 4617 7.357482 6.924940 -2.712365 -0.2988592 -0.3476506 -0.3616219 0.8118201 +VERTEX_SE3:QUAT 4618 7.306909 6.938299 -2.462511 -0.0432964 0.2770212 0.2592969 0.9242022 +VERTEX_SE3:QUAT 4619 7.363227 6.889306 -2.590662 0.0229374 -0.6957411 -0.6802275 0.2295838 +VERTEX_SE3:QUAT 4620 7.281960 6.845218 -2.541130 -0.3224312 0.5839468 -0.4859846 0.5646797 +VERTEX_SE3:QUAT 4621 7.244913 6.773048 -2.629222 -0.4541009 0.3555619 -0.8144771 0.0632074 +VERTEX_SE3:QUAT 4622 7.448773 6.684369 -2.554149 -0.5849155 0.3356954 -0.3356351 0.6576713 +VERTEX_SE3:QUAT 4623 7.479480 6.508024 -2.607929 0.0291686 0.7203571 -0.0659591 0.6898437 +VERTEX_SE3:QUAT 4624 7.558957 6.485498 -2.533849 0.4244004 0.0525846 0.7529747 0.5001482 +VERTEX_SE3:QUAT 4625 7.427551 6.478908 -2.584601 0.1293919 0.3308270 -0.7334603 0.5795233 +VERTEX_SE3:QUAT 4626 7.411753 6.420752 -2.464544 0.1267458 0.5648493 0.2013630 0.7901479 +VERTEX_SE3:QUAT 4627 7.487429 6.422265 -2.461008 -0.5858187 -0.5100230 -0.6289503 0.0333839 +VERTEX_SE3:QUAT 4628 7.490133 6.457147 -2.407387 0.0718543 0.0210087 -0.4204380 0.9042276 +VERTEX_SE3:QUAT 4629 7.560963 6.290728 -2.504863 -0.1567952 0.8329526 0.2335946 0.4764858 +VERTEX_SE3:QUAT 4630 7.587554 6.282045 -2.524621 -0.3913831 0.7652438 -0.3826953 0.3387706 +VERTEX_SE3:QUAT 4631 7.537140 6.124620 -2.408093 0.2153925 0.5683574 -0.5466119 0.5760134 +VERTEX_SE3:QUAT 4632 7.545568 5.984156 -2.431637 -0.2747299 0.0424816 0.3801769 0.8821475 +VERTEX_SE3:QUAT 4633 7.677780 6.034389 -2.428256 0.1804274 0.7906476 0.5843625 0.0290299 +VERTEX_SE3:QUAT 4634 7.554494 5.931341 -2.343192 0.0407233 -0.1079862 0.9896557 0.0852183 +VERTEX_SE3:QUAT 4635 7.523389 5.841729 -2.155655 -0.5628490 -0.3467400 -0.7084124 0.2472334 +VERTEX_SE3:QUAT 4636 7.728533 5.827289 -2.261264 0.3231416 0.7749291 0.5431977 0.0008125 +VERTEX_SE3:QUAT 4637 7.612415 5.530054 -2.389907 0.8006566 -0.0844951 0.5900530 0.0603911 +VERTEX_SE3:QUAT 4638 7.501133 5.376173 -2.218031 -0.2301211 0.3327226 -0.1916487 0.8942096 +VERTEX_SE3:QUAT 4639 7.363062 5.142778 -2.146212 0.2962107 0.4136836 0.8569267 0.0824728 +VERTEX_SE3:QUAT 4640 7.349504 5.131962 -2.317054 0.3744867 -0.0188802 0.8596069 0.3471012 +VERTEX_SE3:QUAT 4641 7.184009 5.004803 -2.141734 0.4722073 0.6491770 0.5953674 0.0335743 +VERTEX_SE3:QUAT 4642 7.106966 4.940690 -2.225098 -0.8681198 0.0035472 -0.4962987 0.0065565 +VERTEX_SE3:QUAT 4643 7.183886 5.025174 -2.221707 -0.0221314 -0.3117716 -0.8390173 0.4453748 +VERTEX_SE3:QUAT 4644 7.047606 5.075162 -2.251300 -0.2185968 -0.3460330 -0.4753893 0.7787692 +VERTEX_SE3:QUAT 4645 7.015033 5.070817 -2.170318 -0.5429314 -0.5252279 -0.6505662 0.0782613 +VERTEX_SE3:QUAT 4646 6.914158 5.288992 -2.347908 -0.5322488 0.3681567 -0.6500684 0.3982247 +VERTEX_SE3:QUAT 4647 6.749324 5.301671 -2.339697 0.2724387 0.1226306 -0.5299127 0.7936822 +VERTEX_SE3:QUAT 4648 6.476580 5.258679 -2.221531 -0.1216118 -0.2758272 -0.7415883 0.5993136 +VERTEX_SE3:QUAT 4649 6.517977 5.224251 -2.095025 -0.2021693 0.3071521 0.3457424 0.8632771 +VERTEX_SE3:QUAT 4650 6.554035 5.285466 -2.115682 -0.2935799 0.5987574 -0.7423415 0.0650337 +VERTEX_SE3:QUAT 4651 6.363459 5.386347 -2.089814 -0.5515452 -0.3539157 -0.6872553 0.3134035 +VERTEX_SE3:QUAT 4652 6.381741 5.384393 -2.242600 -0.4983158 -0.0127012 -0.2494217 0.8302463 +VERTEX_SE3:QUAT 4653 6.392889 5.234919 -2.157190 -0.3740947 0.7120608 0.5410996 0.2454259 +VERTEX_SE3:QUAT 4654 6.366072 5.203646 -2.247607 0.1282645 0.3244763 -0.1384981 0.9268666 +VERTEX_SE3:QUAT 4655 6.330210 5.437611 -2.231194 -0.4185374 0.6037752 0.2762388 0.6196564 +VERTEX_SE3:QUAT 4656 6.294395 5.478497 -2.107393 -0.1889398 -0.2854963 -0.8905260 0.2995949 +VERTEX_SE3:QUAT 4657 6.048916 5.508345 -2.265596 0.2963349 0.2329533 0.4878291 0.7873634 +VERTEX_SE3:QUAT 4658 5.921702 5.404035 -2.158816 0.1758495 0.8981631 -0.2257279 0.3338066 +VERTEX_SE3:QUAT 4659 5.765635 5.300586 -2.230166 0.3712217 0.4522238 0.4884011 0.6474199 +VERTEX_SE3:QUAT 4660 5.717718 5.437059 -2.295866 -0.5356395 0.6726171 -0.1527704 0.4871733 +VERTEX_SE3:QUAT 4661 5.596099 5.561718 -2.322737 -0.1299620 -0.7419889 -0.6566310 0.0373908 +VERTEX_SE3:QUAT 4662 5.589924 5.645874 -2.225828 0.3030431 0.2285842 0.8683099 0.3192993 +VERTEX_SE3:QUAT 4663 5.615634 5.525228 -2.226995 -0.7755045 0.5970152 0.1268921 0.1614434 +VERTEX_SE3:QUAT 4664 5.533290 5.734677 -2.162572 -0.2650106 0.0634665 -0.8574674 0.4364529 +VERTEX_SE3:QUAT 4665 5.370768 5.860488 -2.101299 -0.1699701 -0.2940947 -0.7540725 0.5621326 +VERTEX_SE3:QUAT 4666 5.203488 5.969557 -2.112274 0.4620657 -0.0067068 0.7259908 0.5093012 +VERTEX_SE3:QUAT 4667 5.125543 5.894110 -2.026881 -0.1423619 -0.4694306 -0.8070562 0.3286767 +VERTEX_SE3:QUAT 4668 5.077449 5.822586 -2.107389 0.7092351 0.4217849 0.5455868 0.1463492 +VERTEX_SE3:QUAT 4669 4.996890 5.790714 -2.161275 -0.4332529 0.6646063 -0.5149889 0.3246181 +VERTEX_SE3:QUAT 4670 4.813905 5.682311 -2.135063 -0.1171760 0.3948064 0.0473147 0.9100324 +VERTEX_SE3:QUAT 4671 4.778208 5.591854 -2.194510 -0.6900862 0.0204037 -0.3418270 0.6375885 +VERTEX_SE3:QUAT 4672 4.737169 5.584293 -2.433016 -0.8128534 -0.0312580 -0.0617971 0.5783367 +VERTEX_SE3:QUAT 4673 4.612621 5.591440 -2.581928 -0.7760366 -0.2280691 -0.1166983 0.5763100 +VERTEX_SE3:QUAT 4674 4.678619 5.542063 -2.574836 -0.0734137 0.5851278 0.3663273 0.7197501 +VERTEX_SE3:QUAT 4675 4.657385 5.823003 -2.608614 -0.2641380 0.4913164 0.8177498 0.1418613 +VERTEX_SE3:QUAT 4676 4.754293 5.719221 -2.672213 -0.5933281 0.5196124 -0.0680643 0.6110090 +VERTEX_SE3:QUAT 4677 4.749821 5.633593 -2.777974 0.1083392 0.9553007 -0.1227193 0.2461771 +VERTEX_SE3:QUAT 4678 4.798961 5.763727 -2.892385 0.8873337 -0.4510181 0.0940720 0.0192882 +VERTEX_SE3:QUAT 4679 4.848917 5.719126 -3.051745 -0.7473293 0.2524694 -0.3369543 0.5140233 +VERTEX_SE3:QUAT 4680 4.780099 5.757059 -3.090853 -0.8725357 0.4014091 0.0177169 0.2779180 +VERTEX_SE3:QUAT 4681 4.763024 5.760523 -3.041879 0.3010030 0.3042280 0.8913058 0.1497214 +VERTEX_SE3:QUAT 4682 4.836895 5.707032 -2.989226 -0.4857550 0.6291664 0.2071224 0.5703437 +VERTEX_SE3:QUAT 4683 4.946519 5.768497 -2.892793 0.0389753 0.0489253 0.9788679 0.1946918 +VERTEX_SE3:QUAT 4684 5.005275 5.841233 -2.927573 -0.6374448 0.6421972 -0.3410595 0.2548045 +VERTEX_SE3:QUAT 4685 4.980012 5.918474 -2.928904 -0.8193491 -0.0738987 0.0859008 0.5619850 +VERTEX_SE3:QUAT 4686 5.060654 6.207956 -2.883577 -0.1179386 0.8848554 -0.2809175 0.3524297 +VERTEX_SE3:QUAT 4687 4.983927 6.321577 -2.918374 0.3119030 0.3614354 0.8016064 0.3598724 +VERTEX_SE3:QUAT 4688 4.918003 6.208287 -2.787255 -0.9119033 -0.0822596 0.2715403 0.2965325 +VERTEX_SE3:QUAT 4689 5.072839 6.267141 -2.836671 -0.4605078 0.7823188 0.2182375 0.3581652 +VERTEX_SE3:QUAT 4690 5.060618 6.381228 -2.779830 -0.2344665 0.8029426 0.1779376 0.5183116 +VERTEX_SE3:QUAT 4691 5.026937 6.401578 -2.850824 -0.3089224 0.5587718 0.0784274 0.7656305 +VERTEX_SE3:QUAT 4692 4.915774 6.500528 -2.901559 -0.0150485 -0.3194491 -0.9252328 0.2041324 +VERTEX_SE3:QUAT 4693 4.890531 6.695661 -2.781899 0.7468013 -0.4162630 0.5182556 0.0205942 +VERTEX_SE3:QUAT 4694 4.847373 6.983180 -2.783329 -0.5960524 -0.0579479 -0.6064100 0.5230970 +VERTEX_SE3:QUAT 4695 5.079782 7.165898 -2.813652 -0.0184232 -0.8236159 -0.4459573 0.3499135 +VERTEX_SE3:QUAT 4696 4.942174 7.103458 -2.926965 -0.2973783 0.0255509 0.0400760 0.9535760 +VERTEX_SE3:QUAT 4697 5.041566 7.313058 -2.887972 -0.1303756 0.5956828 0.3923830 0.6886216 +VERTEX_SE3:QUAT 4698 5.176375 7.347833 -2.992978 -0.2156878 0.0693322 -0.8054489 0.5476531 +VERTEX_SE3:QUAT 4699 5.139533 7.276471 -3.128646 -0.5443782 0.1396280 0.6065701 0.5623424 +VERTEX_SE3:QUAT 4700 5.102040 7.283680 -2.989071 -0.8266256 -0.3626919 -0.4280080 0.0442024 +VERTEX_SE3:QUAT 4701 5.167243 7.506428 -3.037383 0.7262842 0.4249984 0.5385782 0.0426756 +VERTEX_SE3:QUAT 4702 5.116141 7.576854 -3.011269 -0.2206264 0.3304368 0.5224793 0.7544208 +VERTEX_SE3:QUAT 4703 4.984883 7.653246 -2.900309 0.3468893 0.4165172 -0.0149125 0.8402136 +VERTEX_SE3:QUAT 4704 4.903808 7.702015 -2.976500 -0.0048158 0.4615447 -0.2951039 0.8365805 +VERTEX_SE3:QUAT 4705 5.097487 7.732146 -2.919662 -0.9022604 0.0015159 0.1655715 0.3981332 +VERTEX_SE3:QUAT 4706 5.078960 7.781123 -2.854272 -0.1737540 0.9057434 0.3361198 0.1909501 +VERTEX_SE3:QUAT 4707 5.083937 7.867867 -2.833313 -0.4092737 0.1672333 0.3887252 0.8083445 +VERTEX_SE3:QUAT 4708 4.952709 8.139165 -2.972612 0.3045254 0.5410165 0.5545109 0.5541508 +VERTEX_SE3:QUAT 4709 4.940717 8.154628 -2.793606 -0.5403235 0.3211822 -0.4693399 0.6201714 +VERTEX_SE3:QUAT 4710 4.986789 8.156770 -2.690222 -0.7596338 -0.0624939 -0.6257243 0.1658915 +VERTEX_SE3:QUAT 4711 4.898374 8.196940 -2.668462 -0.4170632 0.5008137 -0.4734685 0.5925128 +VERTEX_SE3:QUAT 4712 4.929054 8.354303 -2.516600 -0.6785460 0.3074359 0.2937695 0.5989641 +VERTEX_SE3:QUAT 4713 4.938774 8.519131 -2.595382 -0.2302149 0.3385000 0.8598402 0.3051126 +VERTEX_SE3:QUAT 4714 5.059840 8.414904 -2.628637 0.4841390 0.2828701 0.6199312 0.5488891 +VERTEX_SE3:QUAT 4715 5.087853 8.421047 -2.558929 0.0887230 0.4057237 0.1325521 0.8999702 +VERTEX_SE3:QUAT 4716 5.166092 8.457130 -2.587720 -0.3246295 0.1887652 -0.6147120 0.6936228 +VERTEX_SE3:QUAT 4717 5.184731 8.449888 -2.668741 -0.6024643 -0.4139904 0.0657217 0.6792123 +VERTEX_SE3:QUAT 4718 5.198566 8.472746 -2.614846 -0.5513669 0.0947147 0.1121014 0.8212533 +VERTEX_SE3:QUAT 4719 5.201838 8.443610 -2.352273 0.4541071 0.8209315 -0.0018373 0.3462005 +VERTEX_SE3:QUAT 4720 5.171940 8.370857 -2.150180 -0.5436014 0.4236666 -0.7244669 0.0123201 +VERTEX_SE3:QUAT 4721 5.197575 8.354931 -2.244700 -0.0902337 -0.6578747 -0.6430897 0.3814373 +VERTEX_SE3:QUAT 4722 5.167202 8.193989 -2.344362 -0.1862803 0.7225307 0.3737369 0.5509716 +VERTEX_SE3:QUAT 4723 5.111500 8.155706 -2.260653 -0.9251419 0.2404742 -0.1569252 0.2483125 +VERTEX_SE3:QUAT 4724 5.126534 8.245868 -2.023080 -0.1624437 0.6195630 0.5954145 0.4850105 +VERTEX_SE3:QUAT 4725 5.173715 8.253142 -1.955446 -0.5857117 0.5103071 -0.4954035 0.3887207 +VERTEX_SE3:QUAT 4726 5.209496 8.342541 -1.742671 0.3229018 0.2148377 0.6767672 0.6257518 +VERTEX_SE3:QUAT 4727 5.041990 8.401178 -1.773785 -0.2134253 0.3507354 -0.6481039 0.6414013 +VERTEX_SE3:QUAT 4728 5.085223 8.471897 -1.857989 0.3321573 0.7492754 -0.0917703 0.5655405 +VERTEX_SE3:QUAT 4729 5.137357 8.385757 -1.916970 0.0024789 0.8441563 0.4786338 0.2414617 +VERTEX_SE3:QUAT 4730 5.185789 8.457788 -1.839145 0.0064814 -0.9923761 0.0932626 0.0803101 +VERTEX_SE3:QUAT 4731 5.183632 8.501401 -1.823885 -0.8694434 -0.2949911 -0.0157619 0.3959798 +VERTEX_SE3:QUAT 4732 5.248971 8.560703 -1.773167 0.7838985 0.3527186 0.3992714 0.3188653 +VERTEX_SE3:QUAT 4733 5.167309 8.615635 -1.623697 0.0987471 0.4573678 0.4998618 0.7288360 +VERTEX_SE3:QUAT 4734 5.167175 8.562057 -1.513652 -0.0657203 0.7167099 -0.3318438 0.6098258 +VERTEX_SE3:QUAT 4735 5.220196 8.576931 -1.391430 -0.4447130 0.6136460 0.6512555 0.0391823 +VERTEX_SE3:QUAT 4736 5.134661 8.470443 -1.432811 0.0058053 0.8474453 0.3142256 0.4278609 +VERTEX_SE3:QUAT 4737 5.192295 8.608818 -1.395461 0.2307876 -0.3402984 -0.9057759 0.1024897 +VERTEX_SE3:QUAT 4738 5.159350 8.535339 -1.443507 -0.0360192 0.5580401 -0.1730531 0.8107691 +VERTEX_SE3:QUAT 4739 4.980268 8.390843 -1.496654 -0.4890682 0.4922886 -0.1524840 0.7037136 +VERTEX_SE3:QUAT 4740 4.960654 8.423562 -1.360952 -0.6623674 0.2880433 0.3583811 0.5914926 +VERTEX_SE3:QUAT 4741 5.028450 8.508388 -1.502769 -0.3783171 0.9133818 -0.0035899 0.1503226 +VERTEX_SE3:QUAT 4742 5.057105 8.220144 -1.333371 -0.5216873 0.7722333 0.0514353 0.3589603 +VERTEX_SE3:QUAT 4743 5.218386 8.280018 -1.311358 -0.0755943 -0.7264830 -0.5360406 0.4232830 +VERTEX_SE3:QUAT 4744 5.212777 8.278035 -1.330757 -0.0149615 0.8628634 -0.2029220 0.4626723 +VERTEX_SE3:QUAT 4745 5.172005 8.231188 -1.409237 -0.9588942 -0.0964904 0.1023840 0.2464326 +VERTEX_SE3:QUAT 4746 5.282992 7.960765 -1.291941 -0.3483720 0.0855551 0.0821044 0.9298259 +VERTEX_SE3:QUAT 4747 5.365338 7.882598 -1.212754 -0.5327137 0.1888733 0.5999968 0.5661686 +VERTEX_SE3:QUAT 4748 5.293865 7.811308 -1.207944 -0.5908943 0.0956521 0.0204112 0.8007984 +VERTEX_SE3:QUAT 4749 5.214658 7.890665 -1.162268 -0.6978580 -0.5388179 -0.1917054 0.4311828 +VERTEX_SE3:QUAT 4750 5.091568 7.762656 -1.015057 -0.4927231 -0.1104465 -0.7969130 0.3315949 +VERTEX_SE3:QUAT 4751 5.182545 7.737681 -0.961876 -0.1090179 0.4363275 0.8118834 0.3722618 +VERTEX_SE3:QUAT 4752 5.162537 7.503529 -0.947719 0.5685835 0.6353316 0.3505579 0.3875251 +VERTEX_SE3:QUAT 4753 5.079704 7.371024 -0.765971 -0.5629069 -0.0273967 0.2678476 0.7814364 +VERTEX_SE3:QUAT 4754 5.169862 7.313766 -0.684639 -0.1602096 -0.1574976 -0.5132708 0.8282998 +VERTEX_SE3:QUAT 4755 5.168409 7.180816 -0.829489 0.3898867 0.7913529 0.0140594 0.4706923 +VERTEX_SE3:QUAT 4756 5.011927 7.163534 -0.861760 -0.5913472 -0.6473662 -0.1599812 0.4534662 +VERTEX_SE3:QUAT 4757 5.062369 7.165721 -0.794534 -0.4761059 -0.8633030 -0.0159033 0.1666680 +VERTEX_SE3:QUAT 4758 5.178271 7.128562 -0.712846 0.3662859 -0.8067804 -0.4544837 0.0915672 +VERTEX_SE3:QUAT 4759 5.087824 6.985677 -0.700442 0.2165115 -0.8920593 -0.3598245 0.1669707 +VERTEX_SE3:QUAT 4760 5.067762 6.905491 -0.588582 -0.6198225 0.0959187 0.2810090 0.7263977 +VERTEX_SE3:QUAT 4761 4.990999 6.913634 -0.733826 -0.4377365 0.2073939 0.0479194 0.8735435 +VERTEX_SE3:QUAT 4762 4.985128 6.919378 -0.800558 0.4314429 0.7597688 0.1991738 0.4437772 +VERTEX_SE3:QUAT 4763 4.768239 7.000805 -0.917994 -0.7783658 -0.2234420 -0.2720300 0.5198269 +VERTEX_SE3:QUAT 4764 4.828165 7.014772 -0.724888 0.9595587 -0.1847379 -0.1620406 0.1373383 +VERTEX_SE3:QUAT 4765 4.952310 7.059882 -0.731181 -0.3650706 0.5716981 -0.5502455 0.4869442 +VERTEX_SE3:QUAT 4766 5.030302 6.815753 -0.834438 -0.3624445 0.6167716 0.5596559 0.4183444 +VERTEX_SE3:QUAT 4767 5.071530 6.646558 -0.680576 -0.3932885 0.3075307 -0.5380345 0.6791670 +VERTEX_SE3:QUAT 4768 4.890926 6.515408 -0.759882 -0.8554330 0.2325311 -0.4398032 0.1440028 +VERTEX_SE3:QUAT 4769 4.823817 6.582940 -0.793394 -0.9548666 0.1123038 -0.0478824 0.2707858 +VERTEX_SE3:QUAT 4770 4.783994 6.609025 -0.983075 -0.4633960 -0.8708493 -0.0186108 0.1629087 +VERTEX_SE3:QUAT 4771 5.031499 6.422246 -1.145516 -0.3657695 -0.7329557 -0.5039561 0.2738921 +VERTEX_SE3:QUAT 4772 4.953297 6.229912 -1.095949 -0.4785323 -0.1009373 -0.6793212 0.5471208 +VERTEX_SE3:QUAT 4773 4.770344 6.081778 -1.070807 0.1059312 0.4721169 0.7506208 0.4499474 +VERTEX_SE3:QUAT 4774 4.596411 6.053443 -1.069974 -0.6253541 0.7637372 -0.1522174 0.0496738 +VERTEX_SE3:QUAT 4775 4.556335 6.080633 -0.941705 -0.4507729 -0.4845076 -0.6735784 0.3291631 +VERTEX_SE3:QUAT 4776 4.536828 6.011947 -1.085825 0.0223713 -0.8850112 -0.4645353 0.0214860 +VERTEX_SE3:QUAT 4777 4.547800 5.932715 -1.186228 0.3979723 0.6905298 -0.0173597 0.6037262 +VERTEX_SE3:QUAT 4778 4.598407 5.861066 -1.190244 -0.9224206 0.0709518 -0.3702145 0.0839483 +VERTEX_SE3:QUAT 4779 4.428185 5.943743 -1.186464 0.6298124 0.5076114 0.3485722 0.4734601 +VERTEX_SE3:QUAT 4780 4.493856 6.066024 -1.379778 -0.4667415 0.4148676 -0.1716101 0.7619628 +VERTEX_SE3:QUAT 4781 4.610843 6.141601 -1.469935 -0.9353738 0.3088933 -0.0831565 0.1508168 +VERTEX_SE3:QUAT 4782 4.726484 5.992699 -1.566832 -0.1454741 0.7339385 0.5029769 0.4326498 +VERTEX_SE3:QUAT 4783 4.724319 6.116609 -1.617772 -0.6759871 0.3201634 -0.0165480 0.6635232 +VERTEX_SE3:QUAT 4784 4.675376 5.970554 -1.751670 -0.5155129 0.3987851 -0.1039988 0.7512664 +VERTEX_SE3:QUAT 4785 4.749772 6.013919 -1.800103 0.8870009 0.4454042 -0.0583283 0.1069684 +VERTEX_SE3:QUAT 4786 4.906132 6.091400 -1.913881 0.4395728 0.8701831 -0.2066479 0.0827870 +VERTEX_SE3:QUAT 4787 4.990976 6.149846 -1.931712 -0.1128207 0.7507444 0.4554002 0.4650430 +VERTEX_SE3:QUAT 4788 5.023529 6.098483 -2.035112 -0.4032624 0.6355001 0.6367952 0.1673644 +VERTEX_SE3:QUAT 4789 4.851423 6.147897 -2.150195 -0.1897214 0.4502223 -0.1917467 0.8511985 +VERTEX_SE3:QUAT 4790 4.854937 6.399764 -2.134400 -0.4363081 0.5376632 -0.3873349 0.6087078 +VERTEX_SE3:QUAT 4791 4.886028 6.344362 -2.281936 0.8841355 0.3516082 0.0371367 0.3054456 +VERTEX_SE3:QUAT 4792 4.794243 6.358838 -2.270087 -0.8126128 0.2687860 -0.0922091 0.5088340 +VERTEX_SE3:QUAT 4793 4.907592 6.517391 -2.357138 -0.3443446 0.5617302 -0.2298202 0.7162881 +VERTEX_SE3:QUAT 4794 5.052690 6.503143 -2.351408 -0.9277141 -0.3723251 0.0022266 0.0267514 +VERTEX_SE3:QUAT 4795 4.909728 6.510839 -2.539062 -0.7795151 0.5553811 0.2720686 0.0994319 +VERTEX_SE3:QUAT 4796 4.782057 6.497792 -2.595767 -0.7311515 -0.5407542 -0.2921446 0.2960640 +VERTEX_SE3:QUAT 4797 4.819154 6.555645 -2.332836 -0.4486259 -0.4958043 -0.6029624 0.4351428 +VERTEX_SE3:QUAT 4798 4.928093 6.660031 -2.153679 0.9366556 -0.2122881 -0.1442932 0.2383057 +VERTEX_SE3:QUAT 4799 4.794910 6.615422 -2.159375 -0.6764206 -0.0476973 0.1907083 0.7097961 +VERTEX_SE3:QUAT 4800 4.870754 6.470528 -2.028770 -0.1965184 0.7094457 0.6555076 0.1684550 +VERTEX_SE3:QUAT 4801 4.879736 6.392799 -2.233592 0.0760011 0.6472162 -0.1554517 0.7424081 +VERTEX_SE3:QUAT 4802 5.106916 6.351551 -2.202790 0.3428456 -0.8357412 -0.3982314 0.1593906 +VERTEX_SE3:QUAT 4803 5.274149 6.375908 -2.257815 0.2811482 -0.8584314 0.4213304 0.0808200 +VERTEX_SE3:QUAT 4804 5.210424 6.385047 -2.346267 -0.1468955 -0.8744366 -0.1910311 0.4210575 +VERTEX_SE3:QUAT 4805 5.163777 6.407210 -2.458379 0.8170376 0.2723455 0.5015305 0.0821263 +VERTEX_SE3:QUAT 4806 5.299285 6.390666 -2.337323 -0.6276267 0.2432599 0.6364882 0.3765529 +VERTEX_SE3:QUAT 4807 5.371348 6.351274 -2.492654 0.5805990 0.7618356 -0.2847961 0.0374501 +VERTEX_SE3:QUAT 4808 5.520363 6.317923 -2.654775 -0.4328473 0.1032614 -0.6135549 0.6523271 +VERTEX_SE3:QUAT 4809 5.524592 6.383090 -2.596353 -0.3012611 0.7449212 0.4978682 0.3262843 +VERTEX_SE3:QUAT 4810 5.579914 6.362889 -2.493046 0.0994322 0.9635250 -0.2306641 0.0923416 +VERTEX_SE3:QUAT 4811 5.659047 6.378355 -2.487059 -0.7867523 0.1014271 0.5988122 0.1102599 +VERTEX_SE3:QUAT 4812 5.672738 6.402948 -2.654718 0.2901637 -0.8754509 -0.3515082 0.1607255 +VERTEX_SE3:QUAT 4813 5.642471 6.472571 -2.520949 0.2871226 0.5866195 0.7568092 0.0260367 +VERTEX_SE3:QUAT 4814 5.483783 6.429210 -2.376316 -0.3820461 -0.8933112 0.0650773 0.2275980 +VERTEX_SE3:QUAT 4815 5.822888 6.349100 -2.543675 -0.3879225 -0.8881541 0.2067512 0.1339865 +VERTEX_SE3:QUAT 4816 5.886037 6.254896 -2.486385 -0.6908391 0.1756023 -0.3560000 0.6042923 +VERTEX_SE3:QUAT 4817 5.976758 6.335460 -2.494519 -0.7294309 0.2606829 -0.0297809 0.6317342 +VERTEX_SE3:QUAT 4818 5.949673 6.412603 -2.337987 -0.1751870 0.9149007 -0.3420563 0.1235466 +VERTEX_SE3:QUAT 4819 5.936989 6.414315 -2.260866 -0.7622565 0.2902257 -0.3942962 0.4233965 +VERTEX_SE3:QUAT 4820 6.062096 6.518557 -2.354790 0.8850098 -0.2400408 0.2544396 0.3072435 +VERTEX_SE3:QUAT 4821 6.233485 6.381420 -2.465084 -0.3934840 0.5859210 -0.6433621 0.2965672 +VERTEX_SE3:QUAT 4822 6.150548 6.426751 -2.502430 0.1191906 -0.7394373 -0.4750705 0.4618811 +VERTEX_SE3:QUAT 4823 6.195579 6.518801 -2.669907 -0.5209405 -0.7230237 -0.4288634 0.1481011 +VERTEX_SE3:QUAT 4824 6.232536 6.471943 -2.824754 0.0175470 0.8751374 -0.2741562 0.3983279 +VERTEX_SE3:QUAT 4825 6.171063 6.537311 -2.869092 0.4762126 -0.8510114 -0.0981505 0.1984126 +VERTEX_SE3:QUAT 4826 6.128134 6.762887 -2.908920 -0.5680362 0.5197493 -0.6319641 0.0884128 +VERTEX_SE3:QUAT 4827 6.108464 6.950723 -2.719463 0.3636163 0.7804548 -0.4870384 0.1465166 +VERTEX_SE3:QUAT 4828 5.929629 6.997024 -2.476869 -0.6090070 0.5786778 -0.0596641 0.5391499 +VERTEX_SE3:QUAT 4829 5.981020 7.099788 -2.401646 0.8603818 0.3514252 0.0587453 0.3644071 +VERTEX_SE3:QUAT 4830 5.845900 7.269586 -2.295778 0.8598423 0.4752011 0.1157524 0.1464804 +VERTEX_SE3:QUAT 4831 5.800521 7.632566 -2.098110 -0.8544365 0.4400005 -0.1395089 0.2384849 +VERTEX_SE3:QUAT 4832 5.839681 7.516192 -2.128924 0.8055869 0.2766286 0.3731269 0.3678080 +VERTEX_SE3:QUAT 4833 5.846667 7.317312 -1.947481 0.1117280 0.8058783 -0.2286464 0.5346007 +VERTEX_SE3:QUAT 4834 5.864833 7.480443 -1.746274 -0.2674663 -0.8185717 -0.5080251 0.0176814 +VERTEX_SE3:QUAT 4835 5.883112 7.544556 -1.673632 -0.6670783 -0.5369635 -0.2974501 0.4221377 +VERTEX_SE3:QUAT 4836 5.894193 7.633591 -1.720556 0.1776220 0.9591111 -0.0596526 0.2121269 +VERTEX_SE3:QUAT 4837 5.874840 7.779280 -1.693159 -0.3384874 0.8240318 -0.3882957 0.2358481 +VERTEX_SE3:QUAT 4838 5.919491 7.869444 -1.760592 -0.9076061 0.1340022 -0.2091630 0.3384457 +VERTEX_SE3:QUAT 4839 5.929975 7.973547 -1.714330 0.9661335 0.1213957 -0.0966859 0.2061575 +VERTEX_SE3:QUAT 4840 6.041824 7.985410 -1.530144 -0.5948186 -0.2092653 -0.6352770 0.4458947 +VERTEX_SE3:QUAT 4841 6.180711 7.913464 -1.387723 0.4068239 0.7098072 0.5670974 0.0952295 +VERTEX_SE3:QUAT 4842 6.051472 8.046260 -1.180064 0.7635271 -0.2725684 -0.1730635 0.5592690 +VERTEX_SE3:QUAT 4843 6.212923 8.160146 -1.015918 0.4521356 -0.8906940 0.0391091 0.0266102 +VERTEX_SE3:QUAT 4844 6.140609 8.259132 -1.072768 0.4715246 -0.5702259 0.4795974 0.4716919 +VERTEX_SE3:QUAT 4845 5.982899 8.165197 -0.971836 -0.2457852 -0.7965227 0.5356002 0.1351803 +VERTEX_SE3:QUAT 4846 6.012975 8.136950 -0.943800 0.7127301 0.3278772 -0.0792820 0.6150014 +VERTEX_SE3:QUAT 4847 6.018342 8.108152 -0.667318 0.6600265 -0.0637259 0.5132849 0.5448327 +VERTEX_SE3:QUAT 4848 5.862841 8.117334 -0.416625 -0.1764716 0.7670284 -0.1829394 0.5891166 +VERTEX_SE3:QUAT 4849 5.766742 8.148785 -0.341919 0.3441564 -0.8692954 0.3146065 0.1640263 +VERTEX_SE3:QUAT 4850 5.868828 8.042933 -0.319503 -0.1264371 0.8721326 0.2122624 0.4223068 +VERTEX_SE3:QUAT 4851 5.770805 8.080227 -0.184996 -0.2378390 0.6189521 -0.6521382 0.3674868 +VERTEX_SE3:QUAT 4852 5.684210 8.061767 -0.222418 -0.6288185 0.6816915 0.1793157 0.3282223 +VERTEX_SE3:QUAT 4853 5.630686 7.988567 -0.324935 -0.4473816 0.5656036 -0.4347099 0.5394160 +VERTEX_SE3:QUAT 4854 5.605417 7.939668 -0.306515 0.5478443 0.5037256 0.2616978 0.6145254 +VERTEX_SE3:QUAT 4855 5.450578 7.973287 -0.129436 0.0830713 0.7515119 0.5992694 0.2630687 +VERTEX_SE3:QUAT 4856 5.226746 8.056255 -0.105362 -0.2289675 0.7358425 0.3808686 0.5109294 +VERTEX_SE3:QUAT 4857 5.215929 8.054674 -0.098369 0.4836894 -0.8535849 0.1659639 0.0994653 +VERTEX_SE3:QUAT 4858 5.112146 7.952955 -0.203426 -0.3874538 -0.9110997 -0.1298452 0.0540110 +VERTEX_SE3:QUAT 4859 4.908153 7.917942 -0.107104 0.3129159 0.7205727 0.1032310 0.6100836 +VERTEX_SE3:QUAT 4860 4.702241 7.836451 -0.138929 0.8969785 -0.1650465 0.3992594 0.0937082 +VERTEX_SE3:QUAT 4861 4.553716 7.816315 -0.173120 -0.9476862 0.2807732 -0.1134204 0.1009609 +VERTEX_SE3:QUAT 4862 4.556074 7.948026 -0.000019 0.7461601 0.0263454 0.6294475 0.2152832 +VERTEX_SE3:QUAT 4863 4.606368 7.970176 -0.106331 0.5326869 -0.8181747 0.1991110 0.0847915 +VERTEX_SE3:QUAT 4864 4.594695 8.089159 -0.069580 0.6617168 0.1224168 0.4498165 0.5872053 +VERTEX_SE3:QUAT 4865 4.661441 7.967954 -0.019556 -0.3462204 0.7110849 -0.5894941 0.1642754 +VERTEX_SE3:QUAT 4866 4.627192 7.904926 -0.114494 0.5945944 -0.0945977 0.7718772 0.2042410 +VERTEX_SE3:QUAT 4867 4.453033 7.864525 -0.187889 -0.4970564 0.7033648 -0.0005700 0.5081462 +VERTEX_SE3:QUAT 4868 4.358513 7.780713 -0.149099 -0.1761290 0.5089825 -0.2865824 0.7923294 +VERTEX_SE3:QUAT 4869 4.297161 7.828170 -0.109994 -0.7911737 0.1546463 -0.1491016 0.5726232 +VERTEX_SE3:QUAT 4870 4.194941 7.734716 -0.117286 -0.0395479 0.9044095 0.3959058 0.1540716 +VERTEX_SE3:QUAT 4871 4.136390 7.676304 -0.014069 -0.8526873 -0.0046999 0.0086247 0.5223293 +VERTEX_SE3:QUAT 4872 4.168368 7.573917 -0.122009 -0.0287181 0.5722228 -0.6901609 0.4420570 +VERTEX_SE3:QUAT 4873 4.170672 7.510520 0.018968 0.6366651 0.7282351 0.1001815 0.2330126 +VERTEX_SE3:QUAT 4874 4.096780 7.457040 0.075265 -0.2044049 -0.8751103 0.4253236 0.1072400 +VERTEX_SE3:QUAT 4875 4.057654 7.363908 0.011576 0.7995243 0.5116081 0.3059829 0.0734330 +VERTEX_SE3:QUAT 4876 4.067314 7.410916 0.004712 -0.6843826 0.3389507 -0.6454823 0.0092473 +VERTEX_SE3:QUAT 4877 4.122911 7.346568 0.104947 -0.6230440 -0.5125869 -0.5906501 0.0142546 +VERTEX_SE3:QUAT 4878 4.008330 7.334010 0.069880 -0.9244461 -0.3760282 0.0465006 0.0428935 +VERTEX_SE3:QUAT 4879 4.014452 7.268799 -0.019997 -0.2134254 0.6777867 -0.1397550 0.6895820 +VERTEX_SE3:QUAT 4880 3.943764 7.148531 -0.036935 -0.7718028 0.5500647 0.2340756 0.2166976 +VERTEX_SE3:QUAT 4881 3.783376 7.107368 -0.334806 -0.7516889 -0.2708213 -0.0090953 0.6012793 +VERTEX_SE3:QUAT 4882 3.901853 7.313140 -0.552221 0.3288268 0.6149441 0.2952967 0.6530823 +VERTEX_SE3:QUAT 4883 3.724693 7.337671 -0.599677 -0.0075736 0.5781166 -0.2745700 0.7683327 +VERTEX_SE3:QUAT 4884 3.583362 7.313958 -0.680996 -0.2359204 0.8572472 -0.3995830 0.2231642 +VERTEX_SE3:QUAT 4885 3.665643 7.222092 -0.909911 -0.8443558 0.0948725 -0.0522104 0.5247252 +VERTEX_SE3:QUAT 4886 3.787397 6.970777 -0.964965 -0.7934141 -0.2257452 0.0795116 0.5596527 +VERTEX_SE3:QUAT 4887 3.886850 6.932241 -0.969468 0.9302657 -0.1913992 0.2850587 0.1292814 +VERTEX_SE3:QUAT 4888 3.928206 6.968630 -1.006509 0.5499646 0.4221444 0.4483431 0.5641999 +VERTEX_SE3:QUAT 4889 3.967411 7.200137 -1.074781 0.1023176 -0.8648893 -0.4560884 0.1829779 +VERTEX_SE3:QUAT 4890 4.012398 7.189811 -1.026832 -0.7732903 -0.2549442 -0.2574994 0.5203073 +VERTEX_SE3:QUAT 4891 4.029199 7.016290 -1.106484 0.5584002 -0.6932022 -0.4181995 0.1810226 +VERTEX_SE3:QUAT 4892 4.069741 6.938261 -1.226445 -0.7431463 0.2730894 -0.3846677 0.4745382 +VERTEX_SE3:QUAT 4893 4.139752 6.868083 -1.247638 0.6772064 0.3616458 0.2378614 0.5950006 +VERTEX_SE3:QUAT 4894 4.240518 7.003697 -1.438834 -0.7182314 0.2424558 -0.6250249 0.1862866 +VERTEX_SE3:QUAT 4895 4.186332 7.040938 -1.525228 0.2492100 0.7092944 0.0332115 0.6585536 +VERTEX_SE3:QUAT 4896 4.151179 6.993168 -1.600620 -0.7086625 -0.3892884 -0.4938768 0.3199027 +VERTEX_SE3:QUAT 4897 4.138932 7.007766 -1.613077 -0.3320818 -0.7608785 -0.5568401 0.0267363 +VERTEX_SE3:QUAT 4898 4.118862 7.039750 -1.779077 0.6905621 -0.0834001 0.5917662 0.4074079 +VERTEX_SE3:QUAT 4899 3.960824 6.895227 -1.850126 -0.8237674 -0.3101045 0.2610964 0.3963220 +VERTEX_SE3:QUAT 4900 4.015010 6.941882 -1.855645 0.2071540 0.6224181 0.1367549 0.7422810 +VERTEX_SE3:QUAT 4901 4.028913 7.119853 -1.887816 -0.4860917 0.2854535 -0.3017033 0.7688994 +VERTEX_SE3:QUAT 4902 4.252336 7.212222 -1.823035 -0.8428389 0.5045580 -0.1858069 0.0227962 +VERTEX_SE3:QUAT 4903 4.152633 7.163406 -1.903562 0.3764696 0.7956361 0.0730366 0.4689344 +VERTEX_SE3:QUAT 4904 3.993860 7.204596 -1.945332 0.4200097 0.7937241 -0.3361305 0.2839193 +VERTEX_SE3:QUAT 4905 4.060186 7.208637 -2.158929 -0.2573655 0.6910629 0.4831551 0.4719705 +VERTEX_SE3:QUAT 4906 4.231516 7.103003 -2.261173 -0.8944340 0.2655252 0.0805683 0.3507034 +VERTEX_SE3:QUAT 4907 4.236811 7.039639 -2.329958 -0.5327903 0.6530159 0.3320578 0.4236064 +VERTEX_SE3:QUAT 4908 4.212975 7.090862 -2.359333 -0.3096137 0.7766356 0.5277496 0.1498559 +VERTEX_SE3:QUAT 4909 4.269361 7.269454 -2.513088 -0.7440875 -0.5312870 0.2723977 0.2997788 +VERTEX_SE3:QUAT 4910 4.422331 7.369768 -2.575655 -0.5225168 0.2217271 -0.8168666 0.1026753 +VERTEX_SE3:QUAT 4911 4.403473 7.202583 -2.684280 0.1011207 0.9908957 0.0147108 0.0876581 +VERTEX_SE3:QUAT 4912 4.357204 7.331390 -2.842944 -0.0169141 0.8387288 0.4933991 0.2297941 +VERTEX_SE3:QUAT 4913 4.369001 7.389516 -2.959575 0.4678152 -0.8665268 -0.1159332 0.1297679 +VERTEX_SE3:QUAT 4914 4.398510 7.466756 -2.953300 -0.0496750 0.8715142 0.4743100 0.1141292 +VERTEX_SE3:QUAT 4915 4.406459 7.595552 -2.832616 -0.1974478 0.6865995 0.3208361 0.6218196 +VERTEX_SE3:QUAT 4916 4.464038 7.648450 -2.877154 -0.6422762 -0.6641391 -0.2149974 0.3165069 +VERTEX_SE3:QUAT 4917 4.609324 7.727753 -2.839377 0.2770380 0.5871446 0.0850059 0.7558341 +VERTEX_SE3:QUAT 4918 4.662787 7.866486 -3.050814 -0.4787540 0.8234005 0.2262260 0.2040295 +VERTEX_SE3:QUAT 4919 4.519955 8.060200 -3.186907 0.4571088 0.6106613 0.5521677 0.3365341 +VERTEX_SE3:QUAT 4920 4.534054 7.892993 -3.195205 -0.6692586 0.3327318 -0.3369435 0.5725833 +VERTEX_SE3:QUAT 4921 4.687371 7.980968 -3.154208 0.5700658 0.5885051 -0.5498913 0.1621918 +VERTEX_SE3:QUAT 4922 4.641914 7.957214 -3.266888 -0.5811332 0.5505497 -0.2758886 0.5320383 +VERTEX_SE3:QUAT 4923 4.724803 7.955229 -3.261229 -0.4355879 0.3214180 -0.6889070 0.4820381 +VERTEX_SE3:QUAT 4924 4.667004 8.116362 -3.230848 0.1349518 0.9078776 0.0993822 0.3842779 +VERTEX_SE3:QUAT 4925 4.609938 8.417846 -3.273973 -0.1378925 0.4981519 -0.7667066 0.3807774 +VERTEX_SE3:QUAT 4926 4.581367 8.510322 -3.404814 0.4111208 -0.8079259 -0.1831348 0.3803907 +VERTEX_SE3:QUAT 4927 4.606835 8.620726 -3.418143 0.0056094 0.9142491 0.3337765 0.2295873 +VERTEX_SE3:QUAT 4928 4.670357 8.746199 -3.420496 0.7185561 0.3922326 -0.5331912 0.2133959 +VERTEX_SE3:QUAT 4929 4.674190 8.615222 -3.496391 0.5050175 0.5346605 -0.0650887 0.6744323 +VERTEX_SE3:QUAT 4930 4.647213 8.629339 -3.461733 -0.8910449 0.0232260 0.1418448 0.4305573 +VERTEX_SE3:QUAT 4931 4.517829 8.822902 -3.516043 -0.0512222 0.7761120 -0.3183986 0.5418937 +VERTEX_SE3:QUAT 4932 4.528729 8.755660 -3.648667 -0.0046875 0.8728907 -0.4403978 0.2099752 +VERTEX_SE3:QUAT 4933 4.427815 8.921773 -3.631156 0.2976135 0.7328427 0.5563421 0.2546592 +VERTEX_SE3:QUAT 4934 4.288027 8.935612 -3.610365 -0.8550103 0.2667511 -0.0646260 0.4400281 +VERTEX_SE3:QUAT 4935 4.331597 8.961165 -3.517180 0.1372633 0.9405783 0.0309609 0.3090512 +VERTEX_SE3:QUAT 4936 4.477374 8.991348 -3.471529 0.6476590 -0.3798881 0.6476428 0.1295442 +VERTEX_SE3:QUAT 4937 4.386297 8.970629 -3.458003 0.2349610 -0.9410487 0.1714930 0.1726580 +VERTEX_SE3:QUAT 4938 4.541372 9.220457 -3.496846 -0.8035101 0.1721989 -0.5694110 0.0221406 +VERTEX_SE3:QUAT 4939 4.524744 9.428649 -3.548802 0.8724079 -0.2080246 0.3625734 0.2533193 +VERTEX_SE3:QUAT 4940 4.592529 9.596830 -3.376532 0.0975929 0.9241394 0.2643706 0.2579731 +VERTEX_SE3:QUAT 4941 4.610289 9.699395 -3.282571 -0.5587454 -0.7008439 -0.2230682 0.3832258 +VERTEX_SE3:QUAT 4942 4.553929 9.790935 -3.191813 -0.4629530 0.6342233 -0.6166858 0.0559821 +VERTEX_SE3:QUAT 4943 4.577998 9.780317 -3.097071 0.3173020 0.8106250 0.4195616 0.2572443 +VERTEX_SE3:QUAT 4944 4.520386 9.845125 -3.124126 0.4921048 0.6244855 0.0065014 0.6064722 +VERTEX_SE3:QUAT 4945 4.616316 9.782865 -3.151792 0.4937577 -0.6300331 0.1653320 0.5761310 +VERTEX_SE3:QUAT 4946 4.575713 9.575523 -3.163981 0.5436396 -0.4820313 0.4162029 0.5466964 +VERTEX_SE3:QUAT 4947 4.620893 9.435415 -3.103525 -0.8533515 -0.1715678 -0.3941325 0.2949835 +VERTEX_SE3:QUAT 4948 4.651219 9.339578 -3.221271 0.5140507 0.5767627 0.5453965 0.3250222 +VERTEX_SE3:QUAT 4949 4.728425 9.276632 -3.220547 -0.5454393 -0.6020262 -0.2171711 0.5411997 +VERTEX_SE3:QUAT 4950 4.625396 9.395941 -3.229227 -0.7128463 0.4669350 -0.0219411 0.5228197 +VERTEX_SE3:QUAT 4951 4.674091 9.328969 -3.184399 -0.7621215 0.0131184 -0.3551562 0.5411680 +VERTEX_SE3:QUAT 4952 4.845802 9.168361 -3.077511 -0.6176069 0.5126487 -0.5462327 0.2395470 +VERTEX_SE3:QUAT 4953 4.933563 9.225612 -3.147974 0.3236204 0.6720150 -0.2516798 0.6167032 +VERTEX_SE3:QUAT 4954 4.755783 9.196762 -3.231200 -0.2948984 0.8220204 0.1708156 0.4562230 +VERTEX_SE3:QUAT 4955 4.592507 9.224815 -3.235931 0.6154612 0.6184897 -0.3790236 0.3082517 +VERTEX_SE3:QUAT 4956 4.425328 9.286615 -3.158469 -0.7360497 0.6750194 0.0471716 0.0188253 +VERTEX_SE3:QUAT 4957 4.256788 9.262045 -2.850615 0.8581937 -0.1791173 0.3140084 0.3644438 +VERTEX_SE3:QUAT 4958 4.222464 9.237783 -2.906298 -0.7310119 0.2427107 -0.6237079 0.1330472 +VERTEX_SE3:QUAT 4959 4.227245 9.265648 -2.805458 -0.9736478 -0.0096774 0.2174093 0.0681870 +VERTEX_SE3:QUAT 4960 4.293694 9.148972 -2.605073 -0.8742576 0.1116266 -0.1074217 0.4600802 +VERTEX_SE3:QUAT 4961 4.188136 9.127675 -2.563919 -0.3684929 -0.7131347 -0.5862955 0.1091301 +VERTEX_SE3:QUAT 4962 4.116717 9.080176 -2.504077 0.6939110 0.7136037 0.0763032 0.0586095 +VERTEX_SE3:QUAT 4963 4.039138 9.054725 -2.516974 0.5304522 0.5672141 -0.5549880 0.2981224 +VERTEX_SE3:QUAT 4964 3.883697 9.045445 -2.417244 0.9666126 -0.1132622 -0.1813264 0.1412535 +VERTEX_SE3:QUAT 4965 3.970872 8.952739 -2.383777 0.1532586 -0.9523279 0.2589549 0.0502575 +VERTEX_SE3:QUAT 4966 3.841974 8.997064 -2.384753 0.4518242 0.6549676 -0.2208072 0.5640182 +VERTEX_SE3:QUAT 4967 3.935213 9.036396 -2.410110 -0.4399654 0.8964713 0.0277735 0.0447023 +VERTEX_SE3:QUAT 4968 3.914792 8.737853 -2.482468 0.2856540 -0.9273470 0.1644289 0.1771795 +VERTEX_SE3:QUAT 4969 3.917314 8.802404 -2.293922 -0.8362585 0.2837179 0.0915015 0.4602210 +VERTEX_SE3:QUAT 4970 3.813468 8.538369 -2.268528 0.9402466 0.1294194 0.2039938 0.2399449 +VERTEX_SE3:QUAT 4971 3.785624 8.483556 -2.271318 -0.2323211 0.6780358 -0.6943248 0.0648646 +VERTEX_SE3:QUAT 4972 3.740345 8.459368 -2.302965 0.0241446 -0.8255395 -0.5489948 0.1284770 +VERTEX_SE3:QUAT 4973 3.741554 8.232432 -2.325661 -0.6730205 0.1903918 -0.3110958 0.6434390 +VERTEX_SE3:QUAT 4974 3.692172 8.329162 -2.297560 0.5456139 -0.8009714 -0.2043425 0.1378200 +VERTEX_SE3:QUAT 4975 3.477533 8.329985 -2.402108 -0.9115045 0.2392992 -0.0736677 0.3262950 +VERTEX_SE3:QUAT 4976 3.554942 8.368389 -2.592897 -0.6409612 -0.2328043 -0.5157412 0.5186347 +VERTEX_SE3:QUAT 4977 3.323803 8.184971 -2.899419 0.1501930 0.8447862 -0.4931344 0.1435156 +VERTEX_SE3:QUAT 4978 3.282173 8.219836 -2.943090 -0.6740027 0.0031395 -0.4043542 0.6182298 +VERTEX_SE3:QUAT 4979 3.234439 8.219803 -2.950206 -0.3965906 0.4245642 0.5250364 0.6219308 +VERTEX_SE3:QUAT 4980 3.106382 7.970819 -3.051972 -0.1907799 0.4980333 0.6729366 0.5125643 +VERTEX_SE3:QUAT 4981 3.008010 7.914869 -2.992183 -0.6048192 -0.1369899 -0.5331674 0.5754650 +VERTEX_SE3:QUAT 4982 2.974379 8.027530 -2.972546 -0.7888493 0.2346105 -0.0936473 0.5602721 +VERTEX_SE3:QUAT 4983 3.006627 7.939071 -3.011650 0.9542548 0.0354403 0.0827862 0.2851108 +VERTEX_SE3:QUAT 4984 3.077566 8.104841 -3.178445 -0.6478967 0.7485192 0.0571997 0.1291398 +VERTEX_SE3:QUAT 4985 3.179356 7.987089 -3.195241 -0.1119376 0.7695403 -0.6256290 0.0621778 +VERTEX_SE3:QUAT 4986 3.070528 7.643290 -3.224926 0.8569271 -0.2668847 -0.3842913 0.2162606 +VERTEX_SE3:QUAT 4987 3.136541 7.714520 -3.283357 -0.7258150 -0.6781368 0.1064341 0.0446638 +VERTEX_SE3:QUAT 4988 3.083566 7.688193 -3.354911 -0.3168351 0.7861788 0.4993952 0.1792844 +VERTEX_SE3:QUAT 4989 3.000933 7.778093 -3.340846 0.7343950 0.1372644 0.0949577 0.6578796 +VERTEX_SE3:QUAT 4990 3.005853 7.738028 -3.452506 -0.3421021 0.4290822 -0.8347714 0.0448480 +VERTEX_SE3:QUAT 4991 3.065229 7.797812 -3.563442 -0.3567743 0.8746043 -0.1696202 0.2810843 +VERTEX_SE3:QUAT 4992 3.061897 7.620983 -3.616763 -0.6275841 0.4636553 -0.2449759 0.5754553 +VERTEX_SE3:QUAT 4993 3.166703 7.370971 -3.638882 0.0111678 0.5795013 0.0676260 0.8120839 +VERTEX_SE3:QUAT 4994 3.113418 7.273538 -3.603004 0.4790976 0.4267131 -0.0690949 0.7639419 +VERTEX_SE3:QUAT 4995 3.185496 7.154538 -3.586942 0.7246239 -0.4018054 0.5576344 0.0501650 +VERTEX_SE3:QUAT 4996 3.222147 7.233205 -3.692905 -0.3666599 -0.9222447 -0.0087912 0.1222621 +VERTEX_SE3:QUAT 4997 3.235541 7.263151 -3.811328 -0.8487692 -0.5152211 -0.0312839 0.1147146 +VERTEX_SE3:QUAT 4998 3.317958 7.098778 -4.052365 0.4237547 0.6463063 0.4175501 0.4778829 +VERTEX_SE3:QUAT 4999 3.284463 7.102284 -3.949481 0.7180895 0.4649307 0.1526694 0.4948524 +EDGE_SE3:QUAT 0 1 0.070877 -0.137909 -0.005088 -0.2800834 -0.4989760 0.7807569 0.2509877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1 2 0.149575 -0.091334 0.039317 0.3468626 -0.6337388 0.6913962 0.0057289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2 3 0.003952 -0.090986 0.135809 0.1326777 0.5913313 -0.5643247 0.5605904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3 4 -0.058940 0.017070 0.002318 0.1877421 0.1624827 0.5806150 0.7753957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4 5 -0.049543 -0.095344 0.060924 -0.5923793 -0.3981064 0.2814645 0.6413859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5 6 0.125749 -0.172919 0.058789 0.4160684 0.3724978 0.5625044 0.6096895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6 7 -0.099055 0.048298 0.198071 0.5868728 -0.3203299 -0.7430391 0.0293610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7 8 0.037568 0.133802 0.219255 0.0578198 -0.4064822 -0.8850194 0.2194759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 8 9 -0.004890 -0.159839 -0.085688 0.2481183 0.6728661 -0.3202895 0.6189533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 9 10 -0.075648 -0.003241 0.097559 0.5443267 -0.2171922 -0.5362547 0.6074264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 10 11 -0.008264 -0.079132 0.096399 -0.1451378 -0.0267396 0.6405926 0.7535656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 11 12 -0.241954 -0.091642 0.173578 0.6197004 -0.4553478 -0.5257172 0.3636637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 12 13 0.111438 -0.078698 -0.125193 0.0886988 0.8566597 0.4968001 0.1070342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 13 14 0.082665 0.259310 -0.121872 -0.8582470 -0.0409633 -0.3038960 0.4115596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 14 15 -0.032797 -0.078251 0.097671 0.1722208 0.0777954 0.9678972 0.1657195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 15 16 -0.106559 0.085372 0.098586 -0.7127545 0.4991792 0.4662586 0.1593868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 16 17 -0.163501 -0.066325 0.074901 0.2718463 -0.2759819 0.1867510 0.9028055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 17 18 -0.104311 0.117342 0.236479 -0.3771508 -0.6065697 -0.0587844 0.6974058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 18 19 -0.008759 -0.072989 0.158741 0.2734975 -0.2953553 0.6939765 0.5969598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 19 20 0.092814 -0.228064 0.076537 0.6151167 0.3113690 -0.2715469 0.6715230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 20 21 -0.084303 0.238296 0.111343 0.2842895 0.8695930 0.1628230 0.3694267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 21 22 0.055981 -0.076153 -0.183749 -0.1577458 -0.3454809 -0.8006085 0.4634493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 22 23 -0.096549 -0.023908 -0.208964 -0.6240465 -0.3966232 0.2138542 0.6383748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 23 24 -0.052906 0.012506 0.172398 -0.0536709 -0.8187112 0.1880637 0.5398736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 24 25 -0.073278 0.004968 0.050584 0.1954091 0.5493838 0.0976463 0.8065097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 25 26 0.044356 -0.097235 0.200375 0.0283015 0.1750043 -0.7767426 0.6043537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 26 27 -0.020270 0.032332 0.067764 -0.2660101 0.3152234 -0.7122587 0.5679440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 27 28 -0.088966 -0.109844 -0.025064 -0.2289828 0.4131114 -0.8735745 0.1173603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 28 29 -0.001375 0.020838 -0.022788 -0.2010030 0.0928474 -0.2034680 0.9537180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 29 30 -0.056332 0.118985 -0.211934 0.7002850 -0.5418764 -0.2076743 0.4157431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 30 31 -0.011982 0.083943 -0.135552 0.2126125 0.0678770 -0.5207805 0.8240002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 31 32 0.098517 -0.140187 -0.016529 -0.2415442 0.2024739 0.9276824 0.2001649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 32 33 -0.145956 -0.121965 -0.218683 0.8608068 0.1608427 -0.0541569 0.4798003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 33 34 0.140482 0.058268 -0.077755 -0.5980700 0.4780364 0.5402581 0.3491627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 34 35 0.101941 -0.017468 -0.105295 0.5141536 -0.3954577 -0.7188890 0.2499159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 35 36 0.019725 -0.000190 0.020146 -0.1417572 0.2774993 -0.6492918 0.6937717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 36 37 -0.013614 -0.037753 0.094196 -0.3367000 -0.0503592 -0.0416700 0.9393405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 37 38 0.025053 -0.141394 -0.066860 0.6302906 -0.2094860 -0.0007413 0.7475619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 38 39 0.003543 0.124815 -0.246451 -0.3578742 -0.1139348 -0.9041277 0.2037105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 39 40 0.003535 -0.244080 -0.066514 -0.3865458 0.5340923 -0.4514513 0.6012649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 40 41 -0.108889 0.023216 -0.176663 -0.1405097 -0.0176686 -0.6086392 0.7807068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 41 42 0.153126 -0.056439 -0.029050 -0.3305189 0.2259219 -0.1942393 0.8955376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 42 43 0.032954 -0.041259 0.034007 -0.0970836 -0.6961654 0.6197635 0.3490297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 43 44 0.097462 0.136704 -0.012765 -0.6817211 0.1353236 -0.6935078 0.1897122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 44 45 0.023476 -0.021747 0.019309 -0.5940888 0.3853285 -0.5893834 0.3888543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 45 46 0.178374 -0.093786 0.038655 0.5416128 -0.3057225 0.5077862 0.5961061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 46 47 0.005497 0.180493 -0.048193 0.2801272 0.4173903 0.8000277 0.3275208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 47 48 -0.104051 0.071632 -0.099604 -0.1935083 0.3975867 -0.7587892 0.4782451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 48 49 -0.048020 -0.243604 -0.029475 -0.0358816 -0.5638879 0.1002023 0.8189643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 49 50 -0.028879 0.049424 -0.041531 -0.5069054 0.3590240 -0.5522540 0.5560254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 50 51 -0.161146 0.107835 0.109468 -0.0573742 0.4127669 0.0354461 0.9083365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 51 52 0.162791 0.025984 0.199259 -0.0874971 -0.1995193 -0.7080908 0.6716723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 52 53 -0.110716 0.031720 0.007602 -0.0003925 0.0274731 0.9994969 0.0158462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 53 54 0.030816 -0.151397 0.016865 -0.2387856 -0.1925021 -0.8560550 0.4160459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 54 55 0.054189 0.063918 -0.006015 0.4637648 0.6146979 0.4787943 0.4216926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 55 56 -0.056357 0.062778 0.033150 0.2150435 -0.7015149 -0.0023774 0.6794317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 56 57 0.205021 -0.109373 0.020565 -0.2737192 0.8335747 0.2296931 0.4212745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 57 58 -0.008396 -0.130722 0.065747 -0.5762651 -0.5483690 0.5909565 0.1340911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 58 59 0.021354 0.185587 -0.093847 -0.1979151 -0.7792311 0.5552219 0.2129720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 59 60 0.251725 -0.002593 -0.028708 -0.0832003 -0.5045189 0.4675036 0.7210955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 60 61 -0.037028 -0.154827 -0.272299 0.1337143 0.2861836 -0.5400916 0.7800773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 61 62 0.019447 -0.143917 0.056693 0.2759326 -0.3360211 -0.2582994 0.8626891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 62 63 -0.020413 -0.090767 0.101822 0.3695773 0.6168549 0.5368875 0.4411966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 63 64 -0.061551 -0.011345 -0.044362 0.1699587 0.0541268 0.8937480 0.4115808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 64 65 -0.161100 0.047933 0.144532 0.4930391 0.7489187 -0.4043254 0.1804278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 65 66 0.006930 -0.057404 -0.063488 -0.8406071 0.4096269 0.3534475 0.0256979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 66 67 0.080873 0.138427 0.059787 -0.1141370 0.1052030 0.9878766 0.0022255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 67 68 -0.145638 -0.071329 -0.050022 -0.6901627 0.3654805 -0.3075876 0.5435893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 68 69 0.020065 -0.012812 -0.101079 0.6635344 -0.1334041 -0.1612793 0.7182719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 69 70 0.024552 0.037439 0.002343 0.0484395 -0.0398208 -0.0391159 0.9972652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 70 71 -0.052213 0.126598 -0.049207 -0.6438519 -0.1710877 0.0729048 0.7422052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 71 72 -0.024321 0.049211 -0.034059 -0.1995149 -0.0615437 -0.9570873 0.2009730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 72 73 -0.197065 0.045627 0.152597 -0.0099795 0.8577919 0.5135629 0.0186154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 73 74 0.261951 -0.127054 0.054053 0.1928364 0.4772308 0.3078094 0.8001989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 74 75 -0.001920 -0.116001 -0.078953 -0.3542890 0.3540936 -0.1139816 0.8579657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 75 76 0.044993 -0.078298 0.084146 0.1502465 0.1448712 -0.2585427 0.9431829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 76 77 0.086494 -0.075415 0.137819 0.2405042 0.0510150 0.4124303 0.8771867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 77 78 -0.131691 -0.039360 -0.069051 -0.1141839 -0.1403910 -0.6304294 0.7548584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 78 79 0.058478 0.119268 -0.056324 -0.2822957 -0.6711814 0.5572626 0.3991028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 79 80 -0.119058 0.081273 -0.046233 -0.2978705 0.7839457 -0.3395792 0.4258970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 80 81 -0.002506 -0.139996 0.003358 0.0995486 0.4777650 0.3037099 0.8182854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 81 82 -0.199299 -0.075920 0.101282 0.0772403 -0.7106226 -0.1864077 0.6740190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 82 83 -0.005024 0.080535 -0.001517 -0.0878735 -0.0662080 -0.1490693 0.9826867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 83 84 -0.062432 0.039091 -0.076682 -0.6324593 -0.1093199 -0.7639914 0.0660418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 84 85 -0.038826 -0.036059 0.194127 -0.4275831 0.5469744 -0.1849350 0.6955507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 85 86 -0.098889 -0.168751 0.043638 -0.6565915 0.4042611 0.5832063 0.2555991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 86 87 0.217503 -0.015141 0.130497 -0.3861086 0.0353910 0.8959882 0.2165010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 87 88 0.031821 -0.079146 -0.091998 0.6664351 0.1262642 0.6186470 0.3964814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 88 89 0.054648 0.062400 -0.148386 -0.5622507 -0.6101795 -0.4563021 0.3214707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 89 90 0.045106 0.050061 0.178856 -0.1787402 0.3801683 0.3385521 0.8419658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 90 91 -0.063882 -0.029132 -0.012043 0.4986448 -0.2137113 0.7978446 0.2629160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 91 92 0.039127 -0.111212 0.141089 -0.0006150 0.4013412 0.8837863 0.2405134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 92 93 0.031416 -0.041247 -0.034703 -0.1358743 -0.6204272 0.1602924 0.7555889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 93 94 -0.024660 0.100358 0.204331 0.0441038 0.0377017 -0.3800330 0.9231513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 94 95 0.142637 -0.031062 0.060621 -0.3762172 -0.3965703 -0.3673471 0.7524950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 95 96 0.010825 0.001340 -0.069348 -0.2940346 0.2566790 -0.8411047 0.3744361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 96 97 -0.114739 -0.055941 0.065922 0.7124820 -0.0837258 0.4126848 0.5612937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 97 98 -0.071776 -0.019525 -0.045773 -0.9106497 0.3727770 0.1565327 0.0851585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 98 99 0.052413 -0.118939 0.119114 -0.5524369 -0.5552274 0.5764514 0.2328944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 99 100 -0.080900 0.025742 -0.000628 -0.3221263 -0.7024493 0.4606268 0.4366035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 100 101 0.083770 -0.120570 -0.020562 -0.2677160 0.6862172 -0.2629088 0.6231477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 101 102 0.083286 -0.114182 0.060637 0.5641312 -0.3215532 -0.3799503 0.6587847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 102 103 -0.000504 0.007181 0.108724 -0.2091197 -0.0167847 0.1802354 0.9609903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 103 104 -0.088971 -0.018907 -0.006868 0.0491623 0.0687399 -0.1085354 0.9904938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 104 105 0.060236 0.133333 0.293147 -0.0380110 0.5825644 -0.4861405 0.6502625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 105 106 -0.354256 -0.024005 0.009101 0.0438570 0.2839610 0.2242139 0.9312201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 106 107 -0.239086 -0.018215 0.163788 0.8207016 0.3273955 -0.4681975 0.0072222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 107 108 -0.030929 -0.016743 0.117758 0.2265680 -0.6371867 0.4044023 0.6157263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 108 109 -0.092879 -0.032561 0.118011 0.5894451 0.2253074 0.5723293 0.5236699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 109 110 -0.085795 -0.045469 -0.098323 -0.2354525 0.2961184 0.8905969 0.2524148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 110 111 -0.151979 -0.058333 -0.169908 0.0558909 0.2871326 0.4685811 0.8335843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 111 112 0.104080 -0.075435 -0.058531 -0.1899522 -0.3963299 0.8847750 0.1549643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 112 113 0.183689 -0.055832 0.122393 0.2452814 -0.1966623 -0.7493955 0.5827241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 113 114 -0.027702 -0.058002 0.203368 0.0470684 -0.6092740 -0.7858821 0.0946524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 114 115 -0.078061 0.000249 0.137569 -0.5572508 0.1268623 -0.7515580 0.3294511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 115 116 -0.139572 -0.009584 0.171670 -0.6124721 0.7104126 -0.2518876 0.2382112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 116 117 0.140134 0.112901 0.083409 0.0886334 0.5531880 -0.7414131 0.3693693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 117 118 -0.164496 -0.148137 -0.101314 0.0448890 0.2682889 -0.7928166 0.5453878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 118 119 0.224492 0.046996 -0.073146 -0.2710966 0.1220891 0.3947320 0.8693604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 119 120 0.110161 -0.086784 -0.098877 0.4888752 0.5891749 -0.3365256 0.5482924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 120 121 -0.219691 -0.092150 -0.027127 0.3732297 -0.3682125 -0.8308825 0.1864226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 121 122 -0.168031 0.106001 -0.119655 -0.1545602 -0.7259306 -0.4369172 0.5081725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 122 123 0.013928 0.109296 0.004957 0.0973269 -0.2991483 -0.7200109 0.6185645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 123 124 0.204527 0.047365 -0.056664 -0.0794571 -0.0377544 -0.7227748 0.6854617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 124 125 -0.058996 0.212045 0.130088 -0.6044375 0.2948745 -0.7110856 0.2050892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 125 126 0.033014 -0.102537 -0.039015 -0.5780382 -0.3568410 -0.7055405 0.2018636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 126 127 0.078814 0.166179 -0.143436 -0.1747469 -0.2308194 0.9447065 0.1539986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 127 128 0.038539 0.065825 0.089647 -0.0960916 -0.1797282 -0.5112545 0.8349150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 128 129 -0.064576 0.037360 0.115941 -0.4420222 0.6650205 -0.4367946 0.4142155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 129 130 -0.031147 -0.007126 -0.022203 0.7888217 -0.0159184 0.4226441 0.4459584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 130 131 -0.060035 0.099804 -0.009607 -0.8152547 0.3974859 -0.2478528 0.3404904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 131 132 -0.181383 0.004242 -0.063353 0.0134915 -0.1519936 -0.8973782 0.4140389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 132 133 -0.042583 -0.011943 -0.017129 -0.7230315 0.0663887 0.2212586 0.6510473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 133 134 0.006027 0.121705 -0.067227 -0.5127664 0.2976829 -0.7823846 0.1906040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 134 135 0.012348 0.056751 -0.027522 0.5830924 -0.1331053 0.1183657 0.7926385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 135 136 -0.154828 0.054456 -0.051943 0.2120428 0.8258314 0.4286534 0.2988254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 136 137 0.119874 -0.029946 0.150685 0.0420983 0.5132497 0.6376327 0.5729110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 137 138 0.080317 -0.156340 -0.054419 0.3212497 0.3419352 0.8715950 0.1421308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 138 139 0.043853 0.096482 -0.061942 -0.0484723 0.0778866 0.1578000 0.9832005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 139 140 -0.120773 -0.065448 -0.039821 0.3605008 0.0841620 0.9141900 0.1649625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 140 141 -0.002172 0.105268 0.063753 -0.4485873 -0.3943450 0.2239682 0.7701297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 141 142 0.019664 0.229696 -0.026570 0.6488318 -0.4098103 0.5238642 0.3696474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 142 143 -0.090310 0.019697 -0.062131 0.6082658 -0.4739413 0.2739915 0.5747356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 143 144 -0.094782 0.008623 -0.042382 -0.4821962 0.1008127 -0.8702415 0.0018181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 144 145 0.178305 -0.091207 0.030132 0.2072686 0.1813922 -0.0023430 0.9613174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 145 146 0.025232 -0.102643 -0.126189 -0.1664844 -0.1121937 -0.8624503 0.4646235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 146 147 0.032783 0.071574 -0.085912 0.6558178 -0.0669795 0.1146612 0.7431484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 147 148 0.126003 -0.063530 -0.006344 -0.3424000 0.6228049 0.6994864 0.0748002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 148 149 0.087838 0.042597 -0.133667 0.1214811 -0.7118414 -0.6698616 0.1726546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 149 150 0.055728 0.052365 -0.061130 -0.6031957 0.3350384 -0.6256349 0.3639852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 150 151 -0.093158 0.093281 0.082697 -0.0816298 -0.4005190 0.5041701 0.7607454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 151 152 -0.219862 0.042125 -0.124630 0.7111412 -0.1936874 0.1698031 0.6541638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 152 153 0.202131 0.022705 -0.203724 -0.1234319 0.5686799 0.7081023 0.3999486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 153 154 0.211010 0.095478 0.065227 -0.5223097 -0.0111234 -0.6693717 0.5282143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 154 155 -0.178625 0.068121 0.158335 0.2296434 -0.1434566 -0.0696047 0.9601246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 155 156 0.069322 0.152894 -0.040106 0.0568977 0.4772711 -0.2231748 0.8480377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 156 157 -0.016971 0.086915 -0.044955 -0.3944463 -0.4343693 0.5010135 0.6361768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 157 158 0.086648 0.130955 -0.008567 0.7446712 -0.3329020 0.3533474 0.4580248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 158 159 -0.030777 -0.021973 -0.136170 -0.6472821 0.6372972 -0.3457191 0.2352796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 159 160 0.083328 0.060895 -0.012756 0.3868428 -0.3802867 0.5681002 0.6188673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 160 161 0.018677 -0.053296 0.026237 -0.4402148 -0.5850763 0.1402680 0.6664994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 161 162 -0.049000 0.210598 0.115530 -0.1354512 0.8859252 -0.0538156 0.4403333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 162 163 0.065618 0.119753 -0.052508 -0.0210892 0.0632671 0.9957198 0.0639884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 163 164 -0.020859 0.015114 -0.210159 -0.5519931 0.4528108 0.4647629 0.5236997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 164 165 0.081275 0.162590 0.063989 0.0893172 -0.4468301 -0.4662564 0.7582680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 165 166 -0.114379 0.148343 0.118450 -0.8516663 0.3821518 -0.3343296 0.1298010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 166 167 0.056597 0.149993 -0.116455 0.1689931 -0.0647423 0.9382458 0.2948638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 167 168 0.212293 0.101497 -0.012233 0.2836311 0.1025874 -0.4397805 0.8459446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 168 169 0.056653 0.078599 0.052362 -0.2757785 -0.7414056 0.4282901 0.4368427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 169 170 0.112335 0.028118 -0.031591 0.1781607 0.6195209 0.6480196 0.4056147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 170 171 0.086028 -0.081452 0.194427 -0.4478688 -0.5428375 -0.5883119 0.3982840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 171 172 -0.010234 0.221979 0.015040 0.4262143 -0.2696417 -0.2163715 0.8359534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 172 173 0.081210 0.097691 0.071554 0.0575218 0.2969641 -0.9318633 0.2003357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 173 174 -0.024292 -0.014220 -0.228144 -0.4989725 0.1154915 0.8481016 0.1356900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 174 175 0.109107 -0.026169 0.083255 -0.4570354 -0.1464759 0.7023850 0.5256603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 175 176 0.016628 -0.007103 0.012405 0.7924774 0.2062441 -0.2803476 0.5008475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 176 177 0.082818 0.223893 -0.100255 -0.4667418 -0.5041807 0.3634769 0.6291569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 177 178 0.125113 0.049966 -0.015206 -0.5141522 0.2743683 -0.7368135 0.3427470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 178 179 -0.192892 0.094759 -0.001046 -0.1209708 0.5946902 -0.0619427 0.7923842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 179 180 -0.109185 -0.052801 0.123304 0.0017934 0.4549330 0.8895738 0.0411245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 180 181 0.207397 -0.042677 -0.083606 -0.2804658 0.1573568 0.2001284 0.9254871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 181 182 -0.034042 0.116494 0.039670 0.0850224 0.0569255 0.9021953 0.4190159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 182 183 -0.151117 -0.071844 0.117543 -0.2145434 0.2614453 0.9145767 0.2217360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 183 184 0.078433 -0.157687 -0.263296 0.2367494 -0.6986539 -0.0485045 0.6734091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 184 185 0.076484 -0.112007 0.090707 -0.5796978 -0.0745252 0.5737023 0.5738137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 185 186 0.044464 -0.062887 -0.208720 -0.5484937 0.3411403 -0.5308026 0.5486589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 186 187 0.111760 0.078179 -0.006018 -0.3401994 0.1362688 0.6535359 0.6622583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 187 188 0.108834 -0.086113 0.072087 0.1514856 0.6636563 -0.6504191 0.3369978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 188 189 -0.061811 0.007562 -0.007311 -0.2886309 0.1655027 -0.2883358 0.8978661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 189 190 -0.043294 0.110394 0.079697 -0.2709440 -0.1402089 0.7807702 0.5452785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 190 191 0.026731 -0.089254 0.017574 0.1688957 0.9592140 -0.2070614 0.0922408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 191 192 -0.063582 0.135396 -0.060666 0.6024250 0.5959687 0.2644580 0.4603991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 192 193 -0.058896 0.173068 0.029790 0.2494548 -0.1360238 0.5509150 0.7847053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 193 194 -0.059896 -0.126563 0.114314 -0.1340172 -0.0938421 0.9494299 0.2679849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 194 195 -0.018527 -0.068452 0.092929 -0.1610678 0.9039400 -0.2715357 0.2884753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 195 196 -0.273171 0.032125 0.107662 -0.1097997 0.3826293 -0.6362492 0.6608523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 196 197 0.055572 -0.137401 -0.107213 0.6494189 -0.5466086 0.5286452 0.0028896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 197 198 -0.028698 -0.134088 -0.018669 0.7193409 0.5474362 0.3969218 0.1591082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 198 199 0.207264 -0.136568 0.026655 0.1453005 -0.8546611 -0.4452528 0.2240359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 199 200 0.140302 0.173610 0.012217 0.2286602 -0.5919468 -0.3718165 0.6775441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 200 201 -0.044224 0.007198 0.034013 -0.3328367 0.1091088 0.8812176 0.3174437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 201 202 -0.007442 -0.146058 0.007663 0.6179664 -0.4562848 0.4156682 0.4869719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 202 203 -0.004176 -0.037273 -0.113583 0.2618709 0.7707632 -0.0648725 0.5771822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 203 204 0.127617 0.007339 0.111285 -0.4022663 0.4751078 0.5244194 0.5808948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 204 205 -0.026360 0.045316 0.121820 -0.4551357 -0.5824331 -0.1758427 0.6501557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 205 206 -0.050408 -0.050433 0.099355 0.1322142 -0.4179912 0.8488163 0.2954890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 206 207 -0.020525 -0.085880 0.072427 0.0566556 0.0531046 -0.9950841 0.0614635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 207 208 -0.072843 -0.014676 -0.161714 0.1699087 -0.6331454 -0.3194945 0.6842377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 208 209 0.029321 -0.134033 -0.042843 -0.1679606 -0.7133360 0.0622383 0.6775451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 209 210 0.031024 0.108677 0.038064 -0.9438150 0.1317659 -0.1673703 0.2526623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 210 211 0.072199 0.144726 -0.019263 0.1170949 -0.1004395 -0.0611277 0.9861359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 211 212 -0.133821 -0.124779 -0.007732 0.2869391 0.3574162 -0.2623949 0.8491575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 212 213 -0.059677 -0.120451 0.059601 -0.3492792 -0.2532934 -0.4159281 0.8005313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 213 214 -0.052737 -0.052817 -0.012735 -0.2518989 0.4336408 0.6725623 0.5442082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 214 215 -0.137886 0.026404 0.068319 0.0217769 0.1379949 0.8981052 0.4170014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 215 216 0.036344 -0.071038 -0.005407 -0.1657099 0.3432125 0.4943205 0.7812763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 216 217 0.017186 -0.140901 0.103582 0.5982690 -0.3341500 0.6102033 0.3975801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 217 218 -0.020994 -0.111747 0.034732 -0.0622273 0.1211824 -0.9905895 0.0132334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 218 219 -0.119228 0.075810 0.099744 -0.1382619 -0.5004433 -0.3805995 0.7652347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 219 220 0.077675 0.082496 -0.077440 0.2261938 -0.4256418 -0.1683300 0.8598433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 220 221 0.145479 -0.238190 0.016913 -0.5152718 -0.1054698 -0.2760468 0.8044683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 221 222 0.082775 0.123673 0.035284 -0.2817457 -0.0603783 -0.3093753 0.9062344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 222 223 -0.135392 0.024738 0.098475 0.6964829 0.0504265 0.2233726 0.6800540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 223 224 -0.059017 -0.017939 0.003480 -0.5013058 0.2783464 0.5855278 0.5730384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 224 225 0.250912 0.016132 -0.191357 0.9505155 0.0070091 -0.0643687 0.3038549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 225 226 0.221404 0.129315 0.085022 -0.5183753 0.0632077 -0.5071845 0.6856061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 226 227 -0.206978 -0.042091 0.143872 0.6590820 -0.0962333 -0.6626051 0.3424974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 227 228 -0.161649 0.007934 0.111808 -0.0450167 -0.0287097 -0.8052152 0.5905741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 228 229 0.070695 -0.019858 0.086624 -0.5392549 -0.0802315 0.8352225 0.0719054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 229 230 0.073562 0.095738 -0.003245 -0.1844729 -0.6439522 0.5804152 0.4630481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 230 231 -0.108362 0.076977 -0.160259 0.3115094 0.6339889 0.4914822 0.5093772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 231 232 0.141784 -0.035526 0.184854 -0.2126641 0.1656390 0.6265211 0.7313064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 232 233 0.115913 -0.090420 -0.030903 -0.2834656 0.1703096 -0.3909839 0.8589374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 233 234 0.116227 0.181591 -0.050418 -0.5082260 0.2175105 0.7637066 0.3333884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 234 235 -0.129196 0.024674 -0.041933 0.7912529 0.1508247 -0.5278808 0.2692815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 235 236 -0.071616 0.024999 0.038433 -0.0080354 -0.3741073 -0.6996462 0.6086661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 236 237 0.153744 -0.013408 -0.057111 0.5246726 0.4437252 0.3489146 0.6372481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 237 238 0.049154 -0.017069 -0.059639 -0.2812646 -0.4750630 -0.2731086 0.7877925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 238 239 -0.011029 -0.125134 -0.139678 -0.0321827 -0.0313052 0.1065292 0.9932954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 239 240 -0.025212 0.008048 0.109972 -0.3603285 0.6199656 -0.6936127 0.0686115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 240 241 0.096000 0.072884 -0.116129 0.4277379 -0.5417322 0.4242237 0.5861748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 241 242 -0.074342 -0.159993 0.039327 0.0144358 0.7656611 0.2061811 0.6091338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 242 243 -0.048708 -0.031394 -0.054013 -0.5798143 -0.6189881 0.0753501 0.5243963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 243 244 0.146940 0.083007 -0.092098 -0.4028114 0.3007488 -0.7870066 0.3576502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 244 245 -0.022559 0.125862 -0.098751 -0.4482729 0.4602903 -0.1347553 0.7543376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 245 246 -0.110191 0.058836 -0.110671 0.3983790 0.1145554 0.5374108 0.7344119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 246 247 0.155331 -0.041666 -0.058915 -0.4263564 -0.5663626 0.3914025 0.5867347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 247 248 0.187667 -0.010495 -0.002273 0.0096165 0.3564984 -0.7130155 0.6036765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 248 249 0.154471 -0.197656 -0.000082 -0.6461536 0.1389294 0.7420213 0.1121989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 249 250 0.007269 0.128268 -0.101382 0.0759990 -0.1843517 0.2137292 0.9563255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 250 251 -0.013064 -0.153919 -0.009992 0.1915733 -0.5837845 0.4114568 0.6732003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 251 252 -0.153921 -0.151082 0.000889 0.4007575 0.4283167 0.7329607 0.3445386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 252 253 0.064503 -0.109094 -0.116164 0.5705014 0.1005499 0.0575138 0.8130868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 253 254 -0.121496 -0.088416 0.019279 -0.7698083 0.0736235 0.6327438 0.0401259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 254 255 -0.000506 -0.004796 -0.044365 0.2792417 -0.3056984 -0.0091677 0.9102135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 255 256 -0.063641 -0.006856 -0.149884 0.1120296 0.2284765 -0.7677721 0.5880255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 256 257 0.065646 0.101522 -0.029267 0.5051729 0.0820309 0.0918438 0.8541873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 257 258 0.040395 -0.172033 0.136414 -0.2750788 0.4091715 0.3061276 0.8143686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 258 259 -0.082505 0.005414 -0.192129 0.1114868 -0.5527292 -0.7214629 0.4019357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 259 260 0.071425 0.122335 -0.136896 -0.2312786 0.8769943 0.3631965 0.2132593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 260 261 0.185162 -0.014874 -0.128118 0.2368014 0.0289032 0.9710481 0.0124624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 261 262 -0.168084 0.018670 0.008873 0.5609211 0.1245765 -0.6886691 0.4422478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 262 263 -0.084916 -0.118766 0.005357 0.0064900 -0.7779844 -0.6281134 0.0131064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 263 264 0.095567 -0.024034 -0.095256 0.6022962 -0.2824905 -0.5585570 0.4954317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 264 265 0.076735 0.036123 0.075787 -0.3457720 0.0408299 0.7299182 0.5882126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 265 266 0.012999 -0.069721 -0.074994 -0.1248433 0.5175563 0.6362424 0.5583415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 266 267 0.020663 -0.036889 0.052599 0.5119593 -0.1295280 0.7294299 0.4348014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 267 268 -0.146862 -0.080030 0.084896 -0.0709119 0.4137074 0.9072598 0.0264071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 268 269 0.067033 -0.000484 -0.062489 0.6448442 -0.3324256 0.4057873 0.5558829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 269 270 -0.060674 0.025301 -0.017007 -0.5789294 -0.3040003 0.6440088 0.3970859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 270 271 0.135205 0.067390 -0.150675 0.6114267 -0.4396448 0.4736468 0.4566492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 271 272 0.020394 0.052028 -0.005278 -0.6133487 0.0091976 -0.7810839 0.1167340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 272 273 0.050325 0.015078 0.084325 0.5384201 -0.0020911 0.7264133 0.4271103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 273 274 -0.143644 -0.181436 -0.062733 0.7768926 0.2889600 0.3091327 0.4662370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 274 275 0.074876 0.044667 0.050429 -0.2483699 0.1843112 -0.7700051 0.5580627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 275 276 -0.122116 -0.159475 -0.078114 0.5392734 -0.5030116 0.2448446 0.6294559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 276 277 0.061765 -0.015381 0.073336 -0.1052317 0.2479011 -0.5746618 0.7728099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 277 278 0.068775 0.097138 -0.025237 -0.6072076 -0.4058421 0.3194524 0.6037726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 278 279 -0.008160 -0.119607 0.045341 0.5042404 0.0021659 -0.2201670 0.8350230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 279 280 -0.246296 -0.176669 0.183465 0.1768991 0.6088455 0.2927418 0.7157627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 280 281 -0.007037 0.129657 -0.047237 -0.2381986 -0.4021214 -0.1005238 0.8783250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 281 282 0.148628 -0.054268 -0.120037 -0.3511406 0.2602184 -0.0949549 0.8944106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 282 283 0.068093 0.146472 -0.135959 0.2034738 -0.2697024 -0.7158979 0.6110231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 283 284 0.089166 -0.030568 0.035756 -0.6123883 0.0379345 -0.6547578 0.4413997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 284 285 -0.009269 0.019528 0.119916 -0.0258970 0.5788994 -0.7949753 0.1794969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 285 286 -0.027651 -0.011813 0.004891 0.1616986 -0.5248413 -0.7707450 0.3230284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 286 287 0.166276 0.050592 0.118535 0.2680146 -0.3918105 -0.8373264 0.2711775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 287 288 -0.030030 0.141507 -0.027460 0.2206896 -0.9343061 0.1103050 0.2572956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 288 289 -0.073439 0.053993 -0.011361 -0.3664630 -0.0345430 0.5497913 0.7498274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 289 290 0.159777 -0.034846 0.051463 0.9566017 0.1582670 0.0792103 0.2314960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 290 291 -0.029700 -0.120294 0.121024 -0.8407337 -0.0901511 0.1627314 0.5084860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 291 292 -0.113881 -0.218631 0.122019 -0.5140820 0.7140110 -0.4027985 0.2523121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 292 293 -0.011504 -0.084038 -0.067658 0.1978548 -0.0353942 0.8677001 0.4546398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 293 294 -0.245173 0.110394 -0.081059 -0.1637838 -0.1590885 0.6755587 0.7010608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 294 295 -0.029084 0.015683 -0.037690 0.4144933 -0.3228542 0.8466895 0.0841265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 295 296 0.184611 -0.105904 0.108374 0.4608986 -0.3351335 0.7796536 0.2596119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 296 297 -0.022830 -0.012026 0.087856 -0.3771155 -0.3154872 -0.5417776 0.6817101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 297 298 -0.035892 0.066151 0.018348 -0.6042857 -0.0468734 -0.7857586 0.1233901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 298 299 -0.219531 0.090580 0.079187 -0.3581271 0.0627752 0.7630304 0.5344052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 299 300 0.189704 0.044671 0.043259 -0.1921458 -0.8704285 0.0678873 0.4481356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 300 301 -0.076216 -0.090539 0.098304 0.1045910 0.8542492 0.1509353 0.4863512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 301 302 -0.127236 -0.081430 0.007939 0.2641649 0.4687667 -0.8310709 0.1406975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 302 303 -0.013994 -0.094328 -0.099190 0.6897563 0.3777590 0.3388410 0.5164506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 303 304 0.040156 0.165787 0.130466 -0.7071332 -0.0848252 0.6376503 0.2935463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 304 305 0.052941 -0.162288 -0.068449 0.8208655 0.1088196 -0.5396634 0.1519923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 305 306 0.214555 0.053359 -0.003185 0.0741537 -0.4596832 -0.1970265 0.8627706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 306 307 -0.114660 -0.085569 0.245736 -0.7373724 -0.3802440 -0.4657751 0.3078148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 307 308 -0.007452 -0.070020 -0.032209 0.7621421 0.5740245 -0.1982270 0.2243690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 308 309 -0.060868 -0.076854 0.073858 -0.5721380 -0.2926454 0.7661195 0.0088137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 309 310 -0.108095 -0.023194 -0.041225 0.3971734 -0.4183248 0.0744440 0.8134591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 310 311 0.133192 -0.207661 0.001515 0.0140780 0.0021181 0.7032131 0.7108366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 311 312 0.012625 -0.039387 0.106863 0.2980375 0.1250569 -0.8079128 0.4927589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 312 313 0.184216 0.146950 -0.133604 0.4291493 0.3520710 0.7678846 0.3197344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 313 314 0.061673 -0.032545 -0.103194 0.0059221 0.0900716 0.6111136 0.7863792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 314 315 -0.017472 0.148791 -0.031956 0.3531641 0.4112250 0.4557312 0.7060299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 315 316 0.062457 -0.046787 0.248929 0.2257303 0.1180408 -0.9021412 0.3482147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 316 317 -0.262571 -0.054407 0.075348 -0.7633286 0.3023927 0.5673611 0.0631620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 317 318 -0.004655 0.080875 -0.092948 -0.3027855 -0.1524118 0.8547953 0.3929586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 318 319 0.201218 0.057770 -0.032452 0.6278476 -0.4813616 0.6115822 0.0080942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 319 320 0.072105 0.133131 0.120956 0.4112002 -0.6620589 0.6190944 0.0965120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 320 321 0.103391 -0.075051 -0.060967 0.1076940 0.1080435 0.3173911 0.9359442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 321 322 -0.022925 -0.050655 0.085254 0.2760992 0.8277166 -0.4787825 0.0970655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 322 323 0.081693 -0.055501 -0.022640 0.2874683 -0.0887005 0.1970760 0.9330891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 323 324 -0.021531 -0.003537 0.057486 0.3098001 -0.0786198 0.4919307 0.8098438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 324 325 0.117458 0.191496 -0.072625 0.1145189 -0.1191472 0.3357680 0.9273345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 325 326 -0.047939 -0.032678 0.076333 0.3430391 0.2969290 0.4705452 0.7567989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 326 327 0.074287 -0.166752 -0.120903 -0.0466076 -0.4841073 -0.8464157 0.2169062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 327 328 -0.101856 0.082587 -0.079261 -0.5263946 -0.2585965 -0.5652783 0.5800836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 328 329 -0.071831 0.029422 0.023360 -0.0185343 -0.4486535 0.8882334 0.0969941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 329 330 0.052295 0.120191 -0.160345 -0.1714547 -0.0247965 0.7367897 0.6535514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 330 331 0.065771 0.085314 0.006532 0.6571713 0.0467045 -0.0498408 0.7506401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 331 332 -0.002080 -0.048956 -0.038609 0.0693243 -0.4264237 -0.6584695 0.6162588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 332 333 0.035300 0.098855 -0.101748 0.4508399 0.3053783 0.0959700 0.8332330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 333 334 -0.019726 -0.092244 -0.036538 0.0985880 -0.7971339 0.3818048 0.4572560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 334 335 0.107351 -0.014618 0.059708 0.4579971 -0.4601646 -0.7593686 0.0429714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 335 336 0.073780 0.039632 -0.012361 0.5224169 -0.1530100 0.4669344 0.6968793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 336 337 -0.058423 0.143804 0.120616 -0.6026957 -0.0567603 0.7212345 0.3366854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 337 338 -0.208201 0.087256 -0.024620 -0.3094288 0.3368024 0.0298401 0.8887787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 338 339 -0.088938 -0.017299 0.082832 0.2082416 -0.2869489 0.8801808 0.3155591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 339 340 -0.062180 -0.114425 -0.152883 -0.3374072 -0.2873727 -0.5482692 0.7092067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 340 341 -0.093410 -0.066523 -0.148268 0.0397385 0.2396403 0.0988186 0.9650017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 341 342 -0.004250 -0.343735 -0.211900 -0.3604902 0.1670287 -0.8415772 0.3659180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 342 343 -0.049554 0.033940 -0.016328 0.1422494 0.3600259 -0.7316727 0.5610718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 343 344 0.145939 0.038220 0.011979 -0.4493015 -0.0023868 -0.8876390 0.1010915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 344 345 -0.024701 0.026259 -0.111874 -0.4612602 -0.2814693 -0.6652020 0.5152867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 345 346 -0.154186 0.012741 0.017602 0.4874646 0.4419467 0.4819829 0.5785792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 346 347 -0.012511 0.034168 -0.103471 -0.5608456 0.2015355 0.2055608 0.7762606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 347 348 0.015932 0.240062 -0.007817 0.7233912 0.2945350 0.5149870 0.3531894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 348 349 0.043940 0.101374 0.115453 -0.7236715 -0.4204856 0.5343164 0.1183106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 349 350 -0.047333 0.216944 -0.058991 0.1627752 0.1761354 -0.7233726 0.6474663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 350 351 -0.035335 -0.008680 -0.091845 0.1937907 0.0715942 -0.2746159 0.9390982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 351 352 -0.054014 -0.021973 -0.055874 -0.6574201 0.3309952 0.6657784 0.1223931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 352 353 0.140431 -0.037306 0.035221 0.7242867 0.6275383 -0.0708274 0.2767452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 353 354 0.078903 0.014512 0.117576 0.9433804 0.0699265 -0.2822904 0.1595490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 354 355 0.125250 -0.054090 -0.105253 -0.8031584 0.5339243 0.2618249 0.0361832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 355 356 -0.023940 -0.023019 0.070938 0.5983364 -0.7127151 -0.2049999 0.3033246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 356 357 0.026272 0.015099 0.053984 -0.6608368 -0.6645680 -0.1939295 0.2898888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 357 358 -0.152511 0.130882 0.169171 0.0247562 0.1276550 0.7008332 0.7013731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 358 359 0.112821 0.118021 0.025097 -0.6721736 -0.1462771 0.6521178 0.3186347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 359 360 0.039847 -0.138998 -0.073333 0.0802309 -0.7625553 -0.3189849 0.5570646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 360 361 -0.040400 -0.033449 -0.134705 0.0714513 0.3498022 -0.8892272 0.2860213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 361 362 0.085239 -0.054908 0.174182 0.2970057 0.5570625 -0.6328936 0.4482351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 362 363 0.157788 0.136720 0.065996 0.6687132 -0.3389969 0.6270145 0.2115576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 363 364 0.064782 -0.075802 -0.160151 -0.3735854 0.3255614 -0.7875978 0.3662423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 364 365 -0.011345 -0.055014 -0.079616 0.1460062 0.0363352 0.4662779 0.8717493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 365 366 0.153797 0.073343 -0.048775 0.3306094 -0.3074981 0.3887117 0.8031473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 366 367 -0.203300 -0.032001 -0.090674 0.0119256 0.3578682 0.2200657 0.9073914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 367 368 -0.039548 0.088039 -0.050269 -0.0536258 -0.5398059 -0.0464033 0.8387971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 368 369 -0.016016 0.066299 -0.064396 -0.7744577 0.2554799 -0.4210448 0.3970724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 369 370 -0.185655 0.089309 0.045763 0.1980557 -0.1821418 -0.0132754 0.9630276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 370 371 -0.103819 -0.066809 0.082670 0.0538630 -0.0723853 0.7897272 0.6067867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 371 372 0.194471 -0.005507 -0.015493 -0.1967737 -0.5717912 0.1373409 0.7845205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 372 373 0.046660 0.133163 0.038446 0.1346574 -0.7393897 0.5068556 0.4222175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 373 374 0.093306 -0.187731 0.052977 -0.5453100 -0.4269658 0.6581327 0.2952941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 374 375 0.050375 0.045841 -0.238403 0.0662010 -0.4034938 0.0968024 0.9074357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 375 376 -0.112345 -0.011651 0.013464 0.2843122 -0.0297473 0.3925617 0.8741722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 376 377 -0.080233 0.046777 -0.048501 -0.3320824 0.5450236 0.4811243 0.6009908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 377 378 -0.036409 -0.025971 0.018975 0.1543187 -0.4484390 0.8670629 0.1526112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 378 379 -0.035288 0.031210 0.024436 -0.2083639 0.5267249 0.3841626 0.7290847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 379 380 -0.020246 0.074063 -0.121768 0.1548761 -0.0503219 0.5631831 0.8101271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 380 381 0.043346 -0.061298 0.091441 0.5579339 -0.6057337 -0.5424194 0.1660651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 381 382 -0.149102 0.098235 0.142618 -0.6299941 0.2140458 0.3839238 0.6402300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 382 383 -0.045795 -0.048194 -0.071169 0.0389415 0.2610075 0.8963797 0.3561771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 383 384 0.076242 -0.172442 0.053871 0.4988294 -0.6549370 -0.5673712 0.0177938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 384 385 -0.025579 -0.032431 -0.039043 -0.0570269 -0.4140271 -0.8806634 0.2230727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 385 386 -0.035388 -0.192436 0.038668 0.4739527 -0.4798284 0.2836740 0.6816617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 386 387 -0.074039 -0.098667 0.088892 0.7731588 -0.1254834 0.6048251 0.1437564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 387 388 0.121134 0.010079 0.211253 -0.0635875 -0.4607435 -0.8801189 0.0951986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 388 389 -0.051799 -0.056361 -0.062566 -0.1258776 0.1001016 -0.8998268 0.4055196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 389 390 0.220906 0.008181 -0.051997 0.2170766 -0.1159866 0.0513463 0.9678783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 390 391 0.115056 0.032076 0.007921 -0.4806307 -0.1165179 0.6133670 0.6157911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 391 392 -0.201160 0.003705 -0.189630 0.7597505 0.2847781 -0.5537224 0.1872754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 392 393 0.016912 0.104753 0.089637 0.0789971 -0.3741283 0.7788702 0.4971405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 393 394 -0.014396 -0.110600 -0.003786 -0.1105921 0.3735944 0.8817451 0.2659363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 394 395 -0.042932 0.033129 0.135113 0.0464906 0.1554283 -0.9782712 0.1290978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 395 396 -0.089408 0.041693 -0.012552 0.6142718 -0.4129115 0.6600316 0.1285788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 396 397 0.045831 -0.078408 -0.066568 0.3110935 -0.5538427 0.1650988 0.7544677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 397 398 -0.024321 0.113929 0.150432 0.9960811 -0.0125046 0.0838009 0.0253667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 398 399 -0.002024 -0.073031 0.024916 0.2280393 0.3883009 0.0593925 0.8908945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 399 400 -0.060934 0.032980 0.048427 0.1218787 0.3434802 0.5281258 0.7669747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 400 401 -0.038373 -0.136138 0.004647 0.1090590 0.6280827 0.5173550 0.5709308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 401 402 0.050401 0.171809 -0.002330 -0.2445193 -0.0207112 -0.2614741 0.9334949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 402 403 -0.036653 0.059419 0.187720 -0.0771817 -0.5430253 0.7693605 0.3274918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 403 404 0.217698 -0.059529 -0.139606 -0.1831276 -0.3533244 -0.8090124 0.4325796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 404 405 -0.066343 0.013573 0.023795 0.0586319 -0.0617068 -0.9559965 0.2807585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 405 406 0.154495 -0.432889 0.084847 0.1615216 -0.0733071 -0.6067327 0.7748627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 406 407 -0.003084 0.039470 -0.019756 0.4990078 0.0776155 0.5335094 0.6784798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 407 408 -0.002567 0.003045 0.019564 -0.5682674 0.1521287 0.7003207 0.4043264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 408 409 0.173059 -0.016124 0.092695 0.1645058 -0.3618074 -0.0696700 0.9149750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 409 410 0.112044 0.045496 0.001232 -0.1688378 -0.2485130 -0.9512730 0.0693885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 410 411 0.003737 0.080027 -0.004335 -0.2724714 -0.3472974 -0.8923298 0.0942938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 411 412 0.030662 0.038409 0.197588 0.5731858 0.1753109 -0.0055449 0.8004332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 412 413 0.056320 -0.011198 -0.035193 -0.5327770 -0.1087396 -0.1124703 0.8316699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 413 414 -0.060611 0.165843 0.048842 -0.6871456 -0.1626658 0.5599049 0.4334482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 414 415 0.112386 -0.249087 0.271752 0.2942367 0.8324095 -0.3982138 0.2488872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 415 416 -0.018524 -0.151882 -0.038075 0.6033338 -0.3922319 0.6735600 0.1686991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 416 417 0.123525 -0.021083 0.070958 -0.5853017 0.2534300 0.6004806 0.4823052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 417 418 0.065281 0.012628 0.071412 0.4475383 -0.3725409 0.3692267 0.7242889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 418 419 0.066861 0.172110 -0.085017 -0.5192087 0.5245370 0.2995893 0.6045904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 419 420 0.182957 -0.121140 -0.067490 0.0841935 0.3850575 0.9025885 0.1731364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 420 421 -0.033003 0.006873 0.075883 -0.2487627 -0.7258467 -0.5350891 0.3534732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 421 422 0.091690 -0.133643 0.166075 0.1942552 0.5290005 0.4889205 0.6658679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 422 423 -0.016087 0.071277 0.091158 -0.4325748 0.6731843 0.5342650 0.2725121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 423 424 -0.048785 -0.026394 -0.176262 0.0654750 -0.8524340 0.1571499 0.4943412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 424 425 -0.019040 -0.017454 0.131838 0.2123306 -0.6410914 0.5499451 0.4914040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 425 426 0.000252 0.080857 -0.099227 -0.0654154 -0.8881142 0.4491025 0.0726703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 426 427 0.023329 0.045646 0.091061 0.6436090 0.2038374 -0.6420396 0.3633222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 427 428 -0.110813 0.125652 -0.210859 -0.4432953 -0.3501455 0.6071144 0.5588377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 428 429 0.090126 0.188095 -0.228897 0.3454635 0.0438303 0.5968927 0.7228091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 429 430 0.014523 0.203164 0.070164 0.2983814 -0.0412509 0.9108043 0.2823163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 430 431 -0.100041 0.004895 0.085544 0.1714610 0.2063667 0.6304719 0.7283674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 431 432 0.148344 0.080412 0.057574 -0.1995911 -0.1531189 -0.6333262 0.7318578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 432 433 -0.125361 0.053548 0.049614 0.2498349 0.2494547 0.1530924 0.9229938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 433 434 -0.113217 0.107863 -0.023541 0.3608845 -0.3582468 0.7067169 0.4919074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 434 435 0.008271 -0.055540 -0.004901 0.2860147 0.2247544 0.9305570 0.0417709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 435 436 -0.082499 0.072319 -0.033598 0.0897039 -0.4440746 0.4861136 0.7472915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 436 437 0.092809 -0.085017 -0.027916 -0.0164318 0.3208430 0.1571333 0.9338623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 437 438 -0.190545 -0.135126 -0.046805 0.1376366 0.5169119 -0.3991443 0.7446758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 438 439 0.136897 -0.078484 -0.056797 -0.5257700 0.6754932 0.5154365 0.0400009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 439 440 0.060933 -0.039444 -0.083078 -0.5109359 0.2746869 0.6097515 0.5400877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 440 441 -0.064736 0.081532 -0.055474 0.0196391 -0.3739142 0.6960669 0.6126120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 441 442 -0.168212 0.265050 0.031697 -0.5986737 0.3413899 -0.7075060 0.1564545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 442 443 -0.034798 0.073820 -0.160836 -0.5962320 0.2987711 -0.4033693 0.6265273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 443 444 -0.093820 0.084925 0.152317 0.4782893 -0.2277762 0.3679925 0.7641590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 444 445 0.033882 0.035407 -0.053844 0.0771357 0.2238801 0.3974223 0.8865570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 445 446 0.095141 0.049244 -0.118502 0.7760591 0.2742790 -0.5236302 0.2198059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 446 447 0.114179 0.042961 -0.043675 -0.8047810 -0.5312113 0.1499731 0.2182892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 447 448 -0.040644 0.127299 0.037138 0.4795611 -0.2615837 0.7556467 0.3613769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 448 449 -0.049061 0.015156 -0.081717 0.0465877 0.0763195 0.4466256 0.8902418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 449 450 -0.263650 -0.211412 0.021610 -0.3270514 -0.4513316 0.4988769 0.6636708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 450 451 -0.186922 0.002197 0.027000 0.7424654 0.0731563 -0.2588516 0.6135056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 451 452 -0.026091 0.007360 0.131279 0.0318826 0.8059750 0.0135276 0.5909355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 452 453 0.081321 -0.011652 0.021211 -0.4222871 -0.5791132 -0.6807888 0.1510899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 453 454 0.122280 -0.072614 -0.040124 -0.0162454 -0.4705645 0.8733739 0.1245918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 454 455 0.127949 -0.114365 -0.061309 -0.3897408 -0.3779877 0.0818079 0.8357840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 455 456 0.066092 -0.053747 0.026686 0.4867271 0.2564210 -0.5800043 0.6007829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 456 457 -0.152307 0.005535 -0.064321 0.6304707 -0.4331217 -0.1506139 0.6262808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 457 458 -0.068115 -0.233968 -0.096691 0.0480624 -0.4526602 -0.2184975 0.8631614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 458 459 -0.059774 -0.216906 0.121368 -0.4464211 0.4230668 0.5656815 0.5492969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 459 460 0.029228 -0.035951 0.025264 -0.0307516 0.4361492 0.0592861 0.8973925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 460 461 -0.144430 0.209354 0.040114 0.0689495 0.0615920 -0.8373362 0.5388140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 461 462 0.026737 0.064917 0.121720 0.6618971 -0.3108335 0.5973235 0.3293622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 462 463 -0.027598 0.192234 0.228303 -0.1014362 -0.0637122 -0.9730798 0.1968936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 463 464 0.090687 0.080599 0.130027 0.3850375 0.1550946 -0.5553453 0.7206132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 464 465 0.004262 0.087162 0.136912 -0.6112830 -0.5251938 0.3377530 0.4862381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 465 466 -0.073706 -0.023072 0.048129 0.3455288 -0.1954123 0.3369066 0.8537669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 466 467 0.117695 0.182999 -0.024641 0.1423720 0.4071168 -0.8180434 0.3805142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 467 468 -0.049739 -0.111620 0.154446 0.9050671 0.1998653 -0.3678649 0.0747177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 468 469 -0.105339 -0.090163 -0.115491 0.4093715 -0.3352312 -0.8482773 0.0214626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 469 470 0.119726 -0.067537 -0.080362 0.2091498 0.5064901 0.0099836 0.8364356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 470 471 0.101248 -0.100525 -0.274142 -0.5488384 -0.1516472 0.8080059 0.1513472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 471 472 0.013900 -0.025139 -0.086398 0.0742379 0.2073951 0.7962858 0.5633870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 472 473 0.036918 -0.002635 -0.094136 -0.2987022 -0.4809230 0.1801893 0.8043767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 473 474 -0.072762 -0.051028 -0.166981 0.1174530 0.5825301 -0.4004569 0.6974939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 474 475 -0.000320 0.203927 -0.018297 -0.4873629 0.2091899 0.8475220 0.0205788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 475 476 0.130079 0.002613 0.135587 -0.7051038 -0.2638500 -0.1740890 0.6347479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 476 477 0.181745 -0.172862 0.019160 0.3155002 0.0637961 0.9378352 0.1298259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 477 478 -0.107541 -0.051060 -0.115583 -0.4206779 -0.2862073 -0.6609565 0.5515904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 478 479 -0.060691 0.024762 -0.068476 0.3843982 0.7877573 -0.4784269 0.0527650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 479 480 0.186912 0.089365 -0.078395 -0.1456573 -0.8898146 0.4153387 0.1204483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 480 481 0.187884 -0.109434 0.056538 -0.1160509 -0.2597089 0.4464065 0.8484131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 481 482 0.103733 0.001575 -0.147068 0.0777336 0.0521495 -0.5751235 0.8126936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 482 483 0.245155 -0.036623 -0.028992 0.1600944 0.2113899 0.2391074 0.9340834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 483 484 0.103504 0.103312 -0.034560 -0.0875686 0.6253017 -0.2601397 0.7305182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 484 485 -0.030836 -0.118852 0.038199 0.4436023 -0.1604313 0.8815919 0.0165685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 485 486 -0.008715 -0.019401 0.055540 -0.3581586 0.4009770 0.8320345 0.1365961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 486 487 -0.158283 0.039028 0.055530 0.6764391 0.4280038 -0.0943229 0.5919004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 487 488 0.057604 -0.044864 -0.056573 0.1116357 0.0100618 0.5552240 0.8241131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 488 489 -0.055711 -0.051312 0.015378 0.2024091 -0.3141411 -0.3638692 0.8531970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 489 490 -0.027116 -0.053000 -0.016166 0.5163852 -0.3710572 -0.1144490 0.7632590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 490 491 -0.006261 0.034143 -0.063099 -0.7850545 0.1428468 -0.2074753 0.5658960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 491 492 0.031359 0.003043 0.035010 0.7530589 -0.4904733 -0.3552317 0.2571939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 492 493 -0.111003 0.179225 0.031104 -0.5390954 -0.5608327 -0.5544405 0.2957001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 493 494 0.041223 0.142429 -0.142336 -0.1078959 -0.4701795 0.8654416 0.1352795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 494 495 0.098473 -0.024850 -0.072313 0.3056710 0.4403377 -0.0501158 0.8427077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 495 496 0.036175 0.028631 0.113630 0.0206607 0.5084391 -0.7777092 0.3690950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 496 497 0.080157 0.075275 0.248647 0.7066806 0.0233105 0.6780994 0.2005998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 497 498 0.104982 0.148839 -0.115740 -0.8122958 0.2700181 -0.4452808 0.2626611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 498 499 0.220509 0.023362 0.102915 0.4999390 -0.1197533 0.7722018 0.3733960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 499 500 -0.188850 0.092150 0.070979 0.2591374 -0.1637020 0.2578981 0.9162631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 500 501 -0.014209 -0.154881 0.132423 -0.7815216 -0.2545390 -0.0055377 0.5695641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 501 502 0.058244 -0.145916 0.029609 0.7969183 0.4478528 0.3919434 0.1035836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 502 503 0.075433 0.092858 -0.081468 -0.7130172 -0.2053960 0.1786904 0.6461337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 503 504 0.085439 0.060064 -0.003344 -0.4042664 0.6104221 -0.4635566 0.4990679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 504 505 -0.128456 -0.092525 -0.047211 0.7541385 -0.3938350 0.4732740 0.2284313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 505 506 0.020422 0.145539 0.195653 0.4653637 0.5357845 0.4295356 0.5584539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 506 507 0.010702 -0.103798 0.111024 -0.7057132 0.1704388 -0.5480143 0.4154514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 507 508 0.171827 0.078301 0.105531 -0.4435886 -0.1659017 0.8619339 0.1810406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 508 509 -0.189069 0.126400 -0.049604 -0.4894839 -0.4170270 0.7114010 0.2835535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 509 510 -0.026063 -0.027955 -0.009300 -0.0077442 -0.2045979 -0.5336835 0.8205252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 510 511 0.027372 0.052041 0.120412 0.1155024 -0.2545864 0.9526413 0.1196644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 511 512 0.207170 -0.008450 0.037356 -0.3857987 -0.1634583 0.8742456 0.2452251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 512 513 -0.015634 0.164768 0.160946 -0.0402953 -0.0547742 0.7077686 0.7031641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 513 514 -0.065102 0.175418 0.154613 -0.3918761 0.3817891 -0.6895684 0.4745162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 514 515 0.061700 0.010312 -0.001658 0.3072419 -0.2173544 0.2168239 0.9007479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 515 516 0.142655 0.196721 0.215298 -0.3194825 0.3772031 0.0762762 0.8659277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 516 517 -0.165161 0.053652 0.069916 -0.2868404 -0.2461957 0.9232044 0.0693107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 517 518 -0.099975 -0.096120 0.282235 -0.3809507 -0.5390724 0.4509940 0.6007345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 518 519 -0.055117 -0.062260 -0.093704 -0.6268758 0.6879067 -0.3311763 0.1553487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 519 520 0.002011 -0.041393 -0.047284 0.8058454 -0.3208780 0.4654164 0.1761762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 520 521 0.063549 -0.028766 -0.049377 -0.0903454 0.1714534 -0.9679044 0.1600076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 521 522 -0.178608 -0.021350 0.069174 -0.3705954 -0.7391797 0.2766691 0.4896188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 522 523 0.258720 0.095175 0.021284 -0.0076152 0.5664213 0.4781019 0.6712134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 523 524 0.037348 -0.138342 0.032762 0.2981403 -0.3193602 0.4311323 0.7894596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 524 525 -0.015467 -0.070610 0.064858 -0.1647270 -0.1700383 -0.0228967 0.9713021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 525 526 0.112150 0.034962 0.033855 0.0412188 -0.5878075 -0.5452872 0.5961923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 526 527 0.095182 -0.066841 -0.101234 -0.2632290 0.8476272 0.1981642 0.4158961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 527 528 0.108130 0.118116 -0.027015 -0.1399605 -0.0403278 -0.3817421 0.9127200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 528 529 -0.130915 0.025505 0.060873 -0.3995872 -0.3002580 -0.2456829 0.8305511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 529 530 0.090039 0.005547 0.058713 0.9368350 -0.0858147 0.0669427 0.3324073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 530 531 0.171705 0.002697 -0.052922 -0.8247409 -0.2637448 -0.0313814 0.4992558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 531 532 0.104416 0.025222 0.037182 0.5466265 0.5449050 0.5952686 0.2234576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 532 533 0.063574 0.183929 -0.004526 0.0211693 -0.4339391 -0.8971204 0.0801477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 533 534 -0.047315 -0.109977 -0.007335 0.1205489 -0.1788856 -0.5871762 0.7801871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 534 535 -0.085542 0.109916 0.044598 -0.3898528 0.3236806 0.0527342 0.8605026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 535 536 -0.073337 0.047097 -0.081480 0.4659278 0.0765795 0.7494348 0.4641060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 536 537 0.058849 0.230730 -0.035246 -0.0243750 -0.4059676 -0.5253887 0.7473706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 537 538 0.071269 -0.201145 0.099609 -0.0829166 0.2217578 -0.3978925 0.8863576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 538 539 -0.058449 -0.006043 -0.069298 0.3646386 -0.1813893 -0.6902675 0.5980530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 539 540 0.147540 -0.238039 0.065100 -0.0433633 0.0522007 -0.8872704 0.4562302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 540 541 -0.093365 -0.056555 -0.041887 0.5445422 0.3647378 -0.2495821 0.7128456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 541 542 -0.009724 -0.113391 -0.062073 0.0376365 0.1847890 -0.9637650 0.1886623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 542 543 0.022812 0.134930 -0.082951 0.1752891 -0.3734557 -0.1699247 0.8949470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 543 544 0.178317 0.036482 -0.026423 -0.1064493 0.1076782 0.9796566 0.1317080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 544 545 0.107747 0.274145 -0.056812 -0.4781273 -0.2321006 -0.5259508 0.6640025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 545 546 -0.174356 0.231704 -0.095371 -0.2102400 -0.1186191 0.0413258 0.9695467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 546 547 0.006417 0.220973 -0.004541 0.5536966 -0.3129046 -0.6641491 0.3929590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 547 548 -0.055683 0.153155 0.044404 -0.0675385 -0.3080271 -0.7807238 0.5394704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 548 549 0.102503 -0.093472 -0.074520 -0.5687779 -0.0625679 0.2594468 0.7779873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 549 550 0.010721 0.009970 0.033980 -0.3520223 0.1051605 0.7170779 0.5923013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 550 551 -0.113757 -0.006981 -0.115326 0.0400759 -0.3641590 0.6793673 0.6358004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 551 552 -0.095145 -0.184887 -0.075608 0.6375735 0.3502791 0.5962762 0.3394986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 552 553 -0.108502 -0.076132 0.019423 0.1098298 0.4962677 0.8331549 0.2179651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 553 554 0.067867 0.091267 -0.101293 0.0804113 0.0129710 -0.8211409 0.5648836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 554 555 0.089829 0.229673 -0.035544 0.1976456 -0.6380789 0.0545242 0.7421715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 555 556 -0.054701 -0.177574 -0.078037 0.5119951 0.1200534 0.6306516 0.5707248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 556 557 -0.020634 0.013872 -0.122555 -0.4195736 -0.3870477 0.5973384 0.5633284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 557 558 -0.125061 0.272826 -0.000277 0.6475613 0.6054526 -0.4202375 0.1936282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 558 559 -0.030287 0.021975 0.029861 0.6202370 -0.3727828 0.1401942 0.6757844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 559 560 0.000617 -0.087668 0.034792 -0.8679665 -0.4749799 -0.1361358 0.0499536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 560 561 0.137168 -0.160771 -0.015584 0.5921583 -0.3838379 0.3281314 0.6279705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 561 562 0.066225 -0.044256 0.005453 0.1793782 -0.2112898 0.9377060 0.2094937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 562 563 0.153338 0.015698 -0.040756 -0.5554803 -0.2067112 0.5132049 0.6207518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 563 564 0.025903 0.007670 0.011250 0.6032885 0.0422149 0.2078850 0.7687944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 564 565 0.108897 -0.024597 -0.057385 -0.6209337 0.3983863 0.5787651 0.3475065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 565 566 -0.201644 -0.332395 -0.088895 0.8038464 0.2972614 -0.5081480 0.0851596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 566 567 0.040260 0.203102 -0.203478 0.8639903 -0.2790169 -0.1886888 0.3742550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 567 568 -0.264772 -0.121088 0.142478 -0.5815273 -0.3773412 -0.6576193 0.2949176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 568 569 -0.055216 -0.049104 -0.169011 -0.1628678 0.3770714 0.6776096 0.6100299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 569 570 -0.099733 0.170222 -0.032265 0.1351805 -0.6111012 -0.4368350 0.6461089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 570 571 -0.085099 -0.157012 -0.132672 0.0200793 -0.4178830 -0.9078172 0.0289575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 571 572 -0.066316 -0.086664 -0.157735 0.0233321 -0.0597325 0.7684993 0.6366289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 572 573 -0.036866 0.235051 -0.290003 -0.4095406 0.5176160 -0.5644699 0.4957055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 573 574 -0.009938 -0.008205 0.054072 -0.1883820 -0.7235700 0.0072626 0.6640075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 574 575 0.121042 0.165703 0.173964 -0.1298486 -0.2736978 -0.8672138 0.3951823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 575 576 0.040932 0.034945 -0.108775 -0.5127070 -0.5134126 -0.0306694 0.6874579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 576 577 -0.086981 -0.152481 -0.107425 0.3877000 0.2372395 0.8435216 0.2861423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 577 578 0.034084 0.005679 -0.106462 -0.2104055 -0.5187380 0.6229758 0.5463897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 578 579 0.146361 -0.079147 0.018441 0.6251421 0.2533247 0.3984648 0.6214899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 579 580 0.069805 -0.216772 0.046619 -0.6568096 -0.2277889 -0.2332761 0.6799232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 580 581 -0.060745 0.120642 -0.012751 0.3566051 -0.1176861 -0.5599770 0.7385178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 581 582 0.124295 -0.037724 0.128982 -0.2087985 -0.2874061 0.9125750 0.2025038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 582 583 0.100868 -0.175761 -0.056902 0.3796459 -0.8252384 0.2132272 0.3597009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 583 584 0.019676 -0.209063 0.093547 -0.2005245 0.6879987 0.4173664 0.5587960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 584 585 -0.022652 -0.147230 -0.022643 -0.0942857 -0.0670278 -0.7267599 0.6770802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 585 586 -0.062152 -0.044555 0.019369 0.2013841 -0.1138541 0.0290427 0.9724393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 586 587 -0.132296 0.137297 -0.014253 -0.3247254 0.0955087 -0.6835634 0.6466627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 587 588 0.221759 -0.031773 -0.053488 -0.1296053 0.1493107 -0.9130335 0.3567613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 588 589 -0.011072 0.117114 0.211987 0.7938758 -0.3832953 -0.4591807 0.1095404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 589 590 -0.046936 -0.112796 -0.056056 -0.4892934 -0.5651500 -0.6617797 0.0569654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 590 591 0.250074 -0.068578 -0.130770 -0.7267416 0.6275718 -0.2672412 0.0811326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 591 592 0.023352 -0.174144 0.222118 0.5808196 0.0198562 0.6524109 0.4864302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 592 593 -0.070506 -0.018035 0.016766 -0.0680571 -0.6540111 -0.5850684 0.4746922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 593 594 -0.121169 -0.020986 0.068082 -0.2440977 -0.4977369 -0.8250906 0.1090859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 594 595 0.060585 -0.059979 0.077692 -0.6681635 -0.1551712 0.3786070 0.6213985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 595 596 -0.048367 -0.014613 -0.003619 0.5714512 0.1093019 0.5847675 0.5652819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 596 597 -0.042880 0.086892 0.147824 0.0532981 0.8564823 0.5098740 0.0602160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 597 598 -0.050495 -0.095444 -0.023748 0.1363542 -0.4136248 -0.8977886 0.0655576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 598 599 0.048320 -0.047041 0.075356 0.4068625 -0.2063916 -0.7367109 0.4991218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 599 600 -0.030405 -0.077596 -0.009597 0.3212640 -0.4238796 -0.7878722 0.3104400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 600 601 -0.104130 -0.011077 -0.014664 -0.7094517 -0.3699404 -0.5011520 0.3296499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 601 602 0.135764 0.015288 -0.188577 0.6386577 0.5847744 -0.3145459 0.3888651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 602 603 -0.083244 0.106204 0.218469 -0.0059837 -0.0461569 -0.9342865 0.3534719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 603 604 0.059895 0.042053 0.042997 0.1783897 0.0498808 -0.9177173 0.3514028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 604 605 0.059731 0.083660 0.144272 0.8391494 0.2156923 0.4990117 0.0171018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 605 606 0.144225 0.112143 0.053851 -0.4594594 0.2075282 -0.7285276 0.4637635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 606 607 -0.254050 0.152785 0.046420 -0.0068872 -0.0859412 -0.6970303 0.7118395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 607 608 -0.071538 -0.020388 0.132812 -0.7134107 -0.1960652 -0.5765976 0.3466104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 608 609 0.173613 0.091636 -0.084407 0.8615021 -0.2382316 -0.1954834 0.4035419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 609 610 0.168886 0.060648 -0.026553 -0.2080600 0.0826244 -0.1954214 0.9548271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 610 611 0.142863 -0.088580 -0.086536 -0.4260547 0.5120823 -0.5778064 0.4715813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 611 612 -0.057113 0.122330 0.106833 -0.3072888 -0.8097505 0.1537445 0.4756472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 612 613 -0.036055 0.077642 0.060057 -0.0945905 0.1604526 0.5165099 0.8357782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 613 614 0.032235 -0.136357 -0.041725 0.9823726 0.0660324 -0.1660954 0.0547376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 614 615 0.021804 -0.021244 -0.024978 0.2891167 -0.2409550 -0.8672849 0.3258359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 615 616 -0.084398 -0.078966 0.199771 -0.4859520 -0.0435439 0.8679117 0.0931870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 616 617 -0.120645 0.031226 -0.046973 -0.3824085 -0.1185024 0.6526165 0.6432827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 617 618 0.030961 -0.095085 0.181597 0.0509178 0.0326844 -0.3907137 0.9185216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 618 619 0.112543 0.028726 0.012789 -0.4403023 -0.4066169 -0.7440896 0.2951733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 619 620 0.019980 0.102921 -0.027122 0.2529283 -0.2378500 0.6339922 0.6910200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 620 621 -0.027391 -0.060557 0.083890 0.3561594 0.0650449 -0.5311639 0.7660186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 621 622 0.037203 -0.144743 -0.127069 -0.0314376 0.1658014 0.6874334 0.7063688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 622 623 -0.046874 -0.325935 -0.039486 0.3417253 0.6583030 -0.3033075 0.5982187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 623 624 0.177318 0.019636 0.006515 0.3692453 -0.2645223 -0.3226740 0.8304019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 624 625 -0.101058 0.093136 0.133271 -0.4371878 0.3978737 -0.8062580 0.0226150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 625 626 -0.075712 -0.117153 -0.006577 0.6037244 0.4753137 0.4642229 0.4405574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 626 627 0.012235 -0.086330 -0.135672 -0.4863707 0.2970646 0.5163221 0.6392243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 627 628 -0.028850 0.018952 -0.006323 -0.2794198 -0.6698560 0.5938524 0.3472131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 628 629 0.192404 -0.041232 0.059819 0.3898332 0.1354241 0.1103630 0.9041628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 629 630 -0.030426 -0.005781 0.019015 0.0870393 0.1573875 -0.9386798 0.2941660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 630 631 0.121262 -0.057023 0.014685 -0.4339663 0.2354659 -0.2216042 0.8409046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 631 632 0.082109 0.048236 0.131881 0.6940500 -0.5558225 0.3057363 0.3404134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 632 633 -0.036820 0.186452 -0.124929 -0.5762099 0.3987956 -0.6549427 0.2828325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 633 634 -0.070807 0.102302 0.225592 -0.8357413 -0.0482520 0.5361747 0.1082813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 634 635 -0.082011 -0.154740 0.119130 -0.3239070 -0.4008837 0.1438665 0.8447952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 635 636 0.058969 -0.048266 0.084638 -0.5383448 0.3438557 -0.0941278 0.7636021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 636 637 0.035604 0.012953 -0.050792 0.5214306 -0.3211697 0.2977379 0.7323334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 637 638 -0.034139 -0.335156 -0.014640 -0.4796184 0.2069316 0.2278344 0.8217280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 638 639 -0.056254 -0.044284 -0.197559 0.1487613 0.4894277 -0.2525826 0.8212993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 639 640 0.016099 -0.094439 -0.079481 0.1038695 -0.5750071 -0.5555626 0.5915472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 640 641 -0.138944 -0.215096 -0.093177 0.3295092 -0.3479577 0.8078164 0.3431935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 641 642 -0.033657 0.172301 -0.150686 -0.1237027 0.2387579 -0.4642137 0.8439182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 642 643 -0.054817 -0.046540 -0.100635 0.3508319 0.8913061 -0.2870974 0.0080900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 643 644 -0.176590 -0.008811 0.109977 -0.3444987 -0.4166016 0.5167969 0.6638409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 644 645 0.011337 0.027989 -0.110990 -0.2598218 -0.0983049 -0.7959550 0.5378516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 645 646 -0.000741 -0.216063 0.028484 0.3018530 0.0853787 -0.6116378 0.7262881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 646 647 -0.046656 -0.012150 -0.034563 0.1822765 -0.0942576 -0.2324524 0.9507138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 647 648 -0.031915 0.051116 -0.274973 0.1786719 0.1702988 -0.9634134 0.1044476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 648 649 0.025983 0.005546 -0.159051 0.9319860 -0.0474852 0.0056490 0.3593262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 649 650 0.134409 -0.036319 -0.107539 -0.7937914 0.1017208 0.2719087 0.5344284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 650 651 0.017311 0.228953 0.126298 0.2506475 -0.4637937 -0.3416865 0.7780241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 651 652 -0.103616 0.095198 0.058034 -0.5655023 0.3921588 -0.6007225 0.4068797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 652 653 -0.193090 0.160431 0.017007 0.3663188 -0.1178969 -0.1055233 0.9169382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 653 654 -0.005498 -0.062934 -0.128574 0.4675048 0.4704699 0.5631339 0.4929276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 654 655 0.148234 -0.092191 0.132896 -0.4506601 0.0805372 0.8864765 0.0676656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 655 656 0.198863 -0.064276 -0.089181 0.4522643 -0.3401016 -0.5649991 0.6004697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 656 657 0.053103 0.138939 -0.135495 -0.3274457 -0.3618595 -0.8718689 0.0410083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 657 658 0.134677 -0.150035 -0.129029 -0.6410522 -0.4871006 0.3563930 0.4740982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 658 659 0.079832 -0.100387 -0.006075 0.2001870 0.8983600 -0.3326326 0.2054997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 659 660 0.081565 -0.060380 -0.174195 -0.5133677 0.0392218 0.8255758 0.2309543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 660 661 0.210946 -0.061523 0.037417 -0.5250159 0.6655661 0.5256973 0.0708687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 661 662 -0.020148 0.014003 0.112186 0.6609464 0.1204246 -0.6706441 0.3144587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 662 663 0.110279 -0.105835 0.024543 0.2357321 -0.7236399 0.6486722 0.0000743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 663 664 -0.099118 0.027323 -0.109600 -0.5450979 0.4638384 -0.2662701 0.6456180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 664 665 -0.096785 0.113176 0.074360 0.3898214 0.7762352 -0.4846267 0.1031271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 665 666 0.009432 -0.071933 -0.119130 -0.8437731 -0.1784133 0.4480730 0.2354700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 666 667 0.023221 -0.040904 0.160290 0.6144943 -0.2152473 -0.2887463 0.7019195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 667 668 -0.077828 0.025406 -0.152305 -0.0377737 -0.8403057 0.1154394 0.5283306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 668 669 0.094217 -0.126372 0.065263 -0.6860827 0.6504131 -0.1221240 0.3022234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 669 670 -0.174844 0.309911 0.014341 -0.2915599 -0.7887694 0.4801812 0.2495230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 670 671 -0.026313 -0.027259 0.055658 0.5084094 -0.3692541 -0.5329996 0.5666416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 671 672 -0.048702 0.100406 0.000928 -0.2551680 -0.2020212 -0.3329928 0.8849817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 672 673 -0.116250 -0.128461 0.110660 0.0513694 -0.4891691 0.8602306 0.1344545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 673 674 0.119250 -0.019281 -0.096282 0.2329033 -0.1481383 0.7213499 0.6351893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 674 675 -0.074701 -0.102015 0.045756 0.8439034 -0.2733200 -0.2503788 0.3878578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 675 676 -0.080727 -0.028499 0.193266 0.9133139 0.2417280 -0.3088019 0.1098483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 676 677 0.013563 -0.113656 0.018529 0.3620972 -0.3482653 0.4274468 0.7515890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 677 678 -0.019389 0.241023 0.039507 0.5799631 -0.0793598 -0.7996477 0.1338219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 678 679 -0.053795 -0.179086 0.068935 -0.1083153 -0.0438446 -0.0590348 0.9913931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 679 680 -0.002481 -0.085582 -0.021616 0.2919241 0.0396765 -0.5194788 0.8020897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 680 681 0.034294 0.133649 0.095372 0.1127415 0.1477332 0.3407452 0.9216056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 681 682 -0.131782 0.076718 0.078246 -0.2883223 0.1979277 -0.5821547 0.7340237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 682 683 -0.130092 -0.035950 0.034783 0.2970388 0.7764244 -0.3904821 0.3955461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 683 684 0.033930 0.050125 -0.096346 -0.0027130 -0.8085187 0.5823670 0.0844923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 684 685 0.134608 -0.148455 -0.121506 -0.2646721 0.1135013 -0.8097747 0.5112055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 685 686 -0.071593 0.031735 -0.162712 0.1448041 -0.1823889 -0.1504961 0.9607898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 686 687 0.102127 0.053299 0.138444 0.2650819 0.0836862 0.6200925 0.7336303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 687 688 0.043979 -0.022701 0.064501 0.1867473 0.4590526 -0.2455887 0.8331160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 688 689 -0.138082 0.151896 0.077643 0.2473927 -0.0116371 -0.7530424 0.6095807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 689 690 -0.243574 -0.021413 -0.232423 0.2239990 -0.1233798 0.9261851 0.2770974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 690 691 0.025959 -0.066034 0.099657 0.6706117 0.2228270 -0.2966036 0.6423818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 691 692 -0.058976 0.181164 0.037601 -0.4312419 -0.7503193 -0.4355001 0.2477722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 692 693 0.008414 0.013689 0.185847 -0.6006490 -0.6794508 -0.4203529 0.0295095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 693 694 0.107807 0.068237 -0.062162 0.8224481 -0.2740074 0.4633020 0.1839843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 694 695 -0.189010 -0.071021 0.019396 0.6772067 0.5759279 0.4286782 0.1610378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 695 696 -0.017566 0.063917 0.014699 -0.3625760 -0.7176515 0.3698821 0.4655129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 696 697 -0.010204 -0.140450 0.154952 0.0524497 -0.5513884 0.8323246 0.0213465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 697 698 -0.013050 -0.181709 0.262475 0.0034616 -0.2892106 0.3089611 0.9060289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 698 699 0.053555 0.158021 -0.087603 -0.2744638 -0.5742043 -0.4319567 0.6390403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 699 700 0.062705 -0.014725 -0.175962 -0.0194590 0.1390946 -0.5496773 0.8234858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 700 701 0.051246 0.076142 -0.097356 -0.5013896 0.0216641 -0.2976094 0.8121378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 701 702 0.033043 0.027514 0.003768 0.0345297 -0.2093031 0.0687214 0.9748217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 702 703 0.056232 -0.044822 0.326615 0.1813957 0.1361035 0.8876547 0.4007998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 703 704 0.015984 0.049708 -0.009234 0.4689807 0.6081502 -0.4028213 0.4979412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 704 705 -0.184079 0.001562 0.169287 0.7944532 0.1642087 -0.4151294 0.4117610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 705 706 -0.004360 0.032745 0.003524 0.0895269 0.0095022 -0.9740458 0.2076763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 706 707 0.043664 -0.025719 0.026078 -0.1212303 -0.0435563 0.3735174 0.9186353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 707 708 0.093720 0.120672 0.225374 0.2662619 0.2990961 -0.6877550 0.6055074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 708 709 -0.031332 0.102638 0.001838 0.2340285 0.2628874 0.8831666 0.3100608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 709 710 0.017454 -0.071428 0.026901 0.4782794 0.1899549 0.8431072 0.1560009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 710 711 -0.115723 -0.072820 -0.072617 -0.2714233 -0.1357615 0.8640359 0.4016718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 711 712 -0.018027 -0.024986 0.062831 0.6723298 -0.1988508 0.3938175 0.5944230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 712 713 0.088849 0.105300 -0.032127 -0.2407085 0.8110150 0.3715943 0.3824025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 713 714 0.070023 0.098605 0.122025 -0.3957052 -0.0480231 -0.9119314 0.0974284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 714 715 0.129234 0.017643 0.006217 0.5254893 0.7026329 -0.2933163 0.3796493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 715 716 -0.192326 -0.016465 0.143805 0.0123726 -0.3304275 0.6210880 0.7105733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 716 717 -0.028521 0.191645 0.010427 -0.5197109 -0.2093354 -0.7961863 0.2284001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 717 718 0.190017 -0.091739 0.118967 0.2081701 -0.4174878 0.7618992 0.4493091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 718 719 0.167768 0.139558 0.053194 0.4811955 -0.0824440 0.4117484 0.7694915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 719 720 0.006480 -0.040020 0.183685 0.0475287 0.5897202 0.4465691 0.6712281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 720 721 -0.014530 0.035350 0.039478 -0.1060885 -0.4881481 -0.3650850 0.7856014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 721 722 0.123764 0.113272 0.159936 0.4917597 0.0250273 0.6614534 0.5657079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 722 723 -0.168166 0.029822 -0.032756 0.1309619 0.3493881 0.3723236 0.8497953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 723 724 0.125394 0.154243 0.132673 -0.1151675 0.7366156 0.5550835 0.3688037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 724 725 0.066868 0.120038 0.001677 -0.6687646 0.0725887 0.4610439 0.5787257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 725 726 0.145579 0.160758 -0.026946 0.6028124 0.0724189 -0.5377717 0.5849567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 726 727 0.033536 0.059407 -0.001594 0.7796711 -0.2794012 -0.5521919 0.0955616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 727 728 0.106068 -0.068246 -0.024324 -0.5468138 -0.6430397 0.3553326 0.4015387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 728 729 0.070771 -0.223640 0.049101 0.8344526 -0.0029758 -0.1311220 0.5352448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 729 730 -0.163518 0.067255 -0.195823 -0.2657158 0.4339361 0.0777859 0.8573470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 730 731 -0.262130 -0.062055 -0.063718 -0.7397647 0.0322954 0.3034047 0.5997089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 731 732 -0.154638 -0.155220 0.270115 -0.2601385 0.0320091 -0.9527543 0.1535011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 732 733 0.092710 -0.040919 0.210907 -0.8409702 0.1211648 -0.0621281 0.5236681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 733 734 -0.064547 -0.073038 -0.137141 0.6151524 0.1430307 -0.5274422 0.5682732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 734 735 -0.145566 0.061314 -0.180054 -0.2605199 0.4493796 0.7139252 0.4695724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 735 736 0.091462 0.023841 -0.150697 -0.3596071 0.3890476 0.7868675 0.3164873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 736 737 0.060945 -0.080226 -0.082864 -0.4939783 -0.0117073 -0.4308580 0.7551224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 737 738 0.032207 -0.154959 0.139284 0.4915299 -0.3271362 0.7729924 0.2320840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 738 739 -0.025801 -0.225304 -0.170593 -0.2006280 -0.5960650 -0.1432180 0.7641620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 739 740 -0.162516 0.194912 0.131727 -0.1809282 0.8990655 0.2135779 0.3366461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 740 741 0.074018 0.168956 0.061817 -0.6079824 0.0415494 -0.0632680 0.7903342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 741 742 0.041898 -0.240143 -0.108504 0.0585101 0.6159116 -0.5634598 0.5474874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 742 743 -0.017833 0.179839 -0.078260 0.9763575 -0.0300818 0.1689945 0.1313844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 743 744 -0.031486 0.063812 -0.078894 -0.3584265 0.4993685 0.5881690 0.5255652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 744 745 0.020591 -0.084101 -0.188505 -0.1791530 0.0957845 -0.9778190 0.0509866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 745 746 0.016732 -0.116119 -0.162762 0.1540028 -0.0784658 -0.5383607 0.8247994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 746 747 -0.117265 -0.154792 -0.067771 0.4843980 -0.5370770 -0.6360316 0.2690180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 747 748 0.076256 -0.089026 0.031080 -0.2093766 -0.6699756 -0.2136705 0.6794402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 748 749 -0.142360 0.031234 -0.214105 0.5251281 -0.2421195 0.5727704 0.5809929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 749 750 0.022152 -0.013689 0.053519 -0.2277987 0.7790410 -0.4624826 0.3568090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 750 751 0.005664 0.107106 -0.067332 0.8530687 -0.1880233 -0.2921763 0.3892995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 751 752 0.053971 0.131248 -0.011326 -0.4689493 -0.1859440 -0.7271903 0.4655166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 752 753 0.144392 0.114701 0.177755 -0.2847055 -0.1037943 0.5577723 0.7726963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 753 754 0.069870 -0.003365 0.071368 0.3510229 -0.7438617 0.0020024 0.5687254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 754 755 0.038816 -0.025996 0.074052 -0.3331908 -0.4357998 -0.6567848 0.5173935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 755 756 -0.072682 0.100555 0.051907 -0.6947565 -0.2246979 -0.5852408 0.3525868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 756 757 -0.011069 -0.011938 -0.095441 0.5816737 0.4236330 0.4773516 0.5043076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 757 758 0.071721 -0.178461 0.005943 -0.4360452 0.4359727 0.7746000 0.1406672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 758 759 -0.195010 0.110010 -0.071608 0.0029342 0.5880326 -0.6666772 0.4579854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 759 760 -0.107859 0.194800 -0.050387 0.0578419 0.8298464 -0.3804251 0.4040866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 760 761 0.009790 -0.045514 -0.168331 -0.0267818 0.0455529 0.7742708 0.6306445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 761 762 0.093185 0.001865 0.003373 -0.6576289 -0.0518007 0.2921481 0.6924524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 762 763 0.186184 0.136687 -0.082924 0.2041617 0.1718836 0.3804320 0.8854634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 763 764 -0.091614 -0.113686 -0.120020 -0.5736765 0.3783664 0.6934409 0.2165037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 764 765 0.094888 0.131244 -0.111885 0.0305009 -0.2171711 0.2075673 0.9533217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 765 766 0.082054 0.188746 -0.096066 -0.2148261 0.6519488 0.6803074 0.2568936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 766 767 -0.053475 0.073856 -0.107918 0.0045787 0.0679153 0.7573090 0.6494995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 767 768 0.042807 0.109595 0.114216 -0.3945572 -0.0847833 0.5272783 0.7477392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 768 769 -0.008650 0.112254 -0.150626 0.0018074 0.6448613 -0.4306416 0.6314258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 769 770 0.061637 0.003333 0.103500 0.5979837 0.0615028 -0.7709289 0.2104793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 770 771 0.023522 -0.023312 -0.139622 0.0670812 0.1325586 0.2326260 0.9611522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 771 772 -0.083982 0.059687 -0.068021 -0.1252833 -0.5355821 -0.2076507 0.8089110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 772 773 -0.078838 -0.177073 0.158821 -0.0089855 0.1936616 -0.6594531 0.7263167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 773 774 0.006800 0.059158 0.086731 -0.3748145 0.1306744 -0.0488466 0.9165437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 774 775 0.007726 0.061171 -0.169326 0.6288789 -0.0021279 -0.2574471 0.7336401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 775 776 0.021445 0.015628 0.039716 -0.3716860 -0.3480084 0.8606619 0.0008529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 776 777 -0.094856 -0.149945 0.009399 0.3662126 -0.4478215 -0.3240569 0.7485529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 777 778 0.115559 0.004296 -0.125196 0.4217491 -0.3505652 0.7370868 0.3948858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 778 779 0.085042 0.114466 0.158746 -0.0357622 0.1408303 -0.9775482 0.1526023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 779 780 0.130768 0.159084 0.107429 0.2862366 -0.5039970 -0.5470261 0.6040017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 780 781 0.213750 -0.060443 0.212389 0.0764759 0.7439017 0.6417327 0.1701202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 781 782 -0.018023 0.037069 -0.142543 0.2843713 0.8519271 0.2547426 0.3584125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 782 783 -0.029346 0.136779 0.137536 0.3434862 -0.4351036 -0.8041250 0.2146745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 783 784 -0.174394 -0.052287 -0.053958 -0.1225008 -0.2305742 0.9452734 0.1956715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 784 785 0.154557 -0.088592 0.056040 -0.3561489 -0.2959898 -0.4680771 0.7526299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 785 786 0.057803 0.126759 0.135948 0.0675923 0.0264804 0.5765187 0.8138527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 786 787 0.064526 0.058587 0.042258 -0.1749980 0.1289046 -0.9753579 0.0378980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 787 788 -0.151879 -0.052534 0.048603 0.3118034 -0.4706847 -0.6080886 0.5580886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 788 789 0.127630 -0.037932 -0.110569 0.2290049 -0.0314405 0.9332787 0.2748801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 789 790 0.055330 -0.090235 0.055902 0.3533740 0.5070016 0.1635973 0.7689682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 790 791 0.093677 -0.201707 0.046600 0.1835909 -0.6750401 -0.5163768 0.4939334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 791 792 0.133385 -0.089229 -0.030212 -0.9465628 -0.1991954 -0.1860229 0.1724401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 792 793 -0.004462 -0.109551 0.013076 -0.2890863 0.7412241 0.0873419 0.5994893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 793 794 -0.136365 0.117867 -0.085441 0.7509235 0.4624157 -0.3121504 0.3533379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 794 795 -0.192209 0.076925 0.117175 0.1144662 -0.0018725 0.0184576 0.9932539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 795 796 0.011840 -0.115344 0.022787 -0.3371274 0.4548202 0.6109190 0.5534091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 796 797 -0.018286 0.309030 -0.012822 -0.1044406 0.0339029 0.9261816 0.3607359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 797 798 -0.198411 -0.172974 -0.076352 -0.0697075 0.7368295 -0.3335707 0.5839124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 798 799 -0.096393 -0.001660 0.068740 -0.3607952 0.2756890 0.8685490 0.1986076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 799 800 0.048565 -0.151849 0.039384 -0.3059618 0.7174972 0.6253854 0.0218682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 800 801 -0.023052 0.138167 -0.096717 -0.5375367 -0.4222619 0.0978398 0.7233094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 801 802 0.213694 -0.181843 -0.150947 0.7638496 -0.1342847 -0.1175807 0.6202227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 802 803 0.152970 0.021168 -0.081366 -0.6936895 -0.3551521 -0.3480015 0.5211112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 803 804 -0.070588 -0.003513 0.058999 -0.4386930 0.0266106 -0.7408776 0.5078785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 804 805 -0.012336 0.085676 0.003163 0.5555851 0.0874720 0.5998614 0.5690695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 805 806 0.132104 -0.004083 0.079280 0.6535856 0.1646388 0.7387239 0.0026447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 806 807 -0.140968 0.042259 0.011058 -0.1727305 0.4729467 -0.8639729 0.0060439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 807 808 -0.012984 0.180797 0.069213 0.0984790 -0.0778355 -0.0939110 0.9876357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 808 809 -0.088206 -0.118691 0.098465 0.0227356 0.1413657 0.3785189 0.9144519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 809 810 -0.039968 -0.184338 0.046754 0.5625079 -0.4624627 0.0828287 0.6803326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 810 811 -0.090627 0.055381 -0.213915 0.0625800 0.1700424 -0.4943907 0.8501454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 811 812 -0.271516 -0.183629 0.068229 -0.3709027 -0.1144152 -0.3614549 0.8477563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 812 813 -0.007234 -0.217457 0.026529 -0.2255870 0.1793262 -0.1045814 0.9518484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 813 814 -0.085355 -0.091413 -0.216851 0.1055289 -0.5846331 0.7901738 0.1506426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 814 815 0.330387 0.144770 0.076054 0.2705165 -0.2420877 0.5392004 0.7599193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 815 816 -0.121481 0.082456 -0.056765 0.6962734 -0.1196885 0.3581470 0.6104169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 816 817 0.059311 -0.165840 -0.036667 0.4287260 0.0911274 0.2507805 0.8631333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 817 818 -0.018277 0.029017 0.004821 0.0261883 0.8124790 -0.1482531 0.5632167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 818 819 0.017588 -0.041121 -0.039224 -0.3580268 0.4323744 0.3841320 0.7330156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 819 820 0.252836 0.064441 0.008243 -0.0410730 -0.1579897 0.4952833 0.8532566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 820 821 -0.137142 0.083395 -0.307217 -0.2245451 0.3247874 0.8761241 0.2765850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 821 822 0.055668 -0.136424 -0.061698 -0.5428201 -0.1229684 0.8114557 0.1782266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 822 823 -0.051309 0.167929 0.041652 0.2647011 -0.8531611 -0.4358583 0.1098956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 823 824 0.036091 0.067895 -0.007194 0.3172884 0.7572919 0.1229891 0.5574143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 824 825 0.006007 -0.019184 0.164816 -0.4174209 0.6491152 0.3075346 0.5566253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 825 826 0.097334 0.195718 -0.158140 -0.2043263 -0.1934743 -0.2516984 0.9259948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 826 827 -0.179184 0.024909 -0.083465 0.0625811 0.3300653 -0.7634083 0.5516776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 827 828 -0.137194 0.069714 0.039664 0.0033564 0.3611159 0.1066943 0.9263910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 828 829 0.142373 -0.103374 -0.109060 0.2686250 -0.8423135 0.0946479 0.4575919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 829 830 0.003383 -0.021421 0.193912 -0.0217511 0.4660002 0.8829687 0.0523168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 830 831 0.068323 -0.009560 0.149665 -0.3275936 -0.3009700 0.8918143 0.0822599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 831 832 0.194599 0.065950 -0.060982 0.7502989 0.1036564 -0.0117514 0.6528161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 832 833 0.180942 -0.005187 -0.138843 -0.2614485 -0.1706860 -0.5271969 0.7903002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 833 834 0.084120 -0.111515 -0.013795 -0.0582109 -0.5565051 -0.4475338 0.6975866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 834 835 -0.004522 -0.025767 -0.004687 -0.1914245 0.6077418 -0.5963568 0.4882266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 835 836 0.052424 0.018960 0.241290 0.3411732 -0.6126349 -0.6484598 0.2962755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 836 837 -0.150857 -0.109747 0.036452 -0.5219273 0.3330642 -0.2893509 0.7300248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 837 838 -0.017392 0.036213 -0.006431 0.5900393 -0.4806425 0.6382932 0.1158369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 838 839 -0.057997 0.155139 0.051307 0.4161694 -0.4080407 0.2073205 0.7856997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 839 840 0.020221 0.135406 -0.018794 0.6741283 0.1690864 -0.3959225 0.6001718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 840 841 0.024896 0.208708 -0.097673 -0.3282823 -0.2300687 -0.9157065 0.0279407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 841 842 0.096013 0.024637 -0.056569 0.3914170 0.3772871 0.1004538 0.8332804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 842 843 0.136929 -0.004162 -0.191208 -0.1152597 0.3368972 0.9343153 0.0164416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 843 844 -0.048068 -0.004935 -0.063666 0.2304118 0.7902759 0.5093975 0.2507760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 844 845 -0.079436 0.011574 0.106372 -0.3541330 -0.1918631 -0.1023153 0.9095658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 845 846 0.005512 -0.027058 0.085416 0.1025203 -0.4184276 0.5534088 0.7128440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 846 847 -0.244252 -0.172417 -0.191048 -0.4120440 -0.0221868 0.1231546 0.9025300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 847 848 -0.088194 0.119545 -0.089188 0.5345929 0.3885392 0.4825519 0.5747969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 848 849 0.020141 0.076518 -0.102975 -0.1054150 -0.1716898 0.1443746 0.9687963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 849 850 0.051114 -0.135211 -0.055012 -0.2204192 0.0285084 -0.1273938 0.9666300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 850 851 -0.097778 0.049239 -0.066387 -0.6165685 0.0740450 0.3787237 0.6862427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 851 852 -0.074837 -0.103478 -0.232176 -0.0965057 -0.1783191 -0.1934935 0.9599214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 852 853 -0.040086 0.059426 0.106292 0.8529093 -0.4614569 0.1217573 0.2116089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 853 854 -0.260291 0.015455 -0.220087 0.1788681 0.5202832 -0.4311867 0.7151151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 854 855 -0.166452 0.057218 -0.202962 -0.0558463 -0.6322421 -0.4450772 0.6317099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 855 856 0.149877 0.056026 0.050273 0.1818381 0.5809641 -0.7312394 0.3077412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 856 857 0.083682 -0.033618 0.035774 -0.1085088 0.5565066 -0.6485274 0.5078765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 857 858 0.034801 0.201660 -0.068639 0.8831201 -0.0043659 -0.2512911 0.3961473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 858 859 -0.187796 -0.140163 -0.089604 0.5058803 0.0149304 0.8328891 0.2239598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 859 860 -0.025490 0.047046 0.058936 0.7968822 -0.0133939 -0.1063629 0.5945471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 860 861 0.218692 -0.077316 -0.022141 0.3885101 -0.6878212 -0.6003939 0.1244552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 861 862 -0.039605 0.020985 -0.020424 -0.7490738 0.4498728 0.4745391 0.1063745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 862 863 0.069578 0.125712 -0.149030 -0.6612717 -0.2346959 -0.2523783 0.6662903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 863 864 0.052736 0.050665 -0.017544 0.9633511 0.0830673 -0.2359881 0.0967678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 864 865 0.005597 0.007086 -0.225024 -0.2433503 -0.9342837 -0.2393517 0.1029820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 865 866 -0.127031 0.025811 -0.011608 0.2347736 0.0103472 0.8853018 0.4012668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 866 867 -0.040933 -0.079878 0.037150 0.1749694 0.1060074 -0.9576058 0.2028282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 867 868 -0.110937 0.103283 -0.058408 0.2718813 -0.4776171 -0.2624798 0.7931373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 868 869 -0.058458 -0.249783 -0.007634 -0.1944851 -0.9677122 -0.0127665 0.1598297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 869 870 0.020323 -0.107787 0.048065 -0.7102698 0.4048075 -0.3349442 0.4684656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 870 871 -0.056922 -0.027207 -0.045555 -0.0051899 -0.8063549 -0.2000824 0.5565356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 871 872 -0.125341 0.127029 -0.024146 -0.2234694 0.0261681 0.5942289 0.7721844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 872 873 0.182502 -0.125330 -0.131244 0.6313582 -0.4235527 0.2019801 0.6174091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 873 874 0.035773 0.077304 -0.019488 0.2272257 -0.6124334 -0.7344713 0.1839723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 874 875 0.029880 0.016307 -0.077593 -0.4476288 0.3601815 0.7813375 0.2437406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 875 876 0.046977 0.026745 -0.093319 -0.4461066 0.0816883 -0.7451092 0.4890074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 876 877 0.062301 -0.006940 -0.027699 0.0269836 -0.0440950 0.9968847 0.0595679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 877 878 -0.210630 -0.038227 0.148706 -0.0033318 -0.7873823 -0.0374320 0.6153186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 878 879 0.131040 -0.101748 -0.183876 -0.6781849 0.0525791 -0.5715873 0.4588994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 879 880 -0.003342 0.129321 -0.028176 -0.8193616 -0.0960457 -0.5648943 0.0177809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 880 881 0.288381 -0.003800 -0.168506 0.4417748 0.0616054 0.8396681 0.3098342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 881 882 0.074126 -0.048774 0.101636 0.1212629 -0.2138867 0.2069788 0.9469464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 882 883 0.173622 0.139034 0.140721 -0.4147046 0.3778342 -0.3060057 0.7691696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 883 884 -0.002343 0.004849 0.066492 -0.0193118 0.9576379 -0.2605570 0.1211062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 884 885 -0.023448 0.076693 -0.205962 0.6508612 0.6205069 -0.2553364 0.3551820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 885 886 0.126731 -0.011699 -0.139179 0.4828481 0.1905498 -0.1666875 0.8383100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 886 887 0.022598 -0.003326 0.194580 0.6966934 -0.4364706 -0.2818140 0.4946642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 887 888 -0.123457 -0.094456 -0.140343 -0.1739844 0.0860699 0.0706360 0.9784334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 888 889 -0.144414 -0.127151 0.079601 0.4580335 0.0446170 -0.8373837 0.2949629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 889 890 0.023318 0.074710 -0.009585 0.1364113 -0.0570262 0.8519509 0.5023143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 890 891 -0.011497 0.054786 0.043585 -0.1512800 -0.3959023 0.1988110 0.8836571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 891 892 0.116169 0.237150 -0.041886 -0.8455416 -0.0210436 -0.3043276 0.4381796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 892 893 -0.045034 -0.050021 0.023718 0.1359776 0.5720520 -0.0820355 0.8046967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 893 894 -0.031224 -0.074132 0.016122 -0.4834171 -0.4070042 -0.5595387 0.5362573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 894 895 0.155477 -0.117202 0.010735 0.5506051 -0.4627431 0.2760183 0.6375867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 895 896 0.050275 -0.058656 -0.007556 -0.4484078 0.5269222 -0.3049953 0.6544168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 896 897 0.250002 -0.008283 -0.082425 -0.6919899 0.1871997 -0.5248421 0.4589630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 897 898 0.012092 0.097027 0.010986 0.6349233 -0.2271310 0.5522528 0.4902048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 898 899 -0.008097 -0.024975 0.040824 0.3609253 0.8043349 0.2672589 0.3890386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 899 900 -0.135320 0.191129 0.020920 -0.7696019 -0.0865961 0.3329877 0.5378971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 900 901 0.105906 -0.001593 -0.090668 -0.1241900 0.1365422 -0.8011618 0.5692739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 901 902 0.217811 -0.126945 0.085366 0.0360288 0.6103939 -0.7793192 0.1370504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 902 903 -0.194065 0.046950 0.064258 0.5103143 -0.0536952 0.4282916 0.7438162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 903 904 -0.016675 0.065828 0.021219 0.4041726 0.1160031 0.8397344 0.3435607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 904 905 -0.001485 -0.165172 -0.027349 0.7441274 -0.1212022 0.5702060 0.3262662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 905 906 0.040442 0.038700 0.134959 0.2242098 0.2596548 0.0910818 0.9348869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 906 907 -0.083337 -0.016781 -0.017822 -0.3889139 -0.2645538 0.7229494 0.5060646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 907 908 -0.028771 0.085588 0.085102 -0.0855338 0.0552483 0.9682224 0.2284229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 908 909 0.101429 0.107078 0.013002 0.7561117 -0.5397619 -0.3604324 0.0839094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 909 910 -0.091924 -0.016565 -0.001687 -0.6251285 -0.6796269 0.1463901 0.3548121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 910 911 -0.074923 -0.163710 -0.013956 0.4392480 0.6603377 0.2361258 0.5614801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 911 912 -0.025547 0.096190 0.155806 0.0329672 0.1265606 -0.3957717 0.9089886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 912 913 0.145333 -0.027586 -0.059315 0.7961182 -0.2972314 -0.5233791 0.0626389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 913 914 0.027549 0.004332 0.175409 -0.2486145 -0.5112844 -0.1475145 0.8093322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 914 915 0.075915 -0.091806 0.007991 -0.3350111 0.3232737 0.8031699 0.3717255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 915 916 -0.016407 -0.132078 0.024100 0.3395415 -0.1307544 0.2142330 0.9064872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 916 917 -0.122334 -0.059716 -0.227383 0.1932572 -0.1244632 0.4305201 0.8728190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 917 918 -0.005369 0.159578 0.049000 -0.1869860 0.9313057 0.0907347 0.2991205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 918 919 0.005313 0.075013 -0.121100 0.4829935 0.3584773 -0.7883782 0.1291165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 919 920 0.063701 -0.104104 0.000819 -0.1020173 0.4341625 -0.8433961 0.2996305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 920 921 -0.035280 -0.086237 -0.016231 -0.1217170 -0.3556321 0.9074893 0.1875471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 921 922 0.003768 0.201785 0.060680 0.3192059 0.0267167 0.9083849 0.2687578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 922 923 0.045925 -0.105911 -0.124535 0.0713475 0.8113682 0.4713816 0.3382167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 923 924 0.073941 0.017162 -0.159895 -0.7789996 0.0032594 -0.1139829 0.6165686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 924 925 0.034526 0.040648 0.017451 0.3461355 0.0300292 -0.9376867 0.0056683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 925 926 -0.011409 -0.227602 -0.039864 -0.4382097 0.1833061 0.3644397 0.8009712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 926 927 0.111796 0.015067 -0.062576 0.0504415 -0.9001708 -0.0429412 0.4304698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 927 928 0.082048 -0.075719 0.019505 0.3598614 0.3296504 0.8303453 0.2689928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 928 929 -0.045097 0.130391 0.038504 0.5734549 0.0647560 0.7596543 0.2998024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 929 930 -0.115154 0.041170 -0.300480 0.6756919 -0.0015486 0.6872904 0.2665896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 930 931 0.019109 0.099551 -0.141755 0.0199427 -0.4879156 0.8549198 0.1750793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 931 932 0.001264 0.021772 -0.166783 0.0235549 -0.6427917 0.4634373 0.6094997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 932 933 -0.087296 -0.012876 0.086578 0.5555310 -0.3140756 0.7464097 0.1887178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 933 934 -0.028038 0.058950 0.074083 -0.5138821 -0.3042576 0.7895431 0.1413302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 934 935 -0.026729 0.115982 0.060350 -0.1842841 -0.4062280 -0.4849341 0.7522348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 935 936 0.006671 0.009792 -0.046060 0.0231506 -0.5470206 0.2090753 0.8102592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 936 937 0.123202 0.023995 -0.231737 -0.5377879 0.2784667 -0.7923692 0.0734270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 937 938 -0.061170 -0.004500 0.276867 -0.0670750 -0.0979480 0.6024187 0.7893028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 938 939 -0.032421 0.050277 -0.112914 0.4789217 -0.0318738 -0.4127097 0.7741374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 939 940 0.048585 0.088185 0.092963 -0.3951856 0.6162655 -0.6214022 0.2791138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 940 941 -0.017212 0.066777 0.116858 0.1784861 -0.0968377 0.7301810 0.6523809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 941 942 0.182392 0.162183 -0.215593 -0.7918245 0.0384739 0.0716200 0.6053134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 942 943 0.025937 -0.087290 0.144684 -0.2278527 -0.1144347 0.9384454 0.2330409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 943 944 0.040026 0.122057 0.063368 0.6123364 0.6127587 0.4662157 0.1794823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 944 945 -0.054014 -0.171063 -0.083542 -0.4764192 0.3090235 -0.8130883 0.1281275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 945 946 0.051399 -0.036142 -0.051583 0.4353108 -0.7054668 -0.4790051 0.2887478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 946 947 -0.157483 0.061135 0.003257 -0.8242767 -0.0693827 -0.5018657 0.2527545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 947 948 0.048138 0.124103 -0.026003 0.1266194 0.6730205 0.7247081 0.0762175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 948 949 -0.181613 -0.169156 -0.038104 -0.1171910 0.4597627 0.8800132 0.0214768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 949 950 -0.037725 -0.158204 -0.037054 0.0349496 -0.1843757 -0.1914769 0.9633902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 950 951 -0.027425 -0.084986 0.053729 0.4587688 0.2107357 -0.6358853 0.5837565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 951 952 0.044789 -0.037517 0.033075 0.3926735 -0.8151119 -0.3861696 0.1796473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 952 953 0.242066 -0.052376 -0.199123 -0.5656674 -0.5932137 0.2658992 0.5073613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 953 954 -0.150558 -0.053751 0.003197 0.7608125 -0.0239369 -0.0627871 0.6454837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 954 955 -0.063479 -0.148420 -0.094368 -0.4216104 0.5555238 0.1017768 0.7094219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 955 956 0.001284 0.083491 -0.072354 -0.4483051 -0.3807263 0.4615102 0.6641373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 956 957 -0.010854 0.176869 -0.241433 0.3398147 0.0537092 -0.6791273 0.6484037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 957 958 0.203018 -0.000758 -0.115770 0.4508784 -0.2662804 0.5582523 0.6435509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 958 959 -0.115199 0.132135 -0.110974 0.5780647 0.2516727 0.5977861 0.4951301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 959 960 -0.145377 -0.054120 0.051564 0.4361973 -0.0251954 0.4052979 0.8030136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 960 961 -0.202541 -0.154808 0.052179 0.0738625 0.6832938 0.4338958 0.5825705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 961 962 0.113109 0.136926 -0.178093 0.0169408 -0.5095723 -0.8596228 0.0331333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 962 963 -0.168395 0.079433 0.019421 -0.4806178 0.4390157 0.4926547 0.5775492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 963 964 0.167098 0.245867 -0.160002 0.2751870 -0.1043828 -0.3813199 0.8763398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 964 965 -0.133159 0.075163 -0.024476 0.4239060 -0.1822346 -0.0441437 0.8860844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 965 966 0.099753 -0.033877 0.004459 0.2865383 0.1368669 0.7181701 0.6191889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 966 967 0.081897 0.037229 -0.093231 0.4033889 0.2196808 -0.2556535 0.8506815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 967 968 -0.105668 0.228763 -0.209123 -0.4388447 0.8003675 0.2259828 0.3402336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 968 969 0.079921 0.051645 -0.055880 -0.0699630 0.1058410 -0.4107744 0.9028661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 969 970 -0.001405 0.116447 0.046327 -0.1379160 -0.0892955 -0.8392736 0.5182908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 970 971 0.097745 0.019121 -0.112481 0.0580582 0.8848508 0.0988936 0.4515401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 971 972 -0.117449 -0.029321 -0.182307 0.2227764 -0.1870756 0.5440271 0.7870247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 972 973 -0.038731 0.159894 -0.206488 0.0458495 0.3639405 -0.1432545 0.9191971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 973 974 -0.020739 -0.123088 -0.075595 0.0670095 -0.1761069 0.5818546 0.7911646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 974 975 0.199883 0.074078 0.068100 -0.0376710 0.6603520 0.1465535 0.7355530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 975 976 0.099580 0.024564 -0.011934 -0.6423582 0.1345932 0.2940990 0.6948139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 976 977 0.143537 -0.144112 -0.055416 -0.5784768 -0.3920078 0.6500422 0.2985626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 977 978 -0.266545 0.164396 0.038783 -0.0691532 -0.0911874 -0.7661494 0.6323905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 978 979 -0.088853 -0.109180 0.045272 0.7381753 0.5778697 0.3183156 0.1408507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 979 980 -0.238591 0.162429 0.099793 -0.3349464 -0.2830902 0.4007951 0.8043843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 980 981 -0.129008 0.089595 0.080004 0.4243340 -0.0233142 0.6921227 0.5834066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 981 982 0.043877 -0.063859 0.041752 -0.7681153 0.3283223 -0.5426703 0.0878195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 982 983 0.035213 0.091193 -0.136096 0.3519559 0.7504686 0.0161335 0.5591634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 983 984 0.030500 -0.023630 -0.170452 -0.5753920 -0.3264057 0.1109155 0.7416745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 984 985 -0.100066 -0.013902 -0.112606 0.4335116 -0.4279053 0.2215773 0.7614908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 985 986 -0.146425 0.040652 0.105833 0.0761415 0.1766246 0.9543590 0.2284844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 986 987 0.033572 -0.186849 0.024828 0.0920412 0.1629045 -0.8730885 0.4502300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 987 988 -0.029057 0.123559 0.017786 -0.5872731 -0.3191399 -0.7425452 0.0434341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 988 989 0.166040 0.128932 0.000731 -0.2275150 0.0450049 -0.2800627 0.9315451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 989 990 0.051796 0.215587 0.003541 -0.4304876 -0.0025904 0.7397300 0.5171782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 990 991 0.064902 -0.014446 0.044240 0.1718834 0.1007393 -0.5250704 0.8274109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 991 992 0.014425 -0.151923 0.087741 0.2348161 0.7252340 -0.1095629 0.6378817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 992 993 0.015071 0.077613 0.072006 0.2289130 0.0116226 -0.5364399 0.8122167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 993 994 0.187752 -0.007724 0.009557 -0.0877503 -0.6617721 0.7163649 0.2029257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 994 995 0.090662 -0.235582 -0.068567 0.0922358 0.3668419 0.7792671 0.4996623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 995 996 -0.026497 -0.119468 -0.070406 0.5651226 0.1240835 -0.6369760 0.5094127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 996 997 0.120701 0.065830 0.152160 -0.1532415 -0.8752040 0.4134844 0.1989111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 997 998 0.010967 -0.029277 0.024804 0.7429168 -0.1363535 0.4191566 0.5037759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 998 999 -0.011582 -0.025013 -0.011204 0.0591911 0.5461458 -0.4595933 0.6978504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 999 1000 0.040029 0.028508 -0.102849 -0.3011559 -0.2756339 -0.4377470 0.8010672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1000 1001 -0.131952 -0.064452 0.083714 0.9030706 -0.1509394 -0.2598661 0.3068393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1001 1002 0.053543 0.032923 0.145202 -0.4468820 0.5548242 0.4136339 0.5668982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1002 1003 0.009525 0.022773 -0.052480 -0.3158532 0.2465259 0.8430149 0.3588698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1003 1004 0.011636 0.052182 -0.017796 0.5196569 -0.2921479 -0.2051988 0.7762086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1004 1005 -0.095703 0.035957 0.285214 -0.3706004 0.5283121 0.1904027 0.7397895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1005 1006 -0.060121 0.003671 -0.041444 -0.1373737 -0.1242225 0.1656055 0.9686444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1006 1007 -0.101829 -0.125275 0.071732 -0.1038167 -0.2727091 -0.8279702 0.4788707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1007 1008 0.002706 -0.212940 -0.077132 0.3049495 -0.2527759 -0.9076358 0.1389511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1008 1009 -0.101612 -0.076181 0.006185 -0.3238190 0.0971399 0.5790739 0.7418750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1009 1010 0.070003 0.012094 0.098669 0.3293207 -0.4230968 0.7289527 0.4256348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1010 1011 -0.015699 -0.138294 0.000287 0.1810341 0.3748232 0.6554542 0.6301698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1011 1012 -0.061050 0.091199 0.189817 -0.0376621 -0.0402083 0.9975249 0.0436908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1012 1013 0.062927 -0.124041 0.114201 -0.2054125 0.3309389 -0.3711561 0.8429284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1013 1014 -0.141065 0.171122 0.234631 0.2204596 0.3083601 0.8851997 0.2696908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1014 1015 0.109765 0.204817 -0.036583 0.1291741 0.5161360 0.4222934 0.7338842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1015 1016 -0.116009 0.059447 0.169642 -0.8171421 0.2850966 0.1492658 0.4782451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1016 1017 0.025741 -0.090540 0.031510 0.8242244 -0.0403496 -0.3360017 0.4540143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1017 1018 -0.088060 -0.009104 0.072790 -0.0199654 -0.4113566 0.8437242 0.3442625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1018 1019 0.020284 -0.076234 0.155276 0.2920142 0.2717344 -0.9101600 0.1117900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1019 1020 -0.070934 -0.099354 -0.079667 -0.6181584 0.6445704 0.3200971 0.3161439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1020 1021 -0.051411 0.047255 -0.083080 0.1449889 0.0067836 0.8802089 0.4518457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1021 1022 0.069940 -0.132427 -0.004918 -0.4481695 0.4469953 -0.6439410 0.4297432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1022 1023 0.004498 0.136674 -0.039139 0.5697585 0.5188057 -0.6169922 0.1598014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1023 1024 -0.048614 -0.231166 -0.071356 0.5106324 0.3589247 -0.7262469 0.2880852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1024 1025 0.026776 0.088484 -0.100045 -0.1119364 -0.0404646 -0.9093708 0.3985945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1025 1026 -0.065056 -0.222299 -0.131744 0.5536537 -0.1190815 0.1719022 0.8060625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1026 1027 -0.128311 0.065062 -0.043859 -0.1847371 0.6777414 0.6374670 0.3165038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1027 1028 0.126400 -0.016108 0.015034 0.5762937 0.6202271 -0.5317471 0.0211902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1028 1029 0.062776 0.034404 0.026328 0.4591776 -0.3460715 -0.6358011 0.5149247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1029 1030 0.047942 -0.001775 0.158324 0.1175304 -0.0222676 0.9063662 0.4052050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1030 1031 -0.046579 0.006642 -0.032217 -0.5953011 -0.5676676 0.4619739 0.3315875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1031 1032 0.020953 -0.061695 0.063331 0.3991154 0.0135942 0.6098739 0.6845260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1032 1033 -0.024762 -0.160582 0.015510 -0.5316007 0.6039258 0.3408168 0.4863315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1033 1034 -0.023687 -0.094410 -0.066941 0.1004940 -0.5492037 0.3172558 0.7665670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1034 1035 0.122517 0.098867 0.020900 -0.6405657 -0.0029521 0.0670085 0.7649684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1035 1036 -0.049059 0.249072 0.107965 -0.3599077 -0.0206808 0.8431339 0.3989535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1036 1037 0.145384 0.135607 -0.141808 0.0187023 0.5172988 -0.7014290 0.4899486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1037 1038 0.034138 0.045015 -0.002841 -0.3623253 0.4280598 -0.6892766 0.4586753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1038 1039 -0.046235 -0.015892 -0.021214 -0.5123308 0.4243450 -0.7307807 0.1529970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1039 1040 0.018833 -0.035049 0.234984 0.2120837 0.8381917 -0.4428023 0.2374475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1040 1041 -0.032532 -0.076982 -0.138801 0.8631328 -0.0888756 -0.3814078 0.3187962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1041 1042 0.049632 -0.109030 -0.054170 -0.5276108 -0.0590758 0.8347767 0.1458928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1042 1043 -0.046555 -0.146711 -0.053955 0.5075504 0.1749253 -0.8121854 0.2283609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1043 1044 0.026774 -0.142369 -0.124896 -0.3970530 0.5850881 0.4328464 0.5591644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1044 1045 -0.030725 -0.106308 -0.081448 -0.8304850 -0.0847799 0.1566014 0.5278096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1045 1046 -0.086171 0.035628 -0.055117 0.5321346 -0.3235800 -0.2524783 0.7405292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1046 1047 -0.049484 -0.133112 0.059067 -0.3670460 0.5015190 0.3881700 0.6804998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1047 1048 -0.027488 0.134855 0.050273 0.3000297 -0.2649583 0.3175923 0.8596013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1048 1049 -0.039835 -0.036107 -0.187341 0.1237074 -0.3173600 0.4590634 0.8205120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1049 1050 -0.193294 -0.108190 0.057188 -0.3227873 0.5878599 -0.5729417 0.4711337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1050 1051 0.006634 -0.041591 -0.062192 -0.4102810 0.3909383 0.6682493 0.4819540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1051 1052 0.013192 -0.193420 -0.154973 -0.4905238 -0.5811405 -0.6208080 0.1904193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1052 1053 -0.177151 -0.113029 -0.205711 -0.3069386 -0.3231808 -0.7880050 0.4247245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1053 1054 -0.076004 -0.105354 -0.007048 -0.2808842 0.4622355 0.8338852 0.1098996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1054 1055 0.186412 -0.113946 -0.080194 -0.2912061 -0.2392217 0.2734307 0.8849902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1055 1056 0.203140 -0.064874 -0.085806 0.2041519 0.1414002 -0.7924571 0.5570814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1056 1057 0.079465 -0.106266 -0.008662 -0.4765035 -0.3607723 -0.6719589 0.4373317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1057 1058 -0.063852 -0.026835 0.032483 0.5405107 -0.0437963 0.8044016 0.2426277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1058 1059 0.122252 -0.056143 -0.119063 -0.6164885 0.6024715 -0.5011943 0.0759888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1059 1060 -0.005741 0.129358 -0.067250 -0.5562801 0.6098317 0.1072444 0.5542169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1060 1061 -0.010338 -0.006841 -0.173076 0.8198457 0.3973335 -0.0619626 0.4076024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1061 1062 0.150583 -0.085755 0.082400 0.3810938 -0.6895554 -0.2498611 0.5628945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1062 1063 -0.053831 0.083536 -0.032219 -0.5136143 -0.8088249 -0.1604577 0.2371832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1063 1064 0.094316 0.007747 -0.157890 -0.6257498 0.0510500 -0.6630359 0.4076941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1064 1065 -0.125282 -0.152040 -0.044792 0.7131992 -0.0923115 0.5541453 0.4192237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1065 1066 -0.229364 -0.334047 -0.188125 0.1671961 0.6591774 0.0585900 0.7308200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1066 1067 0.125039 0.149143 0.009391 0.1519397 0.5451715 0.2795856 0.7755864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1067 1068 0.184703 0.048852 -0.031888 -0.9481641 -0.1037338 0.2993410 0.0248828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1068 1069 0.009557 -0.019862 -0.063944 0.0697225 0.0190174 -0.9570234 0.2808619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1069 1070 -0.082529 -0.006128 -0.017085 0.8417021 0.4048185 0.3289321 0.1395107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1070 1071 0.002860 0.138271 0.105425 0.0618406 0.8557651 -0.1435138 0.4931993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1071 1072 0.221441 -0.079749 -0.096921 0.4843159 -0.4107423 -0.4135110 0.6524857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1072 1073 0.131196 -0.122844 0.004616 0.0350270 -0.5715949 0.7610542 0.3047111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1073 1074 -0.000595 -0.126637 -0.101286 -0.8277589 0.3357812 -0.4393813 0.0949226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1074 1075 0.173443 0.086742 0.017840 0.0231468 -0.1921807 0.7636862 0.6158849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1075 1076 0.105214 -0.128985 -0.215407 -0.1755708 0.4339684 -0.5914478 0.6565332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1076 1077 0.047429 -0.104519 -0.090315 0.3705504 -0.0078733 0.9075939 0.1972405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1077 1078 -0.114610 -0.051307 0.107923 0.2495632 0.2065461 0.4135197 0.8509162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1078 1079 0.057796 -0.049860 -0.018616 -0.4652669 0.5850501 0.4254778 0.5101096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1079 1080 -0.130603 0.153604 -0.057771 0.0580151 -0.5396563 -0.3045167 0.7827355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1080 1081 0.075311 0.049183 -0.005387 -0.5957063 0.1003817 -0.4899225 0.6285169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1081 1082 -0.001468 -0.134797 0.042480 0.2959315 -0.1794325 -0.2792117 0.8956949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1082 1083 -0.099475 0.081587 -0.002866 0.3625482 0.1941603 -0.6032913 0.6833010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1083 1084 0.026145 0.122276 0.014208 -0.5551441 -0.1922667 -0.7894289 0.1779059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1084 1085 0.222690 -0.125401 -0.159742 0.4783533 -0.4900955 0.2004463 0.7005753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1085 1086 -0.014980 -0.020826 -0.013486 -0.3809538 -0.2156904 0.8147517 0.3801730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1086 1087 0.017706 -0.072881 -0.264568 0.6599328 0.3101916 -0.6311757 0.2643617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1087 1088 -0.009795 0.022831 0.187874 -0.0557407 0.0311067 -0.7123304 0.6989355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1088 1089 -0.093178 0.045422 0.167881 0.1783356 0.4515512 0.7851667 0.3844621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1089 1090 -0.003675 0.169386 -0.213809 -0.2636923 -0.7054411 -0.6508033 0.0963030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1090 1091 0.061520 -0.035603 0.069595 0.1977750 0.8682522 0.2574100 0.3751844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1091 1092 -0.132312 0.037473 -0.070266 -0.5767692 -0.3868765 0.4982962 0.5190037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1092 1093 -0.074332 -0.016609 0.051634 0.0390418 -0.7370177 0.6747443 0.0008713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1093 1094 -0.029558 -0.012120 0.103029 -0.0573076 -0.4372609 -0.1672545 0.8817849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1094 1095 0.053651 -0.067769 0.124045 0.2580653 0.3854334 0.5150671 0.7207976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1095 1096 -0.110929 -0.025635 0.069862 0.7409641 -0.3410526 -0.3575071 0.4548011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1096 1097 -0.054976 0.075798 -0.030663 0.0203149 -0.6057228 -0.6656947 0.4353594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1097 1098 -0.012888 0.183240 0.104211 -0.0786979 0.2926621 -0.1339984 0.9435041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1098 1099 -0.102208 -0.020908 0.030710 0.1741987 -0.5525980 -0.4340373 0.6898564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1099 1100 0.166182 -0.069046 0.069789 0.2527264 -0.0593304 0.7952305 0.5479213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1100 1101 0.066549 -0.062906 0.088888 -0.5900240 0.4325763 -0.6073676 0.3096029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1101 1102 -0.081415 0.008318 -0.101300 0.3551178 -0.6320697 0.3302875 0.6043918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1102 1103 0.137716 0.136415 -0.102663 0.4277042 0.5116602 -0.6198160 0.4136437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1103 1104 0.121277 -0.153725 0.211154 0.3800070 -0.5817058 -0.6232551 0.3588400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1104 1105 0.131780 -0.131557 -0.078934 0.0970476 -0.6374034 0.1427212 0.7509522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1105 1106 0.056534 0.058379 -0.072879 -0.4649185 0.3741478 -0.7973460 0.0900196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1106 1107 -0.050748 -0.139051 0.132760 0.4306159 0.0752861 0.6725422 0.5971508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1107 1108 -0.084857 -0.282271 -0.060341 -0.9286462 -0.1404947 0.2827730 0.1947228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1108 1109 0.126377 0.055442 -0.226163 -0.3128805 0.9110293 -0.2469178 0.1056551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1109 1110 0.218498 0.068034 0.101707 0.6099409 0.7141306 0.0327288 0.3419333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1110 1111 -0.076998 0.140770 0.082396 -0.0845541 -0.3471960 0.9170817 0.1768242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1111 1112 0.116421 0.106288 -0.037342 0.1868582 0.2844114 -0.9395343 0.0383320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1112 1113 0.002762 0.108179 -0.028457 0.4458580 -0.4811235 0.1306634 0.7434097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1113 1114 -0.205642 -0.003275 0.232009 -0.2504773 0.2067931 0.4326369 0.8410250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1114 1115 -0.046941 0.035968 -0.001263 -0.1303575 0.0901900 -0.3351797 0.9287235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1115 1116 -0.047515 -0.023427 -0.043631 -0.4107982 -0.2614888 -0.7680157 0.4159570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1116 1117 0.081743 0.053275 0.031188 0.5148252 0.5096419 -0.5668313 0.3923295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1117 1118 -0.091786 0.001109 0.105222 -0.0494562 -0.3187578 -0.9298171 0.1771661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1118 1119 -0.132331 0.032397 0.057426 0.6238213 0.4008229 -0.4238788 0.5201104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1119 1120 -0.091721 -0.128500 0.006559 -0.2666995 0.7562627 0.5607550 0.2061359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1120 1121 -0.018182 -0.024653 -0.103499 -0.0235264 -0.0650440 0.8951441 0.4403781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1121 1122 -0.104839 -0.247944 -0.039046 -0.6560688 0.2660086 -0.6164411 0.3446934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1122 1123 0.118438 0.122391 -0.145822 -0.4361441 0.6852398 -0.1396314 0.5663283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1123 1124 0.114280 -0.080696 0.032250 0.4019362 0.8391565 -0.3647566 0.0348748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1124 1125 0.046220 0.158846 0.168932 0.3960880 0.0807559 0.3512749 0.8445109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1125 1126 0.021329 -0.075347 0.016377 -0.2663767 0.2956613 0.8979436 0.1879500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1126 1127 -0.091712 -0.073142 -0.103240 -0.1486990 0.1544557 0.9672732 0.1357007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1127 1128 -0.103265 -0.159093 -0.052094 -0.2226938 -0.4528523 -0.1753594 0.8453292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1128 1129 -0.284170 -0.056991 -0.026803 -0.0031339 -0.0554104 -0.9552853 0.2904305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1129 1130 0.062766 0.096085 -0.020529 0.4079657 0.5855777 0.6434322 0.2768713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1130 1131 0.021406 -0.011110 0.134090 -0.3363495 0.5380671 0.6602011 0.4018549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1131 1132 -0.006802 0.152734 -0.059527 0.4034923 0.2343855 -0.7343265 0.4929726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1132 1133 0.077869 -0.132229 -0.057481 0.3564041 0.4267215 0.5532519 0.6203203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1133 1134 0.015651 -0.082981 -0.115870 0.0264775 -0.9800224 -0.1302495 0.1479532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1134 1135 -0.110583 0.070267 0.019442 -0.6469389 0.4443838 0.4855634 0.3849952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1135 1136 0.152991 0.085438 -0.181482 0.2720166 -0.0571780 0.9302737 0.2394339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1136 1137 -0.013829 0.199065 -0.013570 0.4134855 -0.0743756 -0.3590779 0.8334033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1137 1138 0.133832 -0.099149 -0.056292 -0.8048935 -0.4236787 -0.3800269 0.1679949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1138 1139 -0.141685 0.170075 -0.032926 0.3511560 0.6102587 -0.6909635 0.1638389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1139 1140 0.064452 -0.165356 0.009866 -0.4100821 -0.2542184 -0.5743098 0.6613425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1140 1141 0.113068 0.106816 -0.039262 0.1314486 0.2081156 0.3109566 0.9179952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1141 1142 0.016843 -0.024075 -0.076006 -0.6740580 0.3062824 0.6715819 0.0285415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1142 1143 -0.029745 -0.028724 -0.025816 -0.4267770 -0.4749454 -0.6160339 0.4612922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1143 1144 0.063678 0.151340 0.012587 -0.0557680 -0.6678248 0.5323437 0.5172138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1144 1145 -0.002556 0.173556 -0.035747 0.4127643 0.8000518 -0.1256185 0.4168485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1145 1146 0.085759 -0.074582 0.025629 -0.4350599 -0.3579060 -0.3773294 0.7350161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1146 1147 -0.173134 0.003835 -0.060644 0.3469949 -0.5759821 0.2566359 0.6942458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1147 1148 -0.017049 0.277030 0.002917 0.4857652 0.3667415 0.0070541 0.7933997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1148 1149 0.031008 0.064881 -0.150705 0.1029102 0.3883577 -0.5903201 0.7000785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1149 1150 0.084093 -0.026624 -0.131852 0.3236748 -0.2209986 0.4481243 0.8034792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1150 1151 0.198274 -0.136662 -0.061467 -0.4762887 -0.0706651 -0.5155272 0.7087928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1151 1152 -0.114227 0.102291 -0.085348 0.1670722 -0.4674376 0.6111090 0.6165507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1152 1153 0.090979 -0.073894 -0.059282 -0.0136764 -0.1225531 0.5394403 0.8329453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1153 1154 0.014715 0.142585 -0.138430 -0.0236367 0.3505578 0.9281006 0.1232060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1154 1155 0.047692 0.056253 0.087904 0.0896071 -0.2742789 -0.7936087 0.5356556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1155 1156 -0.137871 0.071024 -0.193387 0.3867829 0.1590904 0.1838514 0.8895436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1156 1157 -0.118851 -0.013026 0.035364 -0.8228888 0.0981553 0.3402585 0.4443464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1157 1158 0.160820 0.163168 -0.123542 0.3455010 0.3550759 -0.5839528 0.6430780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1158 1159 0.064830 0.071246 -0.110115 -0.0695648 -0.6946744 0.6689163 0.2552237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1159 1160 -0.019614 0.042690 0.204959 0.7612123 -0.0074597 0.0140588 0.6483075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1160 1161 -0.136734 -0.134762 -0.152516 -0.6331768 0.4408127 0.4422259 0.4573922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1161 1162 0.029025 0.035895 0.126325 0.3538476 0.3748985 -0.4248908 0.7441174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1162 1163 0.170038 0.013110 -0.004617 0.2954809 -0.0667018 0.8738814 0.3802277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1163 1164 -0.109517 0.042681 0.072951 -0.3150236 -0.0816526 -0.6038162 0.7276668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1164 1165 0.098405 0.103847 -0.014841 0.4251682 0.4086538 -0.7817735 0.2026431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1165 1166 -0.071320 0.006048 -0.136762 0.5002867 0.6693313 -0.5483343 0.0322237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1166 1167 0.176637 0.166277 -0.000373 0.1834976 0.1876360 0.4838674 0.8348615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1167 1168 0.207979 -0.005019 0.102437 -0.5847155 -0.4909813 0.0355735 0.6448098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1168 1169 -0.209290 -0.184793 -0.063243 -0.0104335 -0.6285099 0.2075029 0.7495392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1169 1170 0.037253 -0.051973 -0.127447 0.5019582 0.4500730 -0.4653639 0.5735056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1170 1171 -0.066920 -0.106647 0.036718 -0.0281745 -0.4018878 0.8542981 0.3284313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1171 1172 0.247117 -0.007918 0.080100 0.3224942 0.7788348 0.0882786 0.5306795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1172 1173 -0.033620 0.223194 0.020164 0.2431901 -0.1809401 -0.9514001 0.0543788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1173 1174 -0.031375 0.082788 0.029669 0.1811419 0.8896194 0.0365037 0.4176510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1174 1175 0.101853 0.064323 0.021311 -0.5328116 0.5574498 -0.0721580 0.6325779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1175 1176 -0.132517 -0.099660 0.147639 -0.2627862 0.3296936 0.5141122 0.7469499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1176 1177 0.056882 0.062831 0.026941 -0.9134998 -0.2971412 -0.0407386 0.2748920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1177 1178 0.071534 -0.032220 0.096402 -0.6124224 0.6299238 -0.4264434 0.2151297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1178 1179 -0.049451 -0.226553 -0.092075 0.1783298 0.7074260 -0.4830829 0.4841259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1179 1180 0.046397 0.174282 0.100943 -0.0231032 -0.2514495 -0.4380606 0.8627527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1180 1181 -0.041076 0.069824 -0.146854 0.2738399 0.0246948 0.0037772 0.9614508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1181 1182 -0.100027 0.204092 0.207388 -0.2207658 -0.0879803 -0.9696095 0.0581315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1182 1183 0.127566 0.075704 0.001094 -0.1307939 0.6034476 0.7355684 0.2787168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1183 1184 -0.091598 0.056569 -0.134798 -0.1846570 -0.7771415 -0.1737355 0.5759939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1184 1185 0.172929 0.099360 0.120803 0.4345872 0.4734067 -0.5503253 0.5330686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1185 1186 0.037386 -0.057081 -0.076219 -0.8717838 0.3241511 0.3642720 0.0471703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1186 1187 0.102803 0.142518 0.051167 -0.3556465 -0.1024172 0.2794949 0.8859508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1187 1188 -0.032799 -0.011708 -0.055494 -0.2264831 -0.2650285 0.8185617 0.4565326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1188 1189 -0.093427 -0.047527 0.039806 0.4481687 -0.6810112 0.5525681 0.1733118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1189 1190 0.091549 -0.171391 0.012120 0.4884556 0.5593476 0.3353340 0.5797349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1190 1191 -0.064497 0.030176 0.020339 0.0497536 0.1237854 -0.4423289 0.8868748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1191 1192 -0.052399 0.146662 0.077809 0.1851224 0.8490796 -0.4745631 0.1399410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1192 1193 -0.016654 0.039385 -0.031445 0.6466219 -0.3256238 0.3583765 0.5894196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1193 1194 0.017215 -0.125076 0.078511 -0.5742291 0.0400003 -0.4041084 0.7108849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1194 1195 0.061332 -0.030264 0.087764 0.8309460 0.0349101 0.5530630 0.0493088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1195 1196 0.042752 0.138661 0.051463 -0.8375752 0.0158051 -0.0220732 0.5456471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1196 1197 0.107143 -0.032673 -0.057594 -0.1309222 -0.4059212 0.8365405 0.3439292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1197 1198 0.064136 -0.022147 0.139433 0.2105752 -0.2947062 0.4762842 0.8012239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1198 1199 -0.042989 0.078409 -0.002851 0.5024096 0.1047632 -0.8552035 0.0723613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1199 1200 -0.096504 -0.069318 0.021468 0.3777087 0.4095157 -0.3602633 0.7482268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1200 1201 -0.071306 0.041568 -0.076126 -0.0879017 -0.1215539 -0.2470098 0.9573318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1201 1202 0.000089 -0.033292 0.099182 0.5317464 0.4051580 0.1119672 0.7352252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1202 1203 -0.137837 0.075586 -0.012888 0.2967328 0.2927720 -0.8048939 0.4223505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1203 1204 -0.058340 0.152382 0.031464 0.3372745 -0.8180343 0.4460962 0.1344028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1204 1205 0.017671 -0.139024 0.110703 0.2190497 0.1931347 -0.0445539 0.9553696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1205 1206 -0.021551 0.076686 0.059609 0.1672006 -0.8320437 0.5083259 0.1461234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1206 1207 0.160990 -0.210585 0.077193 0.9385358 0.1721995 0.2543887 0.1574301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1207 1208 0.017056 0.056139 -0.081528 -0.1605908 0.2018263 0.2131142 0.9423689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1208 1209 0.036364 -0.010284 -0.011795 -0.6443168 0.2266582 -0.2595636 0.6827215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1209 1210 0.012771 0.026804 0.003288 -0.0344167 0.0726371 0.4108668 0.9081453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1210 1211 0.003571 0.004114 0.038581 -0.3119365 -0.5317882 -0.1041596 0.7804151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1211 1212 0.007621 -0.113224 0.091108 0.2247562 0.3800575 0.2389956 0.8648249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1212 1213 0.059187 0.022812 0.032460 -0.5322840 -0.4840284 -0.1934306 0.6670643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1213 1214 -0.033340 0.035009 0.146663 -0.5972463 0.0503057 -0.7889926 0.1351180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1214 1215 -0.024992 0.038562 -0.014484 -0.3615443 0.1574856 0.9054519 0.1569739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1215 1216 0.015971 -0.014270 -0.007860 0.0682245 -0.8375659 0.1547579 0.5194985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1216 1217 0.059405 -0.122025 -0.104805 0.7349654 0.6200219 -0.0166458 0.2740833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1217 1218 -0.070001 -0.109608 0.059015 0.3117230 -0.4288423 -0.6672108 0.5232139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1218 1219 0.056141 0.157736 0.014959 -0.2395050 -0.1513145 0.2863067 0.9152976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1219 1220 0.183405 -0.114231 0.121333 -0.2071136 0.2737551 0.6289371 0.6975674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1220 1221 0.116536 -0.083361 0.136772 -0.1786920 0.2577848 0.1609239 0.9357989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1221 1222 -0.186457 0.011979 -0.014513 -0.0205088 -0.9597319 0.0519586 0.2753076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1222 1223 -0.162051 0.018854 0.166044 -0.9742113 0.1141877 -0.1942368 0.0120687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1223 1224 0.149062 0.059107 -0.078108 0.1595181 0.3229951 -0.2851442 0.8882122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1224 1225 0.076806 -0.218290 -0.043474 -0.2600342 0.4844614 -0.6946901 0.4637726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1225 1226 0.084493 -0.078703 -0.026060 0.5086730 0.3249056 -0.7970859 0.0184995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1226 1227 0.013572 -0.170187 -0.135365 -0.0027640 0.4674359 0.8830720 0.0409876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1227 1228 -0.078094 0.045722 0.007800 -0.4066436 0.5871017 0.6314977 0.3019325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1228 1229 0.001036 -0.036915 0.081021 -0.1564859 0.2602378 -0.9386234 0.1636292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1229 1230 0.003342 0.074295 -0.107132 -0.5324367 0.6823462 -0.4921183 0.0934577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1230 1231 -0.083926 0.120866 0.017272 0.4104634 0.4798702 0.1303767 0.7643601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1231 1232 0.090842 0.041090 0.387356 0.2994648 0.8448625 -0.4035455 0.1835191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1232 1233 0.000352 -0.062803 -0.102060 0.3932498 0.0939269 0.6205633 0.6718880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1233 1234 -0.018896 0.008148 0.071908 0.0157762 -0.7959231 0.0431668 0.6036506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1234 1235 0.117685 -0.095720 0.115947 0.2702674 -0.2906653 0.7420812 0.5401710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1235 1236 -0.025355 -0.112738 -0.021661 -0.1643933 0.6362336 -0.4845129 0.5774331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1236 1237 -0.049504 -0.001176 -0.034018 0.0148671 -0.3873367 0.7638365 0.5160457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1237 1238 -0.054654 0.016741 -0.125635 0.5331072 0.5625896 -0.5430859 0.3230285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1238 1239 -0.009314 0.129706 0.075355 0.8799680 -0.2396214 -0.3653540 0.1864250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1239 1240 0.025593 0.054237 -0.157218 0.0002018 0.6891421 0.5480486 0.4740526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1240 1241 -0.006172 0.078990 -0.004023 0.1928156 -0.6462600 -0.6251994 0.3928051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1241 1242 -0.076973 -0.336585 -0.056581 -0.7463023 -0.6474875 0.0894439 0.1256689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1242 1243 0.093734 -0.029188 0.141008 0.2923853 -0.1782778 0.8378734 0.4250836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1243 1244 -0.031558 -0.114391 0.057465 -0.4624041 -0.3893609 -0.3303012 0.7249011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1244 1245 -0.143127 0.199964 -0.080683 0.8320953 0.2588796 0.0167522 0.4902226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1245 1246 0.000878 -0.157930 -0.102910 -0.3258266 0.1185312 -0.8061069 0.4795614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1246 1247 0.036012 0.139066 -0.256339 -0.7548134 -0.0512712 0.6419320 0.1247047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1247 1248 0.028167 0.069620 0.131295 -0.3845595 -0.7473368 -0.3313716 0.4287127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1248 1249 -0.220578 0.009939 0.088138 0.2613673 0.7568359 0.2021114 0.5639482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1249 1250 -0.017587 -0.183012 -0.154777 -0.5226744 -0.2157038 0.7345278 0.3751697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1250 1251 0.084714 0.073398 -0.101080 -0.0920408 0.1496083 0.8762836 0.4486346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1251 1252 -0.154418 -0.028773 -0.002192 0.5343233 -0.6045933 -0.1707193 0.5655267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1252 1253 0.149908 -0.148773 -0.141329 0.0997850 -0.6109568 -0.0268999 0.7848892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1253 1254 0.019163 0.126022 0.133768 0.7802009 -0.4309904 -0.4496817 0.0576211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1254 1255 -0.034701 0.119146 -0.153113 0.5367773 -0.6871246 -0.4763372 0.1132825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1255 1256 -0.151282 0.063291 -0.058257 -0.6652122 0.2869408 0.1580314 0.6709574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1256 1257 0.053638 0.202984 0.124976 0.6867882 0.1075469 0.4920460 0.5240672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1257 1258 0.040983 -0.162885 -0.167399 0.3616696 0.4790499 0.7879252 0.1374053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1258 1259 -0.145468 0.003926 -0.021073 -0.0690018 0.7734331 -0.0081134 0.6300589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1259 1260 0.096358 -0.055103 0.105867 -0.4393675 -0.7357773 0.3628660 0.3659456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1260 1261 0.001150 0.194787 -0.049222 0.2062278 0.3505318 -0.0783210 0.9101996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1261 1262 -0.012382 -0.063190 -0.028218 0.4622923 0.0289255 -0.8158695 0.3461301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1262 1263 0.108810 -0.099469 -0.063670 0.2170345 -0.2725603 0.0288737 0.9368955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1263 1264 0.084363 -0.004969 0.043847 -0.3602240 -0.0445468 -0.2519410 0.8970953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1264 1265 -0.248558 -0.103013 -0.004959 0.4413280 -0.3704630 0.1012916 0.8110036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1265 1266 0.178384 -0.058081 -0.051538 -0.5118983 0.1548477 0.1678670 0.8281322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1266 1267 -0.060989 0.069506 -0.035835 -0.2463846 0.0508049 -0.8903256 0.3795180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1267 1268 0.018593 0.119120 0.006779 0.2531723 0.5316032 0.3723558 0.7173932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1268 1269 0.041120 0.117996 0.199847 -0.0041057 0.8877937 0.4485905 0.1028200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1269 1270 0.010365 -0.261010 0.051515 -0.3729296 0.4282350 -0.5616865 0.6017031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1270 1271 0.027369 0.111686 -0.106739 0.6230455 -0.0616564 -0.5378874 0.5645264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1271 1272 -0.094068 -0.311263 -0.135988 0.0122824 0.1326257 0.7039764 0.6976222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1272 1273 -0.058127 0.020167 -0.097070 -0.5478881 0.3058114 -0.2359168 0.7420520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1273 1274 -0.025859 0.017608 -0.006003 -0.2408236 -0.3041142 0.8928227 0.2288805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1274 1275 0.073870 0.142770 -0.082117 0.1547063 0.3834569 -0.8681566 0.2744647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1275 1276 -0.012628 -0.169456 -0.068489 -0.0377864 0.4505080 0.8762246 0.1668688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1276 1277 0.135178 0.157333 -0.012974 -0.1513910 0.8394412 0.0882527 0.5144227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1277 1278 0.083542 0.046359 -0.014688 0.0170423 -0.6989137 0.1704919 0.6943786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1278 1279 -0.099478 -0.000224 -0.102103 -0.5447275 0.7306764 -0.3387486 0.2337377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1279 1280 0.129291 -0.117298 0.123103 0.0805278 -0.4765951 0.1411953 0.8639655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1280 1281 0.024292 -0.006625 -0.175052 -0.0994452 -0.4650869 -0.5358518 0.6976157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1281 1282 0.257321 0.154128 -0.109933 0.6770562 0.4169240 0.2941748 0.5303117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1282 1283 0.232987 0.023626 0.019968 0.5951713 0.0247906 0.7398119 0.3127858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1283 1284 -0.037749 -0.046549 0.052103 -0.5188767 0.3791387 -0.6900277 0.3329903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1284 1285 -0.062041 -0.080638 0.090396 0.1049507 -0.4472517 0.5544497 0.6939285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1285 1286 0.113277 -0.094549 0.019508 0.8737195 0.1155217 -0.0267360 0.4717564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1286 1287 -0.014821 0.132511 -0.044068 0.6926921 0.6232493 0.3292126 0.1528297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1287 1288 0.005901 0.193674 0.287168 -0.0676478 0.8832521 0.3685729 0.2818572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1288 1289 -0.006637 0.063036 0.073551 0.0740242 0.0892986 -0.1301237 0.9846898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1289 1290 -0.047211 -0.016278 0.171662 0.1034645 0.0460361 0.5970164 0.7941960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1290 1291 -0.109445 0.226477 -0.259126 0.0863757 0.1904969 0.7898327 0.5765540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1291 1292 0.116972 0.142788 -0.040171 0.0048735 -0.0234983 -0.9910664 0.1311922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1292 1293 -0.038221 0.041443 0.053637 -0.6781123 0.2594200 0.6825028 0.0839933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1293 1294 -0.214498 -0.062713 -0.063693 0.4708770 -0.5967324 -0.1290582 0.6368118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1294 1295 0.038925 -0.063257 -0.134118 -0.7700432 0.1828854 -0.4163929 0.4474408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1295 1296 -0.247773 -0.051417 0.187510 0.6097441 -0.3603044 -0.1061731 0.6979400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1296 1297 -0.221167 0.038989 -0.047143 -0.1466708 -0.4124502 -0.6836704 0.5839240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1297 1298 -0.026244 0.166415 0.127158 -0.2168465 -0.3064187 0.9123038 0.1636672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1298 1299 -0.144957 0.117764 0.100029 0.5455364 0.0684491 -0.6562596 0.5167477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1299 1300 -0.070050 -0.085342 0.044617 -0.0286392 -0.1274759 -0.3467117 0.9288276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1300 1301 -0.088229 0.002993 0.089430 0.2755592 0.0048193 -0.1342875 0.9518460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1301 1302 -0.023143 0.175880 0.019782 -0.7881916 -0.2929506 0.1059529 0.5307617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1302 1303 -0.025058 -0.056998 -0.006975 -0.3124304 0.8163112 -0.3563786 0.3301781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1303 1304 0.107896 0.095790 0.212139 -0.2582685 -0.3828228 0.8098781 0.3617203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1304 1305 -0.016122 -0.084957 0.091988 -0.6306595 -0.2454621 0.3452602 0.6502402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1305 1306 -0.050587 -0.054166 0.046479 0.0530260 -0.1984595 0.8921837 0.4022564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1306 1307 0.057832 -0.069419 -0.023077 -0.0826598 0.0426820 0.9016746 0.4222897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1307 1308 0.163109 -0.012553 0.038407 -0.3380085 -0.1408248 0.8511895 0.3760253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1308 1309 0.015443 0.025111 -0.064544 -0.2328502 0.0450672 0.9699265 0.0547014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1309 1310 -0.020221 0.240926 -0.015495 -0.5422204 -0.4184518 -0.5595445 0.4666959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1310 1311 -0.059822 -0.170401 0.005134 -0.5525242 0.5323313 0.1728488 0.6176275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1311 1312 0.008050 -0.014447 0.131690 0.6291429 0.2558640 -0.7142467 0.1690104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1312 1313 0.157163 0.142988 0.118736 0.3788148 -0.4749543 -0.1964439 0.7696282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1313 1314 0.168248 0.213685 -0.079972 0.0778058 -0.2673241 -0.7242379 0.6308435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1314 1315 0.046885 -0.009199 0.024454 -0.3749728 -0.4848055 0.5720428 0.5450927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1315 1316 0.055459 -0.099589 0.161176 -0.2871964 0.8156293 -0.4789109 0.1513655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1316 1317 -0.018347 0.012703 -0.071758 -0.0193884 0.5099097 -0.4120596 0.7548662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1317 1318 0.093535 0.032858 -0.295239 -0.3626227 0.8391457 -0.3536306 0.1982039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1318 1319 0.038842 -0.069142 0.017780 0.3916051 -0.4183185 0.8040843 0.1584409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1319 1320 0.115129 -0.010946 0.074029 0.4297971 0.5821721 0.4618231 0.5129031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1320 1321 -0.043598 0.008199 0.153142 0.3313587 0.5805074 0.5343140 0.5174177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1321 1322 0.174096 -0.094360 -0.167050 0.7199734 0.1612354 0.3341038 0.5865288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1322 1323 -0.154057 0.191836 -0.111402 -0.8128850 0.3832334 -0.1473027 0.4131007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1323 1324 0.022954 0.003411 -0.111886 0.2539836 -0.5983024 0.4674789 0.5991578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1324 1325 -0.159411 0.008615 -0.042080 -0.0472638 0.2659298 0.9480284 0.1681950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1325 1326 -0.018482 0.052640 -0.105890 -0.4592777 -0.6436847 -0.2344471 0.5654809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1326 1327 -0.029286 0.147085 -0.055274 0.0102244 0.1006533 -0.2670555 0.9583558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1327 1328 -0.081338 -0.028474 -0.009115 0.4867829 -0.1757457 -0.0170879 0.8554904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1328 1329 0.015821 0.024996 -0.022061 -0.4147779 0.0610642 -0.0818375 0.9041754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1329 1330 -0.029418 0.211367 -0.066503 -0.1182233 0.2182984 -0.9243402 0.2897659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1330 1331 0.058650 -0.106061 -0.132101 -0.0021496 -0.1898167 -0.9709191 0.1458803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1331 1332 -0.157236 0.000569 -0.159474 -0.6648498 -0.2395108 0.1420966 0.6931218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1332 1333 -0.055883 0.066417 -0.087804 0.3440268 0.0829635 0.4412328 0.8246673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1333 1334 0.019046 0.096176 -0.007140 0.7079368 -0.2454736 0.6576914 0.0775256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1334 1335 0.044330 -0.199490 0.061967 -0.3568404 0.0772565 -0.7785614 0.5104298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1335 1336 0.067806 0.177035 -0.135578 -0.1833099 0.4983252 0.8439307 0.0764881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1336 1337 0.051677 -0.065736 -0.163769 -0.5750565 0.3377799 0.7227567 0.1812111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1337 1338 0.147751 -0.010785 0.064249 0.5258379 -0.1562064 -0.7972434 0.2519861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1338 1339 -0.026294 0.049987 -0.118638 -0.0997852 0.2810856 -0.9543519 0.0156921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1339 1340 -0.047180 -0.042611 -0.020004 -0.0166313 0.1365788 -0.8582542 0.4944384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1340 1341 -0.261083 -0.109101 -0.082176 0.3198696 -0.2751961 -0.2983676 0.8561118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1341 1342 0.030033 -0.109450 -0.036320 -0.7448124 0.5775830 0.2872338 0.1707313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1342 1343 0.068331 0.039831 -0.048600 0.6689199 -0.0971798 -0.4743452 0.5640025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1343 1344 -0.056903 -0.068480 -0.059439 -0.5502438 0.1860714 0.6166731 0.5313412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1344 1345 0.185010 0.190982 -0.104321 -0.1163614 -0.1136889 0.7389707 0.6538021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1345 1346 0.049862 -0.008856 -0.035737 -0.5538757 0.4930111 0.4499148 0.4977333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1346 1347 0.058561 -0.075187 -0.036392 -0.1944705 -0.0047479 -0.3801321 0.9042446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1347 1348 0.082354 0.123352 -0.019305 0.8039208 0.1418491 -0.2825515 0.5037408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1348 1349 -0.187969 0.111090 -0.259931 -0.7420315 -0.3573062 -0.2037720 0.5293378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1349 1350 0.074098 0.150885 -0.027208 0.0758271 0.2987647 0.4781397 0.8224186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1350 1351 0.055336 0.048231 0.037669 0.7505844 0.0367498 0.3337933 0.5690822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1351 1352 0.078874 -0.112822 -0.000327 -0.8637498 0.0327435 0.4960289 0.0825806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1352 1353 0.038671 -0.143703 -0.064727 0.7952129 -0.1269326 -0.5527966 0.2143374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1353 1354 0.045049 -0.038219 -0.073175 -0.6278073 -0.6306991 0.2867619 0.3547454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1354 1355 -0.147279 -0.073288 0.001175 -0.5255351 0.2515778 -0.7036381 0.4067122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1355 1356 -0.094574 0.037704 0.138871 -0.2154076 -0.6514165 -0.4292334 0.5873797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1356 1357 -0.223952 -0.107568 -0.006889 -0.5215284 0.2120547 0.6311659 0.5335453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1357 1358 -0.102373 0.048637 0.122800 0.3834562 0.3651780 -0.7812127 0.3306254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1358 1359 0.321768 -0.133191 0.020224 -0.2117154 0.1359586 0.1823218 0.9505002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1359 1360 -0.089802 0.102331 0.063409 -0.4113185 -0.6491538 -0.4777482 0.4256442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1360 1361 -0.067704 -0.162853 0.099662 0.5462346 0.7793114 0.0982123 0.2909568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1361 1362 0.066871 -0.146075 0.027559 -0.3054695 -0.4870556 0.8171391 0.0418205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1362 1363 0.067355 0.084643 0.199302 -0.6500598 0.5856053 -0.2909740 0.3870695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1363 1364 -0.065368 0.011861 0.123203 0.2585282 -0.1872477 0.9250132 0.2060388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1364 1365 -0.135642 0.051807 0.071871 0.5072325 0.1051827 -0.5991303 0.6104872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1365 1366 0.045100 -0.040827 -0.044755 -0.2895995 0.1970278 -0.8686807 0.3502942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1366 1367 -0.045709 0.066372 -0.249359 0.6244114 0.6174137 -0.4254230 0.2189203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1367 1368 0.077616 -0.006590 -0.025773 -0.0311980 -0.8647293 0.0541918 0.4983304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1368 1369 -0.161585 0.025204 -0.099268 -0.5617187 0.7141379 0.3388291 0.2442827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1369 1370 -0.059786 -0.071035 0.090954 0.6453727 0.0332288 0.1765278 0.7424472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1370 1371 -0.002820 0.147336 -0.089989 0.0747187 -0.3377074 0.0150746 0.9381597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1371 1372 0.185684 -0.346713 -0.062932 0.3535198 0.1710256 -0.7991571 0.4551065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1372 1373 -0.054005 -0.108581 -0.057834 0.1846680 -0.1836168 -0.8777621 0.4021396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1373 1374 -0.014946 0.059924 -0.148226 0.7112609 0.4004336 0.1190995 0.5653107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1374 1375 -0.177760 -0.092691 0.009398 -0.1047046 -0.8634311 -0.3933053 0.2980514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1375 1376 -0.012146 0.010129 0.049424 0.1811675 -0.6631591 -0.5511060 0.4729487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1376 1377 -0.041005 0.043327 -0.062572 -0.4915045 0.0605885 0.1945939 0.8466910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1377 1378 -0.083745 0.022141 -0.316475 0.3424612 -0.1578963 0.4023396 0.8342134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1378 1379 -0.023016 0.002799 -0.065172 -0.7236957 -0.1526882 0.1785631 0.6488961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1379 1380 0.172109 -0.065498 -0.006330 0.5383488 0.5678224 0.1214404 0.6107459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1380 1381 0.004853 -0.084300 0.071350 0.7048164 -0.2680565 -0.5771852 0.3134275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1381 1382 -0.120896 -0.080687 -0.043542 -0.1756321 -0.0725580 -0.0480029 0.9806041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1382 1383 0.030202 -0.126487 -0.162304 -0.1221284 -0.0437023 -0.1118914 0.9852183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1383 1384 -0.063607 -0.141861 -0.031235 0.6276082 0.2349262 -0.7145942 0.2006805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1384 1385 -0.112428 -0.002729 0.182546 0.0553743 0.0347527 -0.9853896 0.1572680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1385 1386 -0.091136 0.223536 0.084957 -0.0218092 0.5795733 0.6005827 0.5503813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1386 1387 -0.142727 -0.087677 -0.155499 0.5539530 -0.3380107 -0.6510842 0.3936676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1387 1388 -0.087289 -0.093528 0.096329 -0.2053928 0.0471206 0.2991926 0.9306327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1388 1389 -0.085430 -0.055123 0.003733 -0.3349951 0.2241892 0.3165586 0.8586665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1389 1390 -0.155688 0.030494 -0.011526 0.1227618 0.2385440 0.9586536 0.0949185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1390 1391 0.144307 0.117239 0.184873 0.6288740 0.0490093 0.7705295 0.0916508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1391 1392 -0.084409 -0.106051 0.116005 0.3727850 -0.1888319 -0.6942795 0.5859607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1392 1393 -0.078709 -0.022527 0.033197 -0.0126440 0.3138996 0.7257610 0.6120279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1393 1394 -0.062428 0.043594 0.041102 -0.4092856 -0.3605754 -0.4519792 0.7058226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1394 1395 0.048944 0.029353 -0.203853 0.3410127 0.9357080 0.0161913 0.0888749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1395 1396 -0.004326 0.038893 -0.014278 -0.1820004 0.8737894 0.4421424 0.0887578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1396 1397 -0.187849 -0.077372 0.039432 0.1086951 -0.5541266 -0.0504151 0.8237642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1397 1398 0.088246 0.008203 0.103454 -0.3961650 0.3949149 0.5071066 0.6556968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1398 1399 -0.068352 0.121598 0.101222 0.0159844 0.2290641 -0.8126654 0.5355829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1399 1400 -0.028562 -0.205645 0.134094 -0.0605412 0.4711977 -0.8032997 0.3591894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1400 1401 0.086433 -0.184739 0.024005 0.9444054 -0.1301659 -0.0484194 0.2980115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1401 1402 -0.115501 0.143066 0.037957 -0.7963073 0.1842435 0.5579863 0.1435280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1402 1403 -0.057008 0.039457 -0.042911 0.8204211 -0.2968030 0.1161077 0.4746958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1403 1404 0.019123 -0.008496 0.023941 0.1606545 -0.5247763 -0.5847424 0.5973913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1404 1405 0.029875 0.215638 0.187003 -0.6154427 -0.1257648 0.7770493 0.0400992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1405 1406 -0.199037 -0.002480 -0.121436 0.4479928 -0.5736714 0.5944892 0.3417399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1406 1407 0.053707 -0.066426 0.131020 0.1326632 -0.3564659 -0.3682999 0.8483441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1407 1408 0.191544 0.019197 0.019808 0.6023405 0.6334039 0.4401317 0.2055957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1408 1409 0.078920 -0.090783 0.026052 -0.4908907 0.4271379 0.6056900 0.4579512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1409 1410 0.097307 -0.037231 -0.020825 0.7354095 0.2772824 -0.5021960 0.3606751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1410 1411 -0.142533 -0.062567 0.047924 -0.4716881 -0.6165502 0.3353670 0.5337651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1411 1412 -0.092007 -0.028209 0.005317 0.0687586 -0.2332095 -0.8860258 0.3947706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1412 1413 0.072637 -0.088350 0.019012 0.8104207 0.3067085 0.4805851 0.1348559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1413 1414 0.204294 -0.138210 -0.077698 0.3002774 -0.2180017 0.9244891 0.0873427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1414 1415 -0.031344 0.029686 0.108325 -0.2626783 -0.0267937 0.0421466 0.9635901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1415 1416 0.012628 0.066523 0.041593 0.3899109 -0.5252999 0.5839729 0.4806300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1416 1417 0.199764 0.010273 0.054097 -0.6595097 -0.4642211 -0.5633025 0.1795438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1417 1418 -0.134417 0.052806 -0.020117 -0.0556790 0.5356210 0.7585176 0.3669619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1418 1419 0.074139 0.255876 0.041769 0.2643425 -0.1218130 -0.9564132 0.0236314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1419 1420 0.077689 -0.058808 0.002069 0.1409995 0.2353482 -0.9596860 0.0611002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1420 1421 0.088932 -0.009445 0.123455 -0.2678528 0.4834778 -0.5887372 0.5898242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1421 1422 -0.105158 0.091390 0.084866 -0.7214365 -0.2740042 -0.6350230 0.0345974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1422 1423 0.165539 -0.022215 0.160025 -0.7246109 0.0423768 0.6779112 0.1165317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1423 1424 0.021462 -0.095479 0.083332 0.6169690 -0.2996771 0.6000242 0.4117206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1424 1425 -0.010570 0.061836 0.148818 0.3187099 0.0446219 -0.5709598 0.7552733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1425 1426 0.089274 0.047474 0.110095 0.7133379 -0.1882376 -0.5430631 0.4009966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1426 1427 -0.079495 -0.010174 0.069064 0.2169827 0.3939827 -0.8368870 0.3119556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1427 1428 -0.113004 -0.074919 -0.133616 0.0702276 0.3709878 -0.9138704 0.1492550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1428 1429 0.144393 -0.164079 -0.368653 -0.3406613 -0.4108074 -0.3138625 0.7852881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1429 1430 0.130018 -0.018403 -0.156813 -0.5291569 0.3609108 -0.6675337 0.3796513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1430 1431 -0.148589 -0.106165 0.045727 0.4847759 -0.3334144 0.4233170 0.6889339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1431 1432 0.079732 0.091944 -0.041741 0.5361779 -0.4007669 0.7420562 0.0353801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1432 1433 0.053486 0.122360 -0.008359 0.5495430 0.0667686 -0.1858021 0.8118017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1433 1434 0.149705 -0.027257 -0.078491 -0.1017958 0.1088344 -0.2503719 0.9566121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1434 1435 0.073762 0.032445 -0.018945 -0.7499773 0.2691801 0.0397675 0.6029052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1435 1436 -0.019730 -0.130465 0.150501 -0.7388170 -0.4887247 0.1959766 0.4205839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1436 1437 -0.203778 0.237791 -0.300630 0.7107947 -0.3366390 0.0978043 0.6098192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1437 1438 0.030724 0.040621 -0.184421 0.0282842 0.1643596 -0.9487955 0.2682777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1438 1439 -0.074434 0.069980 -0.109459 0.1664663 -0.0125170 -0.9301408 0.3270632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1439 1440 -0.051208 -0.041015 -0.084141 -0.7373408 -0.0597957 -0.2108122 0.6389924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1440 1441 -0.113152 -0.131798 -0.089837 -0.7822796 0.2451972 -0.5702109 0.0526921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1441 1442 0.017926 -0.090192 0.036892 -0.6779295 0.4560798 -0.0966186 0.5683904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1442 1443 -0.206650 -0.005935 -0.085338 -0.2078909 -0.5413234 0.7848237 0.2186369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1443 1444 -0.057382 0.155542 -0.020937 0.0488295 -0.4757719 0.8580893 0.1869212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1444 1445 0.021745 0.103729 0.064741 -0.4911212 0.7408770 -0.1742924 0.4237021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1445 1446 0.060681 -0.116551 0.035276 -0.0557502 -0.3683214 -0.3981141 0.8382938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1446 1447 -0.074496 0.043425 0.236179 0.1362473 0.2476333 0.3761815 0.8823842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1447 1448 0.083788 -0.050221 -0.087962 0.8414831 -0.3165724 0.3695586 0.2347651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1448 1449 0.046390 -0.102120 -0.240033 0.4228942 0.1439990 0.8762693 0.1804909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1449 1450 -0.113255 0.168558 -0.077505 0.1404290 0.8022692 -0.5729827 0.0912946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1450 1451 -0.043044 0.289068 0.000944 -0.1674622 -0.4307073 -0.6047557 0.6486279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1451 1452 -0.097212 -0.101159 -0.055229 0.1918167 0.2507536 -0.7033509 0.6368881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1452 1453 -0.009892 0.005635 0.022339 -0.1782494 -0.3085569 -0.7660596 0.5349510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1453 1454 0.096418 -0.081706 -0.112799 -0.1537960 0.3809978 -0.8635886 0.2922366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1454 1455 0.033143 -0.017086 0.009833 0.5342091 -0.0134355 0.8432286 0.0583582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1455 1456 -0.132619 -0.208542 0.143550 -0.5074496 0.3037452 0.5758938 0.5644290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1456 1457 0.320918 0.137821 0.112923 -0.2463691 0.5357016 -0.4283781 0.6847030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1457 1458 0.145392 0.097194 0.092317 -0.4709805 -0.5315197 0.5963097 0.3742713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1458 1459 -0.062366 0.008738 -0.035273 -0.2483405 0.0805938 -0.5214885 0.8123308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1459 1460 0.061258 0.098996 0.038272 -0.0325958 0.3956241 -0.4259391 0.8130160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1460 1461 0.085282 0.158092 -0.111597 0.4153368 0.6181988 -0.6188991 0.2495788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1461 1462 0.061066 0.036203 -0.148572 -0.6079192 0.3328315 0.7174790 0.0698663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1462 1463 0.178156 -0.026203 -0.063891 -0.4827486 0.1164954 0.2082928 0.8426130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1463 1464 -0.119565 -0.034637 -0.013642 0.1760993 -0.0636953 -0.3902976 0.9014431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1464 1465 -0.115910 0.126505 0.012511 0.3865161 -0.4713610 -0.6681087 0.4266789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1465 1466 -0.066814 -0.086954 -0.019785 -0.1368835 -0.6895745 -0.4582737 0.5438154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1466 1467 0.066886 -0.063418 0.185225 0.0686254 0.0224565 0.8582924 0.5080555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1467 1468 -0.221766 -0.161478 0.312192 -0.1908604 0.4017149 -0.5238073 0.7265146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1468 1469 -0.128586 0.046012 0.071918 0.5306698 0.0695570 0.6946467 0.4806425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1469 1470 -0.127517 0.215712 -0.107624 -0.2678131 0.2081197 -0.7328426 0.5898339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1470 1471 0.076589 -0.010801 -0.101623 -0.5408887 -0.0899022 -0.4791537 0.6853968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1471 1472 -0.001554 -0.041182 -0.106882 -0.0393889 0.1120235 0.2439426 0.9624922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1472 1473 0.102188 0.054076 0.040291 0.1255307 0.0855958 -0.9391707 0.3080159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1473 1474 0.011563 -0.024298 -0.025056 -0.0515336 0.3256731 0.9083754 0.2571681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1474 1475 -0.101880 -0.058035 0.056809 0.8296956 -0.2261133 -0.0417712 0.5086583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1475 1476 -0.072605 -0.092830 0.099203 -0.4381105 0.2670893 -0.1193805 0.8499828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1476 1477 0.016554 0.053118 0.195584 -0.3324074 0.0774025 0.9091421 0.2386941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1477 1478 -0.053555 0.036951 0.011455 -0.1257365 0.5138927 -0.2891876 0.7977939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1478 1479 -0.031934 0.040938 -0.189755 0.1242072 -0.1681743 -0.8956510 0.3925548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1479 1480 -0.075383 0.081140 0.050933 -0.2883109 0.1934976 0.0961278 0.9328424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1480 1481 -0.037174 -0.060654 0.018491 -0.3894366 -0.2752123 -0.6663448 0.5732207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1481 1482 -0.053530 0.091629 -0.060660 -0.0642008 0.1720162 0.6442204 0.7424748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1482 1483 0.011001 0.136321 0.154773 0.0223445 -0.0333853 -0.0711184 0.9966586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1483 1484 0.061468 -0.049645 0.033761 0.7109724 0.5072868 0.3061827 0.3787223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1484 1485 0.196381 -0.044966 0.261736 -0.3122377 0.0367167 -0.9491514 0.0164661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1485 1486 -0.081336 -0.153152 0.045579 -0.9623958 -0.0501785 -0.2563000 0.0747447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1486 1487 0.071383 -0.156770 0.180700 0.5353709 0.7022519 0.1345639 0.4495695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1487 1488 0.022679 -0.051134 0.173255 -0.2858215 0.0344262 -0.4410247 0.8500695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1488 1489 0.010662 0.058862 0.002351 -0.5585545 0.7058300 0.3638148 0.2397074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1489 1490 0.119159 -0.172827 -0.016180 -0.6265507 0.0993411 0.6295325 0.4486139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1490 1491 0.060908 0.120184 0.043599 0.1452131 0.0553947 0.8883293 0.4321060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1491 1492 -0.107243 -0.024529 -0.044223 0.6036221 -0.2870558 0.7421082 0.0501482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1492 1493 -0.096313 -0.053711 0.086617 0.7200649 -0.4542123 0.2292974 0.4718267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1493 1494 0.141071 -0.129424 0.039768 0.8456086 0.2364283 0.2331377 0.4179647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1494 1495 0.039180 0.229258 -0.015847 0.5829901 0.5006398 0.5150798 0.3797038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1495 1496 -0.180069 0.041350 -0.043402 -0.3074509 0.2343607 0.8451914 0.3690534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1496 1497 0.076868 -0.174293 0.232679 0.0905725 0.5220049 -0.7029496 0.4745201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1497 1498 0.023398 -0.127465 0.071389 0.2583209 0.1231902 -0.1901450 0.9391163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1498 1499 0.143544 -0.055186 0.099224 -0.6075929 -0.0893668 -0.7653692 0.1924954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1499 1500 0.074389 -0.049052 0.037533 -0.7393596 -0.0212060 -0.5200580 0.4271268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1500 1501 -0.081634 0.024824 0.093246 -0.0960045 0.0285662 -0.7602066 0.6419136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1501 1502 0.174654 0.149776 0.273252 0.3475448 0.3087590 -0.1112642 0.8783512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1502 1503 -0.172112 -0.024096 0.057549 -0.3223010 -0.5545061 0.2333557 0.7308831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1503 1504 -0.066866 0.028049 -0.082467 0.3446576 0.2370022 -0.4273419 0.8015110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1504 1505 0.008459 0.111881 -0.012230 -0.6162863 0.2606480 0.5918703 0.4493811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1505 1506 -0.012470 -0.092466 0.027888 0.5836668 -0.5149575 0.6102208 0.1475886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1506 1507 0.076473 -0.093524 -0.025055 -0.7403419 0.5241095 -0.3448308 0.2414432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1507 1508 0.150790 -0.154552 -0.023169 -0.3257646 0.3904196 -0.5785376 0.6377650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1508 1509 0.010523 -0.100477 -0.045186 -0.6814850 0.3808466 -0.5849458 0.2199373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1509 1510 -0.024639 -0.110424 -0.028502 0.2977200 0.6198720 0.3276663 0.6478860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1510 1511 -0.015018 -0.150356 -0.119276 -0.3643077 -0.0772346 0.3255195 0.8691098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1511 1512 -0.230645 0.066269 -0.026450 0.7699113 -0.1691604 -0.5127554 0.3401519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1512 1513 -0.163282 0.055892 -0.004181 -0.3351917 -0.1991941 0.8636451 0.3195079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1513 1514 0.245059 -0.124494 -0.209833 0.0351676 0.6855785 -0.1365716 0.7142084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1514 1515 0.077672 0.069930 0.030191 0.1098614 0.4997173 -0.7501950 0.4188324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1515 1516 -0.222557 0.035043 -0.187868 0.0198817 0.1257204 0.9660900 0.2246534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1516 1517 -0.027980 0.088849 -0.178476 -0.2985698 -0.0340662 -0.0388837 0.9529867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1517 1518 -0.070150 -0.033081 0.025919 -0.3557356 0.2624961 0.0650926 0.8946010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1518 1519 0.018661 0.075897 -0.158178 -0.6906071 -0.2130342 0.6786716 0.1307027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1519 1520 -0.115819 -0.103683 -0.198262 0.3203884 0.5466983 -0.6579631 0.4068869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1520 1521 -0.204047 0.021199 0.113635 0.2710875 -0.3314701 -0.7707250 0.4718285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1521 1522 -0.023873 -0.147081 -0.023484 -0.4081161 0.2840131 -0.4641791 0.7330181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1522 1523 0.058273 -0.025277 -0.040625 -0.0645988 0.4829720 -0.6259002 0.6089451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1523 1524 0.101525 -0.203448 0.032887 0.3406244 -0.6712912 0.6038249 0.2621804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1524 1525 -0.110234 -0.064975 0.211340 -0.5075692 0.6859319 0.0242179 0.5208497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1525 1526 -0.008742 0.138648 -0.046086 -0.0324801 0.1007971 -0.1137078 0.9878540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1526 1527 -0.065015 0.060439 -0.028054 0.7568235 0.5142189 -0.3480282 0.2041407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1527 1528 0.105924 0.017697 -0.076258 -0.3107355 0.3812659 0.8406933 0.2265271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1528 1529 -0.022954 -0.045448 0.120789 -0.4676111 0.1005601 -0.3401306 0.8096534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1529 1530 0.029165 0.025719 0.082980 0.2012726 0.5215222 -0.5315684 0.6363481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1530 1531 0.029890 0.034682 -0.005638 0.5447785 -0.7884525 -0.1705835 0.2290420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1531 1532 0.052757 0.002009 -0.157937 0.0835210 -0.0799600 -0.3384933 0.9338377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1532 1533 -0.053074 0.031175 -0.093081 -0.4854355 0.0010260 -0.7320786 0.4779249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1533 1534 -0.180318 0.113822 -0.067836 -0.2847577 -0.7794239 0.4522575 0.3269169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1534 1535 0.132808 -0.000359 0.024006 0.6695123 0.0147303 0.7405612 0.0557260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1535 1536 -0.092160 -0.121183 -0.116328 -0.4240824 -0.0756145 0.4923674 0.7563140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1536 1537 0.012018 0.043609 -0.024933 -0.4225566 0.5227340 -0.5722800 0.4697773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1537 1538 -0.109107 -0.165563 0.053112 0.1455970 -0.5815755 0.5912030 0.5394909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1538 1539 -0.161008 0.145557 0.046055 -0.1647345 0.1828654 0.3217624 0.9142712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1539 1540 -0.119358 0.196479 -0.190005 0.3734593 -0.9166114 0.1390572 0.0318567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1540 1541 0.112252 0.088138 0.094338 -0.0167674 0.5742645 0.3464321 0.7415685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1541 1542 -0.015142 0.029389 0.045800 0.4465838 0.3841238 -0.8067751 0.0461052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1542 1543 -0.260056 -0.099440 -0.252272 -0.6914188 -0.3461281 -0.4198557 0.4752437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1543 1544 -0.179761 0.120919 0.056287 0.8049521 -0.1056600 -0.3748452 0.4476373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1544 1545 -0.060307 0.075665 0.128146 -0.3705021 -0.7490440 -0.3658652 0.4096388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1545 1546 -0.014149 -0.158175 0.093374 -0.3509531 0.2681108 -0.2910394 0.8486722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1546 1547 -0.047464 -0.093279 0.051987 -0.0174984 0.6360871 0.7687491 0.0641243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1547 1548 -0.009415 -0.106397 -0.000613 -0.0670772 -0.0353149 0.7588059 0.6468903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1548 1549 0.006015 -0.030292 0.063500 -0.3392013 0.0224548 0.9370189 0.0802108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1549 1550 -0.025345 -0.257372 0.024317 -0.4605007 0.2365386 0.8408925 0.1577605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1550 1551 -0.340758 -0.168774 -0.197046 -0.3128085 -0.5724492 0.6245675 0.4293811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1551 1552 -0.117312 0.174563 -0.033569 -0.3588632 -0.8368290 0.2537416 0.3264193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1552 1553 0.081486 0.081655 -0.012076 -0.6578693 -0.5140830 0.3457973 0.4281949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1553 1554 0.143649 -0.141806 0.055687 0.1372793 0.2850225 -0.6715148 0.6700630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1554 1555 -0.046207 0.075155 0.034612 0.2675689 0.2617658 0.8950986 0.2422478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1555 1556 0.078289 -0.245703 -0.031633 -0.0619036 -0.3369821 -0.3306148 0.8793776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1556 1557 0.216068 -0.059430 -0.060890 0.5330826 0.5791626 -0.6154564 0.0400877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1557 1558 0.115139 -0.054416 -0.056829 0.3604377 -0.0015898 0.8514642 0.3809079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1558 1559 0.093861 -0.038651 -0.075825 0.5109309 -0.7524488 -0.3612107 0.2056629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1559 1560 -0.067940 0.002716 -0.010100 0.0338414 -0.8129729 0.0079749 0.5812626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1560 1561 -0.001627 -0.068396 0.009527 -0.2599475 0.8928849 0.2584114 0.2615481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1561 1562 0.023279 -0.148883 0.051473 -0.1990681 -0.4987681 0.7662316 0.3528335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1562 1563 -0.077194 0.007063 0.204359 0.3888801 0.8416415 -0.0342577 0.3731465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1563 1564 0.198312 0.233702 0.023371 -0.2482563 -0.5200624 0.5716893 0.5840165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1564 1565 -0.143221 -0.099261 -0.183157 0.3316102 0.7546435 0.1427846 0.5478691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1565 1566 0.210389 0.001899 -0.044479 0.2559975 -0.9061771 -0.3365965 0.0033321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1566 1567 -0.175668 -0.069451 0.054482 -0.2620078 0.0686511 -0.7743890 0.5718047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1567 1568 0.027290 0.031220 -0.143952 0.3442831 0.5825893 -0.6384509 0.3666597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1568 1569 -0.036129 -0.085529 0.074356 0.8408793 0.0360881 -0.2417298 0.4828936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1569 1570 0.035554 0.095855 -0.102196 -0.1411622 -0.4424064 -0.0836643 0.8816746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1570 1571 -0.147519 -0.123361 -0.137434 -0.3503988 -0.2381327 0.5282330 0.7358555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1571 1572 0.069338 0.185103 0.056811 0.2688139 0.3749935 0.5629280 0.6857339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1572 1573 0.111521 -0.043974 0.034935 0.0353747 0.2844339 0.8128596 0.5070555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1573 1574 0.005186 0.031870 -0.040619 -0.7386623 0.4906882 0.3646986 0.2838980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1574 1575 -0.017114 -0.020027 -0.245108 0.4274360 -0.0399610 -0.8343748 0.3457170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1575 1576 -0.052088 0.134131 0.027531 0.0052421 0.2011560 -0.0287073 0.9791245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1576 1577 0.157743 -0.118327 -0.140761 0.3555034 -0.6633783 -0.0648656 0.6552396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1577 1578 -0.059157 -0.138452 0.026704 0.4583855 0.1039205 0.6670179 0.5780748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1578 1579 -0.041728 -0.138781 0.335618 0.3777170 0.0418408 -0.2292340 0.8961200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1579 1580 -0.120031 -0.074843 -0.163670 -0.6569964 0.4072423 -0.5925520 0.2266971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1580 1581 0.002141 -0.212908 0.041184 -0.6339440 -0.2632433 0.7109353 0.1529343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1581 1582 0.112995 0.073149 -0.108821 -0.0386705 0.2989115 0.6214331 0.7231717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1582 1583 0.043578 -0.070835 0.132543 0.3463800 -0.6815757 -0.6206338 0.1740378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1583 1584 0.014843 0.044009 0.018324 -0.1328709 -0.1760197 0.8886237 0.4021321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1584 1585 0.250630 0.099076 0.035218 -0.1856620 -0.2851194 0.9279466 0.1521565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1585 1586 0.017664 -0.042560 -0.141930 -0.0694207 -0.1391655 -0.3539915 0.9222276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1586 1587 0.146537 0.187348 0.129680 0.3016375 0.3390910 -0.7061385 0.5435076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1587 1588 -0.077758 -0.087465 -0.255022 0.4238634 -0.1987600 0.8577210 0.2124831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1588 1589 0.203115 0.127649 0.111160 0.2937707 0.2907653 0.8431980 0.3437607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1589 1590 0.016278 -0.020714 -0.056333 0.4301664 -0.7010714 0.0445316 0.5669856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1590 1591 -0.096311 -0.024641 -0.083009 -0.6495410 -0.0836932 0.4222024 0.6267671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1591 1592 -0.017387 -0.083186 -0.071382 -0.0752149 0.1547936 0.9822836 0.0741661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1592 1593 0.053683 0.033427 0.032674 -0.6414807 0.0083012 -0.4714433 0.6051238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1593 1594 0.135477 0.031244 0.164727 0.5995637 -0.4817481 0.1875006 0.6109711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1594 1595 -0.039012 -0.024633 0.060710 0.5417270 -0.2083813 -0.2469149 0.7759782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1595 1596 0.001408 -0.075285 -0.019491 -0.7170185 -0.4602102 -0.5038104 0.1423593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1596 1597 0.021212 0.022313 -0.027306 0.5916046 0.6016982 0.0322428 0.5356525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1597 1598 -0.086501 -0.022170 -0.126088 0.6911434 -0.2165574 -0.6673025 0.1735830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1598 1599 0.111843 -0.086121 0.039157 0.4786669 -0.1163881 0.3270947 0.8064372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1599 1600 -0.104536 0.077971 -0.000525 0.0593074 0.6538982 0.7172876 0.2332344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1600 1601 0.067136 -0.131981 0.217986 -0.0349751 -0.2292876 -0.1516913 0.9608297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1601 1602 0.000122 0.008812 -0.003557 -0.5107326 -0.2069639 -0.6907590 0.4681561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1602 1603 0.058950 0.072779 0.010294 -0.1865893 0.3547575 0.5267934 0.7495467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1603 1604 -0.280205 0.106177 -0.013063 -0.6898343 -0.4345426 0.0234676 0.5785765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1604 1605 -0.085829 -0.221043 0.027591 0.7802528 0.0573108 0.0565398 0.6202615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1605 1606 0.000287 0.117047 -0.055763 -0.4130302 0.1063606 0.7471838 0.5097154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1606 1607 0.034100 0.079888 0.212558 0.3559247 0.1999456 0.8561834 0.3166847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1607 1608 0.049137 -0.059251 0.087324 -0.2279342 0.9027210 0.3053207 0.1998000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1608 1609 -0.103549 0.080282 -0.155583 -0.2400225 -0.1931148 -0.7673279 0.5624090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1609 1610 0.033835 -0.095441 0.039722 0.4555855 0.8120575 -0.3547676 0.0845247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1610 1611 -0.027115 -0.112402 -0.084928 0.4007198 -0.4265803 -0.8014887 0.1227545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1611 1612 -0.016987 0.263325 0.019997 0.0421227 0.5738928 0.4683305 0.6704770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1612 1613 0.003822 -0.146894 0.163567 -0.3381641 0.4672675 -0.3133276 0.7544083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1613 1614 -0.040886 0.054914 -0.024421 0.0702672 -0.3105940 0.5055017 0.8019114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1614 1615 -0.045986 -0.084588 0.010779 -0.0286252 -0.0161912 -0.4096249 0.9116611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1615 1616 -0.083532 0.078132 0.008931 0.3351931 -0.2211325 0.8628792 0.3068966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1616 1617 -0.012692 0.059157 0.037196 0.6091668 0.5004213 0.5659353 0.2412709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1617 1618 0.037530 -0.094567 -0.051153 0.1155746 -0.3753100 -0.8620733 0.3203351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1618 1619 -0.202969 0.102235 0.050375 -0.1238398 -0.5126738 0.6590564 0.5361660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1619 1620 0.037137 0.151109 -0.245393 -0.4754215 0.2523671 -0.7800034 0.3191865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1620 1621 -0.034443 0.024248 -0.055363 -0.4709162 0.1963839 -0.6173531 0.5987875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1621 1622 0.060672 0.019434 0.086203 -0.2519547 0.6488852 -0.4946545 0.5203688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1622 1623 0.020019 0.095601 0.073408 0.2600993 -0.0087404 -0.5790374 0.7726498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1623 1624 0.018902 0.059823 -0.026879 0.2163250 0.0123025 -0.9678637 0.1276402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1624 1625 -0.027150 0.046003 -0.011785 -0.5466180 0.2373566 0.7408225 0.3099236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1625 1626 -0.124482 0.063344 -0.050929 -0.6813018 -0.3380652 -0.6359531 0.1307805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1626 1627 0.179792 -0.010713 -0.078847 -0.2724305 0.4030172 -0.5796819 0.6537030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1627 1628 0.101902 -0.121157 -0.037504 0.5183153 0.5311184 0.3489462 0.5722753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1628 1629 0.032967 -0.039216 0.141231 0.0959385 -0.1808782 0.9386380 0.2775564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1629 1630 -0.187148 -0.141685 -0.143364 -0.6958681 0.7049664 -0.0951831 0.0986413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1630 1631 0.017594 -0.053353 0.057949 0.3070146 0.2121466 0.6244594 0.6861387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1631 1632 -0.129155 0.016844 -0.215385 0.3319238 -0.5868376 0.1559637 0.7218888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1632 1633 0.078564 0.010066 0.038993 0.2426544 -0.1774778 -0.6723234 0.6764627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1633 1634 -0.055412 -0.161996 0.007505 0.0046173 0.7446587 0.6353828 0.2043302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1634 1635 -0.133312 -0.007152 0.018982 -0.4767687 0.6175973 0.1072827 0.6162431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1635 1636 -0.052782 0.054848 -0.040190 -0.2545813 0.0531624 0.5360513 0.8031259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1636 1637 -0.002118 -0.187598 -0.114431 -0.1631339 -0.2998421 0.6401039 0.6882943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1637 1638 -0.162108 0.020421 0.108904 0.2246271 0.2759018 0.3069825 0.8827132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1638 1639 0.076287 0.025044 -0.016293 -0.0994167 0.4142856 0.7089153 0.5620701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1639 1640 0.018289 -0.062178 -0.159312 -0.0349757 -0.8049441 0.5239317 0.2762919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1640 1641 -0.214115 -0.244300 0.025497 0.8770744 -0.0955205 0.1609290 0.4424004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1641 1642 -0.024097 -0.128759 -0.033353 0.1653840 0.3080831 -0.3590512 0.8653410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1642 1643 0.012761 0.043530 -0.136900 -0.3590164 -0.4274347 0.6774892 0.4789731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1643 1644 -0.167348 -0.010425 0.003930 0.5475772 0.6581273 -0.1951828 0.4784677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1644 1645 -0.002959 -0.181499 -0.003190 -0.4293217 -0.3052733 0.5809049 0.6205164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1645 1646 -0.130399 0.021937 -0.101902 -0.1261818 0.0105276 0.7935864 0.5951370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1646 1647 0.146125 0.184425 -0.138296 -0.1071852 -0.1536984 0.7485909 0.6360030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1647 1648 0.146952 0.103121 -0.236081 -0.1820342 0.2585684 0.9466302 0.0624274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1648 1649 0.057555 0.044045 -0.060936 0.4464044 -0.3324159 -0.7623238 0.3302806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1649 1650 -0.019179 -0.168594 -0.063056 0.2559822 -0.1427582 -0.5139129 0.8062176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1650 1651 0.122086 0.131417 -0.130813 0.0626729 0.3488120 0.8425108 0.4056819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1651 1652 -0.112538 -0.011348 -0.032412 0.2030497 0.2123525 0.2776165 0.9146618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1652 1653 -0.184430 -0.087150 0.166514 0.0844069 0.9403540 0.3175228 0.0882558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1653 1654 0.144278 -0.092354 -0.004304 -0.8660637 -0.2917847 -0.0668382 0.4004098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1654 1655 0.059228 0.069631 0.084415 0.2456449 0.5096571 -0.5243945 0.6363322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1655 1656 -0.076619 0.097207 -0.102919 0.5789683 0.0170688 -0.8051633 0.1273439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1656 1657 0.066305 0.096036 -0.028250 0.1250576 -0.2042989 0.4891334 0.8386722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1657 1658 0.040197 -0.089287 0.045051 -0.8579170 -0.2526739 -0.3795985 0.2367260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1658 1659 -0.097335 0.286249 0.034412 0.9029263 0.0628669 0.4225758 0.0469213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1659 1660 -0.060160 0.022794 -0.051253 0.8706451 0.2390519 0.4285147 0.0347351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1660 1661 0.168010 -0.167249 0.054036 0.2843521 0.1392796 -0.9174693 0.2408220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1661 1662 0.076061 -0.039644 0.148990 -0.7026221 -0.3649871 0.3408937 0.5068512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1662 1663 0.036817 -0.023956 -0.051555 -0.1095628 -0.2327450 -0.6675859 0.6986808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1663 1664 -0.143678 0.004513 -0.050661 0.6057043 0.5145954 0.4365614 0.4215780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1664 1665 0.099734 -0.151037 0.095083 0.3834231 0.3612239 -0.1289672 0.8401615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1665 1666 0.094775 -0.096495 -0.070441 0.0096508 -0.3557324 -0.7017018 0.6172325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1666 1667 0.101212 -0.036146 -0.090124 0.7600869 -0.1985477 -0.6154145 0.0641226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1667 1668 -0.035825 -0.047261 -0.008588 -0.2015900 0.6200907 0.7518414 0.0978959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1668 1669 0.068954 -0.022996 -0.009470 -0.1651669 -0.3188170 -0.9324067 0.0411494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1669 1670 -0.114787 -0.120592 0.010024 0.5136997 0.2248285 -0.7218687 0.4055493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1670 1671 -0.157239 0.035967 0.063114 -0.1667857 0.6427801 0.7308998 0.1574856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1671 1672 0.055087 0.078147 -0.053163 -0.2791010 -0.8594550 -0.4282219 0.0081089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1672 1673 -0.102200 -0.043175 0.154416 0.2757695 -0.7305095 -0.6112905 0.1289612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1673 1674 0.063149 0.045021 0.089742 -0.2148129 -0.0501634 0.6876401 0.6917298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1674 1675 0.159619 -0.014500 0.018409 0.0454494 0.5397184 0.8110433 0.2210138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1675 1676 -0.024022 0.133282 -0.265425 -0.3962042 -0.6916802 -0.2491650 0.5500159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1676 1677 -0.001824 -0.086579 0.062441 0.5547675 -0.4357814 0.5772845 0.4111814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1677 1678 -0.035625 -0.032925 -0.023575 0.0392019 0.3998411 -0.1623110 0.9012466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1678 1679 0.025939 -0.024530 0.083621 0.3357601 -0.2608151 0.3573301 0.8315984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1679 1680 0.018071 0.164826 0.086510 0.4423514 0.0498973 0.5061049 0.7387106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1680 1681 -0.049775 0.100952 -0.029356 -0.1934412 0.5108877 -0.3188265 0.7745476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1681 1682 -0.023193 0.133888 -0.039544 -0.3457147 0.2626649 0.8706379 0.2312533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1682 1683 0.095444 0.185982 0.016971 -0.2741522 -0.3161460 0.0339140 0.9076024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1683 1684 -0.013373 0.010260 -0.128099 0.0570010 0.1657922 -0.8344085 0.5225191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1684 1685 -0.091195 -0.077069 0.116539 -0.1209592 0.8100402 0.5699349 0.0661664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1685 1686 0.044772 -0.055891 -0.092672 -0.5574182 0.5973414 0.5320831 0.2221617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1686 1687 0.059968 -0.010845 -0.136195 0.1848767 -0.3489665 -0.3352816 0.8553533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1687 1688 -0.082747 0.081435 -0.134938 -0.3308746 -0.1471702 -0.7429387 0.5629432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1688 1689 -0.133589 0.061283 0.228142 0.0605612 -0.5502744 -0.7766866 0.3004804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1689 1690 -0.101030 0.003380 -0.003508 -0.1979704 0.1653948 0.8310192 0.4928076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1690 1691 0.053220 0.068788 0.018981 -0.0280632 0.3447451 -0.7659801 0.5418836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1691 1692 0.003141 -0.065783 0.156634 -0.5118906 0.0839000 -0.3192739 0.7930908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1692 1693 0.024035 -0.235408 -0.049298 0.7586937 -0.2889672 0.4871597 0.3218032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1693 1694 -0.011503 0.089248 -0.249452 -0.3137474 0.2005593 0.5480874 0.7489585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1694 1695 -0.040525 0.095706 0.062108 -0.4050841 -0.0301795 0.4864573 0.7735344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1695 1696 0.023986 -0.038823 0.169912 -0.1705663 0.0165066 -0.1475636 0.9740943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1696 1697 0.001085 0.024724 0.011669 0.7889392 -0.1715193 0.5477591 0.2193536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1697 1698 0.226768 0.080818 0.021355 -0.4828142 -0.2346336 -0.7425841 0.4005076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1698 1699 0.098260 0.014543 -0.061559 -0.0230648 -0.4906318 0.8695884 0.0506405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1699 1700 0.080624 -0.250636 0.164286 0.2838173 0.4613971 -0.1625115 0.8247124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1700 1701 -0.328189 0.163002 -0.128848 -0.1431468 -0.9427180 0.2639731 0.1452924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1701 1702 -0.141903 -0.209465 0.133639 0.3446543 0.6864856 -0.0992936 0.6325280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1702 1703 0.080597 0.086003 -0.025864 0.1418622 0.6059833 -0.2507082 0.7414882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1703 1704 -0.026774 -0.139185 0.024124 0.2268335 0.4040932 -0.7655942 0.4462295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1704 1705 0.136130 -0.084245 -0.023486 0.1154244 0.8293537 -0.3126671 0.4484295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1705 1706 -0.007390 -0.044054 0.151588 0.2467247 -0.1591425 -0.3020775 0.9069453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1706 1707 -0.142910 -0.089972 -0.007217 0.1670616 0.2020174 -0.1010100 0.9597272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1707 1708 -0.053535 0.170296 0.040402 0.2603085 0.3795262 -0.8581081 0.2277056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1708 1709 0.013566 0.056316 0.063607 0.6965603 0.2091514 -0.6051980 0.3237204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1709 1710 -0.140940 0.053325 0.106421 0.3304241 0.0707873 -0.7065665 0.6217498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1710 1711 -0.000718 0.051094 -0.155302 -0.0744601 0.1628200 0.7748951 0.6062037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1711 1712 -0.104404 0.018804 0.055188 0.1197416 0.0993936 0.9786184 0.1344953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1712 1713 0.116215 -0.081599 -0.038987 0.0204722 0.3963976 -0.8200649 0.4122419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1713 1714 0.105682 -0.024351 0.007697 -0.5676872 0.1026582 -0.2087275 0.7896996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1714 1715 0.094624 0.082569 0.149223 -0.1037588 -0.0170677 0.9566979 0.2714257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1715 1716 -0.042410 0.193643 0.243323 -0.1302467 -0.0628016 -0.9090969 0.3906848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1716 1717 0.107426 -0.012649 -0.061975 0.1707377 0.3678871 -0.6514804 0.6411560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1717 1718 0.041423 0.092468 0.056661 0.5640394 -0.2240103 -0.7814457 0.1449879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1718 1719 -0.117735 -0.000428 0.201712 -0.5031777 0.6587483 0.5565789 0.0555235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1719 1720 -0.107699 0.167464 0.051200 -0.0523246 -0.5316406 -0.7490967 0.3917583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1720 1721 0.069025 -0.070531 -0.047374 -0.1497946 0.1182567 0.8172232 0.5438043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1721 1722 -0.089161 0.056541 0.125157 0.4097519 0.3920789 -0.7195995 0.4006919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1722 1723 0.028346 0.004023 -0.028299 0.5282357 0.4454687 -0.7104968 0.1331128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1723 1724 -0.087324 -0.065140 0.078191 -0.2201924 -0.4209574 -0.3978884 0.7848535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1724 1725 0.017834 -0.177140 0.011021 -0.1296818 0.9600281 0.0078244 0.2479265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1725 1726 -0.053992 -0.045255 0.014728 -0.0008263 -0.6253100 -0.0194925 0.7801325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1726 1727 0.063501 0.113699 -0.025331 0.6560504 -0.6487144 0.2727504 0.2727174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1727 1728 0.100296 0.189534 -0.026837 0.8632495 0.3605203 0.3320044 0.1208244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1728 1729 0.030257 -0.062849 0.145688 -0.5673089 0.1585772 0.3947470 0.7051161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1729 1730 0.034574 -0.035532 0.162426 -0.0907249 -0.6382672 0.6925245 0.3237187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1730 1731 -0.128212 0.058094 0.214771 0.6173969 0.0350014 0.5029175 0.6038791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1731 1732 0.039174 -0.021572 -0.263444 -0.0603156 -0.0272952 -0.6183395 0.7831177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1732 1733 -0.025830 0.032036 0.079428 0.0103072 -0.9534856 0.0318511 0.2995738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1733 1734 -0.060681 0.079909 0.051418 0.3348619 0.8228752 -0.2047983 0.4108546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1734 1735 0.156837 0.006393 0.017600 0.1623022 0.0070664 0.3287105 0.9303534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1735 1736 -0.049005 0.078180 -0.055808 -0.0600869 -0.2837322 -0.2495497 0.9239105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1736 1737 -0.107059 0.013333 -0.074071 -0.0806036 -0.7353432 -0.0414608 0.6716059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1737 1738 -0.012764 -0.015621 0.050948 0.1665536 0.6747712 0.1941244 0.6922857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1738 1739 -0.130563 0.006313 -0.250565 -0.1152845 0.0183662 0.1733564 0.9779160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1739 1740 -0.184814 0.172469 0.133416 -0.3125024 0.1831629 0.9292583 0.0726131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1740 1741 0.145757 0.012433 -0.084180 0.7487065 -0.1768990 -0.4721075 0.4304182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1741 1742 0.154240 -0.053347 0.086117 -0.2528280 -0.5508178 0.4206332 0.6750892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1742 1743 -0.004299 0.073276 -0.220115 0.9199806 -0.1233538 0.3719907 0.0065187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1743 1744 -0.081673 0.070687 -0.162123 -0.3043083 0.6461185 -0.6607016 0.2310860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1744 1745 0.097141 -0.059175 -0.000781 -0.5402354 -0.0198960 -0.0340135 0.8405908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1745 1746 0.159703 0.163265 0.183411 0.1882872 -0.5928414 -0.2097124 0.7543923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1746 1747 0.029039 0.174051 0.057082 0.7201771 -0.0674742 0.3666223 0.5851327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1747 1748 -0.013521 -0.119464 -0.161605 0.1823385 0.3582958 -0.9000119 0.1683906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1748 1749 -0.002535 0.126277 -0.077153 0.7648736 -0.4110758 -0.2598867 0.4224262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1749 1750 -0.082829 -0.079218 -0.133250 -0.0609589 0.7391824 0.6590549 0.1246597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1750 1751 0.134143 0.002158 0.039925 -0.2613668 -0.5451522 0.2759856 0.7472137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1751 1752 0.023794 0.130604 0.015099 -0.4324046 0.2649384 -0.1800016 0.8428721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1752 1753 -0.080975 0.001273 -0.108553 -0.0043989 0.6111981 0.4342911 0.6616712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1753 1754 0.147080 0.006983 0.046339 0.3351390 -0.1592472 0.4179910 0.8292199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1754 1755 -0.099973 -0.009529 -0.055150 0.0993250 -0.2936678 0.6652930 0.6791752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1755 1756 -0.023391 -0.130596 -0.076217 -0.8442840 0.3206299 -0.3442590 0.2566452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1756 1757 -0.090234 0.178368 -0.081732 0.0311276 0.8617555 0.0273314 0.5056298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1757 1758 -0.125417 0.071887 -0.148755 0.1840691 0.0906237 -0.9786804 0.0095223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1758 1759 0.038193 0.049885 0.068801 0.2638163 0.2549603 0.1651319 0.9154931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1759 1760 -0.038905 -0.111693 0.068687 -0.7282397 -0.2402433 -0.2217444 0.6023118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1760 1761 -0.076825 -0.082704 -0.017992 0.3320135 0.6676071 -0.2601665 0.6134991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1761 1762 0.201972 -0.057787 0.104328 -0.3981796 0.7619593 0.4713300 0.1967716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1762 1763 -0.047423 -0.163308 -0.055848 0.4728408 0.0641636 0.8782235 0.0320637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1763 1764 -0.073568 -0.114698 -0.036586 0.2138220 0.1347422 -0.3289891 0.9098851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1764 1765 0.284960 0.032001 -0.352455 -0.0607431 0.0269757 -0.9716621 0.2268379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1765 1766 0.060363 -0.097444 0.000838 -0.3789022 0.5612143 0.3543418 0.6449136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1766 1767 0.058574 0.130481 0.063304 0.1163403 -0.0128337 -0.6911180 0.7132013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1767 1768 -0.072309 0.173434 -0.093280 -0.2279881 -0.3698351 0.0425007 0.8996872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1768 1769 -0.101229 -0.075494 0.051593 0.2899963 -0.2200571 -0.1549020 0.9184130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1769 1770 -0.007010 -0.104753 0.200476 -0.3308230 0.0715830 -0.9282650 0.1541300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1770 1771 0.160661 -0.174686 -0.036719 0.1502391 0.1268651 0.8547274 0.4803901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1771 1772 -0.001033 -0.200758 0.100147 0.5311633 -0.1783880 -0.5840789 0.5872777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1772 1773 0.034843 0.057988 0.021098 -0.0994859 0.8178559 0.3232157 0.4655597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1773 1774 -0.017141 0.313047 -0.092905 0.1255090 -0.0613968 0.8994004 0.4141941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1774 1775 0.029983 -0.118473 -0.135981 -0.7792093 0.1994284 -0.5387301 0.2506613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1775 1776 -0.194436 0.211224 0.155364 -0.6313620 0.6012616 0.4256558 0.2422471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1776 1777 -0.174694 0.092578 -0.035858 -0.0904538 -0.3121193 0.3579732 0.8753598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1777 1778 0.077051 0.149831 0.058413 0.3750992 -0.5058025 -0.2621436 0.7312627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1778 1779 0.003065 -0.041280 -0.095212 0.2760864 -0.5800135 -0.7418403 0.1924411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1779 1780 -0.067284 0.012395 0.003422 0.1353237 0.5122388 0.8407218 0.1117397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1780 1781 0.280750 0.194988 -0.066010 -0.2983417 0.7138890 -0.3047383 0.5554181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1781 1782 -0.150246 0.075687 0.057582 -0.1834526 0.2914902 -0.8468282 0.4052907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1782 1783 0.230945 -0.128863 -0.116258 0.4866778 0.4916864 0.6523095 0.3096474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1783 1784 0.001264 -0.061880 -0.001154 -0.4375098 -0.6606136 -0.2372998 0.5620174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1784 1785 -0.014307 -0.117403 0.100809 -0.7999694 0.1426224 -0.5479076 0.1987588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1785 1786 -0.089949 0.018896 -0.087068 0.4657915 -0.5023546 0.5867782 0.4317052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1786 1787 0.016799 0.010796 -0.083434 -0.1706131 -0.7350552 0.5123511 0.4099774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1787 1788 -0.102990 0.060008 0.156208 0.7643654 0.4853985 -0.2572271 0.3375915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1788 1789 -0.104409 -0.024550 0.069233 0.4996778 0.2026771 -0.4845108 0.6888348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1789 1790 -0.276194 -0.056620 -0.156900 -0.1131141 -0.7320697 0.0287216 0.6711589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1790 1791 0.039616 0.042753 -0.045621 -0.5000785 -0.5494920 -0.6681528 0.0393941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1791 1792 -0.280835 -0.033056 0.041441 -0.3387014 -0.8988572 -0.0307222 0.2763934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1792 1793 0.071975 -0.070370 -0.137523 -0.2893412 -0.3459130 -0.1452669 0.8806380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1793 1794 0.048316 -0.078173 0.162643 0.4270575 0.8452967 0.1296117 0.2937622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1794 1795 -0.223171 0.085970 -0.076916 -0.7425135 -0.3873031 -0.4700744 0.2787474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1795 1796 -0.043169 -0.001102 0.070868 0.6353354 0.2808653 0.4850844 0.5311843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1796 1797 0.033593 0.073587 0.113155 0.2639091 -0.4521698 -0.3274358 0.7865623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1797 1798 0.013656 -0.053867 0.015305 -0.3922367 -0.6458196 -0.3170913 0.5731671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1798 1799 -0.158967 -0.090410 -0.040822 0.2492705 -0.5670484 -0.7740725 0.1308894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1799 1800 -0.394494 0.156822 -0.032499 -0.1804248 0.2970368 0.1417250 0.9268927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1800 1801 0.034047 0.096588 -0.056126 -0.7453954 0.0999799 0.6164737 0.2331304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1801 1802 0.050706 -0.002069 0.059889 -0.2829060 -0.4592527 0.6728907 0.5062304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1802 1803 -0.029479 0.049342 0.067027 0.2662028 -0.4452725 0.3205885 0.7925222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1803 1804 0.125775 -0.148732 0.016219 0.1682972 0.6875299 0.5745650 0.4109182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1804 1805 -0.153022 -0.146947 0.031277 0.8291986 -0.4699891 -0.2901504 0.0857480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1805 1806 0.093680 0.100702 -0.046232 0.2571526 -0.2123167 -0.9411819 0.0545052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1806 1807 0.025111 -0.103579 0.188443 0.5743348 0.3838542 -0.4215576 0.5874391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1807 1808 -0.077611 0.099068 0.018759 0.0147890 -0.8299099 -0.2102154 0.5165659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1808 1809 0.082675 0.013783 -0.010474 -0.7953800 0.0297772 -0.1741680 0.5797840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1809 1810 0.085859 -0.046104 0.091063 -0.0801334 -0.6271176 0.3989644 0.6641758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1810 1811 0.083418 -0.076396 0.014358 0.6592119 0.4210128 -0.4524981 0.4282912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1811 1812 0.089223 -0.015325 0.009047 0.0672345 -0.2710534 -0.6747443 0.6831762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1812 1813 -0.054109 -0.020935 -0.094074 -0.1468843 0.5903807 -0.3907618 0.6907827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1813 1814 0.063095 -0.066662 -0.005944 0.8463550 -0.0410843 -0.0185564 0.5307080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1814 1815 -0.028638 0.025857 0.196866 -0.4516328 0.8305170 0.2863642 0.1557722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1815 1816 -0.087171 0.065480 -0.047212 -0.2987511 -0.0897731 -0.6281979 0.7127805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1816 1817 0.066983 0.111471 0.083477 0.7538544 -0.4673741 0.0983798 0.4512054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1817 1818 -0.024308 0.019076 0.087588 -0.4590832 0.7604500 0.1542771 0.4326164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1818 1819 -0.036708 0.119137 0.030296 0.3642670 -0.0887718 0.4369416 0.8176253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1819 1820 -0.035757 -0.046393 -0.148905 -0.6352887 0.3931326 -0.5168044 0.4180529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1820 1821 -0.089523 -0.012725 0.041952 0.3876040 -0.3470246 -0.3828344 0.7633969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1821 1822 0.033593 0.106208 -0.000289 -0.5134492 0.1284351 0.6819418 0.5048067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1822 1823 -0.084895 0.078308 0.020362 -0.3570580 0.5244410 0.7636409 0.1196820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1823 1824 0.121086 0.009331 -0.220370 -0.3537602 -0.4188888 -0.8201577 0.1634846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1824 1825 0.080736 -0.014134 -0.052394 0.6388751 -0.2338932 0.4049882 0.6108331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1825 1826 -0.134838 0.023248 -0.192895 0.1849441 0.6314310 0.7068100 0.2598273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1826 1827 0.026220 0.082295 -0.014024 -0.7173333 -0.2363659 -0.2126410 0.6199580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1827 1828 -0.092480 0.060741 -0.048284 -0.2236601 0.7950003 -0.3942787 0.4031067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1828 1829 0.120270 -0.136975 -0.004318 0.1963679 -0.4618863 0.3689060 0.7823101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1829 1830 -0.192354 0.029416 -0.142933 -0.0563260 0.2692941 -0.9510996 0.1404197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1830 1831 0.027223 0.109021 0.072655 0.2139555 -0.1538194 -0.2837913 0.9219681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1831 1832 0.045439 -0.107997 -0.042480 0.1024174 -0.4844513 -0.2475542 0.8327872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1832 1833 -0.131309 0.114854 -0.058262 -0.4018916 0.1121585 0.0343746 0.9081421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1833 1834 -0.006678 -0.073551 0.068081 0.1960794 -0.3584638 -0.4585314 0.7891803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1834 1835 -0.035091 -0.073075 -0.017014 -0.2777356 -0.0836234 0.8616306 0.4164885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1835 1836 -0.049109 0.100338 -0.022381 0.1737497 -0.9583870 0.1359080 0.1812027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1836 1837 -0.182228 -0.087055 -0.176055 0.3441314 -0.2279555 -0.0203143 0.9106026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1837 1838 -0.166438 -0.186494 -0.110667 0.2011401 0.8153090 -0.5155182 0.1704550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1838 1839 0.138859 -0.078782 0.068460 0.8516629 0.0237347 -0.5168264 0.0836506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1839 1840 0.071583 -0.041288 -0.133791 -0.0718081 0.5777691 0.6895260 0.4307904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1840 1841 0.129820 0.005943 -0.148037 0.3992648 -0.5231849 -0.7275000 0.1939301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1841 1842 0.077464 0.027815 -0.000992 0.8079933 -0.3692285 -0.1754217 0.4243164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1842 1843 -0.025512 -0.125998 -0.046176 -0.0276277 0.6361633 0.4613957 0.6177758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1843 1844 -0.004820 -0.177833 -0.079096 -0.3923309 -0.8642973 -0.2941865 0.1118971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1844 1845 -0.157250 0.004366 0.009620 -0.2767043 0.6262262 0.0065944 0.7288566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1845 1846 -0.050518 -0.126708 0.080145 -0.3468282 -0.2028730 0.8708992 0.2829970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1846 1847 0.104850 0.140347 -0.045721 0.4074290 -0.6007955 0.6163347 0.3052507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1847 1848 -0.050513 -0.164392 0.035126 0.1455043 0.0021575 0.1987113 0.9691943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1848 1849 -0.152808 -0.202621 0.004865 0.5527639 -0.2243374 -0.2116854 0.7741538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1849 1850 0.034032 -0.018898 -0.056998 0.1294339 0.3354357 -0.0787653 0.9297988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1850 1851 0.053740 0.068065 -0.132772 -0.3872773 0.8065107 0.1625377 0.4160988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1851 1852 0.137634 0.015866 -0.085999 -0.2196467 0.0986365 0.5293388 0.8135272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1852 1853 -0.074392 0.060253 0.047023 -0.2580201 -0.6799753 -0.3043889 0.6151476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1853 1854 -0.073404 0.103542 -0.153571 0.5152467 0.0763130 0.3676936 0.7703886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1854 1855 -0.074923 -0.021012 -0.104908 0.4637437 0.4696356 0.6434947 0.3876839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1855 1856 -0.058832 -0.034830 -0.175865 0.5390252 0.4752602 0.6599749 0.2191179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1856 1857 -0.027062 0.105471 -0.208959 -0.6743073 0.6120111 -0.0842237 0.4045471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1857 1858 -0.018584 -0.103375 0.039494 -0.1731587 0.5984683 -0.4704610 0.6249145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1858 1859 -0.188617 0.028925 0.127229 0.1002680 0.2942858 -0.9496714 0.0382930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1859 1860 0.229766 0.060356 0.141377 -0.4565408 0.0345735 -0.0833028 0.8851191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1860 1861 0.209117 -0.162632 -0.067936 0.5070527 0.3414129 -0.7644169 0.2049431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1861 1862 -0.048714 0.097875 0.043422 -0.5420931 -0.2360675 -0.0077434 0.8064411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1862 1863 0.120905 -0.057242 0.139955 0.1905345 -0.2480543 0.9186177 0.2414686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1863 1864 0.020709 -0.069660 0.082177 0.0458959 -0.1895247 0.9807195 0.0127778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1864 1865 -0.252895 -0.023536 -0.027341 -0.2536875 -0.9135901 0.1786200 0.2628512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1865 1866 0.099872 -0.015902 -0.087194 0.7916608 -0.4791412 0.3123112 0.2148455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1866 1867 -0.011497 -0.144785 0.127057 -0.0009250 0.3047302 0.4438938 0.8426725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1867 1868 -0.132509 -0.052965 0.030999 0.3407782 0.3881773 -0.4199089 0.7462339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1868 1869 0.011749 -0.102548 -0.136386 -0.2764410 0.1983597 0.8639093 0.3713416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1869 1870 -0.107545 -0.047841 0.137277 -0.4977623 0.2183398 -0.4820458 0.6871625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1870 1871 0.077979 -0.054997 0.035281 -0.1299604 0.2670924 -0.9432759 0.1483325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1871 1872 0.104214 -0.313988 -0.033768 -0.4008653 -0.4155801 0.7597013 0.2990888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1872 1873 0.007350 -0.004216 0.082339 0.8972103 -0.0649306 0.2576369 0.3527334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1873 1874 -0.033731 -0.083117 0.042809 -0.7718755 0.3798221 -0.0474227 0.5076361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1874 1875 -0.149931 -0.031074 0.209245 -0.5893186 0.2153976 0.6311014 0.4560905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1875 1876 -0.109567 0.103345 0.131449 -0.4726729 -0.2602080 -0.3089104 0.7832282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1876 1877 -0.079075 0.090297 0.091366 0.0537203 0.1516132 0.4789629 0.8629728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1877 1878 -0.077091 0.053037 0.156354 -0.1478702 -0.2416471 -0.7534662 0.5933210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1878 1879 0.147185 -0.061806 -0.043558 0.1099350 0.7147748 0.0466410 0.6890834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1879 1880 -0.076974 -0.039282 0.074742 0.0755613 -0.6537203 -0.1329727 0.7411197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1880 1881 -0.162830 0.107276 0.037064 0.2076328 0.3811443 -0.6995081 0.5677200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1881 1882 0.024138 0.083273 0.066691 -0.1908065 -0.7462587 0.4739911 0.4266419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1882 1883 0.209426 -0.062782 -0.008538 -0.0323321 0.6714190 0.0835202 0.7356463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1883 1884 -0.034836 -0.076822 0.152604 -0.3368185 0.1859836 -0.5375422 0.7503411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1884 1885 0.045748 -0.050601 0.085031 0.0051670 0.8507998 -0.0290346 0.5246618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1885 1886 0.035877 0.022915 -0.061951 0.1260991 -0.6282822 0.7676476 0.0088143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1886 1887 -0.181684 0.117852 0.033306 0.4936722 0.3149142 -0.7199149 0.3726116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1887 1888 -0.104193 0.088558 -0.123031 -0.8446604 0.0736851 -0.0288465 0.5294216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1888 1889 -0.049589 0.002958 0.064722 0.7505893 -0.5501583 -0.0896108 0.3548400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1889 1890 0.151037 -0.186843 0.011740 0.0436185 -0.1120850 0.3349430 0.9345307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1890 1891 -0.101258 0.013228 0.124411 -0.2880314 0.0283165 -0.9307305 0.2235550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1891 1892 -0.080348 0.003777 0.041287 -0.7818261 0.0914015 0.5998199 0.1435611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1892 1893 -0.049132 -0.027571 0.129918 0.4257013 -0.4973417 -0.2180647 0.7237938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1893 1894 0.063568 0.051263 0.111401 -0.7800832 -0.3630174 -0.3483112 0.3719783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1894 1895 -0.286480 0.036164 -0.037061 0.4919415 0.1849549 0.4405608 0.7277991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1895 1896 -0.040600 0.209545 0.005544 0.2712559 0.0880820 -0.4274550 0.8578718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1896 1897 -0.038548 -0.145918 0.220787 0.1099082 -0.6940378 0.4397130 0.5593605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1897 1898 0.139746 0.005186 0.007090 0.4370802 0.4353580 0.7490529 0.2415450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1898 1899 0.029974 -0.107959 0.036641 0.0142443 0.0290980 0.9993577 0.0153133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1899 1900 0.009844 0.065876 0.254150 -0.0891885 0.5178076 -0.7773768 0.3458410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1900 1901 0.097894 -0.136666 -0.244269 -0.0944608 0.3921824 0.3455849 0.8472551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1901 1902 -0.110508 -0.029571 0.115170 0.2380095 -0.0299231 -0.0428982 0.9698535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1902 1903 0.046422 -0.094855 0.029665 0.7340476 0.4512652 -0.4755435 0.1771782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1903 1904 -0.129591 -0.001165 -0.017605 -0.1690001 -0.1185202 -0.0423162 0.9775486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1904 1905 0.163384 -0.085702 -0.041367 0.3715602 -0.4059968 0.8294501 0.0955100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1905 1906 -0.024731 -0.057568 0.121538 0.5335103 -0.1015436 0.8147912 0.2029062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1906 1907 -0.041898 -0.084413 0.083728 0.0123482 0.3325513 0.8857058 0.3237012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1907 1908 -0.105827 0.081605 0.033218 0.9539366 -0.0932716 -0.2830203 0.0347116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1908 1909 -0.066168 -0.162553 0.098261 -0.1183845 -0.2575322 -0.2058682 0.9366326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1909 1910 -0.038385 -0.170132 0.029137 -0.1673685 -0.5815099 0.2068961 0.7687835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1910 1911 0.149453 -0.016057 0.007852 0.4773485 0.4626232 0.0150335 0.7469218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1911 1912 0.042362 -0.061896 -0.056273 0.7067031 0.1517775 -0.3770088 0.5791361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1912 1913 0.041142 0.002657 -0.022272 -0.0718914 -0.6742926 0.4771954 0.5589684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1913 1914 -0.042253 0.053677 -0.055745 0.6104700 0.0545708 -0.1514543 0.7755063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1914 1915 0.135635 -0.000668 0.016582 -0.0600148 0.7217554 0.4905494 0.4845912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1915 1916 -0.000525 0.106192 0.186795 -0.6011385 -0.0423366 0.6201309 0.5022726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1916 1917 0.074976 -0.014173 0.095216 -0.0358153 0.3738829 -0.3613858 0.8534220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1917 1918 0.019712 0.039492 -0.099401 0.0353585 0.8807240 -0.3707164 0.2926505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1918 1919 -0.365086 0.050831 0.075630 -0.2007845 0.4648460 0.0001508 0.8623246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1919 1920 0.024286 0.039654 -0.004091 -0.4925453 0.3344426 -0.7430079 0.3057557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1920 1921 0.054941 0.026594 0.194626 -0.4688107 -0.6957899 -0.5409809 0.0585886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1921 1922 -0.077151 -0.000540 0.178227 -0.6212536 -0.0541329 -0.7276767 0.2856576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1922 1923 -0.097952 -0.048783 0.042694 0.5080045 -0.2541197 0.5562219 0.6066068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1923 1924 -0.125663 -0.025499 0.141860 0.2157989 0.1749734 -0.3863247 0.8795273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1924 1925 -0.018421 -0.084146 0.002769 0.4780240 0.0764480 0.7165803 0.5021568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1925 1926 -0.067242 0.201171 0.031349 0.7136094 0.2970507 0.4855084 0.4084166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1926 1927 0.156367 0.097910 -0.101339 0.0276138 0.1485830 0.8305465 0.5360533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1927 1928 0.045282 0.093105 -0.098036 0.9189031 -0.1287935 -0.1795475 0.3267906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1928 1929 0.085707 0.010223 0.344990 -0.7396876 0.0950306 -0.4590044 0.4828524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1929 1930 0.016267 -0.079001 0.053469 0.5596182 0.1454081 -0.3514506 0.7363196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1930 1931 0.147267 -0.069179 0.148984 -0.4781731 -0.3358496 0.8115069 0.0034775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1931 1932 -0.067602 0.123354 0.022323 -0.2351795 -0.7609053 0.5093211 0.3260458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1932 1933 0.026036 0.180973 0.033604 0.5019331 -0.6835445 0.1740689 0.5005299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1933 1934 0.235045 -0.117973 0.001195 -0.1794063 0.2669995 -0.7888618 0.5236618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1934 1935 0.035069 -0.035570 -0.162410 -0.0055545 0.1099893 0.5281010 0.8420100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1935 1936 -0.023627 0.015711 -0.013405 0.2342114 0.0743940 -0.9671799 0.0646033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1936 1937 0.090775 0.013694 0.057503 0.2878391 0.2173877 -0.4492781 0.8173374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1937 1938 -0.009908 0.156150 0.025973 0.0184199 -0.8639303 0.4987998 0.0669623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1938 1939 0.069334 0.097890 -0.094275 0.3164585 0.6138363 -0.7121591 0.1260494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1939 1940 0.031022 0.118859 0.109702 -0.5382967 0.4194779 0.7252226 0.0912532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1940 1941 -0.058232 0.064540 0.086922 -0.0538053 -0.2470513 -0.5167429 0.8179532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1941 1942 -0.088677 0.044195 0.010512 0.0816023 0.0892570 -0.7907828 0.6000306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1942 1943 0.074394 -0.001648 0.055767 0.2311838 0.0337340 -0.4173796 0.8781858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1943 1944 0.154475 0.092052 -0.094054 0.0978523 -0.2532841 0.7471551 0.6066559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1944 1945 0.014186 0.025092 -0.061355 -0.2081225 0.1145929 -0.5919004 0.7701996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1945 1946 0.061704 0.004007 -0.158801 -0.0649263 0.2001972 -0.0498653 0.9763294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1946 1947 0.015963 0.052367 -0.220724 0.3245343 -0.6083424 0.2986483 0.6598531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1947 1948 -0.124419 -0.084432 -0.017218 0.2354752 0.6925648 -0.0031712 0.6818323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1948 1949 0.129697 -0.034804 -0.116345 -0.1444778 0.5648990 0.4757035 0.6585754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1949 1950 0.025376 0.064915 -0.086945 -0.0492098 0.7811782 0.2707040 0.5604091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1950 1951 0.094539 -0.087761 -0.119505 -0.7283019 0.2411143 0.1046980 0.6328337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1951 1952 0.159110 0.115595 0.134433 0.0738187 0.3471388 0.9348891 0.0052800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1952 1953 -0.282691 -0.227593 0.040947 -0.5160923 0.3483330 -0.1773158 0.7621496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1953 1954 0.127578 -0.093616 0.042289 -0.3317777 -0.1486124 -0.8461581 0.3896850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1954 1955 -0.054570 -0.052342 0.049817 0.0373035 0.7227740 0.2122795 0.6566153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1955 1956 0.037036 -0.060951 -0.107382 -0.7124609 -0.0166966 0.6685018 0.2126642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1956 1957 0.025969 -0.163524 0.010634 0.7234003 -0.3227714 -0.1295206 0.5964353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1957 1958 -0.063204 0.072667 -0.161547 0.1821609 -0.5987320 -0.5175304 0.5835235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1958 1959 0.036521 -0.080456 0.104007 0.7404084 -0.1537870 -0.6485845 0.0865053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1959 1960 0.079469 0.099789 0.161946 0.8179214 -0.3381827 -0.3720222 0.2797080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1960 1961 0.159940 -0.027938 -0.172120 -0.2332019 -0.1212797 0.4328186 0.8623086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1961 1962 0.085728 0.197086 -0.074622 0.0562776 -0.1312611 0.0470030 0.9886324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1962 1963 0.044718 0.152374 0.005259 -0.4468197 0.0044297 0.6086937 0.6556100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1963 1964 -0.228819 0.029789 -0.098648 0.2807816 0.2972566 0.1648717 0.8975620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1964 1965 0.001070 -0.066124 -0.001652 0.0979016 0.4361073 -0.5351510 0.7168257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1965 1966 -0.141921 0.213104 0.094205 -0.4757983 -0.8235718 0.2681510 0.1531028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1966 1967 0.026421 -0.045078 0.235043 0.1632887 -0.4117194 0.6973725 0.5634674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1967 1968 -0.000745 -0.185638 0.103430 -0.4782051 0.5119361 0.4632814 0.5427815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1968 1969 0.099064 0.048037 -0.052841 0.1390398 -0.0655124 -0.5520637 0.8195131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1969 1970 -0.100365 0.100209 -0.019166 0.5001352 -0.1859430 0.6570962 0.5324608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1970 1971 -0.026213 0.028426 0.018187 0.0813739 -0.8586519 -0.4277887 0.2703553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1971 1972 -0.069889 -0.095071 0.223454 -0.7909317 -0.1577681 0.1717447 0.5657208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1972 1973 -0.058457 0.189115 -0.128319 -0.3259734 0.5658884 -0.7233481 0.2242302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1973 1974 -0.017648 0.026364 -0.194124 0.5939568 0.5121110 0.2473747 0.5690022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1974 1975 0.105174 0.116237 -0.070387 -0.5014518 0.2527081 0.5193769 0.6441524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1975 1976 0.181435 0.082480 0.076729 -0.3935913 0.1679845 0.1258404 0.8950035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1976 1977 -0.040038 0.002839 -0.026916 -0.8230733 -0.3142671 0.4704861 0.0492886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1977 1978 0.148236 0.214775 0.044053 0.1960356 -0.4851314 0.7233472 0.4505402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1978 1979 -0.220408 0.125045 -0.015111 -0.4281968 -0.2241562 0.4100241 0.7734867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1979 1980 0.103800 0.046660 -0.147468 0.4058599 0.3639153 -0.2351500 0.8047036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1980 1981 -0.074680 -0.081160 0.007243 -0.2704738 -0.5322800 -0.6117646 0.5189084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1981 1982 -0.000504 0.135806 0.079554 -0.2026592 0.0114423 0.4241521 0.8825493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1982 1983 0.206257 -0.064545 0.050981 -0.2541467 0.8350815 -0.4321603 0.2264638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1983 1984 -0.041256 -0.115023 -0.022559 -0.1155654 -0.7116280 0.6929601 0.0060439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1984 1985 0.043742 -0.098779 0.102714 0.0970518 0.0073104 -0.5099547 0.8546775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1985 1986 0.159253 0.208451 -0.174274 0.3862372 -0.0883342 0.7462800 0.5348683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1986 1987 0.100364 -0.013417 0.082340 -0.0588606 -0.0150600 -0.5140931 0.8555799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1987 1988 0.037597 0.133516 -0.096124 -0.1574099 0.8307466 0.3003667 0.4414318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1988 1989 0.122691 -0.099961 0.022244 -0.0139268 -0.5314757 0.8425445 0.0863621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1989 1990 0.030352 -0.065535 -0.023209 -0.1651934 0.6433252 0.0615341 0.7450217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1990 1991 -0.163947 -0.153196 -0.116705 0.5083705 -0.5169830 0.1619816 0.6693653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1991 1992 0.129432 0.189253 0.121548 -0.3096734 0.0051709 0.6334559 0.7090905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1992 1993 -0.169053 0.060592 -0.162167 0.8719341 -0.2866539 0.2008496 0.3423739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1993 1994 -0.077187 -0.025664 0.090737 -0.0355750 0.2626226 0.9437556 0.1977096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1994 1995 -0.006144 0.068392 0.002592 0.3149589 0.3064013 0.7244059 0.5311828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1995 1996 0.039229 0.118609 -0.044904 -0.2708455 -0.3149143 -0.7998738 0.4332131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1996 1997 -0.101217 -0.089871 0.048078 0.3698962 -0.1818516 0.8692752 0.2728871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1997 1998 -0.048419 0.054593 -0.069127 -0.0020061 -0.1310911 0.5490068 0.8254712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1998 1999 -0.080531 -0.178589 0.245504 0.3476181 0.2206601 -0.8478638 0.3340625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1999 2000 -0.171040 0.036498 0.162465 -0.0712733 -0.0597400 -0.9194281 0.3821037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2000 2001 -0.019008 -0.070330 -0.078978 0.3782579 0.2464319 -0.1367836 0.8817497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2001 2002 -0.188525 0.026309 0.066638 0.5068965 0.0284487 -0.4496441 0.7348924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2002 2003 0.088127 -0.100249 0.132712 -0.2595782 0.0116645 0.7960671 0.5465896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2003 2004 -0.090632 -0.102006 0.159664 -0.1138447 0.4056138 0.3145029 0.8506496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2004 2005 -0.012875 0.045066 -0.006531 -0.3714760 -0.0495926 0.9151851 0.1482649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2005 2006 0.025990 -0.069009 0.235364 -0.1230561 -0.7618208 -0.4884779 0.4072782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2006 2007 0.098840 0.015293 -0.133478 -0.3391735 -0.1478572 -0.8583530 0.3554289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2007 2008 0.187013 0.083864 -0.059475 -0.0372476 -0.6146279 0.7810684 0.1038139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2008 2009 0.070057 -0.218974 0.093485 0.5421542 -0.0285113 0.5298014 0.6515876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2009 2010 0.072546 0.004793 -0.036228 -0.4747180 0.1968735 0.8398398 0.1747937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2010 2011 -0.242363 0.041479 0.022695 0.4301966 -0.8038386 -0.1979292 0.3599977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2011 2012 0.001690 -0.049066 -0.057957 -0.3435560 0.7752962 0.3789632 0.3705024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2012 2013 -0.024449 0.145325 -0.032401 0.5669016 -0.0103441 -0.0178755 0.8235266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2013 2014 0.100561 -0.230221 0.013936 0.1003901 0.4637792 0.7193219 0.5073527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2014 2015 0.144111 0.086427 -0.225865 -0.0641508 0.0007718 0.9483207 0.3107602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2015 2016 -0.044329 -0.311468 -0.097711 0.4746031 -0.7482034 0.1904016 0.4227183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2016 2017 -0.004639 -0.101667 0.041197 -0.2606983 -0.3696294 -0.6616800 0.5979884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2017 2018 0.012485 0.159076 0.005739 0.2967776 0.8337418 0.3676495 0.2857122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2018 2019 -0.133917 -0.113587 0.100355 -0.3520941 -0.5703553 -0.7296725 0.1352873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2019 2020 0.055480 -0.040977 0.009066 -0.1239274 0.5376011 0.8107050 0.1959197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2020 2021 -0.026555 -0.043720 0.092659 -0.2059494 0.6083071 0.6344045 0.4302072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2021 2022 -0.051395 0.036204 -0.027433 -0.2781723 -0.9003401 -0.3284466 0.0642706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2022 2023 0.152562 0.199172 -0.000066 0.4049683 0.4614850 0.2253342 0.7564766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2023 2024 -0.061300 -0.011798 0.162216 -0.8592801 0.3208634 -0.1075797 0.3835504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2024 2025 -0.177964 -0.028888 -0.040761 -0.1679739 -0.5997442 0.6592109 0.4213462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2025 2026 -0.103912 -0.066209 0.135146 0.3324777 0.5554292 -0.6956151 0.3115713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2026 2027 -0.205423 0.131879 0.051080 0.4654002 -0.5711347 0.6357748 0.2302132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2027 2028 -0.150937 0.049588 0.083069 -0.4992860 -0.4660131 -0.5303058 0.5023158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2028 2029 -0.290773 -0.015103 -0.097939 -0.7308387 0.4915019 -0.3513806 0.3175411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2029 2030 -0.024293 0.104415 0.143721 0.4765944 -0.5377970 0.1349716 0.6822132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2030 2031 -0.037581 0.083885 -0.072763 0.0945195 0.1085468 -0.7675357 0.6246380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2031 2032 -0.004962 0.065482 0.017574 0.3556450 0.3698418 -0.5736240 0.6385054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2032 2033 -0.061162 -0.084341 -0.011347 -0.0033276 -0.9752334 0.0260987 0.2196077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2033 2034 -0.151556 -0.015514 0.031092 0.6045408 0.2053830 -0.6791001 0.3621758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2034 2035 -0.017553 -0.039807 -0.038055 0.0501126 0.5044935 0.8179682 0.2718512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2035 2036 -0.150774 -0.113115 0.049478 -0.0632765 -0.1226736 -0.3058322 0.9420265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2036 2037 0.105198 -0.136692 -0.090107 0.3481751 0.1436597 0.8963730 0.2337767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2037 2038 0.098675 -0.114781 -0.239103 0.2889628 0.0045190 0.8875942 0.3586873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2038 2039 0.113316 -0.018235 -0.010010 -0.5854637 0.4766925 -0.4617274 0.4656225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2039 2040 -0.029322 0.083350 -0.034681 0.4436414 -0.2172865 -0.8272270 0.2677019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2040 2041 -0.275982 -0.074800 0.007275 -0.9519178 -0.1047384 -0.1583455 0.2404354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2041 2042 0.004232 0.163056 -0.079637 0.4671407 0.4082938 0.7384416 0.2641585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2042 2043 -0.049234 -0.104734 -0.039009 0.3988711 -0.6253380 -0.0339358 0.6698527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2043 2044 -0.082605 0.023360 -0.302350 -0.3523600 -0.3736945 -0.6388662 0.5727520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2044 2045 0.189532 -0.087541 -0.101359 0.6879016 0.0759631 0.4093213 0.5945394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2045 2046 -0.024254 0.000924 0.025644 -0.2569264 0.8237007 0.4813878 0.1541811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2046 2047 0.012006 -0.017438 -0.104448 0.1282605 -0.1297803 0.7140667 0.6758810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2047 2048 0.025971 0.098120 -0.110672 -0.4335866 -0.0570542 -0.1600153 0.8849534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2048 2049 -0.154530 -0.053984 -0.097377 -0.5356355 0.1549449 -0.6947389 0.4543397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2049 2050 -0.191526 0.053588 0.087466 0.6194732 -0.1468269 -0.3787822 0.6717283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2050 2051 0.048417 -0.081067 -0.173825 0.0975251 0.9792743 0.1334244 0.1170836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2051 2052 -0.203227 -0.105613 0.005265 -0.2201351 -0.3252490 -0.5483608 0.7382778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2052 2053 0.178755 0.040687 -0.076725 -0.1883631 -0.3418870 -0.5225871 0.7579811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2053 2054 -0.132905 0.122415 -0.045652 0.2586364 -0.0519049 0.2438498 0.9332472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2054 2055 0.196525 -0.164447 -0.057795 -0.0728435 0.7155012 -0.5525076 0.4212922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2055 2056 -0.002600 -0.087666 0.050889 0.0237150 -0.9883184 0.1315119 0.0732730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2056 2057 -0.163787 0.082098 -0.067119 -0.3378251 0.8421417 -0.3050156 0.2892008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2057 2058 -0.056467 0.057915 -0.033246 0.8444360 0.2948346 -0.4212561 0.1501455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2058 2059 0.098309 -0.115058 -0.118843 -0.5609474 0.0879915 0.0493870 0.8216790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2059 2060 0.065895 -0.116644 -0.187320 -0.0161268 0.0644594 -0.8660927 0.4954476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2060 2061 -0.041376 0.075989 -0.144130 -0.2234337 0.6357166 -0.7050160 0.2211202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2061 2062 -0.091608 -0.001013 -0.007497 0.0191558 0.0935954 -0.4361088 0.8948084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2062 2063 0.021106 0.031428 0.017849 0.4620986 -0.3809735 -0.7826673 0.1695757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2063 2064 0.071662 0.148304 0.045365 -0.6575016 0.0260120 0.2128170 0.7223046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2064 2065 -0.045992 -0.028447 0.032140 -0.1961255 0.6292138 0.6120841 0.4370100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2065 2066 -0.046940 -0.207432 0.107768 0.3225430 -0.0169723 -0.9058987 0.2739078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2066 2067 0.261554 0.010530 -0.194323 0.3475242 0.4311221 -0.8286481 0.0818723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2067 2068 -0.199643 0.169150 0.055967 0.0056913 0.0967690 -0.8140197 0.5726913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2068 2069 -0.000245 -0.034333 -0.077538 -0.2210304 0.4026571 0.7740913 0.4356553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2069 2070 -0.005598 0.167118 0.075260 -0.4414009 0.0112977 -0.3358270 0.8320203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2070 2071 -0.051845 0.077057 -0.062282 -0.3346370 -0.1776715 0.8711296 0.3123847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2071 2072 0.102225 -0.031732 -0.066658 0.1164790 -0.5221398 0.6157382 0.5785060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2072 2073 0.056768 -0.028138 -0.018423 -0.0100237 0.1170808 -0.7569542 0.6428157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2073 2074 -0.073091 0.067229 -0.071823 -0.6380760 -0.0744630 -0.4034041 0.6515975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2074 2075 -0.058473 -0.005940 0.190108 0.1337521 0.2954821 -0.4484462 0.8328846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2075 2076 -0.129155 0.199279 -0.086669 -0.4118901 -0.4402338 0.0902735 0.7927115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2076 2077 -0.045845 0.129552 0.034091 0.0782760 -0.8580966 0.4139926 0.2935187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2077 2078 0.041084 0.083277 0.024989 0.3027993 -0.4861248 0.5834152 0.5758662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2078 2079 0.041961 -0.063182 -0.104896 0.3822491 0.0488095 -0.5432216 0.7459313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2079 2080 -0.007480 -0.062244 -0.111263 0.1264644 -0.1320839 0.0103372 0.9830838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2080 2081 0.017661 0.010618 0.055886 -0.0304489 0.2372725 0.0104806 0.9709092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2081 2082 -0.116177 0.328366 0.176669 0.0962102 -0.4857267 0.5563220 0.6673223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2082 2083 0.090053 -0.081634 -0.017423 0.2401964 -0.0145945 0.9242720 0.2963341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2083 2084 0.026178 0.104419 -0.152911 0.6846018 0.2032857 0.5914830 0.3743571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2084 2085 0.214740 -0.051370 0.085430 -0.8359801 -0.3787336 0.1935358 0.3467594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2085 2086 0.016318 0.199953 0.103236 -0.3805827 0.4004971 0.0683762 0.8307127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2086 2087 0.024509 -0.184540 0.045106 0.7607983 0.5806490 0.1435193 0.2518631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2087 2088 -0.162980 0.112439 0.090071 -0.6623556 -0.5586102 0.0132168 0.4990642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2088 2089 -0.036832 -0.022068 0.192876 -0.0048150 0.6740523 0.2679958 0.6883375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2089 2090 -0.048708 0.123879 -0.137132 -0.1751768 -0.6665599 0.6587473 0.3017664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2090 2091 -0.099525 0.117317 0.171006 -0.4474562 -0.5028247 -0.7215317 0.1623030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2091 2092 0.138366 0.057895 0.126107 -0.0919935 0.1522280 0.8719509 0.4561420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2092 2093 0.094942 -0.182698 0.143141 0.5897981 -0.5544777 0.1660625 0.5631305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2093 2094 0.022592 -0.021476 0.014556 -0.1910509 -0.0572113 -0.2527981 0.9467415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2094 2095 -0.111267 0.075475 -0.005212 0.1185401 -0.4168465 0.8570104 0.2787839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2095 2096 -0.029485 -0.031340 0.072792 0.5754146 -0.0557908 -0.1907268 0.7933528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2096 2097 -0.005101 0.153009 -0.022113 0.0320950 -0.3895495 -0.0769942 0.9172203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2097 2098 -0.055878 0.004210 0.034282 -0.2192479 0.8179713 -0.2614038 0.4631646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2098 2099 0.132273 0.096860 0.229109 -0.1674815 -0.1176594 0.9690947 0.1377014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2099 2100 -0.099850 0.078971 0.204479 -0.0387541 0.0238698 0.8317668 0.5532561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2100 2101 0.057787 -0.143685 -0.084122 0.5855161 -0.0667869 0.7655054 0.2582863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2101 2102 0.115772 -0.142134 0.079226 -0.4311291 0.0865827 0.8878530 0.1354556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2102 2103 0.111475 0.083709 0.020286 0.6024671 -0.3235001 -0.1681560 0.7100032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2103 2104 0.035789 -0.007749 0.025634 0.0794315 -0.6388453 -0.1356974 0.7530960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2104 2105 0.139214 -0.090742 0.087113 0.4830026 -0.4779850 0.7334645 0.0163914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2105 2106 -0.074611 0.063930 0.106822 0.2223491 -0.5843756 -0.4141143 0.6614948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2106 2107 0.059079 0.113551 0.011267 -0.4531180 0.4242447 -0.7640412 0.1759022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2107 2108 -0.023796 0.140814 0.213731 0.1790104 0.6030872 -0.6852020 0.3670685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2108 2109 0.013695 -0.135752 -0.139987 -0.7340593 0.0665521 0.6674526 0.1059947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2109 2110 -0.019145 0.026075 0.103427 -0.1745385 0.0467166 -0.2415239 0.9534255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2110 2111 -0.086068 0.136960 0.030881 0.3869870 -0.2663484 0.3358939 0.8163791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2111 2112 0.049034 0.038733 -0.181638 0.1141112 -0.0597531 -0.0497174 0.9904223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2112 2113 0.035630 -0.142533 0.186494 -0.3230126 0.6636368 0.3780801 0.5588421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2113 2114 0.045237 0.002728 0.036936 0.4321841 0.2080546 0.7929005 0.3758178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2114 2115 0.097033 0.023033 0.399307 0.4346369 0.5662189 0.3750690 0.5914475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2115 2116 -0.198041 0.209956 -0.071633 -0.6733195 0.5007418 0.3629102 0.4052096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2116 2117 0.164437 -0.111492 0.054655 0.6630129 0.6420089 -0.2888120 0.2546096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2117 2118 0.139724 -0.219689 -0.120326 -0.0199213 -0.4192562 -0.3905881 0.8193097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2118 2119 0.088943 -0.139880 -0.101577 -0.1861475 -0.0390127 0.2532801 0.9485127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2119 2120 -0.054537 0.121409 -0.073446 0.6317528 0.5737739 -0.0139917 0.5210337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2120 2121 0.000638 -0.092083 0.040990 0.0301919 -0.6005745 -0.6588222 0.4520532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2121 2122 -0.012394 0.154219 -0.202649 0.0052801 -0.2840365 0.6931629 0.6624354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2122 2123 0.089497 -0.029703 -0.066047 -0.3349913 0.1258692 -0.9268805 0.1132710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2123 2124 -0.160730 0.141882 -0.073608 0.7042404 -0.2920956 -0.6431452 0.0713431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2124 2125 0.259840 -0.007465 -0.255594 -0.6958920 -0.2870851 0.6506008 0.1001755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2125 2126 -0.223082 0.036107 0.009476 0.2740860 -0.1646874 -0.9344348 0.1568012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2126 2127 0.017185 -0.169059 -0.133815 0.3861180 0.2545453 0.3958111 0.7933809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2127 2128 0.071306 -0.054980 0.081964 0.2484227 0.7027597 0.6395354 0.1881737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2128 2129 -0.170016 -0.057386 -0.048195 0.2541148 0.0363444 0.5752152 0.7766802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2129 2130 -0.041345 -0.034928 0.100293 0.5696338 0.2985820 0.7607801 0.0870620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2130 2131 0.037010 -0.113052 -0.087763 0.0703007 0.2309247 0.5620375 0.7911039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2131 2132 0.065676 -0.028790 -0.049398 -0.2010461 0.0255183 0.8534047 0.4802392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2132 2133 -0.046380 -0.098346 0.325806 -0.1744080 0.8882819 -0.3654522 0.2167529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2133 2134 -0.063578 -0.110844 -0.057929 0.6961536 0.1610558 -0.6616013 0.2274091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2134 2135 0.088767 0.072620 0.041626 -0.0334238 -0.6375228 -0.7636044 0.0967258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2135 2136 -0.070957 0.136682 -0.179413 0.7314874 -0.0825467 -0.5180755 0.4355571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2136 2137 0.007838 -0.056619 0.061366 0.4730415 -0.4675427 -0.5187252 0.5371775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2137 2138 0.061864 0.006632 0.037550 -0.3636311 -0.4395794 0.0168726 0.8211320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2138 2139 0.095869 0.077915 -0.073854 0.5600834 -0.3784830 -0.0048366 0.7369083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2139 2140 0.059838 0.004340 -0.021227 0.0647335 0.1470509 -0.6354982 0.7552004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2140 2141 0.082734 -0.036008 -0.078573 -0.2873661 0.8285111 0.4717164 0.0920530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2141 2142 0.074760 0.039070 -0.150953 -0.0505278 0.5245605 0.4078228 0.7456298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2142 2143 -0.072040 0.022681 -0.049156 0.1541949 -0.1278033 -0.0229032 0.9794722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2143 2144 0.052572 -0.014762 -0.104842 -0.1730876 0.5496531 0.6437541 0.5034906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2144 2145 -0.054413 -0.097874 0.042077 -0.2015397 -0.3053410 -0.4621669 0.8078059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2145 2146 -0.119162 -0.056691 0.004415 0.7027429 0.4011566 -0.2005213 0.5522834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2146 2147 0.087999 -0.080604 0.017430 -0.9237487 0.2619858 0.1193263 0.2526125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2147 2148 -0.024169 0.250355 0.043807 0.5218812 -0.4651824 -0.6984890 0.1528345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2148 2149 -0.042515 -0.125648 -0.076094 -0.9070465 -0.2272441 -0.2307281 0.2690563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2149 2150 -0.055268 0.000334 -0.021902 0.3847613 -0.2188103 -0.3078962 0.8421881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2150 2151 -0.003242 0.015826 -0.010098 0.1996082 0.7562442 0.5331767 0.3224497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2151 2152 0.046827 -0.063776 0.034161 0.0546681 -0.2997740 -0.5409200 0.7839340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2152 2153 -0.091058 -0.012846 -0.006549 0.0110526 0.7570882 0.3249497 0.5666595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2153 2154 0.043894 -0.161272 0.093975 -0.0054521 -0.2794441 -0.9601349 0.0047092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2154 2155 0.032506 0.094564 -0.120802 -0.2307385 -0.2722296 -0.5763103 0.7351987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2155 2156 -0.093402 -0.161137 -0.071153 0.1673556 0.6965306 0.5062668 0.4801366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2156 2157 -0.013008 -0.114256 -0.035127 0.2553486 0.3656263 -0.5073428 0.7373723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2157 2158 0.101412 -0.255994 0.100532 0.0032889 -0.4233364 -0.8927895 0.1539559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2158 2159 -0.101470 -0.195184 -0.016380 -0.4350812 0.0112023 0.2587093 0.8623505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2159 2160 -0.213933 -0.051147 -0.158303 0.6800075 -0.4820159 0.2768082 0.4781504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2160 2161 -0.226258 -0.002751 -0.073626 0.4157674 0.2036396 -0.4600268 0.7576567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2161 2162 -0.193058 -0.258332 0.212316 0.4440387 -0.3860810 -0.5057762 0.6308419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2162 2163 -0.078126 0.146742 0.157373 -0.9117876 0.1382362 0.3820120 0.0600074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2163 2164 0.004135 0.001041 0.052847 -0.2860289 0.0139272 -0.4097626 0.8660763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2164 2165 -0.127514 0.097937 -0.059517 0.4536543 -0.5918573 0.5981975 0.2933640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2165 2166 -0.027424 0.011495 0.024010 -0.2692798 0.3897691 -0.5694398 0.6717937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2166 2167 -0.064796 0.154677 -0.093342 -0.1677898 -0.5524045 0.7642218 0.2875080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2167 2168 0.032865 0.085029 -0.166105 0.6261729 -0.3446474 -0.4968292 0.4922260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2168 2169 -0.163604 0.065544 -0.091240 -0.1108321 -0.4569807 -0.5080575 0.7216387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2169 2170 0.052214 -0.050344 -0.003640 -0.2536759 0.1257252 -0.7642944 0.5793926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2170 2171 -0.114152 0.062685 -0.078696 0.1566850 0.0435416 0.2351971 0.9582465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2171 2172 0.074906 -0.019663 -0.001426 -0.3633671 -0.4824531 0.5580815 0.5689889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2172 2173 -0.032793 -0.003775 0.197748 0.2250675 -0.3633402 0.8990983 0.0946082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2173 2174 0.148514 0.216735 -0.068051 -0.1972671 -0.1754165 0.0866067 0.9606321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2174 2175 -0.043267 0.071002 0.228418 0.6502108 0.2402800 0.6335422 0.3436796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2175 2176 0.058033 0.001100 0.139690 -0.5166266 0.3063948 0.7860842 0.1459137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2176 2177 0.082239 -0.003587 -0.064078 0.1341705 -0.6325235 -0.7469938 0.1546366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2177 2178 0.050437 0.026877 0.091491 -0.0739084 0.7393114 0.6662914 0.0633394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2178 2179 0.045253 -0.035261 0.090896 0.2504164 -0.1469925 -0.7987451 0.5269640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2179 2180 -0.040473 -0.073685 -0.238118 -0.1237638 0.3136633 0.1801378 0.9240391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2180 2181 -0.053311 -0.150787 -0.117138 -0.1934539 -0.1208270 0.6521117 0.7229985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2181 2182 -0.165735 -0.048014 0.133823 -0.7155017 0.1912653 0.5201367 0.4253618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2182 2183 0.175053 0.033114 0.063811 -0.3431905 -0.3037229 -0.6570454 0.5985516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2183 2184 -0.189357 0.113235 0.120119 0.1090479 0.6607313 -0.6683828 0.3237393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2184 2185 -0.016937 -0.090519 -0.065804 -0.1279769 -0.4987331 -0.5397259 0.6660204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2185 2186 0.070073 -0.028146 -0.024100 0.4836863 0.7044231 0.4965631 0.1525147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2186 2187 -0.098436 -0.094914 0.067690 -0.0638536 -0.6956017 -0.0074621 0.7155454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2187 2188 0.057121 0.112073 0.211456 -0.3159683 -0.0214099 -0.9460699 0.0682454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2188 2189 0.181368 0.052992 0.006849 0.2040519 -0.4828592 0.8227992 0.2195707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2189 2190 -0.035621 -0.036557 0.036552 0.0701975 0.6872562 0.4630471 0.5552825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2190 2191 -0.155723 0.124560 -0.002176 -0.0342217 -0.1462928 -0.8232525 0.5474327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2191 2192 -0.067115 0.047862 0.047546 0.3846017 0.3948154 -0.7144223 0.4310489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2192 2193 0.112424 0.228544 0.062774 -0.4317503 0.0116911 0.4946363 0.7541816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2193 2194 0.011222 0.014288 0.157888 0.4849654 -0.1407710 0.7002617 0.5046045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2194 2195 0.035407 0.149139 0.004356 -0.8003920 0.1401247 -0.5743771 0.0991393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2195 2196 0.222767 -0.078723 -0.046809 0.7214776 0.0415202 0.5819194 0.3729825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2196 2197 -0.172065 0.043844 -0.019778 -0.1463505 -0.6009943 -0.0730742 0.7823346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2197 2198 -0.144125 0.202267 0.033371 -0.3456882 0.3048284 0.3780046 0.8029270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2198 2199 -0.053816 0.023008 0.115454 -0.2191684 -0.1760967 0.6801529 0.6770135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2199 2200 0.053767 0.178236 0.111225 -0.0860570 -0.3435280 0.3099955 0.8823183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2200 2201 0.009691 -0.027894 0.118575 0.2453684 0.7626399 -0.5984686 0.0031636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2201 2202 -0.227792 0.040481 0.111583 0.7211588 0.4061303 -0.5180635 0.2158664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2202 2203 0.024398 0.013878 -0.082458 0.4476941 -0.4526503 -0.7583764 0.1397962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2203 2204 0.112494 0.064285 0.060312 0.3668417 -0.4178104 -0.3903972 0.7337927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2204 2205 -0.020441 0.032228 -0.022152 -0.4752325 -0.2283953 0.4648981 0.7112380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2205 2206 0.152813 0.219660 -0.015513 0.0001849 0.2650795 0.9449895 0.1916447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2206 2207 -0.180730 -0.191223 0.082859 0.1455976 0.1939528 -0.1474729 0.9588719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2207 2208 0.021625 0.127478 0.039715 0.2189117 -0.2562390 0.7593641 0.5565837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2208 2209 -0.082866 0.107123 0.036994 -0.0502034 -0.4825786 -0.7552805 0.4406232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2209 2210 -0.162905 -0.055970 0.012716 0.2779166 0.0205863 -0.8142298 0.5092823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2210 2211 -0.066498 -0.109995 0.064849 0.0105042 0.2941232 -0.8990947 0.3240525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2211 2212 0.053593 0.002356 0.060480 0.5803085 0.2003880 0.3282815 0.7178565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2212 2213 0.064193 -0.145175 0.002196 -0.7409230 -0.1351979 -0.5195930 0.4034572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2213 2214 0.028857 0.011476 0.045741 0.2081697 0.2344106 -0.4588154 0.8313877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2214 2215 0.183066 0.021297 0.136205 -0.0517024 -0.0606580 -0.4938100 0.8659095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2215 2216 -0.093823 0.061270 0.109330 -0.1773170 0.4912643 -0.3991080 0.7536119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2216 2217 -0.110762 0.002836 0.036506 0.6886240 -0.4087631 0.0220534 0.5985176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2217 2218 -0.029846 0.147048 -0.112742 0.1944446 -0.6685416 -0.7177399 0.0096337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2218 2219 -0.162207 0.238977 0.018286 0.3092361 0.0426416 0.4901056 0.8138496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2219 2220 0.065261 -0.049492 0.226061 -0.3754102 0.0735755 0.5649454 0.7310886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2220 2221 -0.172113 0.006599 -0.103902 0.3744447 -0.0257226 0.2542599 0.8913369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2221 2222 -0.101688 -0.052114 0.012964 0.0582938 0.5997409 -0.7617792 0.2379184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2222 2223 -0.005997 -0.222064 0.226977 -0.3019338 -0.4140358 0.5303575 0.6753749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2223 2224 -0.027712 -0.061984 -0.054870 0.6833459 -0.3907986 0.0919709 0.6098001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2224 2225 0.005944 0.019049 -0.019408 -0.2719459 0.1053155 0.8847521 0.3635488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2225 2226 0.003600 0.018785 0.099063 0.6324849 0.0580044 -0.4040725 0.6582733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2226 2227 -0.122987 -0.133216 0.018102 -0.5770213 -0.2207823 0.5958939 0.5130421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2227 2228 -0.018155 0.036312 0.016992 -0.2303072 -0.5370422 0.7166180 0.3807925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2228 2229 0.173001 0.062489 -0.048853 -0.3955535 -0.5056982 -0.6302918 0.4365077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2229 2230 -0.207622 -0.010393 0.103469 0.3640497 -0.7406214 0.5613055 0.0623208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2230 2231 0.175775 0.006729 -0.102446 0.3629165 -0.5907482 -0.0158917 0.7204552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2231 2232 -0.110322 0.150691 -0.256400 0.2906635 0.2232397 0.9170136 0.1573688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2232 2233 -0.065698 0.044662 0.070799 -0.4879302 -0.6704710 0.2997605 0.4717377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2233 2234 -0.013628 0.096464 0.198210 0.6328927 0.6231981 -0.3164966 0.3330177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2234 2235 -0.096142 -0.171637 0.147863 0.1169809 0.2745685 0.9226379 0.2442682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2235 2236 0.013623 -0.187718 -0.045018 0.5355586 -0.1645083 0.7582064 0.3335222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2236 2237 -0.136305 -0.003944 -0.252391 0.1628497 0.7981118 0.0856776 0.5737220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2237 2238 0.123138 0.016221 0.024569 0.3592306 -0.2686564 -0.7287042 0.5174624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2238 2239 -0.143130 -0.068160 0.000818 0.5351618 0.5468228 0.6283613 0.1405300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2239 2240 -0.037918 -0.178776 0.026095 -0.4174915 0.1714329 -0.5463737 0.7055405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2240 2241 0.238787 0.027679 -0.078351 -0.0205507 -0.3442343 0.9382058 0.0291609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2241 2242 -0.076638 0.177727 -0.082966 0.1160829 -0.1002285 -0.8260676 0.5423018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2242 2243 0.020305 -0.111537 0.069749 -0.5041481 -0.0905124 -0.3405251 0.7884700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2243 2244 -0.083936 -0.042768 -0.116149 0.1580738 0.1237259 -0.9786230 0.0447403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2244 2245 -0.023962 0.002573 -0.217548 0.5559266 0.0769964 0.7661247 0.3131616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2245 2246 -0.133108 -0.103323 -0.044820 -0.7358169 0.2294478 -0.3305776 0.5446518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2246 2247 -0.142287 0.017318 -0.016975 0.1308958 0.2901769 -0.9473173 0.0354067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2247 2248 -0.079154 -0.092958 -0.079830 -0.5530228 -0.0395049 -0.6194043 0.5558269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2248 2249 -0.068675 -0.138787 -0.033071 -0.3933022 0.5621943 -0.7259989 0.0466524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2249 2250 -0.049585 -0.002470 0.057387 0.2662607 0.0472884 0.7439348 0.6110892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2250 2251 -0.252652 -0.078642 0.086247 0.4120618 -0.7035559 -0.4004801 0.4181266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2251 2252 -0.040834 -0.126864 0.010242 0.4408602 -0.3754334 -0.7414262 0.3390859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2252 2253 -0.075887 0.026710 0.240733 -0.1388950 -0.6774065 0.4280851 0.5818692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2253 2254 -0.056759 0.058364 -0.068755 -0.4670590 -0.2824720 -0.3230123 0.7731290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2254 2255 0.065849 -0.136640 -0.118345 0.1217668 -0.8651217 0.4841132 0.0487009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2255 2256 0.175507 0.166198 -0.059020 -0.0355467 0.1135983 0.8953984 0.4290614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2256 2257 0.037865 -0.087979 -0.051523 -0.3484776 0.3042281 0.7306571 0.5021443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2257 2258 0.081530 0.322028 -0.228916 0.4757809 0.4088619 -0.4803090 0.6129990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2258 2259 -0.003364 -0.211612 -0.217642 0.1124447 0.6081544 0.7549557 0.2180512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2259 2260 -0.192139 -0.126072 0.182271 -0.1490577 -0.2881955 -0.6244316 0.7105001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2260 2261 0.051609 -0.041587 -0.148801 -0.5355989 0.2966541 -0.5887342 0.5277520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2261 2262 0.090109 0.096930 -0.023918 0.6918548 -0.2331141 -0.4288512 0.5320540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2262 2263 -0.079559 0.011596 -0.071753 -0.0876513 0.5019205 -0.2103514 0.8343532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2263 2264 -0.172004 0.142231 -0.105290 -0.1062793 -0.4352407 0.1609082 0.8794196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2264 2265 0.151510 0.021355 -0.139063 -0.0900717 -0.1583772 -0.4352893 0.8816615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2265 2266 0.052358 0.122693 0.078391 -0.0209471 -0.6265525 0.5962050 0.5015305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2266 2267 -0.065965 0.195608 0.031602 0.7025738 0.4085616 -0.5611720 0.1566954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2267 2268 0.084340 0.148604 0.047209 -0.6773495 0.1122826 0.7251499 0.0524200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2268 2269 -0.019358 -0.064437 -0.010766 0.1674399 0.7229724 -0.6446892 0.1834411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2269 2270 -0.217181 0.194969 -0.140042 -0.1300392 0.5245482 -0.8246986 0.1667670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2270 2271 -0.040215 -0.082983 -0.025628 -0.1463796 -0.2461837 -0.5237779 0.8022614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2271 2272 0.031204 -0.026707 0.102293 -0.1979973 -0.0790280 -0.0192157 0.9768226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2272 2273 -0.032276 0.063481 -0.012994 0.4975648 0.3579520 0.4612676 0.6415075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2273 2274 0.031065 0.121627 0.084459 -0.0952877 -0.2693221 -0.9535217 0.0958236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2274 2275 0.035824 -0.035675 -0.121707 -0.4847601 -0.3752311 -0.0039076 0.7900595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2275 2276 0.264700 -0.041192 -0.097102 -0.3308247 -0.0519727 -0.7799767 0.5286684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2276 2277 -0.042495 -0.067332 0.002142 0.1985410 0.0186378 0.9061204 0.3730682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2277 2278 -0.145882 0.004813 0.041215 0.4275663 -0.1784186 -0.8728187 0.1534317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2278 2279 0.132919 0.168583 0.058662 -0.0998633 0.4215866 0.2021012 0.8783207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2279 2280 -0.100710 -0.019607 -0.119378 0.3747828 -0.4325805 -0.8194509 0.0302033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2280 2281 -0.041641 0.112562 -0.068373 0.0936102 -0.4746208 -0.4297636 0.7624142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2281 2282 0.103607 0.077688 0.032797 0.8259251 0.3151307 0.1865833 0.4286340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2282 2283 0.197672 0.174283 -0.043133 -0.1859472 0.4013145 0.4396741 0.7817014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2283 2284 0.171174 0.222192 0.013866 0.1937969 0.5185182 -0.4206165 0.7187930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2284 2285 -0.112192 -0.079290 0.225526 -0.8548467 0.0810115 0.5102111 0.0485685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2285 2286 0.037425 0.014341 0.001768 -0.2134809 -0.2842669 -0.1507169 0.9224439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2286 2287 -0.016065 -0.231104 -0.062467 0.4574205 0.3934617 -0.4300469 0.6715758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2287 2288 0.023470 -0.181192 0.042366 0.2589362 -0.4408189 0.7518645 0.4163299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2288 2289 0.004417 0.098979 0.170565 -0.1092489 -0.3210497 -0.9124317 0.2290417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2289 2290 -0.006006 -0.060892 -0.148208 -0.1111331 -0.8683549 0.0982594 0.4732381 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2290 2291 -0.042664 0.042828 -0.166538 -0.4998094 0.1205402 -0.6476978 0.5622706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2291 2292 -0.057264 -0.022062 0.044250 0.6141145 -0.0242454 -0.2844259 0.7357836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2292 2293 -0.173244 -0.049156 -0.039054 -0.7155357 -0.2572984 0.0279580 0.6488640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2293 2294 0.037371 0.088166 0.039748 0.1355430 0.6239312 -0.3145431 0.7024248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2294 2295 0.081955 -0.282452 0.022190 0.1523345 0.7594792 -0.5030232 0.3833448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2295 2296 -0.119229 -0.244696 -0.017712 0.5481918 -0.1938529 0.8124525 0.0427516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2296 2297 0.104403 0.041353 0.064846 0.0640677 0.4396630 0.3733711 0.8143622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2297 2298 0.073272 0.029832 -0.142360 -0.2341032 -0.7820745 -0.4871479 0.3102292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2298 2299 0.132966 -0.027540 0.267131 0.0300697 -0.1183569 0.8202030 0.5588869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2299 2300 -0.064652 -0.200874 -0.067485 0.8148551 0.3052063 0.3782509 0.3158900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2300 2301 0.155548 0.251915 -0.020480 -0.2891265 -0.5316758 -0.7160160 0.3479192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2301 2302 0.046038 0.088780 0.048321 -0.4421333 0.3978756 0.3203605 0.7372803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2302 2303 -0.036321 -0.103703 0.043156 0.7149121 -0.1239686 0.2864987 0.6256605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2303 2304 0.001913 0.094517 0.127477 0.0057620 -0.8212753 -0.4265108 0.3788960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2304 2305 0.025709 -0.043139 0.106176 -0.4936002 -0.7038078 -0.4534819 0.2353031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2305 2306 0.096784 0.170860 -0.055887 -0.2658330 -0.6193663 -0.7200859 0.1649072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2306 2307 -0.394777 -0.008726 0.121105 -0.3176665 0.1251355 0.5110866 0.7888090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2307 2308 -0.048896 0.092576 0.174369 0.2579426 -0.3364146 0.2623460 0.8668711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2308 2309 -0.108498 0.183607 0.078565 -0.0105641 -0.0746488 0.9955585 0.0563849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2309 2310 0.229072 -0.151927 0.100891 -0.1184157 -0.7394281 0.3991950 0.5290247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2310 2311 0.080373 -0.073560 -0.050031 -0.5082427 0.0582281 -0.7696975 0.3819222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2311 2312 -0.045974 0.001636 -0.103779 -0.5156797 0.8280708 0.0076779 0.2198050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2312 2313 0.003693 0.018956 -0.088841 0.4382073 0.0819393 -0.8615603 0.2428460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2313 2314 -0.039584 -0.063125 0.012468 0.3321204 0.5694118 0.4587923 0.5957984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2314 2315 0.104263 0.157267 -0.041416 -0.6164554 -0.0660029 0.4200325 0.6627209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2315 2316 0.020265 0.029127 0.001916 0.0302655 0.6244408 -0.6420498 0.4437677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2316 2317 -0.053075 -0.014091 -0.098877 0.3258924 0.3435172 0.1900200 0.8600479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2317 2318 0.078819 0.015245 0.006308 0.2025852 0.4262457 -0.8590083 0.1984402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2318 2319 0.099689 -0.033267 -0.044846 -0.0658320 0.6456933 -0.7602692 0.0271474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2319 2320 -0.118049 0.008294 -0.092353 0.5892074 0.2975026 -0.3772780 0.6496061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2320 2321 -0.121112 -0.154214 0.085783 -0.5013153 -0.4254610 -0.5481578 0.5169032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2321 2322 -0.027140 -0.065374 -0.017433 0.1960388 0.4421135 -0.4517340 0.7496938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2322 2323 0.026370 0.025060 -0.024111 0.4573302 -0.2355534 -0.5201594 0.6817609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2323 2324 -0.015564 -0.082357 -0.094205 -0.2338211 0.6163844 -0.1273552 0.7410659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2324 2325 0.125706 -0.035006 0.127546 -0.0817757 -0.6041043 0.3466829 0.7128687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2325 2326 0.201500 -0.085611 0.159729 0.4360449 0.0249828 0.8434185 0.3128673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2326 2327 -0.130736 0.131701 0.004628 0.6144051 0.1305047 0.2118660 0.7487240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2327 2328 -0.126675 -0.000669 -0.026473 0.0586729 -0.3381874 0.9158718 0.2082439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2328 2329 -0.075742 -0.036852 -0.150743 -0.4844590 -0.6939385 0.4995893 0.1848227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2329 2330 0.027800 0.037429 -0.121263 0.5107764 -0.1090248 -0.4607219 0.7176046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2330 2331 -0.146422 0.329117 -0.062898 -0.2494952 -0.2592958 0.7121097 0.6028412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2331 2332 0.025231 -0.031024 0.069933 0.2310334 -0.0480693 0.1436284 0.9610847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2332 2333 0.130844 -0.233941 -0.125742 0.0708348 -0.2068231 0.2660300 0.9388475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2333 2334 0.162156 -0.159913 -0.077289 0.4250058 -0.1630202 0.8825378 0.1179895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2334 2335 -0.032917 0.104694 0.074128 0.5512146 0.4251849 -0.4430069 0.5649117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2335 2336 0.110849 -0.115785 -0.015109 -0.8384364 -0.4275313 0.0116904 0.3377938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2336 2337 0.011059 -0.145084 -0.150898 0.7286280 -0.0705169 -0.0326215 0.6804883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2337 2338 -0.179160 -0.013204 -0.034228 -0.0776103 0.3875967 -0.9062077 0.1501102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2338 2339 -0.158186 0.008895 0.064231 0.7022533 0.4890249 -0.5153732 0.0456664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2339 2340 -0.166786 -0.056850 0.025714 -0.1953263 0.1380109 -0.8498300 0.4696697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2340 2341 -0.016884 0.046800 0.016028 -0.1310708 0.5026773 -0.5466248 0.6567628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2341 2342 0.198054 -0.092042 0.088391 -0.1985277 0.4699706 -0.4236784 0.7484725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2342 2343 0.155249 0.128303 -0.041905 -0.1524837 0.4691732 -0.5960962 0.6334782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2343 2344 -0.063239 0.139525 -0.153017 0.4691245 -0.4285035 0.6587956 0.4028589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2344 2345 0.008277 0.105973 -0.089868 0.5128014 -0.0345839 0.1452626 0.8454215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2345 2346 -0.038842 -0.089087 -0.043644 -0.2736399 -0.0394817 -0.4782366 0.8335779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2346 2347 -0.053558 0.091949 -0.065869 -0.1239069 0.1763485 0.8947795 0.3910471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2347 2348 -0.195980 0.089470 -0.024455 -0.1447215 0.4492216 -0.1292577 0.8720941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2348 2349 0.099507 0.002773 -0.211833 0.5246281 0.3888994 -0.6717969 0.3495876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2349 2350 0.068237 0.089539 -0.037080 0.0348365 0.5057225 -0.7232618 0.4689600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2350 2351 0.095229 0.023666 0.021324 0.8557219 0.1322152 -0.2517457 0.4322999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2351 2352 0.158680 -0.179052 -0.059706 -0.7722685 0.1856395 0.2344991 0.5604905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2352 2353 0.034728 -0.054379 -0.038695 0.6972320 -0.0918842 -0.0821038 0.7061754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2353 2354 0.024702 -0.141391 -0.255395 -0.1832258 0.1896727 -0.5016384 0.8239001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2354 2355 0.022989 -0.093799 -0.105193 0.0201830 -0.7511490 0.1109911 0.6504220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2355 2356 -0.014857 -0.234752 -0.060229 0.1585937 0.7769216 -0.0847112 0.6033779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2356 2357 -0.122593 -0.117560 -0.006437 0.3652696 -0.0518791 -0.6103929 0.7009331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2357 2358 -0.051421 -0.094787 -0.014087 -0.1696091 -0.6850961 0.6170731 0.3479899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2358 2359 0.059371 -0.040714 0.007889 -0.1950266 0.3082185 -0.4104270 0.8357725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2359 2360 -0.026026 -0.119306 0.116624 -0.3992846 0.3152628 -0.7710356 0.3829952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2360 2361 0.030328 -0.053109 -0.221605 -0.1481216 -0.2862536 -0.6798949 0.6586818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2361 2362 -0.004519 -0.041100 -0.040847 0.0747683 0.3464961 0.9271585 0.1213557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2362 2363 -0.019383 -0.194201 -0.183273 -0.1559597 -0.2105098 0.5321413 0.8051011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2363 2364 0.028469 0.171264 -0.018669 0.4760304 0.1902107 -0.2257710 0.8283975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2364 2365 0.103703 -0.190178 -0.023484 -0.0338285 -0.1387636 -0.2841048 0.9480953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2365 2366 0.058869 0.038432 0.022901 0.3743192 -0.1204875 -0.0530741 0.9179058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2366 2367 0.031429 0.007061 -0.003267 -0.7639740 -0.2937967 0.5595745 0.1300138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2367 2368 -0.057429 -0.086012 -0.102069 0.0430455 -0.1632741 0.9253336 0.3394795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2368 2369 -0.009102 0.079589 -0.005366 0.1352969 0.0614237 -0.9257477 0.3477256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2369 2370 -0.137546 0.093509 0.033050 -0.2749887 -0.3434121 0.5386560 0.7185395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2370 2371 -0.048279 0.198136 0.125310 -0.8242593 -0.1150430 0.3261506 0.4483163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2371 2372 -0.041874 -0.148767 0.116727 -0.5371734 -0.4668897 0.6726448 0.2025037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2372 2373 -0.018162 -0.104297 0.110438 0.2083328 -0.6364010 -0.6757198 0.3082109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2373 2374 0.087726 -0.113268 -0.100796 -0.6326312 0.5311780 0.1955834 0.5285592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2374 2375 -0.107134 -0.049215 -0.125503 0.1938409 0.5304300 -0.4753041 0.6746523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2375 2376 0.204690 -0.128304 0.072830 -0.2286651 -0.7397420 -0.0851782 0.6270875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2376 2377 -0.032981 -0.090234 0.063804 -0.1756511 0.9142818 -0.3647303 0.0143992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2377 2378 -0.162008 -0.203752 0.115873 0.3505063 0.6191838 -0.2236672 0.6661304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2378 2379 -0.173040 0.073027 0.162217 -0.3438949 -0.4022321 0.0692247 0.8456675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2379 2380 -0.019106 0.030854 -0.023979 0.4315851 -0.2240848 -0.7823715 0.3891210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2380 2381 -0.019674 -0.057741 -0.012412 -0.5046143 -0.5777339 -0.5702231 0.2939959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2381 2382 0.020994 -0.105218 -0.201981 0.0026129 0.5539902 0.7203389 0.4173727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2382 2383 -0.118833 -0.010784 0.143365 -0.0411213 0.0793575 -0.7191280 0.6891055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2383 2384 -0.004693 0.024068 -0.044745 -0.0070668 -0.2880193 -0.4766496 0.8305421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2384 2385 0.049853 0.008373 -0.084992 0.0594153 -0.4513817 0.7847017 0.4206753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2385 2386 -0.088787 0.005370 -0.136563 0.4661012 0.3602352 0.5464291 0.5953113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2386 2387 -0.112381 -0.208787 0.066632 -0.9146621 -0.2416989 0.3215283 0.0399303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2387 2388 -0.086092 -0.114078 -0.033464 -0.2604965 -0.0758660 0.8530960 0.4456604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2388 2389 0.024065 0.022272 0.021916 -0.1113882 -0.3992094 -0.5444639 0.7292349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2389 2390 -0.079464 -0.088869 0.174947 0.0468437 -0.5746985 0.8170234 0.0003369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2390 2391 0.013763 0.055079 0.095453 -0.1717048 0.0223285 0.9738402 0.1471537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2391 2392 -0.053779 0.127097 -0.070829 -0.7405917 -0.3413663 0.4156521 0.4027732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2392 2393 -0.070378 -0.011549 0.128233 0.2652919 -0.3084782 -0.5049757 0.7612234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2393 2394 0.045820 0.072801 0.017835 -0.1429163 0.3266513 0.1839903 0.9159811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2394 2395 -0.149411 0.135335 -0.030547 -0.3281830 -0.3301179 0.0273605 0.8846296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2395 2396 -0.152692 0.094207 0.161028 0.7319522 0.4573225 0.2396781 0.4445859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2396 2397 -0.188279 0.149826 -0.001700 -0.1146903 0.3172486 0.4013861 0.8515214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2397 2398 -0.003430 0.082114 0.101204 -0.4714475 0.0332750 0.5640000 0.6771514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2398 2399 0.008749 0.036463 -0.102104 -0.5014524 -0.0222779 -0.8634464 0.0500954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2399 2400 0.138018 0.058738 0.015996 0.2212127 0.9074961 0.2174833 0.2832258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2400 2401 -0.147562 -0.005778 0.166569 0.8313713 -0.0572229 -0.5308175 0.1542079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2401 2402 0.053718 -0.059048 -0.188969 0.5827744 -0.1619262 0.6092657 0.5127858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2402 2403 0.141959 -0.056690 0.104449 -0.3759410 -0.1080989 -0.4647156 0.7943692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2403 2404 -0.155007 -0.154567 0.157749 -0.3237449 -0.6425807 0.5918409 0.3633230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2404 2405 -0.026170 -0.052573 -0.082692 0.1333425 0.6846526 -0.1762921 0.6945442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2405 2406 -0.027582 -0.151648 0.056112 -0.0007576 -0.6583518 0.3557729 0.6633234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2406 2407 0.076009 -0.201924 0.053168 0.3921513 0.4523693 0.3586500 0.7162049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2407 2408 -0.170251 -0.243089 0.011706 0.4220774 -0.3033050 -0.6008672 0.6073017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2408 2409 0.097444 0.046350 0.072251 -0.2616993 -0.4813982 0.5604277 0.6210395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2409 2410 -0.067084 -0.185912 -0.075971 0.1133483 0.5315282 0.0562196 0.8375376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2410 2411 -0.030111 -0.033683 0.024743 -0.2608129 -0.1652353 0.4486075 0.8387045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2411 2412 -0.036521 0.070919 -0.021503 -0.1366055 0.0587395 0.3909967 0.9083007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2412 2413 -0.014383 -0.078646 0.005141 -0.1477127 -0.8255033 0.1409402 0.5261759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2413 2414 -0.152482 -0.039431 -0.151418 -0.0980175 0.8372319 -0.1252979 0.5231977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2414 2415 -0.047721 -0.003085 -0.071644 0.0489441 -0.5552954 0.1651619 0.8136172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2415 2416 -0.035892 -0.050387 -0.043558 0.6937116 0.0336998 -0.4636611 0.5501335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2416 2417 -0.141689 0.032835 -0.079085 0.0715423 -0.7092421 -0.6626645 0.2296370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2417 2418 0.048985 0.001150 0.106454 0.1212215 0.4203565 0.8823238 0.1735236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2418 2419 -0.149042 0.046259 -0.002164 0.0324301 -0.0600429 -0.9643134 0.2558177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2419 2420 0.103455 -0.120067 -0.066858 -0.2722236 -0.8411923 0.3504707 0.3089662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2420 2421 -0.250094 0.027828 -0.146306 0.3279876 0.8700005 -0.2259148 0.2906644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2421 2422 0.127907 0.057822 -0.071251 0.6833592 0.4479214 -0.4390392 0.3736726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2422 2423 0.007797 0.180714 0.012437 -0.1040379 -0.4800458 -0.6707254 0.5557514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2423 2424 0.114904 -0.009479 0.088052 -0.0108401 -0.4026593 0.7322860 0.5490949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2424 2425 0.142423 -0.105792 -0.069142 -0.5324326 -0.7021639 0.1759026 0.4387934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2425 2426 -0.228887 -0.000669 -0.020069 0.7422865 -0.4720117 -0.4703678 0.0704978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2426 2427 0.109566 0.013681 0.092223 -0.3678447 0.2391269 0.5161194 0.7356149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2427 2428 -0.064312 0.125354 -0.066476 -0.1824643 -0.3030853 0.2925507 0.8884032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2428 2429 -0.196154 0.112172 0.169538 -0.7303621 0.2528120 -0.5125409 0.3741111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2429 2430 -0.037872 0.016321 -0.047482 0.7997554 0.4401120 0.3825065 0.1427641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2430 2431 0.037416 -0.110096 -0.069518 0.1421774 0.2660281 0.4415296 0.8450244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2431 2432 -0.219550 0.056945 -0.044189 0.4032068 -0.0409415 -0.4440376 0.7991112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2432 2433 -0.175327 -0.006470 -0.086393 0.0141416 -0.0840491 -0.0308794 0.9958826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2433 2434 0.008461 0.102849 -0.182700 -0.3198772 0.0149339 0.3056323 0.8966853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2434 2435 -0.094834 0.144095 0.035354 -0.3357886 0.1737733 0.0007659 0.9257690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2435 2436 -0.275454 0.024512 0.067366 -0.2340289 -0.2919769 -0.0205221 0.9271240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2436 2437 -0.072028 -0.065245 -0.020845 0.0754971 0.2702088 -0.6885231 0.6687475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2437 2438 -0.159276 -0.200323 -0.055434 0.4696236 0.0538535 0.3810727 0.7945672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2438 2439 -0.006325 -0.041849 0.046973 0.7937680 -0.3166413 0.5003253 0.1390869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2439 2440 0.059066 0.079181 0.002981 -0.5560950 0.7473818 -0.3631841 0.0166158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2440 2441 -0.061288 -0.016772 -0.040421 0.4667691 0.2401215 -0.3669423 0.7679985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2441 2442 -0.100273 -0.099716 0.067626 0.0177375 -0.2451611 0.9651573 0.0897371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2442 2443 -0.110787 -0.115248 -0.096923 -0.0357360 -0.6938401 0.5255736 0.4910003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2443 2444 0.064190 0.074771 -0.185976 0.4641458 -0.6852667 -0.0338920 0.5602049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2444 2445 -0.039813 -0.089918 0.025775 0.0668815 0.5439454 0.8340738 0.0630166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2445 2446 0.014681 -0.023787 -0.024330 0.2342868 -0.6854060 -0.0850258 0.6841776 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2446 2447 -0.011757 -0.005951 -0.092699 0.2143426 0.3149131 0.5876218 0.7138541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2447 2448 -0.019432 0.037658 -0.178529 0.3403447 0.3586594 -0.5320075 0.6873841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2448 2449 0.062694 0.094551 -0.043639 0.0156461 -0.8725941 -0.4878503 0.0183522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2449 2450 -0.070785 0.012836 -0.183781 0.2177609 0.7424024 0.5643825 0.2879084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2450 2451 0.094800 -0.142602 -0.096966 -0.2452847 0.2158886 -0.9447005 0.0277225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2451 2452 -0.090044 -0.112635 0.044511 -0.6130117 0.6809778 -0.3475666 0.1992071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2452 2453 0.010512 -0.002578 0.115230 0.7266835 -0.5959639 0.3416416 0.0062648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2453 2454 0.087525 0.062962 0.225030 0.1275909 0.6497567 0.3231476 0.6761009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2454 2455 -0.058069 0.062836 -0.052574 -0.2305927 -0.1352530 -0.6083271 0.7473097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2455 2456 -0.097040 0.177980 0.147953 0.7425764 -0.0551280 0.3668533 0.5576378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2456 2457 -0.031112 0.047208 0.059832 0.0480698 0.3415486 0.6533620 0.6739080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2457 2458 0.317070 0.060359 0.047533 0.3251900 -0.4747669 0.3271037 0.7495672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2458 2459 0.026301 -0.140730 0.013421 -0.0928638 -0.3710439 -0.9230548 0.0408975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2459 2460 0.267332 0.092833 -0.004371 -0.0287118 -0.7952623 0.2861927 0.5336921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2460 2461 0.123279 0.055913 0.076740 0.7923027 -0.0146446 -0.0267231 0.6093668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2461 2462 0.181169 0.115280 0.180845 -0.4288023 -0.5568118 -0.4972956 0.5087104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2462 2463 -0.248230 -0.110324 0.058938 -0.4829723 0.1086487 0.8357051 0.2377607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2463 2464 -0.020605 0.152670 0.057508 0.5248733 -0.4639924 -0.1045716 0.7058923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2464 2465 -0.040925 -0.022835 0.068521 -0.6373693 0.6508703 -0.1420460 0.3872352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2465 2466 -0.028633 0.061025 -0.032821 0.2632510 -0.2358110 0.9266251 0.1282884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2466 2467 0.258457 0.090790 -0.019548 0.0278951 0.3070706 0.9507892 0.0304854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2467 2468 0.081873 -0.029955 -0.058299 -0.1988007 -0.1852653 0.7728245 0.5734957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2468 2469 0.167098 0.008650 -0.163699 -0.4031745 0.1334357 0.3877612 0.8180993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2469 2470 -0.007474 0.037726 0.066577 -0.2537284 -0.3650343 0.5380206 0.7161744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2470 2471 0.042321 -0.124883 -0.160343 -0.2909836 0.5645896 0.7487566 0.1895541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2471 2472 0.053886 0.115064 0.051567 -0.1565102 -0.8202216 0.2902259 0.4674505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2472 2473 0.055724 -0.114425 0.128180 -0.3376581 -0.0658504 -0.8172071 0.4624104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2473 2474 -0.004695 0.025659 0.167249 -0.0799877 -0.2251996 0.6612663 0.7110654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2474 2475 -0.035435 -0.120224 0.036252 0.3784690 0.7857906 0.4247943 0.2425784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2475 2476 0.047483 0.115943 -0.103897 -0.0949570 -0.9060955 0.0827070 0.4038980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2476 2477 0.085335 0.024194 0.015367 0.4089477 0.0124061 0.8107316 0.4187148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2477 2478 0.035258 -0.098351 0.067870 0.4625560 0.0912275 -0.8465003 0.2472990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2478 2479 0.106923 0.185938 -0.089416 -0.5418860 -0.2115321 -0.4606796 0.6703642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2479 2480 0.014310 0.026358 0.100576 0.1617462 -0.6044627 0.7799409 0.0124562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2480 2481 -0.015055 -0.104987 -0.002036 -0.6340198 0.1401208 -0.7602501 0.0201210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2481 2482 -0.117559 -0.025976 -0.052524 0.0484004 0.3076385 0.3126405 0.8973694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2482 2483 0.082962 0.011316 -0.120645 -0.0261725 0.2094824 0.8809668 0.4234733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2483 2484 -0.029325 -0.001987 0.214431 0.5123620 -0.1360817 -0.5280897 0.6633914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2484 2485 -0.015000 0.251827 0.004064 -0.6612129 0.3348099 0.3653944 0.5631933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2485 2486 0.078517 -0.067900 0.083227 0.2017893 0.1622070 0.9353737 0.2409273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2486 2487 0.108078 -0.080747 0.109892 -0.3734493 -0.3493453 -0.6878285 0.5151557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2487 2488 0.036140 0.114607 0.234281 -0.7658811 -0.0814696 -0.3055228 0.5598612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2488 2489 0.009990 -0.129955 0.010869 -0.0676473 0.4164253 0.4475072 0.7885120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2489 2490 0.088601 -0.040111 0.142114 0.2456805 -0.0715859 0.7939603 0.5514922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2490 2491 0.057719 -0.114955 -0.047438 0.3133956 0.1051750 0.9148256 0.2319817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2491 2492 0.057890 0.047470 -0.034375 0.4717139 0.4336623 0.6596193 0.3928427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2492 2493 -0.032729 -0.134416 0.033829 -0.2626728 -0.2531352 0.0753562 0.9280339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2493 2494 -0.160747 0.080889 0.082844 0.7100099 0.0178590 -0.1375802 0.6903902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2494 2495 -0.031676 0.123078 -0.027960 -0.7047361 0.1812260 0.5516108 0.4077128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2495 2496 -0.027462 0.017690 0.064595 0.7617284 -0.2694242 0.2293654 0.5427448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2496 2497 0.033912 0.207493 -0.048458 0.3660778 0.1878192 0.7718025 0.4848008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2497 2498 0.077929 -0.036838 0.126996 -0.2570431 -0.2461435 -0.8730921 0.3332453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2498 2499 0.128940 0.005971 -0.095572 -0.6928542 -0.0085430 -0.6266508 0.3566354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2499 2500 -0.062464 0.025977 0.092057 0.8834093 0.1178747 -0.4049636 0.2042010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2500 2501 -0.076417 -0.025463 0.040804 0.3270680 -0.5458096 -0.5965491 0.4891295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2501 2502 -0.052682 -0.029505 0.051255 0.2936510 -0.0564887 -0.5122035 0.8051246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2502 2503 -0.003483 0.157937 0.157561 -0.4669538 -0.0789843 0.0045972 0.8807352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2503 2504 -0.087150 -0.088235 -0.017338 0.7109959 0.1646803 -0.4985650 0.4677587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2504 2505 -0.226597 -0.000000 -0.027079 0.2839406 -0.5463709 -0.5386452 0.5750808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2505 2506 0.064275 -0.019699 0.192581 0.1599233 -0.3485178 -0.3630472 0.8492094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2506 2507 -0.030347 0.031592 -0.014247 -0.4435626 0.4426185 0.1927781 0.7551011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2507 2508 0.097796 -0.065371 -0.067691 -0.2384233 0.1348965 0.8283535 0.4886591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2508 2509 -0.062161 -0.217499 -0.052560 -0.0412797 -0.5173652 0.8194234 0.2432580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2509 2510 0.197916 -0.183232 -0.013602 0.3253671 0.1819231 0.8331696 0.4084956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2510 2511 -0.120144 -0.009024 -0.018310 -0.1107944 0.1838078 -0.9766069 0.0133519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2511 2512 -0.174549 -0.058530 -0.128712 -0.0643731 0.6767730 -0.6683285 0.3019460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2512 2513 0.078911 0.072121 0.058270 -0.1062030 -0.1737004 0.8762938 0.4366442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2513 2514 0.033758 0.079503 0.035816 0.1840172 0.4301697 -0.8837931 0.0011699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2514 2515 0.106853 0.067906 -0.012615 0.1243229 -0.5502458 0.6950294 0.4457663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2515 2516 -0.150239 0.185810 0.083198 0.3865063 -0.2145700 0.4251112 0.7898437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2516 2517 0.073426 0.148443 -0.012404 -0.7993173 0.3445241 -0.0390082 0.4907886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2517 2518 -0.191231 -0.184761 0.105748 0.9375478 -0.2254315 0.1502914 0.2181679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2518 2519 0.110386 0.069606 -0.076191 -0.3963772 0.2726007 -0.8199335 0.3102952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2519 2520 -0.078900 -0.132709 0.000870 -0.4356442 -0.6414959 0.4901230 0.3980911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2520 2521 -0.024959 0.047219 0.104819 0.2782428 -0.6427740 0.5736042 0.4247362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2521 2522 0.121276 -0.016156 -0.002074 -0.5689410 0.0614797 -0.7348548 0.3640259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2522 2523 -0.139505 0.130626 -0.123420 -0.7833469 0.2953263 -0.3520462 0.4185851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2523 2524 -0.084531 -0.012350 -0.093051 0.0776650 -0.3613429 0.9221094 0.1145151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2524 2525 0.069475 0.169636 -0.112098 -0.1062562 -0.5166038 -0.7875211 0.3188113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2525 2526 -0.003662 0.095713 0.210134 0.3892297 0.4994639 0.7242362 0.2729797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2526 2527 0.059279 -0.093742 -0.109342 -0.1183491 0.2326635 0.0700687 0.9627832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2527 2528 0.113949 -0.149617 -0.030018 -0.1276212 0.2690973 -0.9541072 0.0312889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2528 2529 -0.154515 0.165543 -0.017426 -0.1019162 -0.0337010 -0.9918398 0.0687831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2529 2530 0.044960 -0.160093 -0.109519 0.0423528 0.4539033 0.5084819 0.7304959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2530 2531 -0.005128 -0.181174 -0.175440 0.5454353 0.7015248 0.4503845 0.0867009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2531 2532 -0.254293 -0.005500 -0.144905 0.3926506 -0.0542437 0.8953456 0.2030748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2532 2533 0.185403 0.116502 -0.032014 -0.3474787 -0.7399010 0.5590409 0.1388465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2533 2534 -0.092097 0.097532 -0.009328 0.4906592 -0.6264749 -0.2445441 0.5540586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2534 2535 -0.089625 -0.152882 -0.100510 0.0241067 0.0666716 -0.9270296 0.3682253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2535 2536 0.077161 -0.003931 -0.090110 -0.3816822 -0.3901754 -0.7775819 0.3121669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2536 2537 -0.075945 0.005949 -0.158493 -0.4570874 0.3178741 -0.8250939 0.0961629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2537 2538 -0.010175 -0.023260 0.001971 0.3238265 -0.1578665 -0.9247479 0.1227021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2538 2539 0.255725 0.014872 0.035375 0.7027024 -0.4015472 -0.5746902 0.1212451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2539 2540 -0.015470 -0.199117 -0.061590 -0.6358697 -0.3861208 -0.0142819 0.6681141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2540 2541 0.017717 0.097173 -0.086934 -0.0321464 -0.0066316 -0.1162404 0.9926786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2541 2542 0.064120 -0.011512 0.004776 -0.3240781 -0.4814969 0.5420458 0.6077175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2542 2543 0.070029 0.106543 -0.000694 0.8781975 -0.3280800 -0.2414168 0.2507000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2543 2544 -0.013665 -0.069732 0.087952 -0.7904903 0.0832064 -0.3420122 0.5012280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2544 2545 0.123368 0.086374 -0.012574 0.4641848 -0.1971877 -0.4718313 0.7232044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2545 2546 -0.038927 -0.070792 0.047699 -0.8938846 0.1577958 -0.3060202 0.2870931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2546 2547 0.043658 0.038915 0.132285 -0.1041719 -0.7644406 0.6353013 0.0342190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2547 2548 -0.014170 -0.133972 -0.315729 -0.1083553 -0.1714416 0.7315547 0.6509183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2548 2549 -0.104247 -0.136823 -0.098540 -0.4760451 -0.5002322 0.2206290 0.6888190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2549 2550 -0.021716 0.083839 -0.184939 0.1129632 -0.1358547 0.9830598 0.0487471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2550 2551 -0.088664 -0.114803 -0.017006 -0.5197466 -0.1025693 0.8418308 0.1032664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2551 2552 0.020646 0.045339 -0.012443 -0.2243220 -0.2617591 -0.9266848 0.1497231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2552 2553 -0.121892 -0.035380 -0.030630 -0.7795173 0.2139475 0.2099229 0.5500105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2553 2554 -0.156050 0.048212 -0.062105 0.3740399 0.3424552 0.7437783 0.4354452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2554 2555 0.047231 0.087561 -0.113656 0.2706098 -0.1133636 -0.9069665 0.3022100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2555 2556 0.107331 0.037945 -0.057146 -0.1380476 0.2830898 -0.9284223 0.1970660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2556 2557 0.004379 0.167485 0.020111 -0.1405368 -0.3925932 -0.4884099 0.7665349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2557 2558 -0.044479 -0.127539 0.098472 0.4681642 0.5070401 0.4443263 0.5712326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2558 2559 -0.208969 -0.149950 0.112773 -0.7331590 -0.0695535 -0.6763962 0.0113303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2559 2560 -0.159832 0.066983 -0.042298 0.4328018 -0.6597388 0.5580368 0.2569480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2560 2561 -0.045659 0.125948 -0.073802 0.0366180 -0.6469800 0.6310030 0.4265106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2561 2562 0.115914 -0.178242 0.046744 0.1899015 0.3486455 -0.8886771 0.2294271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2562 2563 0.012073 0.001591 0.007418 -0.6670374 0.0034039 -0.1161003 0.7359145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2563 2564 -0.212932 -0.063166 0.109829 0.4947168 -0.3944877 -0.0169941 0.7741743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2564 2565 -0.093188 -0.001646 0.070957 0.3352172 0.3968841 0.0532787 0.8528035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2565 2566 -0.148483 0.036997 -0.125231 0.1392989 -0.1361044 -0.9698675 0.1463846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2566 2567 -0.081111 -0.187360 0.034037 -0.6097899 0.0984329 0.3316074 0.7130946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2567 2568 -0.165400 -0.091122 -0.151489 -0.1017521 -0.6976620 0.6172415 0.3491807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2568 2569 0.079344 0.263362 0.076528 0.0288090 0.0691281 -0.2108454 0.9746464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2569 2570 -0.036833 0.113945 0.030012 0.4971924 0.1173300 0.2889401 0.8096586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2570 2571 0.003237 0.155476 -0.139830 -0.5099354 0.4083353 -0.1669876 0.7384736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2571 2572 0.031227 -0.039352 0.198858 -0.0708962 -0.0552618 0.8362201 0.5409767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2572 2573 -0.089554 -0.013778 0.079144 -0.0894508 -0.5818514 0.2210210 0.7775585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2573 2574 0.067019 0.013302 -0.017900 -0.2005908 0.1545568 -0.8233674 0.5078795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2574 2575 0.180917 0.094661 -0.086796 0.2118469 -0.6679665 0.3750864 0.6068375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2575 2576 0.044170 -0.067876 -0.089202 -0.3603605 0.5477716 0.5072269 0.5592919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2576 2577 -0.108604 0.004605 0.000630 -0.1575855 0.1220288 0.4804483 0.8540756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2577 2578 0.112927 -0.023198 0.091475 0.0963985 -0.4108293 -0.7617992 0.4915167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2578 2579 0.031543 0.156543 0.112330 0.1887226 -0.3543695 0.9158260 0.0082914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2579 2580 0.067351 -0.080813 -0.025946 -0.2614967 -0.0435697 -0.7649337 0.5870243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2580 2581 0.042738 -0.164969 -0.042416 -0.2588491 0.7616819 -0.0552969 0.5914221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2581 2582 0.025549 -0.021017 0.111325 0.2063748 -0.2377468 0.0360034 0.9484670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2582 2583 -0.001032 -0.016173 -0.205322 0.0619538 -0.2213983 -0.7100069 0.6656085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2583 2584 -0.042046 -0.079043 0.152306 -0.4031159 0.6529856 0.2139883 0.6044141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2584 2585 -0.113678 0.121256 0.058438 0.5227261 -0.6854208 0.0463098 0.5047882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2585 2586 0.088439 0.157393 0.063625 -0.4335204 -0.1382942 -0.5076071 0.7316214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2586 2587 -0.102260 0.005397 -0.140406 -0.3662143 -0.5354464 -0.4698755 0.5986662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2587 2588 0.105972 -0.026393 -0.072720 -0.2252467 0.0426158 0.5746833 0.7856125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2588 2589 0.133412 0.053824 0.073984 0.0157321 -0.2453150 0.6053617 0.7570404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2589 2590 0.062892 0.086996 -0.063033 -0.2838429 0.4998159 -0.7189075 0.3908827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2590 2591 0.091485 0.007958 0.121099 0.1814876 0.2907120 -0.3689847 0.8639439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2591 2592 -0.001013 -0.079971 0.223054 -0.5221306 -0.1081509 0.4106709 0.7396164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2592 2593 0.106104 0.135187 0.042828 0.2373381 0.0358676 0.8078533 0.5382909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2593 2594 0.039168 -0.011864 0.006026 -0.5352055 -0.2154557 -0.0494586 0.8152838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2594 2595 -0.056538 -0.073919 0.087814 0.0058875 0.4369741 -0.6525329 0.6190475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2595 2596 0.080841 -0.059973 -0.063357 -0.1409674 0.0162440 0.9884289 0.0535977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2596 2597 0.185622 0.048946 0.106678 -0.6695587 -0.5267574 -0.4091290 0.3268506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2597 2598 0.074892 -0.208147 0.111441 -0.1602595 -0.3043340 0.9298104 0.1309592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2598 2599 -0.026510 -0.011458 -0.079088 -0.1424259 -0.2458885 0.7777922 0.5606184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2599 2600 0.058797 -0.075151 0.058789 -0.5248838 -0.5493049 -0.5494830 0.3476055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2600 2601 0.119478 0.175654 0.072760 0.2094443 0.8147588 0.2637206 0.4719668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2601 2602 0.189085 -0.063628 0.031809 -0.0466111 -0.7275978 -0.5546804 0.4009470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2602 2603 -0.021604 -0.022395 -0.028988 -0.0504773 0.1932604 -0.3546298 0.9134222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2603 2604 -0.085885 -0.005559 0.016053 0.0377717 -0.8782961 0.0484669 0.4741520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2604 2605 -0.028793 0.116475 0.198123 -0.2226777 0.2727775 -0.8260614 0.4400336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2605 2606 0.116725 -0.042959 0.036799 -0.2491328 -0.0818746 0.7749762 0.5750142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2606 2607 0.046092 -0.000951 0.158837 -0.3501421 0.0029192 -0.9083630 0.2286234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2607 2608 0.074847 0.032725 0.067417 -0.4903798 0.4504573 -0.1729052 0.7257546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2608 2609 -0.008646 -0.145587 0.042632 0.7612307 -0.3977485 -0.1526755 0.4888907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2609 2610 -0.112252 0.128030 -0.171705 -0.0807079 -0.1177047 -0.8052231 0.5755411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2610 2611 -0.072962 0.075577 0.015544 0.0167801 -0.4541831 -0.8888502 0.0581498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2611 2612 0.212392 -0.065348 0.122514 0.3264563 -0.1763908 -0.5161106 0.7719731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2612 2613 0.000691 -0.220690 0.026394 0.1714551 0.7245561 0.6642167 0.0666164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2613 2614 -0.270809 0.109922 0.072086 0.3277529 0.2915460 0.1159170 0.8911466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2614 2615 -0.063408 -0.254476 0.017656 -0.6849297 -0.4567989 -0.0448021 0.5658611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2615 2616 0.043373 -0.053285 0.070924 -0.7082809 0.4514175 -0.2745799 0.4681519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2616 2617 -0.004601 -0.310010 -0.034742 0.8779784 0.2845135 -0.0549703 0.3810305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2617 2618 0.000641 -0.051312 0.144629 -0.6299797 -0.0635846 -0.6094411 0.4771415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2618 2619 -0.052060 0.090896 0.037593 0.3742779 0.6181043 -0.6886461 0.0602472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2619 2620 0.023472 0.193585 -0.001816 -0.0488385 -0.2259383 -0.8716825 0.4321300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2620 2621 -0.059601 0.085674 0.038108 -0.3496098 0.3243183 0.1110713 0.8719253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2621 2622 0.212538 -0.020000 -0.070225 0.6070185 -0.2875328 -0.0773894 0.7367933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2622 2623 0.041462 -0.009734 -0.067129 -0.2456117 -0.0692619 -0.6587998 0.7077150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2623 2624 0.122440 0.239949 -0.059086 -0.4479139 0.0547369 -0.7752756 0.4419556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2624 2625 -0.216664 0.006235 0.073439 0.5703967 0.3151217 -0.7030383 0.2847507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2625 2626 0.159945 -0.095740 0.085859 -0.5527110 -0.3606154 0.3411277 0.6694020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2626 2627 -0.101763 0.023430 -0.017065 -0.2863647 0.2979024 -0.6640096 0.6231698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2627 2628 0.123763 -0.021727 -0.104055 0.3499716 0.2120295 -0.5145712 0.7535117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2628 2629 0.040950 0.014255 -0.010391 -0.2267141 -0.1075969 0.3044096 0.9188898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2629 2630 0.083190 -0.120435 -0.032017 0.4925706 0.4479837 0.3162200 0.6757883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2630 2631 0.021867 0.094973 0.030970 0.1584221 -0.6625687 -0.5205484 0.5147179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2631 2632 0.218352 -0.014817 -0.156411 0.7817215 -0.5843028 -0.2048255 0.0744864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2632 2633 0.041451 -0.065234 -0.060175 -0.3750983 -0.6388912 0.2930417 0.6043557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2633 2634 -0.149795 -0.006488 0.155636 0.2203813 0.7689799 0.1475699 0.5816572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2634 2635 0.038157 0.005152 -0.074036 -0.0722388 0.2651804 0.6876525 0.6720081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2635 2636 0.037632 -0.126014 -0.118534 -0.6136543 0.3928634 -0.6588191 0.1872006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2636 2637 -0.045051 0.130867 0.033977 0.1415417 0.6710948 -0.6112769 0.3948902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2637 2638 0.039173 -0.164933 -0.142520 0.1180759 0.7961607 -0.2359957 0.5445111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2638 2639 0.173310 0.065115 0.122943 0.5666905 -0.2685596 -0.1950782 0.7541102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2639 2640 0.054287 -0.190632 -0.148342 -0.3884115 -0.3413478 0.3330190 0.7884901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2640 2641 -0.068960 0.224383 0.021772 0.0610369 0.4463054 0.6634766 0.5973984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2641 2642 0.148991 -0.176076 -0.007194 -0.5752562 0.3075961 0.7216613 0.2316677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2642 2643 0.189619 -0.118033 -0.169458 0.7112569 0.2032330 -0.6727561 0.0144610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2643 2644 0.144314 0.179164 -0.085609 0.3091965 -0.3225080 0.2803108 0.8495952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2644 2645 0.089258 0.105036 0.159823 -0.0087499 0.5136598 0.5932398 0.6197932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2645 2646 -0.097949 -0.207349 0.036372 -0.4892074 0.7755267 0.2002331 0.3451682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2646 2647 0.053991 -0.192479 -0.095842 -0.5344248 0.5145266 0.5951550 0.3089387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2647 2648 0.062176 -0.309342 0.159842 -0.2651780 -0.0138352 0.9639871 0.0147665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2648 2649 0.014925 0.006483 0.043430 0.7801526 -0.0072618 0.6103476 0.1370588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2649 2650 0.052781 0.200699 0.055401 -0.0162186 0.8367049 -0.4406454 0.3247977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2650 2651 -0.040897 -0.104963 -0.050249 -0.6825658 -0.7140956 0.1187610 0.1003354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2651 2652 0.047554 0.125198 0.073350 0.0129524 -0.2077352 -0.0356733 0.9774486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2652 2653 -0.124293 0.042356 0.026922 -0.0515738 0.3310684 -0.3190842 0.8865208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2653 2654 -0.053509 -0.147364 0.006572 0.2707061 -0.3992119 0.8705804 0.0971488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2654 2655 -0.016453 0.053402 -0.100987 0.0203798 0.1531732 0.3153200 0.9363204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2655 2656 0.165103 0.027930 0.054246 -0.2095644 -0.8138982 0.5397894 0.0477481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2656 2657 0.080797 0.054103 -0.129910 0.7507416 0.2735164 -0.4339766 0.4162212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2657 2658 0.077815 -0.047970 -0.008860 -0.6598934 0.4162217 -0.1473248 0.6079438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2658 2659 -0.060081 -0.119903 -0.053312 0.0211815 -0.6975222 0.5428990 0.4671989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2659 2660 -0.101668 0.172643 -0.033095 -0.7817513 0.0642693 -0.1494760 0.6019895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2660 2661 -0.058147 0.042442 0.008706 0.5474258 0.3223440 -0.1273282 0.7617131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2661 2662 0.228374 -0.044692 -0.165129 -0.2537557 -0.1708001 -0.5109791 0.8033279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2662 2663 0.092265 -0.242271 -0.193797 -0.6562182 -0.1356645 -0.5847408 0.4572210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2663 2664 -0.028212 0.249074 -0.002935 -0.4858617 -0.3191842 -0.6057625 0.5432418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2664 2665 -0.135703 0.070965 0.094088 0.7585631 0.3420755 0.5107824 0.2160269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2665 2666 0.133335 -0.008079 -0.065692 0.1392813 0.1094739 0.8732272 0.4539719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2666 2667 0.046006 -0.138441 -0.128113 -0.4458744 -0.5202996 -0.0152680 0.7281835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2667 2668 -0.051294 0.032075 -0.183452 0.0499846 -0.3567303 0.0740446 0.9299260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2668 2669 0.005210 -0.048261 -0.107393 -0.9639829 0.0820218 -0.2314461 0.1021871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2669 2670 -0.210814 -0.014088 0.105282 -0.8526472 0.2676995 -0.4286274 0.1326959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2670 2671 -0.050618 0.023422 -0.058419 0.4791676 -0.5075385 -0.5756795 0.4259064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2671 2672 0.000873 -0.128934 0.008058 -0.1940561 -0.2671043 -0.8682385 0.3703504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2672 2673 0.156350 0.053594 -0.000096 -0.1594512 0.2644445 0.7304408 0.6091803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2673 2674 -0.046784 0.051733 0.073046 -0.7968837 0.1881625 0.4348223 0.3748344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2674 2675 -0.044334 -0.018459 -0.056949 0.3987302 -0.7977109 0.3194333 0.3203652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2675 2676 0.042367 0.133625 0.194456 -0.1504101 0.3376044 0.0482140 0.9279415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2676 2677 -0.020205 0.046851 0.231232 -0.5844130 0.5478271 -0.3089418 0.5127396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2677 2678 0.024646 0.037401 -0.117656 0.4461861 0.5467532 0.2707291 0.6547402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2678 2679 0.004664 -0.005131 0.015221 -0.1430479 -0.4352753 -0.1491261 0.8762615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2679 2680 -0.136157 -0.172629 -0.100667 0.1902292 0.2174020 0.2343143 0.9282489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2680 2681 -0.102551 0.057143 -0.152907 0.0543783 0.3890204 -0.8031178 0.4480044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2681 2682 0.104717 -0.086092 0.080703 -0.0449473 -0.1149932 0.8783340 0.4618286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2682 2683 -0.082227 -0.099140 0.104650 -0.1364412 -0.5211408 -0.6557185 0.5289890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2683 2684 -0.003251 -0.032636 -0.091304 0.0401491 0.5839006 -0.3534177 0.7297561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2684 2685 -0.046747 -0.025272 0.134338 0.0589011 -0.0332947 -0.9387449 0.3379055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2685 2686 -0.018993 0.045732 0.115232 0.1207263 0.2572936 -0.9119374 0.2959651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2686 2687 0.023203 0.150840 -0.150391 0.1146663 0.3631020 -0.1787685 0.9072213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2687 2688 -0.068777 0.043380 0.011892 0.4448576 -0.1893697 -0.2917695 0.8252947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2688 2689 0.050988 -0.036489 0.111709 -0.1306074 0.1478565 0.4673520 0.8617786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2689 2690 -0.075887 0.014727 -0.174648 -0.1570492 -0.1325460 0.3905105 0.8973676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2690 2691 0.015674 -0.147048 0.126704 0.2599027 0.5382197 0.8011786 0.0297149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2691 2692 -0.035386 0.182159 -0.038967 -0.6052474 -0.6319986 -0.1647125 0.4551079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2692 2693 0.035256 0.040245 0.031413 0.2925397 0.3576907 0.6003032 0.6527741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2693 2694 0.066245 0.163362 0.099341 -0.0761177 0.2078800 0.8720364 0.4365140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2694 2695 -0.098683 -0.055787 0.205245 -0.5002668 -0.5895413 0.1398886 0.6185510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2695 2696 0.006719 -0.063885 -0.163910 -0.0038933 0.5384407 -0.4770189 0.6946362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2696 2697 -0.001690 0.099015 0.007639 -0.1275366 -0.1629863 -0.9238749 0.3219085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2697 2698 -0.132900 0.091454 -0.044332 -0.6530954 0.3243272 0.5608104 0.3921351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2698 2699 -0.060644 0.121048 0.024720 0.3462876 0.1274971 -0.5596488 0.7420395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2699 2700 0.045136 0.075517 0.099053 0.4241132 0.2798878 0.8612725 0.0006864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2700 2701 0.024176 0.017103 0.083418 0.4720287 0.4621996 0.6251699 0.4155996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2701 2702 -0.004991 0.130773 0.136814 -0.2458257 0.3701558 -0.8091143 0.3845627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2702 2703 -0.064676 -0.114456 0.209501 -0.5412842 -0.6856091 0.2763861 0.4007022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2703 2704 -0.043246 -0.165961 0.079138 -0.0179660 -0.1157652 -0.2606132 0.9583091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2704 2705 0.007251 -0.074088 0.006400 0.4542889 0.3981526 0.6736101 0.4258467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2705 2706 -0.072485 0.110407 0.054736 -0.1781693 -0.7942782 0.0527249 0.5784443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2706 2707 0.032037 -0.181576 -0.044208 -0.0548581 0.3134119 0.2760540 0.9069497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2707 2708 0.066984 -0.067754 0.019085 0.3652102 -0.2867225 -0.0467819 0.8844338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2708 2709 0.058494 0.089049 0.155663 -0.3839635 0.0602048 0.6258839 0.6761781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2709 2710 0.112495 0.121072 -0.207462 0.4967220 -0.3026367 -0.0654854 0.8107959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2710 2711 0.081998 -0.045434 0.115431 -0.3513254 0.7393352 -0.1293760 0.5596568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2711 2712 0.041977 -0.167499 -0.044700 0.3033155 -0.1565723 0.1299337 0.9309146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2712 2713 -0.045280 -0.084513 -0.002654 -0.4851639 -0.6894871 0.4396181 0.3097732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2713 2714 -0.254124 -0.133502 0.090587 -0.4273061 0.7080616 -0.4415390 0.3479964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2714 2715 0.027485 -0.091282 -0.047430 0.4384907 0.2179613 0.8706583 0.0466139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2715 2716 -0.087137 -0.114205 -0.131366 0.7902274 -0.1969845 -0.5784797 0.0458161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2716 2717 0.104328 0.098479 0.122135 0.1821147 0.5965249 -0.7134894 0.3192572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2717 2718 0.037246 -0.019998 -0.028353 -0.4621973 -0.4780749 0.7462495 0.0304921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2718 2719 -0.154946 0.156467 0.067731 -0.7460063 -0.5418619 -0.1338279 0.3632498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2719 2720 0.123497 0.064942 -0.182109 0.2677872 0.1642324 -0.8053321 0.5027503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2720 2721 -0.046838 0.024522 -0.006703 -0.0627259 0.4854538 0.3011601 0.8183537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2721 2722 0.140320 0.095241 -0.113312 0.3767814 -0.1935725 0.8602524 0.2837804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2722 2723 0.185366 -0.101757 0.003701 0.1480022 -0.0422799 -0.8421194 0.5168585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2723 2724 0.168088 -0.034503 0.090556 -0.5642655 0.0617951 0.5027070 0.6519750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2724 2725 0.064994 -0.030597 0.115412 0.2922369 0.5485833 0.1124767 0.7752438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2725 2726 -0.029938 -0.033415 0.069858 0.1001901 -0.8712050 -0.4737577 0.0807308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2726 2727 0.005124 0.170892 0.084877 0.2841433 -0.0190539 0.6978514 0.6571932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2727 2728 -0.022305 -0.188900 -0.199463 0.6918298 0.5452194 0.2820215 0.3802252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2728 2729 -0.269897 -0.075414 -0.051265 -0.0983092 0.4926755 0.7082452 0.4959787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2729 2730 -0.013233 0.046758 -0.171214 0.1718109 -0.4783666 -0.7930317 0.3357784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2730 2731 -0.052645 -0.071170 0.098210 0.1624489 0.0257328 -0.2484588 0.9545766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2731 2732 -0.024408 -0.133749 -0.034345 -0.0075942 0.2234115 -0.8409630 0.4927584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2732 2733 0.027919 -0.031807 -0.051358 0.2937975 0.3769691 -0.1970415 0.8560093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2733 2734 0.020144 0.083710 -0.027105 0.3692286 -0.2624993 0.8914869 0.0039247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2734 2735 0.014502 -0.112021 0.001552 -0.3748487 -0.0519831 0.9040415 0.1987340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2735 2736 0.002000 0.131175 -0.075976 0.2488755 0.1346099 -0.8890639 0.3598702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2736 2737 -0.024518 0.033663 -0.054564 -0.5764217 0.4072042 -0.3751897 0.6009621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2737 2738 0.167695 0.125666 -0.080693 0.2224844 0.6103158 -0.4026144 0.6449162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2738 2739 0.130999 0.224553 -0.111690 -0.4204849 0.2450681 0.6419550 0.5924760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2739 2740 0.205427 0.043315 0.119850 -0.3932816 -0.4806971 -0.6488161 0.4396562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2740 2741 0.029556 0.047280 -0.022423 -0.3124689 0.3002047 -0.8697047 0.2363344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2741 2742 -0.102125 -0.150415 -0.287795 -0.2564224 0.5104794 0.7531400 0.3262491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2742 2743 0.004458 -0.083536 -0.007779 -0.0675129 -0.0589986 0.9792301 0.1818507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2743 2744 -0.007795 -0.000070 -0.095049 0.0807382 -0.1465667 -0.6472755 0.7436625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2744 2745 0.023143 -0.109204 0.054521 0.2195382 0.2896807 0.8368200 0.4094147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2745 2746 -0.001458 -0.124716 -0.131409 -0.2823813 -0.0048602 -0.4834943 0.8285351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2746 2747 -0.277950 -0.104684 -0.025921 -0.0794612 0.1483753 -0.8630093 0.4763252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2747 2748 -0.043719 0.080259 0.019256 0.1485856 0.0477453 0.1405449 0.9776962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2748 2749 0.017399 -0.028203 0.012890 -0.2492548 -0.0848235 0.6014074 0.7543117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2749 2750 -0.031776 0.110005 0.090388 0.4565792 0.2202073 0.7784383 0.3702405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2750 2751 -0.099880 -0.036415 0.221648 0.6913051 0.2045865 0.6217611 0.3060306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2751 2752 0.096529 -0.177236 -0.064951 0.4440340 0.5005369 -0.1025887 0.7360518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2752 2753 -0.040606 -0.030661 0.154502 0.5768956 0.2273382 0.7840565 0.0276458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2753 2754 -0.021172 0.000677 -0.158102 -0.2462280 0.5105496 -0.1108896 0.8163421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2754 2755 0.181214 -0.014365 -0.146594 0.4476385 0.1273732 0.7166493 0.5194321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2755 2756 -0.054838 0.037946 0.089799 -0.7643714 -0.4482050 0.0191125 0.4631234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2756 2757 0.184497 -0.019518 -0.057020 -0.1492278 -0.9238005 0.3497793 0.0444763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2757 2758 0.082373 -0.116400 -0.032526 0.5447696 -0.0430402 0.6062518 0.5777822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2758 2759 0.118394 0.092912 0.000957 0.1087533 0.6323429 0.6608738 0.3893083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2759 2760 0.108920 -0.213053 0.091254 0.5196601 -0.3210879 0.7864270 0.0915887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2760 2761 0.117996 0.109917 0.006539 0.2859111 0.7115649 -0.4210990 0.4843613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2761 2762 0.014044 0.165435 -0.045629 0.0320594 -0.2509748 -0.2247246 0.9410009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2762 2763 -0.133391 0.068769 0.204005 0.6811528 0.1592290 0.6801596 0.2192256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2763 2764 0.038044 -0.076085 0.032056 -0.0198048 0.7515139 -0.0612491 0.6565693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2764 2765 -0.007324 -0.122642 -0.021492 -0.9620378 -0.0238521 -0.0191015 0.2712000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2765 2766 0.065578 -0.104651 -0.044881 -0.0664972 -0.3380410 -0.6576814 0.6698967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2766 2767 0.121638 0.046521 0.153994 -0.5320963 0.3815891 -0.6698226 0.3501443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2767 2768 -0.100956 0.180855 -0.129257 0.4503720 -0.3480514 0.7756058 0.2728753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2768 2769 -0.003684 -0.019192 0.145752 0.1996017 -0.2180868 0.1694206 0.9401564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2769 2770 -0.200091 -0.083014 0.276229 -0.3749603 0.5744784 -0.3079215 0.6592144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2770 2771 -0.021454 -0.018303 -0.158925 -0.2305485 -0.0805538 0.6171195 0.7480121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2771 2772 0.101163 0.071698 -0.002704 0.5756752 0.3749312 -0.4350665 0.5820154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2772 2773 -0.067385 0.020326 -0.088815 -0.3356507 -0.3684244 -0.4489169 0.7416709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2773 2774 0.156260 -0.036407 0.073623 -0.7332149 0.4352376 -0.5036276 0.1390087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2774 2775 -0.275541 -0.025850 -0.019302 0.5784576 -0.0065190 0.7258319 0.3721724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2775 2776 -0.121036 0.093895 0.101193 0.4771752 0.5905017 0.6432945 0.0989128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2776 2777 0.278926 -0.043624 0.106883 -0.3964280 -0.6107341 -0.3509197 0.5888157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2777 2778 0.140912 -0.034396 0.025646 -0.6426644 0.2143225 0.6773759 0.2867233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2778 2779 0.037616 0.162590 -0.047349 0.8752947 -0.2334464 -0.0485705 0.4207172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2779 2780 0.166478 0.059522 0.230734 -0.1710284 -0.3060848 0.8629477 0.3638444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2780 2781 -0.048643 -0.144963 0.160459 0.1523637 0.1070334 0.9669802 0.1740068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2781 2782 -0.079263 0.221476 -0.133951 0.7179518 0.1616764 -0.6658412 0.1227255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2782 2783 0.147377 0.065109 0.135822 0.1641226 0.1473788 -0.1477955 0.9641057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2783 2784 0.082296 -0.018047 0.032308 -0.3162620 -0.8087040 0.4955427 0.0203361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2784 2785 -0.025375 0.056745 0.083448 -0.2704595 -0.7050719 0.3104154 0.5773800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2785 2786 0.036017 -0.111481 0.134350 0.1272161 0.8007139 -0.5533207 0.1910747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2786 2787 0.163782 -0.106937 -0.338348 0.1929348 -0.7650793 0.2071085 0.5783907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2787 2788 0.013404 -0.108005 0.221125 0.7425044 0.0589636 0.6105734 0.2690921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2788 2789 0.098776 0.037339 -0.029673 -0.5933490 -0.2963440 -0.6098499 0.4338206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2789 2790 -0.129110 0.093942 0.108411 0.6018630 -0.1657259 0.7234217 0.2948847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2790 2791 0.290847 0.016172 -0.009032 -0.6136007 0.4721165 0.1325378 0.6188974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2791 2792 0.068269 0.009711 -0.124239 -0.0382540 -0.0906903 0.0718524 0.9925468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2792 2793 -0.026071 0.158119 0.081298 0.0897103 -0.1823668 0.4129704 0.8877780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2793 2794 0.024428 -0.023773 0.127490 0.0377972 -0.5904454 -0.3580038 0.7223426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2794 2795 -0.045790 -0.089734 0.255330 0.4234483 0.6105590 -0.4174067 0.5231453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2795 2796 -0.155609 -0.044246 -0.084092 0.5506952 -0.4189713 -0.4030047 0.5989866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2796 2797 -0.078644 -0.043771 0.040438 -0.5357801 0.3160581 0.3005005 0.7230120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2797 2798 -0.071162 0.034113 0.154728 -0.2744859 -0.7890741 -0.2407749 0.4940111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2798 2799 -0.085229 0.096980 -0.099318 0.1377287 0.3771777 0.1557593 0.9025003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2799 2800 -0.148734 -0.209234 -0.072065 0.3474453 -0.3221805 0.2062788 0.8561136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2800 2801 -0.205367 0.097852 0.147665 0.2081899 -0.0072938 -0.0343820 0.9774567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2801 2802 -0.078218 0.118829 0.001380 0.1923911 0.4080192 -0.1530852 0.8792445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2802 2803 -0.089162 0.063948 0.025656 -0.4172642 -0.1003704 0.3162670 0.8460446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2803 2804 0.025827 0.016014 0.027308 -0.5197402 -0.4290226 -0.5444290 0.4994064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2804 2805 -0.068481 0.000368 0.082709 -0.5915561 -0.2933500 -0.7180623 0.2199858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2805 2806 0.016316 0.298403 0.036825 0.1497440 0.0498120 0.1689087 0.9729159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2806 2807 0.276004 -0.142987 0.099656 0.1185835 0.0455129 -0.1199523 0.9846207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2807 2808 0.076883 0.118975 0.041686 -0.2476770 0.5206209 0.8074790 0.1248505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2808 2809 -0.080702 -0.035092 -0.115097 0.2953255 0.0896520 -0.8296397 0.4652348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2809 2810 0.162493 -0.158903 0.079132 -0.1291358 0.1930996 -0.9078687 0.3490143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2810 2811 0.061187 -0.161354 0.093663 0.6978215 0.4405802 0.1190430 0.5520535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2811 2812 -0.070843 0.015823 -0.086444 -0.5118964 0.3590294 -0.0736472 0.7769402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2812 2813 0.078323 0.052697 0.200563 -0.2768510 0.6020627 0.7435775 0.0892553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2813 2814 -0.122729 -0.020523 -0.082194 -0.5228685 -0.2452838 0.0415322 0.8153033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2814 2815 0.101426 -0.134767 -0.121905 0.4034327 0.0640296 0.8413576 0.3539205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2815 2816 0.008149 0.146972 -0.135152 -0.0278283 -0.1750961 0.9005774 0.3968970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2816 2817 0.071547 -0.072761 0.006505 0.3105088 -0.4371547 0.3228761 0.7798917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2817 2818 -0.100383 0.006379 -0.011153 -0.6722397 0.1691374 -0.6038296 0.3935431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2818 2819 -0.017788 0.287256 -0.118793 -0.5884126 -0.2179525 -0.7340388 0.2597197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2819 2820 -0.020076 0.070337 0.006100 -0.7505502 -0.2208850 -0.4936209 0.3797665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2820 2821 0.199077 0.074055 0.006430 0.3512773 -0.4996494 0.7913819 0.0258712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2821 2822 -0.028109 0.212154 0.020786 0.1634220 0.8731148 -0.3634806 0.2807947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2822 2823 0.129663 -0.046891 -0.115727 0.2082324 0.4576323 -0.8176275 0.2805303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2823 2824 -0.046877 0.137721 -0.008119 0.1190030 0.5024987 0.5382107 0.6660801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2824 2825 -0.087366 0.045118 0.166790 0.4928624 0.0898665 -0.6225705 0.6011793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2825 2826 0.018698 0.098843 -0.083623 0.8255690 -0.1911511 -0.2539996 0.4662416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2826 2827 0.016294 -0.024145 -0.034416 0.1943813 0.0926387 -0.6421702 0.7356979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2827 2828 -0.168239 -0.096526 -0.076091 -0.1133148 -0.1088769 0.9875329 0.0091877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2828 2829 0.084402 -0.182032 0.240575 0.0449522 -0.1786895 -0.0689332 0.9804578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2829 2830 -0.031957 0.013950 0.231657 0.0805040 -0.0055500 -0.6185578 0.7815847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2830 2831 -0.218518 0.085180 -0.060273 -0.0721734 0.9849570 0.1532832 0.0339845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2831 2832 -0.026773 -0.160506 0.050197 -0.1847017 -0.1233010 -0.3917984 0.8928472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2832 2833 -0.010948 -0.000833 0.034815 -0.0560607 -0.1565321 -0.0938795 0.9816015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2833 2834 0.149653 0.054411 -0.009365 -0.5237587 -0.4147731 0.7310507 0.1385816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2834 2835 0.007009 0.105449 -0.008051 0.1103039 0.3808684 0.0747601 0.9149772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2835 2836 0.181613 0.147128 -0.022601 -0.2416595 0.0931520 -0.7328222 0.6292018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2836 2837 -0.106587 0.178922 -0.060529 0.0622762 0.0787928 0.9913180 0.0848649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2837 2838 0.148065 -0.035126 -0.024820 0.0326490 0.5021646 0.7339169 0.4562136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2838 2839 -0.072116 -0.146046 0.057862 -0.7078526 0.2861018 0.2353870 0.6014011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2839 2840 -0.100100 -0.083572 -0.070688 0.3641407 0.5119322 0.2298784 0.7432919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2840 2841 -0.076138 -0.038663 0.018066 0.1585484 -0.8092131 -0.1706560 0.5393636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2841 2842 -0.088985 -0.049449 0.012475 -0.8706070 -0.0095885 -0.3284177 0.3661875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2842 2843 0.008888 0.034018 0.029130 -0.6016474 0.4369977 -0.5302768 0.4072591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2843 2844 -0.100282 0.046616 -0.010275 0.0476285 0.5267298 -0.6481214 0.5479287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2844 2845 0.046913 0.037557 -0.114461 0.6946241 -0.2703304 -0.3942036 0.5376080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2845 2846 0.024028 0.022612 -0.080447 -0.6111230 0.1798442 -0.4682666 0.6122998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2846 2847 0.168815 0.019108 -0.034628 0.1242149 -0.5937076 0.0861141 0.7903583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2847 2848 0.087236 0.226801 -0.046889 -0.0973738 -0.2622023 -0.9119202 0.3002828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2848 2849 -0.172193 -0.051968 0.018198 -0.6672002 0.2865425 -0.5383054 0.4277435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2849 2850 -0.172432 0.123779 -0.076644 -0.2568451 -0.4160430 0.5907876 0.6418013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2850 2851 0.324412 0.098186 0.040677 0.1468684 0.0135150 0.9637980 0.2221271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2851 2852 -0.081181 -0.061654 -0.152591 -0.0179296 -0.3222447 0.0940531 0.9418019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2852 2853 0.039353 -0.093171 0.026924 -0.6184189 -0.3705709 -0.6918502 0.0397315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2853 2854 0.123284 0.214423 -0.231992 0.1458265 0.4060239 -0.8726803 0.2287100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2854 2855 0.011231 0.108651 0.033035 0.5653941 -0.4693931 0.5136484 0.4429052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2855 2856 -0.130199 -0.137520 0.172809 -0.0246710 0.6133781 -0.5188004 0.5949830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2856 2857 -0.115159 0.048306 -0.086811 0.6788330 -0.4136970 -0.1711843 0.5820107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2857 2858 0.030234 -0.009535 0.001550 -0.3640219 0.1828203 0.9073803 0.1035649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2858 2859 -0.014006 0.023908 -0.164677 -0.3110099 0.3901899 -0.5287957 0.6865856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2859 2860 -0.102699 -0.031896 0.048381 -0.1563280 -0.7277063 0.6597640 0.1035211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2860 2861 -0.017121 0.103808 -0.086998 0.8714287 0.2185192 0.2692244 0.3469576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2861 2862 -0.035335 -0.250836 0.094813 -0.5291524 -0.7388900 0.0873470 0.4079336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2862 2863 -0.210060 -0.032425 0.181052 0.2250057 0.0266572 0.5791843 0.7830756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2863 2864 0.105065 -0.100092 0.100605 -0.2234244 0.2147475 0.9322297 0.1868497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2864 2865 -0.020181 -0.083370 0.047230 -0.2860164 -0.1373820 0.9466393 0.0565232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2865 2866 0.023935 -0.135082 0.071069 0.5849060 0.3584580 0.0442023 0.7262499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2866 2867 0.029755 0.132927 -0.130931 -0.2195772 0.0236538 -0.5613246 0.7975845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2867 2868 -0.138773 0.082842 -0.091201 0.6686515 -0.4146625 -0.5855120 0.1952841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2868 2869 -0.158172 0.185370 0.093671 -0.3516748 0.7007280 0.4625364 0.4139628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2869 2870 0.028145 -0.155722 -0.090873 -0.3472228 0.0618108 0.3878774 0.8515673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2870 2871 -0.125256 0.009994 0.045311 -0.1524467 0.0320614 0.9768747 0.1464510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2871 2872 0.069953 0.030080 0.060083 0.4456954 -0.3041899 -0.6739276 0.5046243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2872 2873 0.085543 -0.043473 -0.162264 -0.4600404 0.1780948 0.7214672 0.4859322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2873 2874 0.008189 0.042065 -0.007786 0.5483485 -0.2169245 0.1516038 0.7932679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2874 2875 0.077760 -0.143152 -0.085448 -0.2114828 0.5867338 0.4009331 0.6710225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2875 2876 -0.074085 -0.048458 -0.002614 -0.5297545 -0.0058828 -0.2728094 0.8030570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2876 2877 0.181095 -0.156634 -0.130661 0.7847235 -0.0903081 0.5561594 0.2583410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2877 2878 -0.042080 -0.023625 0.083870 0.2229499 0.6515709 0.7101214 0.1465482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2878 2879 0.068034 0.097481 -0.008444 -0.5506219 0.2092041 -0.5445300 0.5971066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2879 2880 -0.087059 -0.035750 0.125357 0.5525197 0.4893141 0.3533252 0.5748521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2880 2881 -0.104346 0.125811 0.031435 -0.1772080 -0.1895167 0.7897294 0.5558851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2881 2882 0.015566 0.341492 0.056453 -0.1979804 -0.0788728 0.9580048 0.1918584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2882 2883 -0.102521 0.196107 0.172351 0.0484128 0.0326701 -0.7056201 0.7061792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2883 2884 -0.015799 -0.142596 0.115963 -0.0126215 -0.6395357 0.7352778 0.2240567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2884 2885 -0.270337 -0.041016 0.075636 -0.0533856 -0.6788560 0.6468382 0.3433727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2885 2886 0.067026 0.038260 -0.043484 0.1983443 0.6677461 0.6314026 0.3407425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2886 2887 -0.081702 -0.016086 -0.010114 -0.6766169 -0.5275568 0.4177123 0.2989813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2887 2888 0.013602 0.021168 0.170072 -0.0471950 0.2260790 0.9691487 0.0860919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2888 2889 0.100753 0.270649 0.208688 0.0402060 -0.7003564 -0.5884875 0.4019537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2889 2890 0.051064 -0.064788 -0.127747 -0.0308011 0.3186956 -0.9178065 0.2347671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2890 2891 0.087273 -0.120213 -0.010529 0.5262405 -0.4319871 -0.1382028 0.7192761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2891 2892 0.040283 -0.209000 0.086232 0.2384401 0.3509802 0.4016048 0.8115866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2892 2893 -0.014557 0.146233 0.090144 0.6139014 0.4567526 0.4690980 0.4409641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2893 2894 -0.119871 0.003417 0.114431 -0.4608914 0.1994679 0.4193496 0.7562656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2894 2895 0.182692 0.082029 0.186429 -0.5962577 0.6728234 -0.3721973 0.2307697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2895 2896 0.038345 -0.030835 -0.044558 0.0826459 0.3966015 -0.9132142 0.0437798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2896 2897 0.007674 0.010458 -0.048582 0.0271022 -0.3734705 -0.5818749 0.7219466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2897 2898 -0.002463 -0.053952 0.050860 -0.4443811 0.0056178 0.6986335 0.5607184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2898 2899 -0.094963 0.015420 0.011300 0.0125073 0.0269838 -0.9136020 0.4055205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2899 2900 -0.020091 0.057114 0.117349 0.0429721 0.7537225 0.6143942 0.2292937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2900 2901 -0.267844 0.129798 -0.059335 -0.1848586 -0.0407087 -0.1994072 0.9614608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2901 2902 -0.155996 -0.046774 -0.172411 0.0545082 0.1705766 -0.5068275 0.8432428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2902 2903 -0.094479 0.201805 -0.009477 -0.1738423 -0.0774186 0.1099964 0.9755440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2903 2904 0.068678 -0.102907 -0.010865 -0.0424613 -0.7587705 -0.3894588 0.5203712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2904 2905 -0.121567 -0.106265 -0.044968 0.7864859 0.1290682 0.4405978 0.4131040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2905 2906 -0.054628 -0.065020 0.116860 0.1991908 -0.2648318 -0.8933056 0.3036318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2906 2907 0.105854 0.053478 0.257971 0.0395067 -0.3500856 -0.6753167 0.6479403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2907 2908 -0.075669 0.190738 -0.009962 -0.2043564 -0.5156822 -0.5750671 0.6013387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2908 2909 0.091187 0.182944 -0.033277 -0.2929616 0.8471007 0.1285840 0.4243348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2909 2910 -0.071968 0.180368 0.125309 -0.0170421 -0.0959899 -0.3500603 0.9316401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2910 2911 -0.159258 -0.057500 0.074144 -0.7052441 -0.0408635 0.6960713 0.1282409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2911 2912 0.024583 0.037291 0.189209 -0.7503681 0.5164948 0.2523338 0.3263564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2912 2913 -0.051023 -0.044698 0.096929 -0.0472120 0.9001770 0.4329307 0.0048275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2913 2914 0.159803 -0.028978 0.084690 -0.0349195 0.1202980 -0.8730952 0.4711833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2914 2915 -0.008169 -0.023806 0.036358 -0.4354133 0.5153846 0.5749422 0.4628558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2915 2916 -0.059672 0.237666 0.103487 0.3159305 0.6653559 0.6138437 0.2840516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2916 2917 -0.030883 0.041505 0.046196 0.1057792 0.5159645 0.5814250 0.6201100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2917 2918 0.034684 0.089774 0.004579 0.3650313 0.2313970 -0.5705010 0.6983811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2918 2919 -0.057038 0.081822 0.116380 0.4977147 -0.4287990 -0.0483590 0.7523781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2919 2920 0.035158 0.073638 -0.117674 -0.1359025 -0.5915311 -0.7210545 0.3342182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2920 2921 -0.136387 -0.039688 0.022348 -0.3028006 -0.3836601 -0.1511422 0.8592280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2921 2922 -0.038689 -0.033714 0.053825 -0.6000905 0.1104541 -0.1592972 0.7760900 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2922 2923 0.224604 -0.110186 -0.071108 -0.1180006 -0.0613993 0.1586457 0.9783341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2923 2924 -0.090647 0.004307 -0.026081 0.1877718 0.7368078 -0.3977590 0.5134626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2924 2925 -0.076072 -0.026308 -0.029769 -0.2608638 -0.0948309 -0.9104129 0.3067664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2925 2926 -0.064997 -0.030863 0.139400 -0.3197989 -0.3204287 -0.5957897 0.6633919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2926 2927 0.014338 -0.037425 0.002271 -0.8150724 -0.2806428 -0.1229481 0.4917116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2927 2928 -0.124605 -0.071606 -0.021403 0.5694983 0.1337218 0.8102213 0.0364907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2928 2929 0.097574 0.036029 0.182325 -0.3566907 -0.1198019 0.3135532 0.8718392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2929 2930 -0.020020 -0.113800 0.046419 0.3835659 -0.1401417 -0.2210728 0.8856435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2930 2931 -0.036459 -0.130531 -0.185622 0.2219859 -0.3577027 -0.8439028 0.3325645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2931 2932 0.038989 -0.023263 -0.056686 -0.0145070 -0.4480196 -0.8916721 0.0631564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2932 2933 0.028246 0.031134 0.077067 0.0727165 0.1571473 0.8743009 0.4534478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2933 2934 0.129872 -0.132304 -0.017880 0.3526975 0.5585987 -0.4240323 0.6194906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2934 2935 0.030089 0.070713 -0.232605 0.0440957 -0.9095646 0.2770648 0.3065664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2935 2936 -0.222802 -0.018965 -0.091911 -0.0586643 -0.0399781 -0.9905241 0.1175680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2936 2937 -0.075763 -0.046729 0.013153 0.2586793 0.2762019 -0.7830666 0.4935628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2937 2938 0.131162 -0.063014 0.112386 -0.6206314 -0.5083115 0.5865390 0.1113917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2938 2939 0.157971 0.163983 -0.113473 -0.0315356 0.1891198 -0.9422844 0.2744802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2939 2940 -0.093692 0.081493 -0.073498 -0.1010065 0.4345052 0.4735533 0.7594407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2940 2941 0.130398 -0.146917 -0.045262 0.5760414 -0.2140909 0.2812562 0.7370457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2941 2942 0.032944 0.058841 0.086551 -0.8977813 0.0451510 -0.0749204 0.4316678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2942 2943 0.152408 0.053639 -0.093404 0.5987368 0.1119638 -0.1520778 0.7783641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2943 2944 -0.011962 0.085160 -0.076330 -0.1966967 -0.2938174 -0.5156205 0.7804597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2944 2945 -0.192398 0.263529 0.092466 -0.2430623 -0.0226600 -0.1763699 0.9535727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2945 2946 -0.152865 0.057971 0.001084 -0.0262212 -0.0460974 0.1537511 0.9866854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2946 2947 0.061815 0.101401 -0.056509 -0.6147605 -0.2437186 -0.7252924 0.1913678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2947 2948 0.049836 0.058535 -0.074121 -0.4818073 -0.2690557 -0.0559582 0.8320694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2948 2949 -0.124066 -0.147640 0.104745 -0.3291211 0.5705110 0.6842065 0.3131421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2949 2950 -0.050692 -0.150228 -0.229358 -0.0891979 0.0421628 -0.2210226 0.9702655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2950 2951 0.026323 0.151779 -0.034371 0.7496918 -0.2874890 -0.5958171 0.0177268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2951 2952 0.027631 -0.001704 -0.105998 -0.0585111 0.0434994 -0.7276095 0.6821061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2952 2953 -0.078792 0.001565 -0.092450 -0.3419217 -0.8374489 0.3167822 0.2853383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2953 2954 -0.066748 -0.084782 0.082519 0.8695730 -0.2093986 -0.0993351 0.4360361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2954 2955 -0.063322 0.100625 -0.130829 -0.0423012 0.9327024 0.2621372 0.2440510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2955 2956 0.152635 -0.233304 0.005034 -0.2084293 0.0286753 -0.0555625 0.9760368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2956 2957 0.034059 -0.078924 -0.042143 -0.3548922 -0.1902833 0.3633201 0.8401442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2957 2958 0.104091 -0.018449 -0.094037 -0.1787037 -0.1977824 0.4011537 0.8763691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2958 2959 0.136528 -0.016774 0.223408 -0.3554305 -0.4142463 -0.7550553 0.3632639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2959 2960 -0.052656 -0.065138 0.151415 -0.3043610 0.7317489 -0.0337741 0.6089066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2960 2961 0.137151 -0.015678 -0.130405 -0.5097059 -0.2478729 0.7934160 0.2219234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2961 2962 0.125243 0.078430 -0.124989 -0.1641912 0.2505299 -0.5107845 0.8058382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2962 2963 -0.060575 0.031812 -0.191335 0.2876961 -0.5118003 -0.1808513 0.7890401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2963 2964 0.040303 0.200116 -0.068815 0.0128049 0.4728059 0.4267665 0.7708184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2964 2965 -0.059556 0.089643 0.008861 0.6689850 0.4398285 -0.3668749 0.4737222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2965 2966 0.017502 -0.093976 -0.069651 -0.1200899 0.3277467 0.8644827 0.3617045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2966 2967 -0.096007 -0.082983 -0.055516 -0.7674057 0.1938623 -0.1023171 0.6025256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2967 2968 -0.148802 0.004670 0.004158 0.0600430 -0.0913563 0.6864806 0.7188833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2968 2969 -0.098955 0.154925 0.081129 0.0099087 -0.0579044 0.4385671 0.8967763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2969 2970 -0.023232 0.163816 -0.054346 -0.2081916 0.1307338 0.8376603 0.4877398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2970 2971 -0.048287 0.078589 -0.084761 -0.4622573 0.4285161 0.7322541 0.2578683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2971 2972 -0.156294 -0.146264 -0.144173 -0.0435209 -0.3093799 -0.5864405 0.7473136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2972 2973 -0.149135 -0.136697 0.042694 0.0758776 0.0201766 -0.9946047 0.0678015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2973 2974 -0.017741 0.028280 -0.143537 0.0770680 -0.2330280 -0.7778912 0.5784840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2974 2975 -0.223679 -0.117437 0.003818 0.1533225 0.2260813 -0.9602860 0.0568346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2975 2976 0.211891 -0.021301 0.054318 0.1295061 0.0614854 -0.2522486 0.9569840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2976 2977 0.165154 0.078016 0.126473 0.0222398 0.3061290 -0.3143589 0.8983145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2977 2978 -0.027105 0.055988 0.031817 -0.2671529 0.2448705 -0.8839256 0.2955391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2978 2979 -0.125695 0.120092 0.046567 0.4353492 0.6513344 -0.0338353 0.6205560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2979 2980 0.013449 0.103842 -0.040953 -0.3340597 -0.7525885 -0.2635933 0.5025269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2980 2981 0.075026 -0.030230 -0.074098 -0.1429016 0.2534151 0.8715649 0.3946321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2981 2982 -0.039873 -0.043097 -0.031282 -0.0029312 0.6041973 -0.7942420 0.0641613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2982 2983 0.127109 -0.026666 0.114226 0.8726575 0.0145200 0.3342781 0.3556910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2983 2984 -0.087085 -0.164444 0.103350 0.0286822 0.6426573 0.6698048 0.3708510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2984 2985 -0.096808 0.113471 0.257730 -0.2065898 -0.4660277 0.2562278 0.8212710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2985 2986 -0.053067 0.098281 -0.022755 0.4127205 0.2177693 0.5147064 0.7192466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2986 2987 0.116949 -0.101070 0.128043 -0.5524796 -0.1958076 -0.7721722 0.2453074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2987 2988 0.107333 0.069176 0.144165 0.4475543 0.4323226 -0.1270753 0.7724275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2988 2989 0.003275 0.052201 0.163787 -0.3285751 0.2865160 -0.7422518 0.5089295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2989 2990 -0.042356 -0.181379 0.083504 0.6144601 -0.4266890 -0.2804305 0.6014434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2990 2991 0.086615 0.115859 0.073566 -0.1181718 0.1902328 -0.1658224 0.9603905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2991 2992 0.000507 0.070028 0.015258 0.0812256 -0.1838081 0.9053742 0.3740515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2992 2993 -0.007475 -0.120639 0.176199 0.6196272 -0.3953217 0.4838296 0.4750702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2993 2994 0.026503 -0.092566 0.019893 -0.5747793 0.3777836 -0.1784610 0.7036049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2994 2995 0.107601 -0.128552 0.047519 0.5431544 -0.0943562 0.4025856 0.7307565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2995 2996 0.005442 -0.120521 -0.052302 -0.1066395 0.3110221 -0.5275863 0.7832918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2996 2997 -0.101344 -0.005978 -0.129620 -0.0281109 0.2718078 -0.3833722 0.8822449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2997 2998 0.008076 0.075304 0.055308 -0.1984209 -0.0539929 0.9315402 0.2999114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2998 2999 -0.059269 0.050898 0.037004 -0.5945445 -0.4346354 0.4375024 0.5159463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2999 3000 0.050321 -0.015746 0.085661 0.7045584 0.1466194 -0.3963237 0.5701120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3000 3001 -0.168625 0.060015 0.132275 -0.3259428 -0.1884807 0.6595845 0.6505264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3001 3002 -0.042793 -0.012661 0.002973 0.1825303 0.4394242 0.8454901 0.2423540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3002 3003 -0.116657 0.165403 -0.109512 -0.4569353 -0.0019423 0.5357611 0.7100468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3003 3004 0.046324 -0.034011 0.209391 -0.1753790 0.4835278 -0.7196659 0.4663947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3004 3005 -0.025554 -0.018154 -0.021306 0.4348574 0.2434165 -0.8364829 0.2279120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3005 3006 -0.091867 0.085457 -0.031134 0.6675473 0.1477592 0.5322488 0.4992584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3006 3007 0.057594 -0.101228 -0.107392 -0.2744336 0.2530895 0.0619884 0.9256292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3007 3008 -0.042005 0.180979 -0.048656 -0.1475243 -0.2800601 0.4713089 0.8232076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3008 3009 -0.047375 -0.001498 0.112253 0.6209547 -0.5479753 0.3901862 0.4023594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3009 3010 0.067435 0.007646 0.017928 -0.6090389 0.5789955 -0.4716841 0.2671140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3010 3011 0.027203 -0.046516 0.179734 -0.1263252 0.8135306 -0.5561860 0.1134330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3011 3012 -0.123788 -0.059859 0.107731 -0.4818564 -0.2250381 0.7848590 0.3180702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3012 3013 0.144118 0.113386 0.094225 -0.2757264 -0.4521211 0.4925241 0.6906385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3013 3014 -0.151532 0.145523 -0.112931 -0.3365452 -0.0805053 0.9139193 0.2121502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3014 3015 0.015884 0.109163 -0.064306 0.1872745 -0.3288929 0.3373966 0.8619288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3015 3016 0.007405 -0.032843 0.205695 -0.7529219 -0.0614079 -0.5739465 0.3161061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3016 3017 0.005731 -0.167722 0.140867 0.3334773 -0.0492287 -0.6677632 0.6636729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3017 3018 0.082672 -0.038157 0.127024 0.1412284 0.3081473 0.6829990 0.6470025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3018 3019 -0.145468 -0.063158 0.114028 0.8565508 0.0187056 0.5034855 0.1116832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3019 3020 0.163649 -0.047920 -0.016780 -0.6137528 0.5769585 0.1305218 0.5228676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3020 3021 0.096813 0.009986 -0.139404 0.0838151 -0.2828054 0.3422552 0.8921085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3021 3022 0.034004 0.033885 -0.031924 0.4416245 -0.6044867 0.6207316 0.2329289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3022 3023 -0.115131 0.001506 0.182676 -0.4490203 0.4403227 0.0716575 0.7741847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3023 3024 -0.039678 -0.125414 -0.136059 0.2059872 0.0670162 0.7351600 0.6423534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3024 3025 -0.091472 0.176938 0.149538 -0.2873624 -0.7859447 -0.0193080 0.5471206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3025 3026 0.003477 -0.034907 0.143640 -0.3717497 0.6620420 -0.5235386 0.3865358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3026 3027 0.125920 0.168239 0.055496 -0.1502785 -0.0860051 -0.6264873 0.7599560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3027 3028 -0.085653 -0.078075 -0.265500 0.0907357 -0.3931013 0.6717714 0.6212580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3028 3029 0.155020 -0.018578 0.123307 0.5508226 -0.5200556 0.0339061 0.6519103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3029 3030 -0.025969 0.048357 0.112905 0.2471217 0.0934059 -0.0689597 0.9620035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3030 3031 0.076269 0.091074 -0.061177 0.8179131 0.2527101 0.5138666 0.0556489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3031 3032 -0.050253 -0.044611 0.025922 0.3683711 0.4598826 -0.1665012 0.7906251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3032 3033 0.027665 -0.023106 -0.023154 -0.1791394 0.0583376 -0.9229332 0.3357084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3033 3034 -0.039018 0.015031 -0.002734 -0.3772578 -0.8100935 0.4469867 0.0403480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3034 3035 0.033067 -0.150040 -0.043152 0.2861665 -0.3157872 0.9022505 0.0658120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3035 3036 -0.003485 -0.148910 0.066358 -0.3703072 -0.0573464 0.0430893 0.9261357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3036 3037 0.155054 0.023206 -0.028464 -0.2563140 0.2440951 -0.2679224 0.8960682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3037 3038 0.106855 -0.081730 -0.043056 0.3729118 0.3522532 0.6918544 0.5081260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3038 3039 0.158009 0.007108 0.114557 0.0459162 -0.7589257 0.0043536 0.6495417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3039 3040 -0.120623 0.187558 0.044505 -0.4721099 -0.1615693 0.4364621 0.7486711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3040 3041 -0.051958 0.061751 0.149191 -0.4063099 0.2394745 -0.0125699 0.8817064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3041 3042 -0.108118 0.064263 -0.005523 0.3041150 0.3505679 0.8683387 0.1749405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3042 3043 0.031250 0.003169 -0.003895 -0.2931515 -0.3762742 -0.0761541 0.8756029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3043 3044 0.016548 -0.096121 0.036084 0.5728612 -0.2690193 0.3026789 0.7126319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3044 3045 -0.045895 0.038908 0.159803 -0.1971457 0.0269674 0.8015390 0.5638631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3045 3046 0.024142 -0.150162 -0.067572 -0.5272855 -0.2380931 -0.8081072 0.1106545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3046 3047 0.018774 0.047202 0.242141 -0.7605601 -0.3773970 -0.5265722 0.0429141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3047 3048 -0.027710 -0.047684 -0.028475 -0.5523873 -0.1991450 -0.6806369 0.4381130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3048 3049 -0.015668 -0.055152 0.104914 0.3358588 0.5721457 0.7480302 0.0172880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3049 3050 0.160674 -0.066977 -0.052390 0.1009271 0.3432076 -0.8432260 0.4012383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3050 3051 0.097838 0.059278 0.017819 0.2217548 0.0479287 0.9735276 0.0277788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3051 3052 -0.101179 -0.201513 0.007064 0.4591437 0.0547085 0.6612066 0.5907621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3052 3053 -0.050306 0.053500 -0.011364 0.1823728 0.3105434 0.3078228 0.8806521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3053 3054 -0.004062 0.018923 -0.082868 0.4432892 0.3530825 -0.6905601 0.4493931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3054 3055 0.035476 -0.027547 0.044514 0.2904401 0.2465090 0.2935417 0.8767617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3055 3056 0.102566 0.239373 0.187912 -0.7338835 0.4931327 0.3938903 0.2511685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3056 3057 0.011260 -0.006802 0.033826 0.6663665 -0.4669195 -0.2461302 0.5266515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3057 3058 0.147839 -0.088707 0.155204 -0.5684784 -0.7191430 -0.2262473 0.3293595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3058 3059 0.096102 -0.154123 -0.156614 0.1899224 -0.2285939 -0.9426459 0.1519640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3059 3060 -0.010826 -0.061126 0.121607 -0.0378444 0.3784866 0.7876869 0.4846288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3060 3061 -0.050802 -0.095807 0.134163 -0.3690301 0.3667675 -0.7958703 0.3096592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3061 3062 0.060166 -0.018423 0.115391 -0.6400921 0.4080824 0.6185405 0.2028756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3062 3063 -0.001829 -0.134980 -0.036835 0.5181441 -0.8235103 -0.2019708 0.1120954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3063 3064 0.067802 0.102079 -0.023696 0.1834986 0.2488728 -0.9091968 0.2788401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3064 3065 -0.067360 -0.064617 -0.096556 0.2576428 0.8173244 -0.2995672 0.4193572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3065 3066 0.119007 0.101582 -0.093471 0.8341209 -0.0303519 0.0300412 0.5499260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3066 3067 0.033266 -0.145326 -0.048446 -0.3148063 -0.6302319 0.1097869 0.7011787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3067 3068 0.006373 -0.037289 -0.033302 -0.1267589 0.7309120 0.2269824 0.6310141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3068 3069 -0.014141 0.012585 0.045084 -0.0144643 -0.0341980 0.9785464 0.2026529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3069 3070 -0.163573 -0.022869 -0.245659 -0.2738484 0.0196565 0.7893414 0.5491455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3070 3071 -0.127065 -0.111130 -0.045033 0.3480395 -0.3427075 -0.5516367 0.6761043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3071 3072 -0.045946 0.151598 -0.061144 0.7406789 0.3186530 0.0504967 0.5893260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3072 3073 -0.147934 0.027725 -0.228301 -0.7430711 0.1903189 0.5349134 0.3542481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3073 3074 -0.096265 0.043010 0.026759 -0.0721196 0.4345867 -0.0754138 0.8945647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3074 3075 -0.215016 -0.028259 0.072724 0.1983320 -0.4080938 0.4657992 0.7597072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3075 3076 0.055650 0.097027 0.122815 -0.0232214 -0.3575116 0.9263703 0.1161217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3076 3077 0.048420 -0.026307 0.149528 -0.2328175 0.3804040 -0.4442055 0.7770266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3077 3078 0.026231 -0.009303 0.061693 0.1408881 0.1351537 0.9066070 0.3740960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3078 3079 -0.012331 0.257809 -0.081332 0.1536158 -0.5803928 0.0325401 0.7990542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3079 3080 -0.158149 0.033272 -0.061475 -0.1900301 -0.0032347 0.9593554 0.2086033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3080 3081 -0.105293 -0.009843 0.103003 -0.0441664 -0.7629055 -0.1788216 0.6197155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3081 3082 0.094071 0.163443 -0.084781 0.7358458 0.4541888 0.0419447 0.5004838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3082 3083 -0.071980 0.041296 0.012515 -0.3929764 -0.4104731 0.7064856 0.4218525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3083 3084 -0.109404 0.026867 0.047214 -0.8177614 0.1299580 -0.5590045 0.0434869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3084 3085 -0.081292 0.031806 -0.072164 -0.0639898 0.9347725 0.2184352 0.2727485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3085 3086 -0.321233 -0.071512 0.107999 -0.2910078 -0.4258694 0.2089710 0.8308314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3086 3087 0.044459 0.042060 0.057157 0.1625466 -0.6123718 -0.4810668 0.6059324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3087 3088 -0.025987 0.132543 0.195356 -0.5189746 -0.5708133 -0.1049410 0.6275548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3088 3089 -0.011823 0.076873 -0.023151 -0.0289310 0.2832535 0.6540833 0.7007891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3089 3090 0.172089 -0.005768 0.024180 -0.0283626 -0.7272401 0.6841778 0.0470971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3090 3091 -0.032326 -0.240945 0.157682 0.2321705 0.0441336 0.6978026 0.6761810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3091 3092 -0.024098 -0.071941 -0.008794 -0.1748938 -0.4733181 0.0937590 0.8582490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3092 3093 -0.089321 0.214548 0.102843 0.2782748 -0.7754026 -0.5634858 0.0616246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3093 3094 0.013180 0.128728 -0.078081 -0.3345763 -0.6350320 0.4366617 0.5423279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3094 3095 -0.104759 0.027567 0.157235 -0.4823826 -0.1619680 -0.8552441 0.0981378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3095 3096 0.089095 -0.115786 0.090529 -0.5955429 0.1855998 -0.7268684 0.2873042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3096 3097 -0.019878 -0.117507 -0.012575 0.6447896 0.4357029 0.3238400 0.5380863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3097 3098 -0.100447 0.067546 0.065023 -0.0358783 0.5369338 0.8062985 0.2455556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3098 3099 -0.157150 -0.128342 -0.115204 -0.1933980 -0.4140877 -0.3213605 0.8293709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3099 3100 -0.000842 0.035402 0.089453 -0.7164908 0.4703939 0.2352525 0.4582867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3100 3101 0.078459 -0.002037 -0.071439 -0.1164285 -0.7057146 -0.1673772 0.6785250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3101 3102 -0.136367 0.150601 -0.058764 0.6040617 -0.7129010 0.3175574 0.1613658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3102 3103 0.126535 0.032009 0.192568 0.5622643 0.6086517 0.3024749 0.4710741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3103 3104 -0.010436 0.054296 0.139290 0.0075190 -0.3811682 0.6788603 0.6275372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3104 3105 0.014151 0.100688 -0.028442 -0.8594040 0.2791515 -0.3944166 0.1671367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3105 3106 -0.008078 -0.259260 0.071273 0.7018551 0.4788675 0.5181136 0.0982021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3106 3107 0.161044 0.027535 -0.080754 0.2936464 -0.6946211 -0.6042849 0.2571247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3107 3108 -0.292040 -0.031090 0.047023 0.6454287 -0.3883011 -0.6531810 0.0774513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3108 3109 0.087082 -0.053835 -0.034001 -0.3107029 -0.5898803 -0.5655403 0.4854575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3109 3110 0.127394 0.166603 0.023849 0.7465028 -0.0901508 0.5938401 0.2862870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3110 3111 0.217663 0.053938 0.040668 -0.5503160 0.2242330 -0.8030050 0.0453312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3111 3112 -0.052859 0.027156 0.121816 -0.5045700 0.5264179 -0.3049660 0.6126084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3112 3113 -0.129753 -0.202974 -0.082909 0.1380946 -0.2653852 0.9522407 0.0611413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3113 3114 0.065566 0.015192 -0.033488 0.1620185 0.0084030 -0.9629676 0.2153434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3114 3115 -0.212983 0.017199 0.092296 0.4467910 0.7883962 -0.4191069 0.0562018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3115 3116 0.115934 -0.054447 0.096953 0.3019869 -0.9069196 0.1691055 0.2402166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3116 3117 -0.094986 -0.038480 0.005959 0.7385862 0.3125078 0.2650632 0.5353231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3117 3118 -0.045561 0.047878 0.005620 -0.1052921 -0.5767285 -0.3970249 0.7061650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3118 3119 0.119380 -0.008496 0.112043 0.2378988 -0.7394908 -0.5813941 0.2419472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3119 3120 0.076195 -0.099600 0.021605 0.6052586 -0.4925031 -0.5711578 0.2547185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3120 3121 0.037041 0.018258 -0.016552 -0.3004939 0.2759335 0.1844444 0.8941724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3121 3122 0.053941 -0.117147 0.139595 -0.4141539 0.6377772 0.5847324 0.2824974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3122 3123 -0.084652 0.100051 -0.219687 -0.0662366 -0.0462119 -0.9124895 0.4010487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3123 3124 0.127770 0.035830 -0.278284 -0.4139169 -0.0089662 0.1943567 0.8892794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3124 3125 -0.098647 0.036775 -0.165796 -0.0334656 -0.3042564 -0.4138469 0.8573441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3125 3126 -0.230236 0.004176 0.123574 0.8402179 -0.2911491 0.4207491 0.1795448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3126 3127 -0.119138 -0.096806 -0.137913 -0.5414501 -0.4445127 -0.6852683 0.1991168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3127 3128 0.142734 -0.027330 0.051141 0.0513356 -0.3855259 -0.1675712 0.9058997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3128 3129 -0.079539 0.018272 0.004296 0.1368633 0.4037684 0.4985688 0.7547640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3129 3130 0.083216 -0.073533 -0.098724 0.0852005 -0.0865338 -0.8455196 0.5199513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3130 3131 -0.025929 -0.166257 -0.092301 0.4215090 -0.5563770 -0.7121150 0.0752797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3131 3132 0.162415 0.211431 -0.273719 -0.0980203 -0.6112174 0.7804216 0.0880191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3132 3133 0.019905 0.108964 0.050389 0.4360438 -0.4345309 0.7859308 0.0579788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3133 3134 0.051720 -0.216001 0.097354 0.1927629 -0.0257686 -0.1262010 0.9727547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3134 3135 -0.075966 0.037406 -0.115239 -0.7943380 0.4282654 0.0374094 0.4292044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3135 3136 0.226255 -0.004113 0.096719 -0.4297241 -0.3984904 0.0752597 0.8067705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3136 3137 0.148715 -0.130434 -0.103480 0.1159960 -0.0728356 0.5785812 0.8040421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3137 3138 0.144312 -0.055542 0.149004 0.7768336 -0.0861096 -0.5895597 0.2037990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3138 3139 0.025506 0.075330 -0.024590 -0.1175056 0.3440001 -0.8121564 0.4563534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3139 3140 0.118185 0.175730 -0.017410 0.0969653 0.4921342 -0.5408701 0.6751750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3140 3141 0.072305 0.108443 -0.137892 -0.2950732 0.4892249 0.5348313 0.6225322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3141 3142 0.206502 0.024984 -0.042708 0.2845882 0.1460987 0.2304687 0.9189934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3142 3143 0.022059 -0.056957 -0.218930 -0.1123854 -0.4693414 0.2075610 0.8508858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3143 3144 0.245309 0.185199 0.036723 -0.8572455 -0.1231577 -0.1251119 0.4840552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3144 3145 -0.186464 0.002919 0.187109 0.0469499 -0.0165237 0.2046075 0.9775778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3145 3146 -0.066705 0.114687 0.044886 -0.3158209 0.0198333 0.9257291 0.2070979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3146 3147 0.027919 -0.015890 0.196703 0.1689505 -0.6695700 -0.1465199 0.7082822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3147 3148 0.115456 -0.108176 0.115372 -0.5859073 0.2271217 0.5064564 0.5904492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3148 3149 -0.035590 0.066317 -0.204257 -0.1391807 0.4080559 0.5372286 0.7249169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3149 3150 0.127421 -0.159313 -0.002181 0.2957055 -0.1149718 -0.6952093 0.6449991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3150 3151 0.068076 0.195995 -0.146315 -0.3175415 -0.1824840 0.9189929 0.1460105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3151 3152 0.202156 -0.089220 0.028591 -0.4548476 -0.3848367 0.1408060 0.7906883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3152 3153 -0.064256 0.111129 0.083837 -0.1301245 0.6163578 -0.0278565 0.7761409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3153 3154 -0.016765 0.085008 0.020267 -0.3336345 -0.2650392 -0.3441872 0.8366466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3154 3155 -0.180568 0.303998 0.127644 0.0990761 0.9056630 0.2285661 0.3430977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3155 3156 0.013045 0.352583 -0.000409 -0.7091354 -0.2799957 0.5844700 0.2777124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3156 3157 0.106207 -0.014570 -0.084950 -0.1242042 -0.7041074 -0.0970894 0.6923725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3157 3158 -0.278460 -0.218575 -0.023552 -0.6513890 0.0179664 0.0184110 0.7583077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3158 3159 -0.007511 -0.058255 0.028099 0.6981976 -0.5077182 0.4888829 0.1254429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3159 3160 0.046955 0.013097 -0.084562 0.2265467 0.0251495 -0.5456040 0.8064492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3160 3161 0.006530 -0.099698 -0.070413 -0.0568066 -0.5564563 -0.4451480 0.6992658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3161 3162 0.060597 -0.093973 -0.071853 -0.3660695 0.4335836 -0.5767551 0.5876665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3162 3163 0.172922 -0.014275 0.100395 -0.2354813 0.0038530 0.9359734 0.2617010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3163 3164 -0.036354 0.001151 -0.069484 -0.8348966 0.2881847 -0.3296988 0.3334606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3164 3165 -0.126042 0.030218 -0.114681 -0.7942431 -0.2698484 0.5357194 0.0967700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3165 3166 -0.088228 -0.104503 0.016976 0.1534723 -0.4692239 -0.3266617 0.8059574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3166 3167 0.130153 0.098315 0.069115 -0.1325522 -0.4751861 -0.8697553 0.0124044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3167 3168 -0.042575 0.091678 -0.029791 -0.3044039 0.7207936 -0.0391796 0.6214980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3168 3169 0.032284 0.048833 -0.024353 -0.3493114 0.5027430 0.6121182 0.5005421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3169 3170 0.050947 0.103984 0.028592 -0.5847244 0.6700136 0.2842645 0.3582917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3170 3171 0.135339 -0.114591 0.056851 0.7250433 -0.1445406 -0.6685374 0.0804854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3171 3172 -0.094887 0.072267 0.204649 0.4802455 -0.1644285 0.6476330 0.5682420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3172 3173 0.206062 -0.096649 -0.082502 -0.8383933 -0.3294167 -0.1688374 0.4000940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3173 3174 -0.062777 -0.037609 0.068179 0.2891915 0.1682007 -0.7778796 0.5319588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3174 3175 -0.079021 0.113934 -0.130588 -0.6675706 0.4016461 0.6140877 0.1261991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3175 3176 0.110113 -0.103942 0.122204 0.1297364 0.2774300 0.9178044 0.2526581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3176 3177 -0.052867 -0.114699 0.037741 -0.8588142 0.3357168 0.2688519 0.2783003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3177 3178 0.022261 -0.135708 -0.055231 0.1616187 0.6758753 -0.5245957 0.4918042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3178 3179 0.159470 0.037399 0.058712 0.6457894 -0.0191805 -0.3065461 0.6990119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3179 3180 0.177507 -0.051599 -0.015614 0.4337207 -0.5332631 -0.5436321 0.4816440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3180 3181 -0.043315 -0.185277 0.150716 -0.3700593 0.3816320 0.2684081 0.8033494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3181 3182 0.072349 0.194716 0.075628 0.2672867 -0.7038760 -0.2167583 0.6213954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3182 3183 -0.144482 0.078010 0.101153 -0.0446973 -0.1607561 -0.6632192 0.7295889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3183 3184 0.101787 -0.096533 -0.026417 0.1277425 -0.2671431 0.8003465 0.5213080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3184 3185 -0.087583 0.006512 -0.027045 -0.2125047 0.5105409 -0.7608681 0.3395135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3185 3186 0.156092 -0.261733 -0.065010 0.0874202 0.0730692 -0.9800960 0.1625743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3186 3187 -0.053695 0.118516 0.156509 0.0373017 -0.2374433 0.6166944 0.7496115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3187 3188 0.105224 0.060073 -0.106475 0.0623500 0.3007258 0.1914920 0.9322056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3188 3189 -0.073040 -0.222239 -0.238945 0.0142574 -0.0088043 0.0536019 0.9984218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3189 3190 -0.191413 0.006584 0.131423 0.2847438 -0.0504381 0.5101543 0.8100121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3190 3191 -0.010799 -0.078686 0.172827 0.3813064 0.1683109 -0.7153311 0.5608728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3191 3192 0.104444 -0.032704 0.017615 0.4776386 -0.1104143 -0.4176932 0.7649852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3192 3193 0.047889 0.078445 -0.008601 -0.2620149 -0.0539686 -0.9510391 0.1547907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3193 3194 0.027526 0.061614 0.056201 0.2533712 0.3217710 -0.6081528 0.6800122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3194 3195 0.084627 0.022693 -0.003972 0.3037694 -0.4289587 0.4515217 0.7210040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3195 3196 0.137805 -0.100992 -0.187771 -0.0337485 0.0362228 0.9797482 0.1940167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3196 3197 0.006853 -0.098247 -0.191115 -0.5987734 -0.6884386 0.1068315 0.3951073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3197 3198 0.000748 -0.233423 0.032114 -0.3980985 -0.5393594 0.2694880 0.6913647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3198 3199 -0.113172 -0.167367 -0.060172 0.5860568 -0.6105614 -0.1378693 0.5145330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3199 3200 -0.062218 0.089242 -0.044233 -0.2961336 0.9146510 0.2527895 0.1087007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3200 3201 0.183281 0.159985 -0.084005 0.5175098 0.6260620 -0.5757688 0.0933822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3201 3202 0.166864 -0.111762 -0.094676 0.4425053 -0.1206147 0.0045231 0.8886060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3202 3203 0.050151 -0.209502 -0.038831 0.5254639 0.5750455 0.5502346 0.3007530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3203 3204 0.016825 0.237442 -0.006303 0.4340168 -0.3937797 -0.8088186 0.0487800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3204 3205 -0.041729 -0.141200 -0.066009 0.7491828 0.0966081 0.2133695 0.6195687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3205 3206 -0.107262 -0.077174 -0.048523 -0.7075970 -0.5901797 -0.3301883 0.2048660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3206 3207 0.277170 0.011527 0.020564 0.3549789 0.0413023 -0.9147338 0.1885368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3207 3208 -0.130263 0.178403 -0.091003 -0.0733969 0.1789600 0.9808173 0.0241584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3208 3209 -0.139468 -0.085516 0.006247 -0.4616576 0.5740513 0.0646801 0.6731670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3209 3210 0.003101 -0.081213 0.054499 0.6179118 0.6620110 0.0276446 0.4232757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3210 3211 0.018752 0.045800 0.017359 0.0365112 -0.1338878 -0.9866359 0.0853847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3211 3212 0.100600 0.004499 0.106623 0.3715119 0.4721773 0.7915554 0.1116583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3212 3213 -0.036478 -0.028554 0.142755 -0.0249582 0.4411991 0.6696737 0.5968732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3213 3214 -0.043727 -0.126750 -0.048274 -0.8731334 0.0754384 -0.1130433 0.4681542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3214 3215 -0.011630 -0.060364 -0.033047 0.2149033 -0.4929496 0.1633356 0.8271268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3215 3216 -0.098202 -0.177040 -0.060035 0.4537080 -0.5628410 0.6248933 0.2947328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3216 3217 0.089661 0.068290 0.064893 0.2684819 -0.2806342 0.9151905 0.1076492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3217 3218 0.097574 -0.080351 0.169433 0.3708495 -0.5485280 -0.4372649 0.6085943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3218 3219 -0.177275 0.255900 -0.129407 -0.8236226 0.4536591 -0.3032363 0.1545539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3219 3220 -0.092227 0.150211 -0.108659 0.3009771 0.7989985 -0.2435933 0.4600831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3220 3221 0.021343 -0.068629 -0.159463 0.3114635 -0.4043985 0.6407188 0.5735257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3221 3222 -0.077619 -0.036232 -0.075951 -0.3165428 0.2158205 0.9148839 0.1273168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3222 3223 0.107653 0.077178 -0.098047 0.0365951 0.2251066 -0.5453235 0.8066041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3223 3224 -0.157392 -0.013094 -0.046438 0.2921479 -0.5735694 -0.3237299 0.6934456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3224 3225 0.040664 0.060848 0.046494 -0.3676232 0.1973262 0.7159700 0.5597343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3225 3226 -0.042333 -0.117269 0.075344 0.1813478 0.3922112 -0.3853718 0.8153355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3226 3227 0.148460 0.109662 0.154361 0.6532361 -0.3864599 -0.0946104 0.6441896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3227 3228 0.068061 0.081486 -0.138798 0.3718212 0.2724925 0.8114008 0.3593404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3228 3229 0.122023 -0.108497 0.006365 0.2960750 0.5093831 -0.8050819 0.0686409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3229 3230 0.105845 -0.004710 -0.001142 -0.2496683 -0.4657490 -0.4862215 0.6959398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3230 3231 -0.118677 0.045483 -0.100923 0.2376739 0.3329167 0.5806920 0.7038994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3231 3232 0.117008 0.145631 0.015717 0.0376404 -0.6704757 0.4951737 0.5512246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3232 3233 0.168452 0.140477 -0.022846 -0.3420683 0.2902129 -0.3380058 0.8273559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3233 3234 -0.039887 -0.050716 0.039330 0.0430810 -0.5458598 0.6924199 0.4698253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3234 3235 -0.000703 0.243064 -0.200950 -0.1950973 -0.1944440 0.6552945 0.7033618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3235 3236 0.019336 -0.144686 0.048019 0.3344572 -0.2899272 -0.7286354 0.5226577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3236 3237 0.081767 0.017670 -0.009609 -0.4651276 -0.0547686 0.6124653 0.6368225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3237 3238 0.139940 0.002116 0.170500 -0.1044215 -0.2506307 0.7406469 0.6145914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3238 3239 -0.101558 0.012289 -0.124060 0.2247931 -0.3530634 -0.8902430 0.1796711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3239 3240 -0.133648 -0.054810 -0.109323 -0.0223962 0.3642052 -0.7112404 0.6008244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3240 3241 0.219853 -0.105867 0.042045 0.7769436 0.2216090 -0.5048977 0.3038528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3241 3242 0.076719 -0.024454 0.217390 -0.0158615 -0.7477827 0.6326151 0.2009168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3242 3243 -0.008838 -0.167606 -0.064657 0.3810143 0.7694671 -0.1366646 0.4940356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3243 3244 0.209569 0.028238 0.202902 0.0266470 -0.7145167 -0.4372066 0.5455330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3244 3245 0.001611 -0.068688 0.046935 -0.2678034 0.1471747 -0.7431377 0.5952875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3245 3246 -0.186553 0.084670 0.004293 0.2352170 0.1460394 0.4243477 0.8621337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3246 3247 -0.037550 -0.191920 -0.086227 -0.2131844 -0.2984494 0.7039672 0.6082028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3247 3248 -0.098439 0.068610 0.008008 0.3241057 0.2747111 0.6896705 0.5863821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3248 3249 -0.017948 -0.049917 -0.095626 0.2435822 -0.1418361 -0.7707897 0.5713435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3249 3250 -0.132750 -0.039790 0.107434 -0.0989103 -0.5404542 -0.1955093 0.8123436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3250 3251 -0.175594 0.049342 -0.020882 -0.6244081 0.2099793 -0.3190999 0.6813211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3251 3252 -0.126682 0.115687 0.079743 0.5601951 -0.4608150 0.4434762 0.5264598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3252 3253 -0.126862 0.071415 0.008363 0.3906042 -0.0776483 0.0204097 0.9170510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3253 3254 -0.165428 0.002288 -0.001894 -0.0148090 0.6247874 -0.4632444 0.6283518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3254 3255 0.065425 -0.051436 -0.023652 -0.0335973 0.2153229 -0.9742434 0.0579408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3255 3256 0.104684 0.028394 -0.056259 0.4025705 0.5352023 -0.2507423 0.6990163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3256 3257 0.003389 -0.033110 -0.063409 -0.2145970 -0.6539800 0.3823492 0.6164961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3257 3258 0.067888 -0.125529 0.050645 -0.2529838 0.3407456 -0.8601202 0.2829927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3258 3259 -0.183035 0.247653 -0.005472 -0.2642469 -0.3316826 0.2669155 0.8653995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3259 3260 -0.061901 0.060366 -0.199791 0.6597733 -0.1082773 -0.6600726 0.3424608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3260 3261 0.006577 0.089856 -0.081667 -0.5632107 -0.6505320 0.1468597 0.4878874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3261 3262 -0.159062 -0.019309 -0.190191 0.6189677 -0.0472359 0.7757580 0.1133457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3262 3263 -0.021951 -0.094971 0.070101 0.1316993 -0.4490797 -0.3327413 0.8186977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3263 3264 -0.155934 0.037552 0.114983 0.0816672 0.7708915 -0.0123404 0.6315889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3264 3265 0.039803 0.020702 0.065900 -0.5681859 0.0166784 0.2285566 0.7903471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3265 3266 0.012663 0.031214 0.011004 0.0000170 -0.0599764 -0.8725411 0.4848451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3266 3267 0.067984 0.077456 -0.015112 -0.3834099 0.2683233 -0.8801207 0.0799191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3267 3268 -0.001842 0.095467 0.028262 0.0202967 0.2241317 0.2519708 0.9412034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3268 3269 0.149009 -0.029095 0.007914 0.2579714 0.0019174 0.6058978 0.7525523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3269 3270 -0.094609 -0.107770 0.000160 -0.2719476 -0.6574340 -0.1015888 0.6953451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3270 3271 -0.051168 -0.119796 0.177468 -0.6372759 0.1675490 -0.4702366 0.5870982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3271 3272 -0.104855 0.110091 -0.043106 0.0555791 -0.2532493 0.2151733 0.9415287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3272 3273 -0.084433 0.139568 -0.006100 0.6198371 -0.1871525 0.5062686 0.5696210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3273 3274 0.006670 -0.091720 -0.139560 -0.2720563 0.7188039 -0.6236681 0.1426341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3274 3275 0.012017 -0.157440 0.085664 -0.3982944 0.0627362 -0.8534033 0.3303460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3275 3276 0.073321 0.015175 -0.031663 -0.6794351 -0.4343045 -0.4046902 0.4312462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3276 3277 0.120569 -0.124381 0.040797 -0.1432529 0.0993568 -0.9844290 0.0225027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3277 3278 0.084780 -0.032991 -0.028389 -0.0305621 -0.8069101 0.0244238 0.5893772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3278 3279 0.153174 -0.047717 0.135941 0.5532138 0.6913973 -0.4372656 0.1572357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3279 3280 -0.072292 0.052049 0.080355 0.4634432 -0.8260617 -0.2611748 0.1860919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3280 3281 -0.071958 0.032400 -0.044086 -0.6913661 -0.3770739 -0.5787314 0.2118919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3281 3282 0.054610 -0.080582 -0.026404 0.0799110 0.3512125 0.8444754 0.3963903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3282 3283 0.014407 0.174547 0.002674 0.3284421 0.5937576 -0.7334593 0.0401901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3283 3284 -0.064879 0.076321 0.199776 0.6209167 -0.5696203 -0.0321457 0.5375516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3284 3285 -0.007062 0.114815 0.135837 0.3111772 0.0969786 -0.4735352 0.8182471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3285 3286 0.067593 0.133360 0.142936 -0.7817987 0.3614351 -0.4050077 0.3067966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3286 3287 -0.031970 -0.022628 -0.060602 0.3046853 0.6528911 -0.4443682 0.5323881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3287 3288 -0.178485 -0.054143 0.212442 0.1202652 -0.5615707 0.8093114 0.1232463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3288 3289 -0.008653 0.291653 0.121322 -0.0724961 -0.0147071 0.4679338 0.8806622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3289 3290 -0.033056 -0.242705 0.040870 0.8147476 -0.4375140 0.2937279 0.2418507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3290 3291 0.047652 0.069502 0.063299 -0.0208809 0.1149724 -0.2376560 0.9642951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3291 3292 0.149920 -0.032275 -0.143690 -0.5488316 -0.5044693 -0.3587210 0.5617953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3292 3293 -0.024414 0.000666 0.110739 -0.5351783 0.5115791 -0.5102493 0.4376261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3293 3294 -0.062080 0.018844 0.010665 -0.1428947 0.1364321 0.7397562 0.6432170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3294 3295 -0.072221 0.100211 0.138564 -0.8721038 -0.1531179 -0.1405318 0.4429906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3295 3296 0.044122 -0.143853 0.122046 0.7354373 -0.5204458 -0.0470778 0.4313373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3296 3297 0.078830 -0.142150 0.092062 0.1235701 0.0519306 -0.9858530 0.1006351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3297 3298 -0.012309 0.028768 0.131397 -0.0643545 -0.7350969 -0.2238915 0.6366818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3298 3299 0.073765 -0.045526 -0.071248 0.0482932 0.9229039 -0.2140646 0.3163741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3299 3300 -0.146660 -0.118213 0.030568 -0.1532133 -0.5920653 0.6268925 0.4826906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3300 3301 0.074097 -0.059685 0.020375 -0.0417714 -0.5542444 -0.7681491 0.3178289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3301 3302 -0.035026 0.105560 0.135803 -0.1181983 -0.6582643 -0.6254108 0.4019684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3302 3303 -0.211307 0.080733 0.137928 0.3039533 0.0308131 -0.3365592 0.8907249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3303 3304 -0.093368 0.225204 -0.036995 0.0479262 -0.5009933 -0.3737471 0.7791161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3304 3305 -0.045026 0.039158 -0.092356 -0.6126115 0.0129519 0.7580007 0.2235493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3305 3306 0.169438 0.000618 -0.048768 -0.0129130 -0.1444246 -0.5645124 0.8125888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3306 3307 0.065332 0.009396 -0.068208 0.3941716 -0.3776921 0.8369848 0.0378669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3307 3308 0.144984 -0.099199 0.030626 0.0860053 0.3519023 -0.8244727 0.4347557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3308 3309 -0.077069 0.015704 0.094745 0.3416862 0.5407069 -0.7054478 0.3053358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3309 3310 -0.169326 -0.247652 0.099015 -0.6032665 0.3655015 -0.6920116 0.1536169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3310 3311 0.009699 -0.041630 0.077866 -0.4034938 0.0057698 -0.1552558 0.9016957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3311 3312 0.233121 -0.016461 0.072415 0.0790021 -0.2649492 0.9433372 0.1835090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3312 3313 0.004965 0.040946 0.111411 0.0029240 0.8826843 -0.4601010 0.0957440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3313 3314 0.133398 -0.089450 -0.019699 0.1337920 -0.4114095 0.8918623 0.1319983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3314 3315 -0.001849 -0.070795 0.011949 0.1480285 0.2874835 0.2525225 0.9119612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3315 3316 -0.335664 0.064739 0.050158 -0.5175958 0.0756544 0.6140176 0.5910612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3316 3317 0.115268 0.247301 -0.039277 -0.0213520 0.0960578 -0.1830997 0.9781572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3317 3318 0.197732 0.026687 0.023974 0.2846471 0.3810174 -0.3675371 0.7991985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3318 3319 -0.060568 -0.104470 0.188947 0.1625211 0.7793553 -0.5662900 0.2133257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3319 3320 0.055754 0.160840 0.180320 0.0552852 -0.6617185 0.3147737 0.6782254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3320 3321 0.022862 -0.015887 -0.088725 0.2515186 -0.3187757 0.0320721 0.9132863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3321 3322 -0.050936 -0.007000 0.023051 -0.4972674 -0.5668082 0.6550758 0.0482629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3322 3323 -0.018672 0.136551 0.157288 0.5108197 0.4709556 -0.7157529 0.0704405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3323 3324 -0.015543 -0.069767 -0.167131 -0.0670196 -0.3853996 -0.8374331 0.3816821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3324 3325 -0.104051 0.025438 -0.128146 -0.2314372 -0.4836446 -0.5704454 0.6221871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3325 3326 -0.014786 0.080786 -0.231739 -0.7928655 0.3344466 0.4678390 0.2015848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3326 3327 0.075998 0.106056 0.187994 -0.0593119 -0.8865009 0.4370304 0.1400096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3327 3328 0.042319 -0.053698 -0.149601 0.6336388 -0.2221709 0.1263968 0.7301821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3328 3329 -0.032204 0.065794 -0.074266 0.2657720 0.6518299 0.5932590 0.3905468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3329 3330 -0.098721 0.290081 0.030946 -0.5180686 -0.6685756 0.2755835 0.4567991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3330 3331 0.020519 0.084416 -0.023171 0.9153063 0.2331853 0.2603462 0.2001471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3331 3332 -0.013136 -0.003016 0.063157 -0.4553433 -0.5337211 -0.6183352 0.3542116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3332 3333 -0.018868 0.042930 -0.006958 0.5259620 -0.2308118 -0.2847263 0.7674769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3333 3334 0.119109 -0.151982 0.003862 -0.2074603 -0.3244621 0.4946784 0.7790878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3334 3335 -0.131013 0.103291 -0.040749 -0.1192883 0.4700423 0.1345093 0.8641399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3335 3336 -0.098508 0.025561 -0.214224 -0.4618174 0.5208733 -0.7125794 0.0874431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3336 3337 -0.118839 0.013214 0.248301 0.0520117 0.1570563 0.0423556 0.9853091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3337 3338 -0.044743 0.276472 -0.068442 0.3142598 0.4671006 -0.4536089 0.6908666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3338 3339 0.016791 0.131341 0.141630 0.1175109 -0.6471348 -0.4634283 0.5938366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3339 3340 0.031020 -0.000333 -0.036061 0.7194778 0.1530908 0.6292255 0.2509785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3340 3341 -0.045349 -0.213224 0.032458 -0.1548672 -0.2515917 0.9553623 0.0008402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3341 3342 -0.051374 -0.041904 0.014994 -0.0673496 -0.1489162 0.4803051 0.8617395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3342 3343 -0.036538 0.149258 -0.040053 0.2401000 -0.1418363 -0.4933170 0.8239374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3343 3344 0.017228 -0.091192 -0.043280 0.3863602 -0.3206862 -0.8568966 0.1166809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3344 3345 0.044290 -0.097075 -0.013606 -0.0112912 -0.3450167 0.8725016 0.3457989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3345 3346 0.022055 0.095247 -0.078622 0.2174508 0.8014512 -0.3579310 0.4269385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3346 3347 0.085896 0.184121 -0.044037 -0.8104734 -0.2155055 0.5443334 0.0197825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3347 3348 0.013514 -0.079881 -0.055616 0.3893113 0.0397881 -0.4173414 0.8201706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3348 3349 -0.087338 0.105731 -0.013984 -0.0022045 -0.4139378 -0.7752805 0.4770648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3349 3350 -0.103837 -0.099607 -0.058138 -0.3616483 0.5949393 0.1030225 0.7103830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3350 3351 0.102928 -0.056002 0.151161 0.2074398 -0.0675693 -0.0046821 0.9759002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3351 3352 -0.020492 0.008646 0.034416 -0.4177062 0.4228014 0.7850054 0.1747198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3352 3353 0.146331 -0.005892 -0.069820 -0.4582161 0.6441395 0.6073262 0.0792288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3353 3354 -0.053055 0.052459 -0.046821 -0.6897381 -0.1440913 0.7079229 0.0484172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3354 3355 0.023132 -0.152231 -0.017657 -0.1870718 -0.1194814 0.0733291 0.9722917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3355 3356 0.051606 0.010883 -0.057125 0.1507501 0.2180765 -0.6085746 0.7478998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3356 3357 -0.180950 -0.056217 -0.233633 -0.1887963 0.2317049 -0.8784556 0.3728064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3357 3358 -0.164593 -0.028639 -0.219245 -0.2618384 0.1490357 -0.9393425 0.1639044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3358 3359 0.031255 0.063368 -0.087129 -0.1921107 -0.2160189 0.9173118 0.2738035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3359 3360 -0.097296 0.079522 -0.058753 0.4984979 -0.0912887 0.1822057 0.8425956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3360 3361 -0.037703 -0.203904 0.239243 -0.5979625 -0.4318132 -0.0939630 0.6686921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3361 3362 -0.062486 0.122044 0.111115 0.0153872 0.1485474 0.5147561 0.8442293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3362 3363 -0.117786 0.201867 0.006191 -0.3564548 0.0030824 0.2157439 0.9090572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3363 3364 0.140063 -0.023535 -0.014783 0.8943797 -0.1171884 -0.3532731 0.2480927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3364 3365 -0.033216 -0.051163 -0.033430 0.4893721 -0.0632982 0.8477878 0.1943298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3365 3366 -0.095094 0.123005 0.005704 -0.1562168 0.8157011 -0.4757299 0.2896707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3366 3367 0.065390 -0.051610 -0.144357 0.5243514 -0.5943146 0.5588464 0.2440008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3367 3368 -0.018689 0.037294 -0.196197 -0.0436739 -0.0082559 -0.1004214 0.9939517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3368 3369 -0.102595 -0.030146 -0.142334 0.5286038 -0.2063758 0.2595200 0.7814323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3369 3370 -0.055557 -0.001835 0.234180 -0.1086513 0.8963659 0.0598705 0.4256038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3370 3371 0.120975 -0.025456 0.115794 -0.2731043 -0.3254695 0.5102758 0.7477314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3371 3372 -0.080242 0.187929 0.058855 -0.3039025 -0.5725630 0.5772597 0.4965743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3372 3373 0.003137 -0.065790 0.095728 0.4741002 0.3108794 -0.5684145 0.5962280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3373 3374 -0.037926 -0.067317 -0.121281 -0.8456203 0.1079464 0.0767434 0.5170921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3374 3375 -0.101701 -0.047844 -0.013260 0.0819723 0.7871030 -0.4321978 0.4323822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3375 3376 0.001272 0.039776 -0.282018 -0.2311003 0.5181433 -0.5183056 0.6399059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3376 3377 0.364946 -0.056381 -0.010746 -0.5471695 0.4105891 -0.7290366 0.0229723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3377 3378 0.064524 0.219023 0.004637 -0.2420661 0.6430768 0.0973396 0.7199869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3378 3379 -0.134784 -0.035340 0.103241 0.6515077 -0.6874479 -0.1099249 0.3014458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3379 3380 -0.013631 0.136914 0.131937 -0.3327423 0.1622744 -0.9288476 0.0138458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3380 3381 0.045383 -0.189787 0.134024 -0.0966028 -0.8208279 0.4940195 0.2699152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3381 3382 0.029895 -0.133720 -0.105691 -0.3821098 0.1948692 -0.8962204 0.1131685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3382 3383 -0.122784 -0.067934 -0.028566 0.2226430 -0.3035897 -0.6538215 0.6563390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3383 3384 -0.092654 -0.025812 0.031706 -0.4110453 -0.5213391 -0.4867211 0.5677586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3384 3385 -0.114165 -0.154767 -0.034117 0.2621889 -0.5687556 0.6764502 0.3875424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3385 3386 0.122912 -0.012839 -0.145998 -0.2242841 0.3372437 -0.8466455 0.3451880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3386 3387 -0.132495 -0.148630 -0.061223 -0.2689430 -0.2382315 -0.2232095 0.9061418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3387 3388 -0.054788 0.007984 0.146421 -0.1400493 -0.0350036 -0.2180882 0.9651935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3388 3389 0.161590 0.044616 -0.029349 0.5219365 0.5990773 0.3717354 0.4801057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3389 3390 -0.005964 0.289044 -0.054929 -0.1436281 -0.7605174 -0.6250059 0.1017443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3390 3391 -0.100290 -0.089904 -0.099479 -0.2627679 0.0901761 -0.3632851 0.8892948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3391 3392 0.169030 0.293775 0.081783 -0.3192581 -0.2476751 -0.3394110 0.8494301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3392 3393 -0.042360 0.038939 0.019972 -0.2021556 -0.0337490 0.2328580 0.9506688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3393 3394 -0.021526 -0.128270 0.033338 -0.2610697 -0.2036333 -0.7523802 0.5694735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3394 3395 0.219380 -0.025283 0.027926 -0.9277111 0.0638345 -0.0066674 0.3677401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3395 3396 0.144185 -0.091273 0.162251 0.1617042 0.0851360 0.9818247 0.0512234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3396 3397 -0.103492 0.008296 -0.070637 0.2916648 0.0129098 -0.7410042 0.6047129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3397 3398 0.022242 -0.085117 -0.038546 0.5712045 0.1037629 -0.6777976 0.4511642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3398 3399 0.013571 -0.053781 0.008642 -0.3851470 -0.2402597 -0.7016506 0.5492026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3399 3400 -0.083361 -0.193213 0.053748 -0.5598494 0.1304753 0.0514727 0.8166367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3400 3401 0.105914 -0.164141 0.020053 0.4827435 0.3430247 0.8017989 0.0800704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3401 3402 -0.050865 -0.047442 0.142330 -0.2062709 0.2084336 0.7920428 0.5354212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3402 3403 0.128454 0.085764 0.019404 -0.4288549 0.4211044 0.6261338 0.4967001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3403 3404 -0.095101 -0.135196 0.055004 -0.1496248 -0.0537735 0.9838142 0.0826465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3404 3405 -0.057938 0.024342 0.059285 -0.4633296 -0.2281014 -0.8383913 0.1743431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3405 3406 0.139297 -0.050940 0.096100 0.1426305 0.4319878 -0.7588878 0.4659746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3406 3407 -0.121233 -0.041484 -0.032866 0.0061857 -0.8181959 0.3732717 0.4372475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3407 3408 -0.149027 0.073384 0.010211 0.7919879 0.3143423 -0.3541694 0.3853675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3408 3409 0.195888 0.040440 -0.119588 -0.5171832 0.3719558 0.2387093 0.7329313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3409 3410 -0.005275 0.217886 0.035114 -0.3594330 -0.1676075 0.5109607 0.7626498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3410 3411 0.123354 -0.008036 -0.065523 -0.4053393 -0.4432307 0.3089584 0.7374221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3411 3412 0.070320 -0.035896 -0.015852 -0.1231798 -0.5466051 0.4095674 0.7199335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3412 3413 -0.164860 -0.129544 -0.073865 0.6681399 -0.3866875 -0.5054072 0.3855196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3413 3414 0.039690 0.127285 0.079142 -0.3748075 -0.2556373 0.7098365 0.5387959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3414 3415 0.076488 0.063852 0.201038 -0.0084118 -0.2638245 0.4549575 0.8504937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3415 3416 0.066653 0.100669 -0.017001 0.8391788 -0.3754062 0.2067750 0.3348033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3416 3417 0.182118 0.246235 0.045767 0.2743409 0.4444848 0.0480643 0.8513872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3417 3418 -0.035789 -0.026008 0.084388 -0.3239973 0.8773113 0.2693533 0.2297813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3418 3419 -0.047502 -0.080692 -0.208313 -0.2018817 -0.6086536 -0.7558454 0.1322204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3419 3420 0.063423 -0.036857 0.098030 -0.1856821 -0.0291461 -0.1876518 0.9640848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3420 3421 0.045400 0.033460 0.045859 0.0635424 -0.7654116 -0.6372457 0.0634466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3421 3422 0.000946 -0.076622 -0.059164 -0.5881060 -0.6572120 -0.0997991 0.4606993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3422 3423 -0.017935 -0.000747 -0.133579 0.4792175 0.3349629 0.3598652 0.7270815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3423 3424 -0.019941 -0.073491 -0.085171 0.1324529 -0.8284022 -0.4910969 0.2345846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3424 3425 0.016141 0.136286 -0.051963 -0.0510112 -0.5491136 -0.6259851 0.5513753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3425 3426 -0.143329 -0.191486 -0.013099 0.1108337 0.1182084 -0.5066613 0.8467804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3426 3427 -0.021035 0.071833 0.072419 0.2903467 -0.4032933 0.8335370 0.2413906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3427 3428 -0.030604 -0.036154 -0.042668 -0.4865568 0.6107837 -0.6048831 0.1559556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3428 3429 0.127541 0.081232 -0.181941 0.7965848 -0.5086806 0.0146586 0.3263155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3429 3430 -0.048246 0.053780 -0.235460 -0.6730569 0.0952694 0.0941512 0.7273608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3430 3431 0.083682 -0.032225 -0.062212 0.3974751 -0.5648433 0.7087693 0.1435677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3431 3432 -0.174171 -0.189794 -0.028650 0.5378748 -0.4484891 0.6665731 0.2553989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3432 3433 -0.030855 0.107388 -0.079565 0.7671353 0.0506354 0.6390737 0.0228957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3433 3434 0.000969 0.179117 0.008989 -0.0676749 0.9083123 0.2115010 0.3544802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3434 3435 0.169889 0.151926 -0.046426 -0.3568490 -0.5463617 0.5224086 0.5488505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3435 3436 -0.005478 0.056757 -0.056665 0.6151573 0.0979896 0.6808535 0.3852506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3436 3437 -0.054606 0.085654 0.024364 -0.4265173 -0.2366288 -0.5388403 0.6868340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3437 3438 -0.026816 0.124886 -0.163116 -0.3109835 -0.3616368 0.1647192 0.8633514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3438 3439 0.040782 0.056789 0.060958 0.7026699 0.3093416 -0.3197275 0.5552811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3439 3440 0.042599 -0.065036 0.084000 -0.9278066 -0.1905879 -0.3132892 0.0685635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3440 3441 0.060649 0.086511 -0.052205 -0.6211990 0.5617368 -0.4894992 0.2428045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3441 3442 0.008026 0.229971 -0.004083 0.3692569 0.0830447 -0.0296164 0.9251355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3442 3443 0.023345 -0.042238 -0.000365 0.4827900 -0.0591537 0.3840159 0.7848225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3443 3444 -0.047226 -0.090581 -0.138967 -0.3772988 0.8658274 -0.1445656 0.2951089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3444 3445 0.091536 0.074520 -0.004077 -0.2663743 0.0305410 -0.5509503 0.7902947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3445 3446 -0.025196 0.085557 -0.055712 -0.1826415 0.3110240 -0.8324816 0.4205717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3446 3447 -0.041088 -0.140594 -0.191183 -0.3493444 0.4333729 -0.7985464 0.2290634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3447 3448 -0.063167 -0.034525 -0.061251 0.4216918 -0.4265606 0.3547439 0.7172021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3448 3449 -0.004614 0.015615 0.002637 0.1096590 -0.2224025 -0.8610313 0.4440013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3449 3450 0.020177 0.085807 -0.059492 -0.0455829 -0.6686254 -0.1649224 0.7236455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3450 3451 0.142314 0.105655 -0.106003 -0.4764762 0.2599016 -0.8061105 0.2358125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3451 3452 0.107885 -0.176209 -0.170219 0.3852447 0.6271972 0.3488110 0.5801216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3452 3453 -0.142990 -0.124417 -0.146873 0.6520017 0.3734247 -0.6458841 0.1352095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3453 3454 0.141480 -0.118933 0.086828 0.6344665 0.3750459 0.3634679 0.5698105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3454 3455 0.182736 -0.014047 -0.094951 -0.2542330 0.2734266 0.7327929 0.5688743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3455 3456 0.183954 0.134821 -0.079020 0.1897934 0.2021963 0.3772081 0.8836341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3456 3457 0.006319 0.006154 0.061886 0.1839397 -0.1713911 -0.9616875 0.1093090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3457 3458 0.113256 -0.058470 -0.107533 0.2685118 -0.5002006 -0.7202823 0.3986153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3458 3459 0.018152 0.051754 0.128062 -0.4923712 0.2269783 -0.0921950 0.8351955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3459 3460 -0.016284 0.019582 -0.163001 -0.0311146 0.1670176 -0.2477177 0.9538202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3460 3461 -0.000931 0.028388 -0.008654 0.5302735 0.3841441 0.7361544 0.1712306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3461 3462 0.177501 -0.161488 -0.128482 -0.0262509 0.1573791 -0.7058519 0.6901563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3462 3463 0.053120 -0.029588 -0.040810 -0.1987649 -0.6689431 -0.6823149 0.2178396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3463 3464 -0.147637 0.251302 -0.050447 -0.1919413 -0.1567011 -0.5198726 0.8175181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3464 3465 -0.095303 -0.220526 -0.129234 0.0741344 -0.2127839 -0.8080651 0.5442958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3465 3466 0.039763 0.180147 0.021136 -0.7028527 -0.4256919 0.4810852 0.3055184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3466 3467 0.200414 -0.026412 0.102151 -0.2378686 -0.7576041 0.6074798 0.0205622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3467 3468 -0.132364 0.208277 -0.034897 0.8778310 -0.2387008 -0.1777505 0.3752858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3468 3469 -0.140355 0.048952 -0.135752 0.1727158 -0.4040050 -0.6959697 0.5679571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3469 3470 -0.012367 -0.084656 -0.015254 -0.3635995 -0.2842925 -0.6354310 0.6190320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3470 3471 -0.128684 0.014282 -0.046323 0.4525705 0.6951695 -0.0856491 0.5518910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3471 3472 0.304869 -0.009818 0.162661 0.1865586 -0.0476403 -0.6341073 0.7488886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3472 3473 -0.014552 0.041181 0.146285 0.3147255 -0.6028295 -0.2561942 0.6869564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3473 3474 -0.039904 0.138071 0.113348 0.4487744 0.5050684 0.6008903 0.4271280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3474 3475 -0.102430 0.065066 0.006496 -0.4189344 0.5212619 -0.1750556 0.7225895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3475 3476 0.038113 0.069121 0.102307 -0.4951663 -0.6767699 0.2043657 0.5050025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3476 3477 0.300753 -0.007395 -0.000298 0.4276503 -0.1059217 0.5588070 0.7025885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3477 3478 0.118635 0.092089 0.093584 0.0265224 -0.5995942 0.7353591 0.3146909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3478 3479 0.102415 -0.116293 0.078585 -0.1104329 0.8506533 0.3577567 0.3690579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3479 3480 -0.059162 -0.136458 -0.070272 0.1762316 -0.6161416 0.0429233 0.7664656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3480 3481 -0.211245 0.004076 0.057833 0.4528809 0.3914776 -0.2588858 0.7580384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3481 3482 -0.081416 0.048380 -0.078505 0.0598508 0.6609894 0.6959571 0.2741434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3482 3483 -0.037459 0.022917 0.177545 -0.5917932 -0.5771620 -0.4767661 0.2989298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3483 3484 0.046230 -0.110150 0.158789 0.0929629 -0.2255594 0.3631690 0.8992158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3484 3485 -0.111387 0.053085 -0.012252 -0.4260191 0.1657140 -0.0464705 0.8881932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3485 3486 0.200126 -0.041709 -0.021941 -0.0712157 0.8717235 -0.4339411 0.2161516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3486 3487 -0.027440 -0.096757 0.310095 0.7119217 -0.4849798 -0.4091818 0.3008861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3487 3488 -0.063459 -0.175989 0.130853 -0.4564119 0.5584807 -0.1606304 0.6737844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3488 3489 -0.075908 -0.094479 0.093803 0.0647895 0.5780841 0.8109370 0.0632634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3489 3490 -0.061234 0.073810 -0.173470 -0.3252038 -0.2304758 -0.5531084 0.7315699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3490 3491 -0.074563 0.089727 -0.036237 -0.6752795 0.2750164 -0.3311255 0.5989320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3491 3492 -0.154087 -0.067608 0.062745 0.1093212 0.1752561 -0.9033635 0.3758572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3492 3493 0.054729 0.022462 -0.009015 0.3070713 -0.3328077 0.8662944 0.2109036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3493 3494 0.008790 0.070777 0.030738 0.2833803 0.7339545 -0.6072135 0.1108971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3494 3495 0.095891 -0.082208 0.028155 0.3510578 -0.0919858 0.8598610 0.3590767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3495 3496 0.057149 0.005468 -0.025286 0.5337134 0.6996612 0.3681661 0.3001298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3496 3497 0.156677 0.242087 -0.049332 -0.1133878 0.8366988 -0.0769177 0.5302471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3497 3498 -0.137380 -0.007735 -0.162485 0.2915059 0.0664637 -0.4684445 0.8313643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3498 3499 0.004341 0.143360 -0.185891 -0.2456214 0.1185815 0.4604250 0.8447588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3499 3500 -0.059657 0.000817 -0.030050 -0.3656098 -0.5830661 0.4399637 0.5768842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3500 3501 -0.032567 0.099838 0.020105 -0.6771759 -0.1555470 -0.7179824 0.0417039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3501 3502 0.057920 0.082371 0.042552 -0.0176137 -0.5386066 -0.5729297 0.6175307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3502 3503 0.055838 0.018914 0.003684 -0.9450047 0.0412915 0.2699661 0.1799428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3503 3504 0.030434 -0.230573 -0.092546 0.2150153 0.1720009 0.8334314 0.4791411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3504 3505 0.045394 -0.006454 -0.005420 -0.1519125 0.5061963 0.8134886 0.2427430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3505 3506 0.121598 0.026246 0.093931 0.0532830 0.5973338 0.0006506 0.8002205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3506 3507 -0.185867 0.112438 0.064223 -0.8154880 -0.1485354 0.3350669 0.4479361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3507 3508 -0.007854 -0.135472 0.141077 0.0357771 -0.6601519 0.3676811 0.6540108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3508 3509 0.042347 -0.120244 -0.039759 0.3758045 0.6744383 -0.4355537 0.4628141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3509 3510 -0.201180 -0.146413 -0.042373 0.4513651 0.2505348 -0.8525011 0.0821207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3510 3511 0.158519 0.115006 -0.010286 -0.3840251 -0.2324956 -0.3773424 0.8099896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3511 3512 0.008892 -0.027399 -0.042191 -0.0026947 -0.7422301 0.6700043 0.0134690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3512 3513 -0.207780 -0.058846 -0.004679 0.2319164 -0.2907537 -0.5465838 0.7502821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3513 3514 0.015182 0.003151 -0.064309 0.2083241 -0.4748493 0.7814001 0.3471788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3514 3515 -0.053405 -0.047425 -0.152994 0.1834483 -0.4108897 0.8799778 0.1521695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3515 3516 -0.184483 -0.244712 0.074951 -0.0637506 0.1613030 -0.9838921 0.0432836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3516 3517 -0.138131 -0.110717 0.055154 0.3679993 -0.5132909 0.7623592 0.1411290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3517 3518 0.062210 0.076067 -0.069842 -0.6647772 0.4823888 -0.3700158 0.4341205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3518 3519 -0.071231 0.041936 -0.167680 -0.0330505 -0.1893796 0.4152366 0.8891691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3519 3520 0.109172 -0.050720 0.010868 0.0103593 0.2749897 -0.2662928 0.9237757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3520 3521 -0.102255 -0.142058 -0.082544 0.7199235 -0.0300009 -0.1149337 0.6838131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3521 3522 -0.109559 0.077902 0.115234 -0.0994788 0.9130391 0.2744588 0.2848436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3522 3523 -0.119821 0.035644 0.038724 -0.3371894 0.4401661 0.4520133 0.6987425 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3523 3524 -0.093452 0.034865 0.062785 -0.3113821 0.2981565 0.1426787 0.8909471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3524 3525 0.084092 -0.192138 -0.056086 -0.5661015 -0.4630273 0.3470476 0.5871054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3525 3526 -0.028336 0.111118 -0.011994 -0.1218433 0.5908117 -0.6631914 0.4430271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3526 3527 -0.130400 -0.076523 0.037507 0.2314688 0.2107565 0.2932776 0.9033228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3527 3528 0.131753 -0.057171 -0.103734 0.1955976 0.4128452 -0.8883518 0.0461684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3528 3529 0.049645 0.107146 -0.057206 0.7941035 -0.1711094 0.4118005 0.4129668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3529 3530 0.046498 -0.202997 0.048782 -0.1359541 0.4517149 0.8469975 0.2450823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3530 3531 0.111107 -0.116447 -0.130692 0.2111259 0.5994352 0.7267714 0.2605890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3531 3532 0.036274 -0.173094 0.120574 -0.9041816 -0.2424826 -0.0846346 0.3413133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3532 3533 0.021469 -0.008081 0.064456 -0.4601484 0.6184794 -0.5082434 0.3839731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3533 3534 0.058543 0.050941 0.035534 -0.6242374 0.4337644 -0.5018390 0.4127151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3534 3535 -0.195411 0.068301 -0.130813 -0.1961708 0.7235536 0.1586591 0.6425064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3535 3536 -0.044901 0.057662 -0.205743 0.4392208 -0.6486550 -0.2944555 0.5473826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3536 3537 0.206984 0.033480 -0.153848 0.1829756 0.4475072 -0.4486904 0.7516210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3537 3538 -0.027354 -0.153056 -0.068893 0.5480791 -0.6089402 -0.5091308 0.2637933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3538 3539 0.064976 0.029055 -0.022247 -0.8837465 -0.2505864 0.2678572 0.2906048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3539 3540 -0.016093 0.163183 -0.197954 0.2836996 0.6804157 0.1702457 0.6538849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3540 3541 0.167674 0.051616 0.033098 0.2449105 -0.2189646 0.6583175 0.6772676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3541 3542 0.154460 0.058029 0.116333 -0.3879533 0.7128349 0.5230146 0.2604121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3542 3543 0.054700 -0.049846 -0.066863 -0.6958991 -0.1509231 -0.6934975 0.1095806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3543 3544 0.113421 -0.041762 -0.027863 0.5221199 -0.1415400 0.7666861 0.3457595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3544 3545 -0.020604 0.021977 0.068331 0.1915144 -0.6459772 -0.0502645 0.7372307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3545 3546 -0.056407 -0.015241 -0.168683 0.3395857 0.9011401 -0.0346329 0.2672613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3546 3547 0.285881 0.056431 0.055366 -0.1641060 -0.6540434 -0.6512599 0.3480763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3547 3548 -0.129078 0.031763 0.049117 -0.2042995 0.1302473 0.9171531 0.3164294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3548 3549 -0.013459 -0.053597 -0.069924 0.1540150 -0.6121315 0.7584218 0.1623907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3549 3550 -0.029608 -0.154590 -0.061377 0.1520626 0.2046116 0.9624661 0.0931128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3550 3551 -0.066356 0.043112 -0.042298 -0.9562384 -0.1334620 0.1998680 0.1668794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3551 3552 0.126013 0.194719 -0.017232 0.8548696 0.1997391 0.1883842 0.4402426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3552 3553 -0.046214 -0.226010 -0.045104 -0.2662150 -0.5768768 0.6057756 0.4789349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3553 3554 0.031074 -0.128117 -0.110743 -0.3041777 0.2934830 0.8320455 0.3592268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3554 3555 0.105420 0.051841 -0.006160 0.5450643 0.8016495 -0.2265323 0.0945833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3555 3556 -0.037700 0.376960 -0.077265 0.9358559 0.0094745 -0.3391451 0.0952079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3556 3557 0.027561 0.108376 -0.196233 -0.1371942 -0.1856025 -0.8149705 0.5315568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3557 3558 -0.028644 -0.032594 -0.122825 0.1483977 -0.7616373 0.5447235 0.3180614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3558 3559 -0.061102 0.198319 -0.096211 -0.7676377 0.4514269 -0.3258275 0.3174628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3559 3560 0.010314 0.149378 -0.027536 0.4743089 -0.6091585 0.4869605 0.4084439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3560 3561 -0.070485 0.131619 0.216300 0.1819377 0.8584398 -0.4750188 0.0658554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3561 3562 0.003151 0.099493 -0.145884 0.1825894 -0.8545900 0.4290585 0.2285736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3562 3563 -0.004541 0.137592 -0.092388 0.1773106 0.0639323 0.9605215 0.2046268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3563 3564 0.066266 -0.008204 -0.055129 0.3703634 -0.7393381 -0.5056398 0.2460456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3564 3565 0.038220 0.026951 -0.046382 0.0254548 0.9514366 0.2607991 0.1615680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3565 3566 0.058651 0.021030 0.131678 -0.0308431 -0.4032628 -0.9072182 0.1156848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3566 3567 -0.089127 0.162562 -0.107795 0.6057221 0.0681185 0.7106148 0.3514075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3567 3568 0.137971 -0.044627 0.101003 -0.3696165 0.3644456 -0.5456915 0.6578632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3568 3569 0.008102 0.048765 0.061713 -0.1953233 0.1240550 0.9720686 0.0392661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3569 3570 -0.279320 -0.096346 0.201733 -0.0137404 0.2759759 -0.7715280 0.5730559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3570 3571 0.025532 0.045418 -0.116874 0.5843523 0.2662289 -0.6991197 0.3144619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3571 3572 0.015510 0.184629 0.005463 0.4030462 -0.6834292 0.2286924 0.5640727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3572 3573 -0.072629 -0.025172 -0.005598 -0.0365617 0.3305162 0.0770995 0.9399351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3573 3574 0.108149 0.050452 -0.078270 0.0480972 0.5775039 0.7879627 0.2080642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3574 3575 0.119535 0.047024 0.032988 -0.3222182 0.4951143 0.6232567 0.5124339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3575 3576 0.020284 0.140037 -0.055920 0.0503201 0.0383456 0.9870427 0.1474593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3576 3577 -0.014443 -0.016607 0.083489 -0.0439851 0.2708919 0.8641305 0.4218547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3577 3578 -0.077670 -0.013810 -0.046560 -0.2073627 0.2427308 0.9465965 0.0451386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3578 3579 0.037808 0.083742 -0.014719 -0.3036890 0.4896989 -0.2608339 0.7745539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3579 3580 0.042965 0.061481 0.138460 0.0617636 0.0012967 0.9838744 0.1678534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3580 3581 -0.086008 -0.094922 0.035931 -0.0802294 -0.5573951 -0.1826921 0.8059141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3581 3582 0.017497 -0.052127 -0.181368 0.8188860 0.2443621 0.5171167 0.0479918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3582 3583 0.076696 0.009320 0.067492 0.3678277 -0.3934456 0.7952467 0.2783633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3583 3584 -0.007825 0.022987 0.014160 0.5232195 -0.2591651 -0.5502034 0.5969515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3584 3585 0.198308 -0.007965 0.082623 -0.3646314 -0.0595381 -0.2399615 0.8977292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3585 3586 0.046534 -0.105048 -0.006730 0.3762560 -0.4745642 -0.7957240 0.0066016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3586 3587 0.058257 0.038869 0.041756 -0.4294470 -0.2933952 -0.5629492 0.6423260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3587 3588 0.085835 -0.171772 -0.135462 -0.3092332 0.1109465 0.9020152 0.2800612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3588 3589 -0.042216 0.094254 0.024974 0.6573414 -0.2185872 -0.7168442 0.0790971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3589 3590 0.072220 -0.165477 -0.047335 -0.1924726 -0.2075482 -0.1688569 0.9441215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3590 3591 0.043909 0.059170 0.044798 0.8448162 -0.3344139 -0.0129161 0.4174760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3591 3592 -0.017341 0.124801 0.007604 0.1146462 0.9700729 0.2018815 0.0711240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3592 3593 0.222034 0.046354 0.064814 -0.3290925 -0.0381240 -0.8833341 0.3316106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3593 3594 0.075454 -0.132402 0.011860 0.3246762 0.0808987 -0.4488588 0.8285931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3594 3595 0.077978 0.069507 0.182039 0.2913995 0.7508485 -0.0552433 0.5901364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3595 3596 0.010903 0.088955 -0.143357 -0.2301318 -0.3109993 -0.7874913 0.4797669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3596 3597 0.150425 -0.105465 0.061693 -0.2488660 0.3402237 -0.5733303 0.7025709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3597 3598 0.002304 0.001685 -0.014217 0.5627817 0.6818813 -0.0666512 0.4624633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3598 3599 -0.026234 -0.024875 0.168140 -0.1552899 0.5145113 0.7735211 0.3358993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3599 3600 0.027864 0.048758 0.086862 -0.3767801 -0.3651280 -0.5703649 0.6319827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3600 3601 0.040287 0.017420 -0.036107 0.0122651 0.8489995 0.0562810 0.5252445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3601 3602 -0.300977 0.146273 -0.124151 -0.3992388 0.1910872 0.3825830 0.8110021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3602 3603 0.067258 0.093352 -0.012044 -0.2212828 -0.0380580 -0.6580380 0.7187291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3603 3604 0.019551 0.136610 -0.014909 0.1320074 -0.4061517 0.9027494 0.0515588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3604 3605 0.012029 -0.055482 0.018341 0.5920711 -0.2481209 0.6339598 0.4312573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3605 3606 -0.102399 0.059692 -0.040163 0.0357569 0.3713960 0.9130871 0.1644942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3606 3607 -0.253898 0.093139 -0.087842 -0.2561784 0.4467924 0.7006653 0.4937786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3607 3608 0.052408 -0.014011 -0.161065 -0.6887472 -0.2837099 -0.0283996 0.6665804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3608 3609 0.131519 0.081914 -0.045750 0.5161728 -0.1612411 0.8356745 0.0959951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3609 3610 0.139291 0.096230 -0.050905 -0.1246064 -0.0999811 0.8437025 0.5124872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3610 3611 -0.006676 -0.022508 0.119473 0.5535375 -0.1772232 -0.1895030 0.7913765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3611 3612 -0.145311 0.108292 0.089282 -0.2141337 -0.3374136 -0.8892421 0.2225921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3612 3613 0.145568 0.079055 0.057482 0.5203522 -0.0860028 -0.6611801 0.5335522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3613 3614 -0.004906 0.085118 -0.034984 -0.3829071 -0.7331128 0.0349320 0.5609880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3614 3615 -0.081695 -0.023907 0.059020 0.7457520 -0.1189517 0.5555349 0.3479733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3615 3616 0.160855 -0.031587 0.023141 -0.6044639 0.6862513 -0.0599925 0.4001043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3616 3617 0.043046 0.125665 -0.055483 0.6354815 -0.4313731 0.6180217 0.1677190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3617 3618 0.189110 0.072338 -0.156404 0.6141018 0.0129828 0.7296823 0.3004567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3618 3619 0.076391 -0.021205 -0.092373 0.8484623 0.2602211 0.4595442 0.0348676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3619 3620 0.058703 0.152605 -0.096038 -0.7333524 0.4578545 -0.4745877 0.1653180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3620 3621 0.025782 -0.120507 0.182445 0.5986966 -0.5280626 0.3290132 0.5044429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3621 3622 -0.049450 0.061838 -0.084992 -0.2779298 -0.2552015 -0.9005117 0.2161156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3622 3623 0.070637 0.271568 0.177020 -0.4736475 0.5975301 -0.5834605 0.2796240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3623 3624 0.103268 0.060358 -0.150489 0.8844726 0.0580077 -0.2576786 0.3846362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3624 3625 0.121613 -0.037986 0.077749 -0.1866660 -0.3070603 0.9067372 0.2206748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3625 3626 0.066719 0.204856 0.052043 0.5205043 -0.5098029 -0.0969402 0.6780700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3626 3627 0.238520 0.231174 0.101362 0.1723987 0.7872808 -0.0567892 0.5892730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3627 3628 -0.092914 0.242080 -0.023466 -0.1426090 -0.4054070 0.0435478 0.9018932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3628 3629 -0.058150 -0.003963 -0.259383 -0.5976911 -0.1102601 -0.7868752 0.1069369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3629 3630 0.057218 -0.087159 0.119474 0.3494539 0.1142498 0.0831796 0.9262344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3630 3631 0.069199 -0.105545 0.074458 -0.6917478 0.0187933 0.3996632 0.6011665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3631 3632 0.078802 0.216551 0.009035 0.4556164 0.7458473 -0.3701408 0.3148353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3632 3633 -0.142901 0.028639 -0.082355 -0.2213238 -0.3790006 0.3926280 0.8082188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3633 3634 -0.008099 0.141608 -0.107173 0.0907873 -0.4005126 0.9036412 0.1215723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3634 3635 0.144998 0.131931 0.213718 0.6303269 -0.3462701 0.2673833 0.6413199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3635 3636 0.056686 0.214495 -0.074951 -0.3669120 0.0100609 0.8957559 0.2507903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3636 3637 0.156750 0.090762 -0.144913 -0.1353338 0.1850022 -0.8931447 0.3869773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3637 3638 -0.140861 0.154189 0.001866 -0.7951312 0.5270478 -0.2956785 0.0506080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3638 3639 -0.023759 -0.064255 -0.105558 -0.0320772 -0.0779529 0.9889724 0.1217702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3639 3640 -0.115786 0.060696 -0.197476 -0.0410224 -0.7598510 -0.2407249 0.6024907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3640 3641 -0.154710 0.025137 0.121642 -0.4189764 0.4275607 -0.5942714 0.5371147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3641 3642 -0.035700 0.309014 0.088524 -0.4901659 -0.2493822 0.7882457 0.2760698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3642 3643 0.240676 -0.128958 -0.058710 -0.3070970 0.5610038 0.3989246 0.6571342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3643 3644 -0.123437 -0.071163 0.166765 0.1506408 0.9188773 0.2969066 0.2117035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3644 3645 -0.017323 0.082385 0.061572 0.3997872 0.4280721 0.2477031 0.7717303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3645 3646 -0.000186 -0.075029 0.044379 0.5204736 0.4062056 0.7358255 0.1505493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3646 3647 0.024312 -0.030767 -0.114931 0.3381443 -0.2325917 0.5577352 0.7214506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3647 3648 0.070963 0.059267 0.049806 -0.2700622 0.4608365 0.6929655 0.4842467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3648 3649 0.063204 -0.047181 0.055291 -0.3510327 -0.5680534 0.3545948 0.6544875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3649 3650 0.044173 0.067230 -0.127739 0.3153513 -0.2897269 0.7794260 0.4572821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3650 3651 -0.278584 0.144549 0.028442 -0.4812503 0.4459322 -0.2179469 0.7225246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3651 3652 0.240532 0.070838 0.046274 -0.1838815 0.3713732 -0.9056478 0.0898420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3652 3653 -0.267875 -0.070675 -0.187164 0.3226455 -0.2162678 0.7961393 0.4639938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3653 3654 0.139768 -0.034889 0.173784 -0.1788186 -0.1652209 -0.0444546 0.9688910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3654 3655 0.027454 0.057660 -0.118863 0.2136606 -0.4887334 0.7282461 0.4302865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3655 3656 0.143361 0.032406 0.009989 -0.0763422 0.0905089 0.9710819 0.2073162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3656 3657 0.171192 -0.031700 -0.156636 -0.6608065 0.3307657 0.0842847 0.6684496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3657 3658 0.109164 0.060267 0.116480 0.0303229 0.2262018 -0.3241646 0.9180580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3658 3659 -0.161307 0.004275 0.022165 -0.5801188 -0.5216473 0.5642305 0.2701669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3659 3660 -0.008533 -0.013974 -0.136333 0.0268554 -0.0112893 -0.7497220 0.6611114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3660 3661 -0.050587 -0.031668 -0.001494 0.8424131 -0.3666791 0.0914949 0.3840772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3661 3662 -0.069567 0.022322 -0.052141 -0.1843572 0.0414697 -0.3600540 0.9135939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3662 3663 -0.131609 0.100106 -0.035103 -0.2725390 -0.4415570 -0.7627077 0.3860399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3663 3664 -0.077166 0.120139 0.065856 -0.0144091 -0.3307771 0.5052259 0.7969477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3664 3665 0.044102 0.027864 0.034001 -0.2874009 0.1667739 -0.7513608 0.5701264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3665 3666 -0.092070 0.020218 -0.255824 -0.1262060 0.2442400 0.6463597 0.7117851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3666 3667 0.006675 0.097998 0.025899 -0.4573823 0.4889261 -0.5084177 0.5415387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3667 3668 -0.120982 -0.021280 -0.104866 0.1456095 0.4769914 -0.2526095 0.8291354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3668 3669 0.075496 0.016581 -0.135463 0.6599148 0.0862372 0.7421711 0.0791051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3669 3670 0.093708 -0.030962 0.008527 -0.1416602 -0.1181793 -0.6302929 0.7541199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3670 3671 0.074052 -0.019717 0.149029 -0.0344681 0.1037330 -0.1295627 0.9855277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3671 3672 -0.074162 -0.118013 -0.039525 -0.2863176 -0.5791153 0.1049605 0.7560629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3672 3673 0.101168 -0.256249 0.043381 0.0286861 -0.3943428 -0.8672306 0.3026252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3673 3674 0.028511 -0.033960 0.086375 -0.1637867 -0.3561022 -0.8970993 0.2039071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3674 3675 -0.006193 0.105035 -0.059455 0.4064664 0.4934044 0.6940011 0.3312093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3675 3676 -0.108592 -0.217633 -0.041940 -0.1170151 0.9701450 0.1824136 0.1088645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3676 3677 0.212274 -0.020159 -0.133119 -0.2187540 -0.0234829 -0.4564180 0.8621356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3677 3678 0.003666 0.143911 0.149200 -0.4763351 0.1737899 0.3237677 0.7987969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3678 3679 0.046964 -0.063921 0.068622 0.8702892 -0.4163227 -0.2630619 0.0083968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3679 3680 -0.003222 0.076380 0.082815 -0.0200098 -0.2817943 -0.6911255 0.6652346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3680 3681 -0.173373 0.043211 -0.060421 -0.3298313 -0.5700276 0.7056321 0.2614635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3681 3682 0.014721 -0.000721 0.099668 -0.1926214 -0.4846118 0.8431708 0.1308103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3682 3683 -0.007224 -0.055238 -0.019035 0.5569056 -0.0079671 -0.7771188 0.2930514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3683 3684 -0.025108 -0.016175 0.155449 -0.4524724 0.6782082 0.5746704 0.0711081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3684 3685 -0.141672 0.018989 0.167633 -0.0927300 -0.3793429 0.8339857 0.3898307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3685 3686 0.042326 0.138304 -0.031107 -0.1977187 0.4281080 -0.6917385 0.5469265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3686 3687 -0.142310 -0.116160 0.179613 -0.2233704 -0.0709542 -0.8088420 0.5393012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3687 3688 0.083986 -0.101951 0.046663 -0.2895974 0.0831298 -0.8886230 0.3457918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3688 3689 -0.187661 0.131915 0.138657 -0.0123139 -0.3412383 -0.9388581 0.0441616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3689 3690 0.019274 -0.032492 0.007860 -0.6283467 0.2994704 -0.0306621 0.7173268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3690 3691 -0.093974 0.048666 0.225940 0.6959601 0.0155648 -0.3437118 0.6302853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3691 3692 -0.052178 -0.029722 0.130170 -0.1361338 -0.3492272 0.0323325 0.9265326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3692 3693 -0.027426 0.019224 0.147652 -0.5268596 -0.1140660 0.6908189 0.4818476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3693 3694 -0.147625 0.102812 0.167731 0.2995307 0.1474547 -0.5948809 0.7312012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3694 3695 0.084278 -0.075420 0.134189 -0.3938471 -0.0408918 0.7194227 0.5706516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3695 3696 -0.150248 -0.104279 0.038059 -0.1118017 0.1700876 -0.5918419 0.7799319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3696 3697 -0.109820 0.021573 -0.047965 0.4864177 -0.2287388 -0.1119951 0.8357831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3697 3698 0.058511 -0.053013 0.062236 -0.6705734 0.2534456 -0.6271226 0.3046538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3698 3699 0.050027 0.049243 -0.071598 0.7329557 0.1693355 0.3842146 0.5352388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3699 3700 0.095175 0.079949 0.061991 -0.6337104 -0.4802629 -0.5841466 0.1628847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3700 3701 0.037487 -0.001527 -0.059030 -0.2090258 -0.0255904 -0.9751172 0.0692805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3701 3702 -0.102508 0.011307 -0.119265 -0.2283225 -0.4986007 0.4553277 0.7013863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3702 3703 0.145167 -0.145806 0.086950 0.0825456 -0.2365326 -0.1818034 0.9508870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3703 3704 0.136338 0.148030 0.038924 0.1062495 -0.4312213 -0.8928349 0.0748673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3704 3705 -0.054191 -0.014101 0.053659 -0.6539224 0.0318174 0.5274493 0.5414522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3705 3706 0.005400 0.068320 -0.062522 -0.6210577 0.2115976 0.3238227 0.6816544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3706 3707 -0.026398 0.162348 -0.027267 0.4836697 -0.2137347 0.5989058 0.6014091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3707 3708 0.076130 0.182343 -0.001224 -0.1078486 -0.7103847 -0.5030817 0.4802406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3708 3709 -0.120563 0.108705 -0.033676 -0.6146131 -0.2466227 -0.4985513 0.5593519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3709 3710 -0.035934 -0.157679 -0.124426 0.3220583 0.4191715 -0.4404515 0.7256557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3710 3711 0.017748 0.058139 -0.030031 -0.7501647 -0.3387208 0.1578418 0.5455338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3711 3712 -0.166032 -0.119990 -0.052224 0.0760914 0.5942444 -0.5236033 0.6057419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3712 3713 0.141322 0.102815 -0.063449 -0.4962764 -0.4102690 -0.7569153 0.1116618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3713 3714 0.021676 0.033505 0.069946 0.2926421 0.2159695 0.6825250 0.6339380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3714 3715 0.110429 0.041317 -0.155406 0.6985333 0.3698125 -0.2817943 0.5439503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3715 3716 0.087464 0.085402 0.004459 0.2082576 0.0074214 -0.9735163 0.0940198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3716 3717 0.069878 -0.130715 0.044931 0.5646075 -0.5520309 0.3205160 0.5232110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3717 3718 -0.128581 0.053921 -0.070918 -0.1795944 0.6315096 -0.3959826 0.6419807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3718 3719 0.089692 -0.014386 -0.084221 -0.4185518 0.1044787 0.5487809 0.7160573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3719 3720 -0.023656 0.171378 -0.074214 -0.5188711 -0.0576170 0.8451712 0.1146241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3720 3721 -0.112552 0.012628 0.180390 0.1338722 0.5356282 -0.6771622 0.4864484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3721 3722 -0.017277 0.013011 0.028846 -0.6444022 -0.5075328 0.4521190 0.3503493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3722 3723 0.117564 -0.047579 0.018449 -0.1693603 -0.5730162 -0.0889395 0.7969061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3723 3724 0.011380 -0.106816 -0.020608 0.3286545 -0.1631211 0.1339317 0.9205651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3724 3725 0.092116 -0.154168 0.007416 0.1213490 0.1997314 0.4701967 0.8510563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3725 3726 -0.154572 0.091759 -0.183907 -0.6508059 -0.3387022 -0.3566973 0.5783594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3726 3727 0.004503 -0.007095 0.089045 0.6050397 -0.0924776 0.6649779 0.4279943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3727 3728 0.177172 0.064755 -0.097583 0.1009542 -0.3949018 0.6822159 0.6069945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3728 3729 0.069707 0.008915 -0.022826 -0.1505446 0.7215161 0.3513009 0.5773547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3729 3730 -0.023293 0.147570 0.007077 0.0950910 0.6789341 -0.6725433 0.2787323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3730 3731 0.028212 -0.051432 0.011306 0.9274231 0.1795864 -0.2335882 0.2303729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3731 3732 -0.233030 0.034464 -0.012059 -0.3554584 0.0320042 -0.7939929 0.4921385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3732 3733 0.203272 -0.127871 -0.005877 0.0191935 0.0642402 0.4922740 0.8678543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3733 3734 -0.219405 0.016556 -0.095132 -0.1879437 -0.5570200 0.6280447 0.5098683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3734 3735 0.053250 0.001683 -0.103938 0.1281857 0.4016764 -0.2505378 0.8714673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3735 3736 -0.083435 0.016607 -0.035982 0.1039976 -0.5862847 -0.7645136 0.2469285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3736 3737 -0.010594 -0.089465 -0.027256 -0.1670283 0.1535058 0.5266720 0.8192400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3737 3738 -0.047913 -0.044595 -0.267013 -0.0648548 0.0761515 0.7968820 0.5957968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3738 3739 0.176728 -0.054444 -0.122636 0.0377645 -0.0850603 0.9821901 0.1632211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3739 3740 0.085139 0.150416 -0.082579 -0.2644825 -0.4938238 -0.6375629 0.5288673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3740 3741 0.075325 -0.078556 -0.129461 -0.8891703 0.0127396 -0.4414668 0.1196703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3741 3742 -0.071034 0.017093 0.104146 -0.4414448 0.2363423 0.0957200 0.8602944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3742 3743 -0.007858 -0.026210 0.045951 0.2550136 0.6869569 0.4499953 0.5104533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3743 3744 0.157574 -0.003693 0.089506 -0.0528676 -0.3196671 0.4093750 0.8528951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3744 3745 -0.041696 -0.061102 -0.002030 0.0241792 -0.3141273 0.4073742 0.8571964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3745 3746 0.048845 0.040533 0.078597 -0.4782888 -0.2980989 0.8256587 0.0257799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3746 3747 0.092802 0.140590 0.092615 0.3926268 0.6810231 -0.6164710 0.0448910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3747 3748 -0.078402 0.077972 -0.020346 0.1194846 -0.6678000 0.4631335 0.5703279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3748 3749 0.160392 0.087492 -0.080889 0.4866909 -0.6219146 0.6113566 0.0509642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3749 3750 -0.021633 0.062919 -0.027585 0.3851661 0.2833981 -0.8287535 0.2906892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3750 3751 0.094331 0.072522 -0.302905 -0.0116799 -0.4629388 -0.6583630 0.5933881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3751 3752 -0.079557 0.014781 -0.017307 0.1624855 0.2054146 0.8922621 0.3677929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3752 3753 0.096281 0.021513 -0.178858 -0.4916655 -0.5616035 -0.3228833 0.5819046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3753 3754 -0.109401 -0.110224 -0.027626 -0.1468225 0.3595292 -0.7570866 0.5253587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3754 3755 -0.143318 -0.065436 -0.206955 0.4205250 0.5848534 0.3500861 0.5987862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3755 3756 -0.012082 0.063813 0.145430 -0.1092089 -0.9340755 -0.1422425 0.3087773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3756 3757 -0.055172 -0.070663 -0.078985 -0.5189445 -0.7375621 -0.3445231 0.2607731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3757 3758 0.144552 0.020237 0.002415 0.7318728 0.5268515 0.4114995 0.1321281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3758 3759 -0.096839 0.072947 -0.231042 -0.3702941 0.0660398 0.7376665 0.5606863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3759 3760 0.089003 0.121252 0.025628 -0.1164606 0.9117981 -0.2532720 0.3015203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3760 3761 0.106898 0.040206 0.082112 0.7811478 0.3343956 -0.5190610 0.0925383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3761 3762 -0.079678 -0.131565 0.074369 -0.6725708 0.0568276 0.3453952 0.6520133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3762 3763 -0.015463 -0.020929 0.023381 0.1954451 0.2752337 -0.5516095 0.7627415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3763 3764 -0.081481 -0.017276 0.003385 0.2961508 0.2095964 -0.5549242 0.7486142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3764 3765 0.010361 -0.058087 -0.115099 0.3210767 -0.4338345 0.0389136 0.8409418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3765 3766 -0.014126 -0.154340 -0.175131 0.0662650 -0.5680078 0.7434114 0.3468653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3766 3767 0.094917 -0.001684 -0.041953 0.0311341 0.2365486 -0.8697815 0.4319208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3767 3768 0.026849 -0.007894 0.030993 -0.4239490 -0.2389640 -0.7221138 0.4916452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3768 3769 -0.010622 0.032991 -0.044545 0.1155006 -0.4689264 -0.8691003 0.1069217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3769 3770 -0.146622 0.044489 -0.105001 0.0572478 -0.3990545 0.4033972 0.8214310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3770 3771 -0.223249 -0.254656 0.096142 0.3737784 -0.1209232 0.6763045 0.6231208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3771 3772 0.165760 -0.022945 -0.018702 0.6047104 0.0561481 -0.4300508 0.6680037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3772 3773 0.040688 0.159693 -0.161449 -0.3318463 -0.8443562 -0.4199738 0.0237217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3773 3774 0.306217 -0.040871 0.134837 -0.2104067 0.1944938 0.9381254 0.1944787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3774 3775 0.010784 0.096003 0.039439 0.7042698 -0.0164811 0.6700892 0.2339078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3775 3776 -0.091216 0.086076 0.038150 0.1292317 0.7549016 0.0392530 0.6417803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3776 3777 0.032780 0.102716 0.149022 -0.5226919 -0.1094682 0.8123222 0.2343981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3777 3778 -0.140629 0.139604 0.125165 0.7014638 -0.3625175 0.6033731 0.1116713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3778 3779 0.018802 -0.007171 -0.017797 -0.6839459 -0.0349499 0.6056869 0.4051419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3779 3780 -0.041052 0.088724 0.067756 0.0007792 0.1670041 -0.9238874 0.3442979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3780 3781 0.096700 -0.006315 0.206948 0.0619547 -0.7558654 -0.6246682 0.1860611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3781 3782 -0.060002 0.102049 -0.030268 0.1793173 -0.6574476 -0.0173736 0.7316462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3782 3783 -0.132977 0.022623 -0.018938 0.5158889 -0.2854363 -0.8068003 0.0381840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3783 3784 0.056468 -0.095293 0.019793 -0.0002380 -0.5106951 0.8445075 0.1612379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3784 3785 -0.191028 -0.017366 -0.210053 -0.2668185 0.5619443 -0.7801189 0.0666401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3785 3786 -0.008927 -0.000335 0.150158 0.5139454 -0.6458507 0.2666564 0.4976258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3786 3787 0.096885 -0.048001 0.164689 0.2187006 -0.2194936 -0.2617126 0.9140564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3787 3788 0.142846 -0.007999 0.107269 -0.0959072 -0.2481114 -0.0692123 0.9614844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3788 3789 -0.007925 -0.013517 0.088962 -0.0214720 0.5518555 0.7928860 0.2575388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3789 3790 0.020856 -0.155704 0.130034 0.6079989 0.0274119 -0.1573643 0.7777033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3790 3791 0.113906 0.060984 0.077754 0.0207711 -0.1530421 -0.5359939 0.8299742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3791 3792 -0.158304 0.132810 0.120455 -0.0391434 -0.6198623 -0.6809542 0.3879947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3792 3793 0.165978 0.054947 0.048701 0.0181979 0.6288409 0.5642786 0.5346192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3793 3794 -0.161033 0.171814 0.013016 -0.0507110 0.2822541 -0.9512473 0.1135319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3794 3795 0.163541 -0.100054 0.028916 0.6324837 0.1023585 -0.5048841 0.5784282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3795 3796 0.107687 0.051157 0.109783 -0.0194783 0.0641181 0.0861962 0.9940220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3796 3797 0.076480 0.119130 0.069473 -0.6158467 0.2311887 -0.2602753 0.7067824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3797 3798 0.117125 0.152968 0.082445 0.6372588 -0.3262215 -0.1796708 0.6746845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3798 3799 -0.039885 0.053001 0.031459 -0.1212119 -0.0907341 0.9872374 0.0493692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3799 3800 -0.042717 -0.084925 0.057446 0.7692685 0.3742315 0.0219327 0.5173932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3800 3801 0.082206 0.075412 0.164610 0.1509301 0.6419749 0.7233705 0.2045079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3801 3802 0.229419 0.060731 0.076781 0.0318468 0.8335102 -0.0426780 0.5499319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3802 3803 -0.152759 0.100675 0.171956 -0.5239920 0.7133343 0.2001962 0.4201285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3803 3804 0.079469 0.192503 -0.109823 -0.3323750 -0.1703226 -0.5233414 0.7659183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3804 3805 -0.150827 -0.079747 0.219950 0.4918440 -0.1805338 -0.2708439 0.8075522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3805 3806 0.103824 -0.076429 -0.051740 -0.2878510 0.1256244 0.7714304 0.5534035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3806 3807 -0.032507 0.011727 0.016584 0.5384686 -0.3732013 -0.7051525 0.2711684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3807 3808 0.115883 -0.029762 0.141612 0.0908978 -0.8418716 0.1667231 0.5051664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3808 3809 0.145394 0.117433 0.053613 0.0136395 0.6114050 -0.0957019 0.7853910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3809 3810 0.050992 0.032962 0.083968 0.4525689 -0.7689814 -0.4223847 0.1594998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3810 3811 -0.071806 -0.098113 -0.012643 -0.0683854 0.3194262 0.9066212 0.2670738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3811 3812 0.145863 -0.029332 -0.114081 0.0411866 -0.1655977 -0.5350398 0.8274137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3812 3813 0.199313 -0.126476 -0.031817 -0.2211721 -0.6773603 -0.4939831 0.4982435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3813 3814 -0.234119 -0.025813 -0.098628 0.3382037 -0.4768927 -0.7992666 0.1391563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3814 3815 -0.043680 0.052638 0.135512 0.4697688 -0.4032097 -0.5521153 0.5584872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3815 3816 -0.166993 0.250059 -0.024581 -0.0502808 -0.7590522 -0.0266387 0.6485384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3816 3817 -0.052520 0.128511 0.168500 -0.6999933 0.6726951 -0.0998887 0.2179746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3817 3818 -0.258316 0.012793 -0.091553 0.6006755 0.7488267 -0.1662544 0.2254040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3818 3819 0.066184 -0.236772 -0.000217 0.2819900 -0.3932910 -0.8571735 0.1762312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3819 3820 0.142907 0.088680 0.020179 0.1619793 0.4509570 0.1751449 0.8600725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3820 3821 0.027905 -0.063674 -0.062311 0.1854838 0.0098319 0.5475882 0.8158715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3821 3822 0.102321 0.022575 -0.118130 -0.0065052 -0.3545219 0.9336545 0.0506084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3822 3823 -0.075102 0.112766 0.150185 0.5265831 -0.6711565 -0.4641434 0.2383906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3823 3824 -0.135588 -0.051328 -0.080898 -0.2630438 0.1951361 0.1801723 0.9275062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3824 3825 -0.027326 0.147101 0.108468 -0.6433889 0.4968277 0.2655172 0.5183759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3825 3826 0.033269 0.120205 0.190208 -0.3870533 -0.0998036 0.9067174 0.1345087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3826 3827 0.206976 0.075165 -0.000020 -0.4029702 0.6831772 0.5939306 0.1346492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3827 3828 0.101982 -0.177911 -0.150644 -0.5434947 -0.4636948 -0.5435660 0.4406095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3828 3829 -0.012178 -0.030658 0.070092 0.6105246 -0.7408861 0.0818366 0.2676756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3829 3830 0.123738 -0.031046 0.154609 -0.0592780 0.4951933 -0.3299701 0.8014920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3830 3831 -0.207058 0.057182 0.069757 -0.1356467 0.4279709 -0.8776119 0.1680421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3831 3832 0.078996 -0.036936 -0.017461 -0.3007255 -0.1794769 -0.5046454 0.7891041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3832 3833 0.024843 -0.060482 -0.069629 -0.6531761 0.2007097 -0.7029284 0.1974041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3833 3834 -0.103273 0.006178 0.059355 -0.1605640 0.6122213 -0.6915481 0.3480883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3834 3835 0.053015 0.213023 -0.126766 0.0471681 -0.6342089 0.5054037 0.5831992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3835 3836 -0.214889 -0.135097 -0.010691 -0.0340347 -0.0791991 -0.7647530 0.6385311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3836 3837 0.019155 -0.064256 0.013882 -0.3924059 -0.1778827 0.8105223 0.3967731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3837 3838 0.175556 0.101681 0.107776 0.0905150 -0.1434568 0.9344146 0.3132036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3838 3839 -0.002050 -0.197639 -0.191695 0.1016869 0.4341240 -0.1206270 0.8869303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3839 3840 0.115825 0.014857 0.261139 0.0522836 -0.3162848 0.6582983 0.6810827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3840 3841 -0.096837 0.048144 -0.059124 0.0570534 0.1400840 0.7299052 0.6666032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3841 3842 -0.119716 0.123231 -0.115756 0.3001035 -0.6302808 0.2654664 0.6649899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3842 3843 0.034927 0.044663 0.130267 -0.2406625 -0.0932564 -0.9611005 0.0983397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3843 3844 0.041122 -0.033508 -0.047071 -0.9470309 -0.1564376 0.2232601 0.1697492 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3844 3845 0.122358 -0.043339 0.004535 0.2219976 0.4951848 0.2590949 0.7989862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3845 3846 0.079638 0.085316 -0.033286 0.5128159 0.5382964 -0.5907680 0.3134485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3846 3847 0.062047 0.118108 -0.087992 -0.0019862 0.1023679 0.7111247 0.6955707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3847 3848 0.222361 -0.266883 -0.144977 0.5510818 -0.4671760 -0.6505635 0.2341424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3848 3849 0.070260 -0.091156 0.080816 -0.6397099 -0.3143476 -0.4018537 0.5748656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3849 3850 -0.140760 0.059354 0.012831 0.3767619 0.0391111 -0.2236149 0.8980630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3850 3851 0.229303 0.199458 -0.009268 -0.7480578 -0.0182149 -0.6407797 0.1716951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3851 3852 -0.134037 -0.020189 0.113251 0.5586074 0.1335818 0.0812509 0.8145624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3852 3853 0.021662 -0.037862 -0.094749 -0.2758228 0.4208937 -0.5387831 0.6756352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3853 3854 -0.042235 0.024567 0.080080 -0.1385750 0.2502042 0.0891021 0.9540732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3854 3855 -0.130402 0.063534 -0.074548 -0.2982827 -0.2703446 -0.0680173 0.9128608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3855 3856 0.088712 0.132627 -0.052838 0.3661617 -0.0914105 0.2743487 0.8844787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3856 3857 -0.028296 0.090641 -0.055390 -0.0470612 -0.7156027 -0.2321329 0.6571243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3857 3858 -0.136152 0.006947 -0.109634 -0.3595179 0.7978904 0.0517631 0.4810804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3858 3859 0.072141 -0.038802 -0.111363 0.2744250 0.0223433 0.6090753 0.7437869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3859 3860 -0.025615 -0.077653 -0.085816 -0.8863388 -0.2780457 0.0665736 0.3642280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3860 3861 0.025938 0.104111 0.175140 -0.0002018 -0.5322350 0.4936823 0.6877526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3861 3862 -0.019794 -0.091012 0.068161 0.7849562 -0.2442649 -0.3769373 0.4267279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3862 3863 0.350434 -0.034003 -0.103126 0.1662951 0.5937792 0.1543526 0.7719764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3863 3864 -0.006471 0.002468 0.109196 -0.3190449 0.9389704 0.1204567 0.0451129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3864 3865 -0.061449 -0.069989 0.177669 0.5035070 -0.4297734 -0.7193138 0.2106257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3865 3866 0.120042 0.153671 -0.170318 0.3486674 -0.0423884 -0.9102058 0.2194532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3866 3867 -0.132027 0.031884 -0.236543 -0.2983283 -0.1193561 0.8800981 0.3495449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3867 3868 -0.021323 -0.084677 0.203168 -0.6170772 -0.0693418 -0.5882379 0.5180576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3868 3869 -0.147875 -0.090159 0.116451 0.1345623 0.6524696 0.0075243 0.7457344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3869 3870 0.201432 0.047674 -0.172533 0.3031023 0.5232133 0.5230543 0.6006589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3870 3871 0.054722 -0.046077 -0.173270 0.3924167 -0.3793893 -0.0956516 0.8324204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3871 3872 -0.096701 -0.003767 -0.088318 -0.7757964 -0.5777138 0.2333519 0.0996674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3872 3873 0.021220 0.167697 0.078580 0.6235160 0.1247660 0.5498619 0.5415840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3873 3874 0.189048 0.080111 0.061105 0.4293333 -0.2804081 0.8578214 0.0344496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3874 3875 -0.040719 -0.005684 -0.006493 -0.1168599 0.4976156 -0.8402495 0.1808403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3875 3876 0.156758 0.163509 -0.027342 -0.1189209 -0.0618179 0.1510993 0.9793903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3876 3877 0.126679 -0.125702 0.014975 0.2382257 -0.6554991 -0.0922571 0.7106744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3877 3878 -0.017426 -0.160833 -0.019325 -0.2275812 -0.6080114 -0.5256876 0.5497104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3878 3879 0.032958 0.071947 0.057929 0.3125481 -0.4410773 -0.8394461 0.0556306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3879 3880 0.193974 -0.082547 0.135344 -0.3736670 -0.4939891 -0.0857772 0.7803781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3880 3881 0.098846 0.037348 -0.062252 -0.2468623 0.5175238 -0.6496717 0.4991540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3881 3882 0.201935 -0.084173 0.107021 -0.5895124 0.0158317 -0.7538417 0.2897364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3882 3883 0.091364 -0.022311 0.023303 -0.2628109 0.7659497 0.0175301 0.5864675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3883 3884 -0.182841 -0.056579 -0.120401 -0.3876972 -0.3916581 0.6644260 0.5048098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3884 3885 -0.131980 -0.090286 0.056190 -0.5727739 -0.1628478 -0.4552125 0.6619609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3885 3886 0.062531 -0.197577 0.066103 0.2147256 0.5977284 -0.3998384 0.6608653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3886 3887 0.021092 -0.029237 0.097584 0.6619518 0.1047758 -0.3513544 0.6537522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3887 3888 0.051321 0.052677 -0.057526 -0.3408300 0.7586682 0.3595279 0.4230806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3888 3889 -0.046110 0.124943 0.082498 0.2757385 -0.3747565 -0.8436604 0.2678861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3889 3890 0.137304 -0.035017 0.024479 -0.1235813 -0.0931661 0.0497528 0.9866977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3890 3891 -0.098579 -0.134296 0.133867 -0.5270820 -0.6619065 0.4537055 0.2796706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3891 3892 -0.065978 0.122048 -0.104167 0.3142276 0.6774298 -0.6398067 0.1816515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3892 3893 -0.076054 0.041982 0.065884 -0.5414717 -0.1719811 0.7623750 0.3098633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3893 3894 -0.045240 -0.041523 0.087473 -0.5372914 -0.2170964 0.6941532 0.4270112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3894 3895 0.009887 -0.126459 0.077246 0.1137515 0.3739763 -0.8986171 0.1992226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3895 3896 -0.107076 0.006877 -0.199846 -0.1456992 0.6276120 -0.7042554 0.2981598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3896 3897 -0.034575 -0.149976 0.040651 -0.3492616 -0.0370282 -0.6738905 0.6500129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3897 3898 0.153548 -0.118840 -0.039996 0.7506115 0.3290429 0.3764051 0.4320096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3898 3899 0.036019 0.002425 0.007532 -0.2643140 0.0558226 0.9526065 0.1398670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3899 3900 -0.042470 -0.103074 0.074710 0.1623394 0.3428395 -0.9250316 0.0205785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3900 3901 0.048780 0.114412 0.084195 -0.4367031 0.4162466 -0.0986048 0.7913951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3901 3902 -0.021714 0.028505 -0.113170 0.0095226 -0.4245365 -0.8100384 0.4043711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3902 3903 0.019722 -0.008858 0.072699 0.7742448 0.1859563 0.5876366 0.1436956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3903 3904 -0.193151 -0.078800 0.051960 0.0190522 -0.1287329 0.9511837 0.2798470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3904 3905 0.032779 -0.161112 -0.110831 -0.3259175 0.0236568 0.5630206 0.7590954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3905 3906 -0.028384 0.084876 -0.021097 -0.4356871 -0.2859652 0.8534434 0.0059267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3906 3907 -0.053841 -0.016775 -0.057526 0.1382881 0.8155366 -0.5599094 0.0477281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3907 3908 0.029954 -0.093624 0.175322 0.6334001 0.6015839 -0.3199070 0.3668250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3908 3909 -0.101693 -0.138244 -0.121485 0.5970726 -0.0415673 0.1294727 0.7905778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3909 3910 0.096147 -0.022903 0.066179 -0.4207728 -0.4362663 -0.2758439 0.7460108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3910 3911 0.045558 0.041495 -0.087360 -0.2844647 -0.4687487 0.8354729 0.0366002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3911 3912 -0.017265 -0.094336 -0.068951 0.2153590 -0.3993312 0.4952836 0.7408436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3912 3913 -0.030358 0.067137 0.036153 0.0034074 0.1449451 -0.6129644 0.7766942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3913 3914 -0.023379 -0.011258 -0.042946 0.7446893 -0.3152748 -0.5046793 0.3022226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3914 3915 0.049499 -0.102768 -0.010422 0.8608948 -0.0577245 -0.5016219 0.0624777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3915 3916 -0.092058 -0.071338 -0.033591 0.1796414 -0.0915415 0.4356827 0.8772284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3916 3917 0.005275 -0.019147 0.086116 0.3479172 0.0760748 -0.6894579 0.6307250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3917 3918 0.009608 -0.201977 0.075672 0.2863573 -0.5390265 0.6941729 0.3815415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3918 3919 0.335318 -0.112257 0.096487 0.1717886 0.0627141 -0.4764358 0.8599794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3919 3920 0.097261 0.007005 0.030566 0.2292303 0.7410373 0.6085079 0.1674373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3920 3921 0.028419 0.198772 -0.001636 -0.3643706 0.6111882 0.4385896 0.5489283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3921 3922 -0.029836 0.042324 -0.004827 -0.3454710 -0.5485493 0.6167135 0.4465511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3922 3923 -0.023788 0.032914 -0.185460 0.6229934 -0.1964162 -0.3758981 0.6572675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3923 3924 0.015645 0.134193 -0.095298 -0.6767528 -0.3020926 -0.0064295 0.6713452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3924 3925 -0.139970 0.034014 -0.097712 0.2286843 0.1772061 0.4714895 0.8330661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3925 3926 0.070368 -0.014586 -0.084083 0.6436222 0.0061538 -0.6367093 0.4246338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3926 3927 0.018457 -0.042556 -0.031026 -0.5089578 -0.8108644 -0.1962467 0.2120099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3927 3928 0.175534 -0.131543 0.055090 -0.0209632 0.7132534 -0.2255729 0.6632850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3928 3929 -0.062119 0.214721 0.118215 0.1567999 -0.2336835 0.3918721 0.8759236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3929 3930 0.027773 -0.025963 0.189768 -0.5089563 -0.3465907 -0.7874775 0.0267864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3930 3931 0.063724 -0.191303 -0.080646 -0.8374142 0.1369824 0.1438837 0.5091863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3931 3932 0.090558 -0.093754 0.106186 0.2681674 0.8039742 -0.5264289 0.0677082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3932 3933 -0.097830 -0.055478 -0.020351 -0.1634445 0.0082131 0.2659066 0.9500064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3933 3934 0.114637 0.015840 -0.101212 -0.2376667 0.2150617 0.9312545 0.1732863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3934 3935 0.169023 -0.133195 -0.064557 -0.0992411 0.4412978 0.2191290 0.8645172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3935 3936 0.059207 0.046296 -0.163951 -0.0813266 -0.3161605 -0.9189480 0.2212761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3936 3937 -0.031476 -0.002847 -0.204625 -0.7407766 0.0919245 -0.2534767 0.6152638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3937 3938 0.002144 0.038851 0.022530 0.4123244 0.5710429 -0.6843843 0.1884586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3938 3939 -0.012140 -0.164642 -0.028379 -0.7309799 -0.3206758 -0.0540937 0.5999244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3939 3940 -0.162213 -0.037972 -0.022398 0.4823367 0.7012303 -0.3692413 0.3732132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3940 3941 0.177579 0.137785 -0.191522 -0.4457551 -0.2609371 0.8547166 0.0517083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3941 3942 -0.025058 -0.074398 0.089920 0.6641632 -0.4346402 0.1004612 0.5999022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3942 3943 -0.185451 0.055240 -0.044445 -0.6417062 0.5970255 0.4553021 0.1564405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3943 3944 0.219669 0.104698 0.019767 0.6234778 -0.4221974 0.6359919 0.1689351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3944 3945 -0.016512 -0.052545 0.031057 0.0351912 0.0535783 -0.9918124 0.1104498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3945 3946 0.028105 -0.076046 0.053885 0.6297471 -0.3501200 -0.3806479 0.5796049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3946 3947 -0.024959 -0.056060 -0.277522 0.6101813 0.2404542 0.1900302 0.7305813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3947 3948 -0.108566 -0.043079 -0.167442 0.3475950 0.6699396 0.3615965 0.5473634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3948 3949 -0.086913 0.095782 -0.091744 0.1837712 0.6817299 0.5025480 0.4989168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3949 3950 -0.054898 0.120785 -0.121123 0.1915206 -0.1446611 0.8576020 0.4548756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3950 3951 -0.153648 0.022674 -0.020071 0.6171650 0.6271371 0.4241708 0.2142091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3951 3952 -0.039994 -0.147982 -0.056958 -0.4968498 0.6822819 -0.0163378 0.5360642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3952 3953 -0.025526 0.075165 0.088169 -0.0480284 -0.0747769 0.1075456 0.9902200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3953 3954 -0.018307 0.043266 0.095364 0.4069671 0.2165603 -0.7944145 0.3954554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3954 3955 -0.031797 0.035781 -0.108700 -0.1908854 0.8144903 -0.5087643 0.2032911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3955 3956 0.117103 -0.020883 -0.007340 -0.0386942 0.8620787 0.2340762 0.4478074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3956 3957 0.065471 -0.008192 -0.126408 0.0559129 0.0339433 -0.6386512 0.7667113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3957 3958 -0.064900 0.076605 -0.061193 0.4856552 0.3812600 -0.2398540 0.7491661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3958 3959 -0.054628 -0.117552 0.026364 -0.0161990 0.4246024 0.4671008 0.7754142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3959 3960 -0.146411 -0.001457 -0.113042 -0.1878147 0.6598105 0.6321091 0.3602968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3960 3961 0.148702 -0.127877 0.010662 0.1833711 0.0264998 0.9727078 0.1396864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3961 3962 -0.035712 0.194355 0.116171 0.3373829 -0.0269136 -0.8495859 0.4045396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3962 3963 -0.067141 -0.242410 0.053967 -0.4300372 -0.8461826 -0.0262746 0.3136123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3963 3964 0.029669 0.103011 -0.002179 -0.7530189 0.3630558 -0.3871843 0.3888976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3964 3965 -0.135485 -0.018149 -0.093894 0.0388371 -0.0562785 -0.6591263 0.7489172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3965 3966 -0.071954 0.122043 -0.039723 0.6282284 0.4146948 -0.3293105 0.5700104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3966 3967 -0.086965 0.082081 -0.069120 0.1059192 -0.7049158 -0.2746352 0.6453296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3967 3968 -0.023501 0.056428 -0.018549 0.2518315 -0.2929902 -0.8634398 0.3243598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3968 3969 0.144460 -0.143319 -0.153054 -0.0812334 0.1249585 0.0561888 0.9872332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3969 3970 0.108334 0.158769 0.109636 0.4057619 -0.4186472 -0.4731725 0.6604541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3970 3971 -0.066381 -0.114223 0.120808 -0.5373681 -0.5861605 -0.0022277 0.6063385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3971 3972 -0.090105 -0.158048 0.053876 0.7062794 0.5886213 0.1101040 0.3775864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3972 3973 -0.478995 0.185662 0.010940 -0.0788109 0.1526117 0.7869086 0.5926832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3973 3974 0.072731 0.031880 0.138731 -0.3905385 -0.2014843 -0.2865235 0.8513448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3974 3975 0.087705 0.009446 -0.339821 -0.0720721 0.3344028 0.8754414 0.3414421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3975 3976 0.063024 0.095061 0.039467 -0.1431696 -0.4560147 0.8155390 0.3262655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3976 3977 0.075070 0.074478 0.027461 -0.2848547 0.4676549 0.2513651 0.7981054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3977 3978 0.024614 -0.023591 -0.125045 0.1045958 -0.3491820 0.1088670 0.9248133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3978 3979 0.151490 0.103362 0.012920 0.5943797 -0.2522301 -0.4491967 0.6175071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3979 3980 -0.035312 -0.032654 0.149843 0.0638691 -0.0837145 -0.9942059 0.0216177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3980 3981 -0.116115 0.050851 0.085176 0.4646707 -0.2054802 -0.5852112 0.6319707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3981 3982 0.126794 -0.014674 0.008573 -0.3262961 0.5715408 0.4968960 0.5656558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3982 3983 -0.203736 0.009527 -0.050290 -0.0364926 -0.8143099 0.3240964 0.4801345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3983 3984 -0.010714 -0.062568 0.207289 -0.0439827 0.7314981 -0.0400297 0.6792450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3984 3985 -0.054289 -0.057463 0.069196 0.2086674 -0.4864220 -0.6606204 0.5323836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3985 3986 -0.043763 0.062684 0.134762 -0.3495017 -0.1689508 -0.6707826 0.6319453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3986 3987 0.078619 0.092115 0.087758 -0.1770705 -0.1490773 0.0763770 0.9698394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3987 3988 -0.097611 -0.114282 0.108882 -0.1624895 0.3486583 0.6506045 0.6547887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3988 3989 -0.030909 0.053898 0.028255 -0.3836082 0.4849616 -0.7636887 0.1855711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3989 3990 0.100600 0.093941 -0.010540 0.0101282 -0.5081843 0.7714290 0.3828100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3990 3991 -0.155284 0.046149 -0.092958 -0.1394365 -0.1355671 0.5987698 0.7769516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3991 3992 -0.031926 0.184008 -0.082635 0.1538778 -0.9119041 -0.2006439 0.3232560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3992 3993 0.124728 0.024674 0.085520 -0.4356628 0.1473232 -0.4812117 0.7462768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3993 3994 -0.133895 0.002819 0.081323 0.6326641 0.1208209 -0.3630423 0.6733043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3994 3995 -0.086071 0.206087 0.015971 0.0930835 0.1257947 -0.9431953 0.2930764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3995 3996 -0.234657 -0.074435 -0.008119 0.9034254 0.0185731 -0.3437245 0.2555995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3996 3997 0.007368 0.210196 0.157173 -0.1249275 0.6121230 0.6238060 0.4696431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3997 3998 0.119054 0.252254 0.003856 0.2731526 0.2236053 -0.9270329 0.1264846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3998 3999 0.024036 0.007510 -0.104790 0.6076050 0.2362332 -0.1353086 0.7461244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3999 4000 0.009201 -0.126440 0.164330 0.4699009 -0.7170696 0.2107013 0.4696906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4000 4001 -0.036447 0.048704 -0.145929 -0.5275048 -0.4743713 -0.2692458 0.6513196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4001 4002 0.115614 0.115117 -0.145885 0.3951893 0.4189904 0.5267556 0.6251408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4002 4003 -0.039686 0.060101 -0.141022 -0.2629018 0.2401899 -0.4634294 0.8114337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4003 4004 0.032179 -0.055679 -0.034655 -0.3124214 -0.4361357 -0.6525881 0.5350769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4004 4005 0.034540 0.095483 -0.064618 -0.0198466 0.2768132 -0.9155788 0.2910258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4005 4006 -0.150398 -0.076536 0.272750 0.7526496 -0.3202511 -0.4608122 0.3443978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4006 4007 0.109262 0.069113 -0.087889 -0.0914410 -0.9626476 -0.0424597 0.2512874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4007 4008 -0.070097 0.143172 -0.068225 -0.6896915 -0.0994852 -0.6710782 0.2531451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4008 4009 -0.240164 0.058034 0.083066 0.0710547 -0.3285066 0.5061676 0.7942475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4009 4010 0.017815 -0.041590 0.151953 -0.2134574 0.3195793 -0.2353778 0.8926939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4010 4011 -0.097936 -0.012034 -0.119510 -0.3600503 -0.1198239 -0.4245931 0.8220260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4011 4012 0.098535 -0.112874 0.016184 0.3743015 0.0681929 -0.6318070 0.6753281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4012 4013 -0.092909 -0.246010 -0.003294 0.6073727 -0.4895198 -0.6109540 0.1349221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4013 4014 -0.066209 -0.099190 -0.147608 0.0611758 -0.7656921 -0.4113128 0.4907085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4014 4015 0.039659 -0.107146 -0.046290 -0.3911806 -0.0616716 -0.8767969 0.2727665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4015 4016 0.136045 0.172941 -0.151480 -0.4480107 0.1869193 0.7628500 0.4270920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4016 4017 -0.061662 -0.029773 0.065899 0.0355410 -0.6651588 0.7306291 0.1499391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4017 4018 0.097703 -0.095632 -0.041510 0.6980111 -0.1292054 0.3061156 0.6343341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4018 4019 0.093791 -0.166115 -0.082470 0.2327925 0.7760577 0.1857723 0.5559054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4019 4020 -0.026176 -0.026175 -0.034092 -0.6768222 0.0402564 0.5232969 0.5161893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4020 4021 0.149452 -0.068604 0.020007 -0.3451737 -0.5064603 0.4697283 0.6353805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4021 4022 -0.065478 -0.047012 -0.071962 0.3293459 0.5887856 -0.7375310 0.0301791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4022 4023 0.044337 0.063802 -0.053016 0.3094546 -0.5810035 0.0309690 0.7521394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4023 4024 -0.008741 -0.068556 -0.186307 -0.5562054 0.0655691 -0.7148574 0.4187065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4024 4025 0.043936 -0.021995 0.044757 0.3385632 0.3358422 -0.7910376 0.3832028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4025 4026 -0.113354 -0.135893 -0.047152 0.2617971 0.3573261 0.3062464 0.8426111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4026 4027 0.022487 -0.171931 0.072449 -0.8387734 -0.2579329 0.4600431 0.1352410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4027 4028 -0.053210 0.041857 0.138303 -0.0599708 -0.4803023 0.2918242 0.8249557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4028 4029 0.175666 -0.025416 -0.073968 0.8315667 0.1752439 -0.1324302 0.5101457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4029 4030 -0.117628 0.082572 -0.037085 -0.1138846 0.0374278 -0.1858305 0.9752418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4030 4031 -0.188634 0.019270 -0.126831 -0.1474234 -0.2461957 -0.8697569 0.4014686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4031 4032 -0.035988 -0.025504 -0.001440 0.3247802 0.4534554 -0.3202842 0.7657114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4032 4033 -0.066607 -0.179691 -0.007727 -0.0969620 0.0974782 0.9715081 0.1930501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4033 4034 0.073103 0.070668 -0.075086 -0.4689122 -0.1691728 -0.8099034 0.3091251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4034 4035 -0.057317 0.060162 0.007493 0.0451150 -0.2709905 0.3934955 0.8773198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4035 4036 0.011641 0.118244 0.154379 0.0473108 -0.5766052 0.3802110 0.7216146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4036 4037 0.012894 -0.128866 0.082173 -0.0360362 -0.6678691 0.4175904 0.6150370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4037 4038 0.069945 -0.041611 0.118890 0.8709909 -0.3162606 -0.0126570 0.3757577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4038 4039 -0.087218 -0.174444 -0.029326 -0.4886562 0.7358569 0.0620999 0.4646217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4039 4040 0.051571 -0.083612 0.106325 -0.2135524 0.1650136 -0.6246304 0.7328047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4040 4041 -0.165680 -0.155449 0.016210 0.8463868 -0.2700781 -0.0302176 0.4580111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4041 4042 0.145885 0.140260 -0.177198 -0.5732441 -0.2108860 0.4758215 0.6328604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4042 4043 0.018065 0.060901 -0.102593 -0.1886825 0.1076247 -0.9554937 0.1996186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4043 4044 -0.172527 0.176962 -0.030574 -0.4433050 0.4057414 0.7654563 0.2300678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4044 4045 0.079021 -0.041427 -0.187653 0.5683007 -0.2106008 0.0740611 0.7919575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4045 4046 0.153354 0.019131 -0.064564 -0.3166285 0.0756948 -0.4450679 0.8342250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4046 4047 0.044888 -0.052879 0.121245 -0.5731952 -0.0588249 0.7166622 0.3929149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4047 4048 -0.021697 -0.009741 -0.240046 -0.3500774 0.5652087 0.6733376 0.3234215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4048 4049 -0.063816 -0.107613 -0.030593 0.2248329 0.0381303 -0.8235601 0.5193699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4049 4050 0.026636 0.169835 -0.049638 0.7414753 -0.0869868 0.2699891 0.6080737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4050 4051 -0.085574 0.035875 -0.168791 -0.7512020 0.2083425 0.4911326 0.3886872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4051 4052 -0.104685 -0.120875 -0.062503 0.4854183 0.2467727 -0.7655068 0.3427413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4052 4053 -0.148790 0.170920 -0.044789 -0.1140475 0.1334337 0.3019845 0.9370133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4053 4054 -0.113159 0.159881 -0.000562 0.5744266 -0.0452361 -0.5785046 0.5773389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4054 4055 0.101047 0.139432 -0.015256 0.5342803 0.3532094 -0.6324965 0.4355868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4055 4056 0.104739 -0.028580 0.154985 -0.3321260 -0.2420186 0.8892673 0.2008056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4056 4057 0.113076 -0.128031 -0.137842 0.3407401 0.2883349 0.4735456 0.7592850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4057 4058 -0.065329 -0.003455 0.076720 -0.4531872 -0.3336762 0.3184235 0.7628159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4058 4059 0.049798 -0.047117 0.060141 0.0138908 0.4515505 -0.0131647 0.8920403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4059 4060 -0.060012 -0.066894 -0.022894 -0.4070183 -0.0103654 0.6698436 0.6209172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4060 4061 -0.040579 -0.012425 0.104836 0.2682884 0.8129491 -0.4825360 0.1851864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4061 4062 -0.143567 0.022372 0.039063 0.4250426 -0.2494156 0.8375105 0.2360230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4062 4063 -0.152812 0.176645 0.001314 0.1177346 -0.1031801 0.9112497 0.3809415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4063 4064 -0.121738 -0.194299 -0.017026 0.0884139 -0.3356917 0.2840122 0.8937735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4064 4065 -0.056113 -0.049199 -0.094274 -0.0025034 -0.4168262 0.9041325 0.0937766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4065 4066 0.058572 0.157241 -0.042423 0.0428386 -0.5554942 0.4523087 0.6964251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4066 4067 -0.082719 -0.029160 -0.004104 -0.5779695 -0.0558140 -0.7874773 0.2066773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4067 4068 0.256589 -0.022996 0.021491 0.0212669 -0.2475039 0.8349946 0.4909924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4068 4069 -0.060157 -0.009205 -0.081502 0.0304525 -0.1889012 0.7116241 0.6760030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4069 4070 0.049041 0.080434 -0.140024 -0.1376969 -0.4487183 0.8691046 0.1560403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4070 4071 0.013281 0.192096 0.009552 0.2411122 0.2971993 0.8320744 0.4014843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4071 4072 0.146430 -0.000276 0.194694 -0.1854330 -0.1735747 0.7926637 0.5542297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4072 4073 -0.164823 -0.190705 0.115051 0.5995962 -0.0101625 0.6662143 0.4433279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4073 4074 0.104332 0.002647 -0.086893 -0.0311667 0.3933936 -0.6877340 0.6093373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4074 4075 -0.047881 -0.104411 0.073580 0.4174506 0.0420371 -0.0077281 0.9076939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4075 4076 0.077663 -0.057439 0.085765 -0.3510644 0.7402506 0.5649240 0.0982025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4076 4077 0.112831 -0.040804 -0.165372 0.0108122 -0.6563133 -0.6902073 0.3045487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4077 4078 0.043240 -0.029005 -0.067785 -0.5171536 0.1752664 -0.1205726 0.8290332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4078 4079 -0.030184 -0.050647 -0.172975 0.5277873 -0.3138208 -0.7159247 0.3322783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4079 4080 0.170917 -0.155928 0.149222 -0.1441441 -0.2141386 -0.5208126 0.8137084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4080 4081 0.110051 -0.114249 0.016270 0.2570431 0.2297656 0.7436440 0.5728266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4081 4082 -0.021216 -0.102929 0.039476 0.1698809 0.2463240 -0.5017972 0.8115815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4082 4083 -0.165205 -0.055902 0.082673 -0.7508586 0.1215952 0.5177669 0.3915908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4083 4084 -0.127224 -0.098101 0.092843 0.1270570 0.2186259 -0.8838907 0.3934417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4084 4085 0.020574 0.063229 -0.088436 -0.1977515 0.3064047 -0.9112832 0.1912418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4085 4086 -0.175763 0.029426 0.091534 0.5462453 0.0796713 0.8312522 0.0654861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4086 4087 -0.083688 -0.027386 0.073863 0.1486813 0.4237748 0.6594538 0.6028511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4087 4088 0.011920 0.052921 -0.085389 0.0869241 -0.4390081 0.7139691 0.5384833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4088 4089 -0.055115 0.020403 -0.023913 -0.2441169 0.5824470 -0.3780325 0.6769446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4089 4090 -0.013030 0.079234 -0.063749 -0.1052875 -0.7543738 0.5538155 0.3363377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4090 4091 0.051042 -0.104512 0.113701 0.5701742 0.2670758 -0.7631585 0.1454679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4091 4092 0.068716 0.181246 0.078295 0.0751970 0.2991325 0.1056027 0.9453641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4092 4093 -0.114325 -0.026412 0.044045 -0.1874235 -0.5902715 0.0353817 0.7843469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4093 4094 0.080521 0.125020 0.124169 0.3392781 -0.1525447 0.8820310 0.2892089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4094 4095 -0.012027 0.145039 -0.017599 0.7263651 -0.0808961 0.5477456 0.4072154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4095 4096 -0.230724 0.066501 -0.051459 -0.5760120 -0.0537977 -0.7588495 0.2991045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4096 4097 -0.034027 -0.080188 0.016291 0.4407997 0.5962498 -0.2287767 0.6307479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4097 4098 0.046109 -0.125987 -0.059437 0.6661911 -0.3286734 -0.4812939 0.4653165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4098 4099 -0.064209 0.064209 0.033416 -0.2515873 -0.6114990 0.3861964 0.6431369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4099 4100 -0.027735 -0.004729 -0.123950 0.5655683 0.1333973 -0.6232231 0.5233838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4100 4101 0.054493 0.258964 0.083409 -0.7201967 -0.6337750 -0.0084704 0.2820890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4101 4102 -0.059761 0.092779 0.080264 0.1940430 0.1326648 -0.4061963 0.8830356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4102 4103 -0.036732 0.005755 0.060520 -0.3100701 0.4598847 0.6824067 0.4761132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4103 4104 0.021852 -0.177346 -0.065265 0.0987132 0.0556463 -0.0031413 0.9935539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4104 4105 -0.109021 0.021883 -0.058372 -0.0267761 0.0564225 -0.0973894 0.9932849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4105 4106 -0.109147 -0.005658 -0.074678 0.5087309 -0.0125620 0.7583852 0.4072922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4106 4107 0.267978 0.013260 0.007600 -0.8881651 0.0091237 -0.0247011 0.4587694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4107 4108 -0.024958 -0.172189 0.064430 0.4565818 0.5608307 -0.1741468 0.6683374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4108 4109 0.005815 0.108107 0.178085 -0.6803540 -0.3637030 -0.3120239 0.5545085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4109 4110 -0.060080 0.027288 0.092232 0.6616813 0.1899988 -0.5902232 0.4215625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4110 4111 -0.051723 0.062312 0.103457 -0.6353964 0.3591735 0.6373906 0.2469797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4111 4112 -0.069698 0.044431 0.101494 -0.0412479 0.7116435 -0.7012881 0.0075601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4112 4113 0.056200 0.015533 -0.114999 0.0881305 -0.1927399 0.2241329 0.9512354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4113 4114 0.062354 0.025872 0.028023 0.4901266 0.7270180 -0.4208417 0.2326219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4114 4115 -0.123687 -0.099060 -0.115959 0.3811635 -0.2114589 -0.3719485 0.8195449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4115 4116 -0.022349 0.063928 0.093277 -0.3978199 -0.2471687 -0.2337479 0.8520615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4116 4117 -0.000103 -0.010959 0.043603 -0.0805147 0.3930844 -0.2818564 0.8715268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4117 4118 -0.035412 0.028539 0.140220 -0.6696695 0.0238586 0.7325900 0.1195217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4118 4119 0.018919 -0.093644 -0.168858 -0.1230905 0.5944463 0.5780546 0.5452845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4119 4120 0.101784 -0.149707 -0.079893 -0.6118101 0.0477074 -0.5009734 0.6102770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4120 4121 0.047126 -0.065460 0.117077 0.0391373 0.5548818 0.7739843 0.3025275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4121 4122 0.151048 0.078339 0.099514 -0.1372424 -0.2050812 -0.5997436 0.7611924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4122 4123 0.052915 -0.083731 0.133849 0.0005511 -0.8550214 0.3186260 0.4091645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4123 4124 0.058311 0.077993 -0.046090 0.1986327 0.1075959 0.9667953 0.1194777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4124 4125 -0.144141 -0.191280 -0.098681 -0.2386407 -0.1908965 -0.7902850 0.5310920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4125 4126 -0.192523 0.016513 0.176909 -0.3870427 0.4455022 -0.3178943 0.7420707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4126 4127 0.043303 -0.023529 -0.001559 0.8215154 0.0056835 0.3471060 0.4523246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4127 4128 -0.087677 -0.136533 0.062726 0.3490071 0.2374685 -0.3738137 0.8258729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4128 4129 -0.072649 -0.226602 -0.031971 -0.8354308 -0.0329572 -0.2521206 0.4872416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4129 4130 -0.069155 0.020801 0.056998 0.1750688 -0.1074750 0.6830665 0.7008710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4130 4131 -0.111564 -0.117209 -0.062138 0.0531948 0.0635999 0.8208318 0.5651199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4131 4132 0.063490 0.008884 0.024771 -0.2114526 0.5569523 -0.8031614 0.0048604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4132 4133 -0.002838 0.009279 0.056453 0.6922621 0.0031371 -0.4032470 0.5984607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4133 4134 0.296026 0.075925 -0.083582 -0.2746460 -0.0981380 -0.8277600 0.4793244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4134 4135 0.050166 0.005909 -0.031460 0.0917681 0.5173216 0.4477775 0.7235000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4135 4136 -0.050060 0.006336 -0.015523 -0.3469327 0.2489398 0.0661107 0.9018293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4136 4137 0.151025 -0.022729 -0.048362 0.1634569 -0.8798863 0.3317064 0.2984173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4137 4138 -0.046512 -0.009688 -0.031097 -0.2459205 0.8911424 -0.3352119 0.1817176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4138 4139 -0.005665 -0.026736 0.023650 0.3986906 0.6921909 -0.3962398 0.4526716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4139 4140 -0.067715 0.014569 0.023921 -0.0333350 -0.4255420 0.4694037 0.7729573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4140 4141 0.121575 -0.074878 0.013238 0.5377034 -0.4060807 0.0246407 0.7384892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4141 4142 0.027923 -0.022751 -0.127406 0.1657642 0.7362805 0.4775087 0.4498874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4142 4143 -0.035035 -0.026880 0.007790 -0.3365881 -0.0180663 -0.7117219 0.6163067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4143 4144 0.168619 0.018536 -0.008976 0.2830857 0.1942089 -0.9051365 0.2507453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4144 4145 0.089821 -0.108701 -0.225499 -0.0903988 -0.5740141 0.7525217 0.3099143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4145 4146 -0.066920 -0.082529 0.067315 -0.4204981 0.8813693 -0.1552050 0.1492679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4146 4147 -0.090344 0.039427 -0.043253 0.3278117 0.0145472 0.3359481 0.8828741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4147 4148 -0.029525 -0.098777 -0.122919 0.2593867 -0.2009212 -0.7068711 0.6266438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4148 4149 -0.092446 0.064636 0.102749 -0.5896222 0.2614368 -0.6541469 0.3950801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4149 4150 -0.025436 -0.024461 -0.189473 0.0759681 -0.0986485 0.6595993 0.7412328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4150 4151 0.063832 -0.021007 -0.064868 -0.1639008 -0.5041761 0.7249731 0.4397238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4151 4152 -0.067198 -0.146271 -0.072393 0.6532975 -0.3314821 0.6383667 0.2362414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4152 4153 -0.198697 -0.101724 0.119846 0.1838473 0.5199967 0.0945030 0.8287779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4153 4154 0.137229 -0.110519 -0.195869 -0.5127992 0.0673343 -0.0660577 0.8533109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4154 4155 0.113397 0.111828 -0.014355 0.2768090 0.2009891 0.9038184 0.2570846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4155 4156 0.032932 -0.049397 -0.036930 -0.1479460 0.7349358 0.5453103 0.3749908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4156 4157 0.170180 0.077582 -0.191562 -0.6623327 -0.1502155 -0.4880490 0.5482325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4157 4158 -0.186377 0.125113 0.025691 0.2915935 0.4959229 0.5389923 0.6152406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4158 4159 0.093168 -0.210031 -0.069173 -0.1114988 0.1273419 0.9187323 0.3567674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4159 4160 -0.101734 -0.092491 0.044623 0.6011888 0.0351947 0.7860933 0.1392500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4160 4161 -0.203371 0.113768 0.032351 0.7615134 0.4174641 0.0382532 0.4943256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4161 4162 0.062529 -0.080406 -0.040291 0.1498677 0.4851356 0.2519358 0.8238395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4162 4163 0.066546 -0.066349 -0.118110 -0.7790264 -0.5066792 -0.2696246 0.2523818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4163 4164 0.111336 -0.145206 0.044691 -0.4535249 0.6045655 0.1787232 0.6299791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4164 4165 -0.092557 -0.073806 0.039755 0.6217617 -0.6227147 0.1285182 0.4572984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4165 4166 -0.009356 -0.100241 -0.254520 0.6390109 0.4510459 -0.0760142 0.6184210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4166 4167 0.077267 -0.056518 0.049759 0.3928670 -0.5829353 -0.6509022 0.2866501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4167 4168 -0.078728 0.085548 0.133233 0.0965275 -0.6662475 -0.4178157 0.6101039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4168 4169 0.131913 -0.090645 0.147975 -0.6891368 -0.0534884 -0.7027674 0.1683672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4169 4170 0.028749 0.069221 -0.084578 0.0002021 -0.1907323 0.3584214 0.9138683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4170 4171 0.147907 -0.100630 0.026670 0.3994667 0.6977957 -0.0218423 0.5941637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4171 4172 -0.068516 0.075580 0.155133 -0.3225181 -0.3421567 0.7463577 0.4710213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4172 4173 -0.125396 -0.119101 0.109019 -0.2712895 -0.3767244 -0.8298061 0.3096815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4173 4174 -0.115747 -0.039850 -0.057581 -0.4857338 -0.0670965 0.1406092 0.8601103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4174 4175 -0.022147 0.051067 -0.172051 0.1219156 -0.0407473 -0.9514351 0.2797274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4175 4176 0.048778 -0.043307 -0.206592 -0.2315871 0.5660673 0.4264350 0.6663996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4176 4177 -0.109567 0.150622 0.142511 0.1772008 -0.5267168 -0.6380791 0.5329394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4177 4178 -0.095839 -0.108314 -0.193768 -0.5236642 0.4745693 0.5305544 0.4680512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4178 4179 -0.052079 0.114372 -0.012009 -0.5349399 -0.2063497 0.7842620 0.2370489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4179 4180 -0.137223 -0.187498 -0.149606 0.4082965 0.4011638 -0.3440465 0.7443075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4180 4181 0.115558 0.022725 -0.109426 0.0268206 -0.1133388 0.9906866 0.0705343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4181 4182 -0.165672 -0.118646 0.099631 -0.2291701 0.8652273 -0.4457803 0.0119433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4182 4183 0.186417 -0.027513 -0.108867 0.0552260 0.2335066 -0.0538910 0.9692887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4183 4184 0.083519 0.140726 0.056196 -0.2177934 0.3395826 -0.9077958 0.1147017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4184 4185 0.042746 0.189352 0.094544 0.6652693 0.2219951 0.7053399 0.1031048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4185 4186 0.013882 -0.246887 0.091344 0.0520020 -0.1054214 0.4740999 0.8725889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4186 4187 -0.056782 -0.087358 -0.046913 0.5469922 0.6095638 0.1145340 0.5622397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4187 4188 0.034547 0.100356 0.066682 0.2530310 -0.7751122 -0.3155399 0.4853977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4188 4189 -0.094818 -0.173781 -0.012538 -0.2324284 0.7874042 0.4835503 0.3035634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4189 4190 -0.097726 0.068281 0.108049 -0.3540876 -0.0390059 0.2084907 0.9108415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4190 4191 -0.257889 0.114197 0.121908 -0.7188761 0.0028984 0.3268431 0.6135001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4191 4192 -0.202202 0.059687 0.099924 0.5886957 -0.2198813 0.2626108 0.7322057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4192 4193 -0.068341 -0.055511 0.153706 0.2898849 -0.1548310 -0.9441012 0.0258285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4193 4194 0.010748 -0.106414 -0.083088 0.3413545 -0.3879014 -0.7900042 0.3300045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4194 4195 0.093670 -0.041812 0.006794 -0.6616071 0.3756266 0.1637778 0.6279789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4195 4196 -0.076295 -0.148811 0.079533 -0.4137344 0.0527002 0.8395154 0.3482247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4196 4197 0.010122 0.098626 -0.018508 0.5017614 -0.1088711 -0.4221286 0.7471211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4197 4198 -0.139628 0.145674 -0.109811 -0.3982781 -0.4732526 0.7710424 0.1513282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4198 4199 0.125203 0.154593 0.123412 -0.3535833 0.4241137 -0.7510930 0.3618919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4199 4200 -0.125432 -0.034080 -0.033554 -0.3660934 -0.0172339 -0.3703235 0.8535450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4200 4201 0.094659 -0.077508 0.050816 -0.1493159 -0.3093409 -0.8760237 0.3385195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4201 4202 0.196293 0.188402 0.182398 -0.3168745 -0.0006298 -0.9457842 0.0712904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4202 4203 -0.029714 0.103984 0.177612 0.2795246 0.5287549 -0.6766578 0.4294397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4203 4204 -0.006272 0.064706 -0.095029 -0.0550057 -0.2723353 -0.5375196 0.7961662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4204 4205 -0.080010 0.027667 0.034459 -0.1169708 -0.1900274 -0.2946085 0.9292003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4205 4206 0.043108 0.188494 0.016895 -0.4778139 0.0637405 -0.8617512 0.1581641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4206 4207 0.066258 -0.125091 0.045234 0.3641366 0.2348111 -0.8012532 0.4126276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4207 4208 -0.141289 0.226483 0.017297 0.2475521 -0.5734020 -0.1256713 0.7708014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4208 4209 0.219616 0.041257 0.081737 0.0605920 0.7723791 -0.1700862 0.6089580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4209 4210 0.043164 -0.121632 0.118232 0.3597129 -0.2967815 0.1061681 0.8782116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4210 4211 0.061393 0.132764 0.017293 -0.5500626 -0.0171230 0.6599043 0.5115314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4211 4212 0.046194 -0.057016 0.005817 -0.0693942 0.5707633 0.7990615 0.1758250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4212 4213 -0.072400 0.041103 -0.077160 -0.0336719 -0.5842897 0.4331027 0.6854880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4213 4214 0.070219 0.095578 0.092276 -0.0535215 -0.2502623 -0.9298857 0.2642287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4214 4215 -0.003294 -0.056301 -0.122793 -0.5384321 -0.5437349 -0.0164883 0.6435615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4215 4216 0.009536 -0.053361 -0.054002 0.6624867 -0.2833668 0.6463917 0.2509827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4216 4217 0.004488 0.233267 0.057509 0.3635866 0.1801860 0.0496909 0.9126163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4217 4218 -0.156838 -0.040227 0.103615 0.0138439 0.6920026 0.3968852 0.6028457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4218 4219 0.258502 -0.094732 -0.090558 0.3905904 -0.3905214 0.1540775 0.8192633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4219 4220 -0.020401 0.081970 0.158846 -0.2009342 0.9374912 0.2416661 0.1494432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4220 4221 -0.057722 -0.041183 -0.027543 -0.4398846 0.2363564 0.0540533 0.8647054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4221 4222 -0.029662 -0.176230 0.051987 0.5143884 -0.6685333 0.0608968 0.5336285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4222 4223 0.167377 0.126149 0.070371 -0.0953567 -0.0317673 0.9311941 0.3503932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4223 4224 0.068034 -0.113232 0.153429 0.3348750 0.1014587 0.7769173 0.5234161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4224 4225 -0.238570 -0.011902 0.218504 0.6972393 -0.1256151 -0.3854695 0.5911780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4225 4226 0.206763 0.179267 -0.022222 -0.1285942 -0.5174698 -0.5144491 0.6715881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4226 4227 -0.064074 -0.123026 -0.037778 -0.4445135 -0.0141400 -0.6684019 0.5961935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4227 4228 0.040050 0.101301 -0.083433 0.3095536 -0.3963360 0.8641439 0.0187019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4228 4229 0.044526 0.033830 0.038313 -0.3285825 -0.7005379 0.4148877 0.4786944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4229 4230 -0.102241 0.072194 -0.060575 0.4159463 0.2224451 -0.8726419 0.1265029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4230 4231 -0.097910 -0.122707 -0.020121 -0.5148198 -0.5096106 -0.5255341 0.4461743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4231 4232 0.024598 0.042322 0.264040 0.4047602 0.6902187 0.2875566 0.5263825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4232 4233 -0.133995 -0.013871 -0.041492 -0.4127240 -0.2140728 -0.8673922 0.1773765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4233 4234 0.050549 -0.027728 0.051589 0.1510233 0.5499058 -0.4729777 0.6716306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4234 4235 -0.012203 0.105621 -0.126925 -0.5410770 0.3169321 0.3878150 0.6755659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4235 4236 0.086553 -0.007521 0.071844 0.0754361 -0.1186006 -0.6798289 0.7197749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4236 4237 0.049919 0.008706 -0.074715 0.4564117 0.2371520 0.6045893 0.6082097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4237 4238 0.024790 -0.084238 -0.116550 -0.7297629 -0.3730136 0.4327313 0.3755669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4238 4239 -0.171647 -0.002490 -0.007384 -0.7776475 -0.1185172 0.6161970 0.0389772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4239 4240 0.207898 0.081042 0.028772 0.0236860 0.3756987 0.6307953 0.6785180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4240 4241 0.165129 0.054530 0.091071 -0.3575067 -0.0345950 -0.9325493 0.0366605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4241 4242 0.015498 -0.077837 -0.134012 0.1065535 0.1003162 0.3409524 0.9286196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4242 4243 -0.045998 -0.070433 -0.137225 -0.4445064 -0.5180517 0.1959798 0.7040088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4243 4244 -0.204357 0.207896 -0.044990 0.1185191 -0.8370500 0.5318690 0.0491517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4244 4245 0.058286 0.072548 0.047558 0.6816314 -0.5831621 0.2155235 0.3858110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4245 4246 -0.183985 -0.041225 -0.115798 0.0455212 0.7472366 0.6622258 0.0319734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4246 4247 -0.042566 -0.102030 -0.005963 -0.1741109 -0.5534090 -0.7069946 0.4044534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4247 4248 0.029626 -0.094411 -0.058786 0.2707235 0.5868256 0.4613915 0.6078342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4248 4249 -0.143671 -0.160194 -0.044164 -0.5091902 -0.5168355 0.2716362 0.6323133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4249 4250 -0.045531 0.021250 -0.041680 0.3460703 -0.1657407 0.3437571 0.8570860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4250 4251 0.085194 -0.009044 0.096195 -0.5600953 0.4334544 0.5301656 0.4661920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4251 4252 0.132124 0.149073 0.028385 0.6016308 -0.5002385 -0.6198584 0.0598119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4252 4253 -0.061856 0.036619 -0.080292 -0.0797142 -0.8150129 -0.5524980 0.1553883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4253 4254 -0.134565 -0.024115 -0.020862 0.5340620 -0.7074635 -0.4525748 0.0972068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4254 4255 0.010558 0.032989 -0.031278 0.3913327 -0.2030818 -0.6622041 0.6058896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4255 4256 0.047160 -0.053632 -0.134605 0.0333009 -0.3178940 0.9033935 0.2858578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4256 4257 -0.022546 0.034619 -0.035856 -0.6628775 0.5762040 0.3227916 0.3526868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4257 4258 0.175414 0.017384 0.074756 0.1921058 0.0207074 -0.9537187 0.2304065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4258 4259 -0.129523 0.005839 0.211683 -0.2803828 0.5446379 -0.3815382 0.6922310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4259 4260 -0.004699 -0.077005 -0.147103 -0.0302359 -0.6664387 -0.4635930 0.5831182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4260 4261 0.200622 0.010183 -0.084737 -0.5649857 0.1850811 -0.7771717 0.2062529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4261 4262 -0.046957 0.105486 0.061387 0.1651298 0.1571447 0.9733481 0.0251230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4262 4263 -0.006281 -0.014119 -0.062425 -0.1487531 -0.3787423 0.0851108 0.9094960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4263 4264 0.089674 -0.018964 0.110576 0.1607949 -0.1606612 -0.2190154 0.9488758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4264 4265 0.014138 0.070420 -0.024239 -0.7221905 0.3828494 -0.5501520 0.1708800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4265 4266 0.076770 0.001473 0.039518 -0.5710855 -0.5838447 0.5551583 0.1574353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4266 4267 0.023174 0.131985 -0.240656 -0.2286323 0.3404290 -0.8459101 0.3409861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4267 4268 -0.011702 -0.014898 -0.028657 -0.6358443 0.3408545 -0.5782473 0.3809859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4268 4269 -0.206929 -0.116571 -0.008247 -0.2926722 0.0422054 0.9094175 0.2924406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4269 4270 -0.085344 0.032329 0.194594 -0.5824104 -0.3573362 0.6741720 0.2803590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4270 4271 -0.046132 -0.174126 0.163997 -0.0025824 0.0885906 0.8444038 0.5283249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4271 4272 0.012458 -0.132560 0.122914 -0.1494572 -0.7427545 -0.4292880 0.4916199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4272 4273 0.086098 -0.068599 -0.059414 -0.4073111 0.7809991 0.3323795 0.3371378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4273 4274 -0.049201 0.072697 -0.221945 -0.1154632 -0.6805077 0.7189151 0.0820887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4274 4275 0.140532 0.076593 0.159041 0.3959345 -0.1102994 -0.6616684 0.6271083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4275 4276 -0.273500 0.063270 0.115190 -0.2410416 0.7134177 -0.1671486 0.6363925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4276 4277 -0.095674 -0.018231 -0.083103 0.2669085 0.0684173 -0.8073688 0.5217609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4277 4278 -0.077015 -0.148832 -0.055669 -0.0424259 -0.2350335 0.4427188 0.8642681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4278 4279 0.045522 0.081644 -0.022031 0.3598948 -0.6350475 -0.6835126 0.0009606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4279 4280 -0.013818 0.079271 0.215264 0.2334948 0.3734452 0.8582337 0.2635411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4280 4281 0.055174 0.097540 0.137970 -0.3312911 0.1199180 0.5803674 0.7341932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4281 4282 0.047189 -0.064994 0.099319 0.2297791 -0.2265575 0.6224655 0.7130288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4282 4283 0.202596 -0.079230 -0.052101 -0.7806788 -0.1254188 0.6013642 0.1147686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4283 4284 0.006225 0.019010 -0.087242 0.6126171 -0.5480516 0.1421797 0.5514749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4284 4285 0.033815 0.195913 0.108504 -0.4005292 0.0441781 0.6625839 0.6313534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4285 4286 0.038640 -0.112735 -0.006212 0.7114681 -0.4533022 -0.0887612 0.5295769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4286 4287 0.080402 0.038482 -0.044587 0.0024330 0.6281550 0.7774331 0.0318294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4287 4288 0.152275 0.082769 -0.111150 -0.4878377 -0.5591482 -0.3062616 0.5962982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4288 4289 -0.057948 -0.144791 0.165789 -0.7009775 -0.0958133 -0.7000194 0.0970734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4289 4290 0.151063 0.208483 -0.001153 0.6809810 0.5382290 0.4898132 0.0815936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4290 4291 -0.084440 0.027702 -0.000093 0.5375376 0.4677008 -0.3807128 0.5893785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4291 4292 0.081792 0.112127 -0.079943 -0.0097783 0.5173455 0.8437686 0.1425222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4292 4293 -0.107788 -0.019363 0.153307 0.2347238 -0.2529662 0.7171596 0.6054708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4293 4294 0.144261 0.019386 -0.013660 0.0784156 0.5882796 0.0863566 0.8002004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4294 4295 0.148266 -0.045823 0.080273 0.1129287 -0.5601614 -0.6176446 0.5403531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4295 4296 0.159427 -0.036158 0.132776 0.7224868 -0.0186494 0.4765659 0.5005497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4296 4297 -0.046953 -0.069007 -0.169658 -0.2122500 0.4807819 0.4515770 0.7210249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4297 4298 -0.015525 -0.140837 -0.074020 0.1268693 -0.4000481 0.2440919 0.8742339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4298 4299 0.085153 0.036851 0.002766 0.6351067 0.1080680 0.3983256 0.6529146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4299 4300 -0.111423 0.036344 0.077146 0.3122709 0.5959224 0.7398329 0.0032558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4300 4301 -0.105728 -0.018765 0.097774 -0.3012940 -0.0377365 0.9406091 0.1518305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4301 4302 0.009927 0.049852 0.007019 -0.3301334 -0.7206337 -0.2020190 0.5752281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4302 4303 0.061748 -0.034548 0.071259 0.5274117 0.7604516 -0.2342815 0.2977622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4303 4304 0.119721 0.003894 0.065215 -0.5807423 -0.2652400 0.7013466 0.3170158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4304 4305 0.102023 0.031340 0.145647 -0.3782139 0.1611062 -0.8860900 0.2141110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4305 4306 -0.072798 0.121283 0.137414 -0.0190295 -0.5351931 0.8091376 0.2418730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4306 4307 -0.004361 -0.076187 0.130541 0.6579990 0.0111664 0.2793311 0.6992044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4307 4308 0.093827 0.143001 0.163187 -0.5701770 -0.1837687 -0.1112819 0.7929335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4308 4309 0.260932 -0.130001 -0.075727 0.3617700 -0.0686143 -0.1361167 0.9197210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4309 4310 0.168982 -0.118542 0.177279 -0.4062957 0.2731738 0.6297970 0.6030386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4310 4311 -0.023037 -0.362491 0.099026 0.3881224 0.0686846 0.0588035 0.9171617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4311 4312 0.137292 0.226882 0.047062 -0.7272374 0.0219529 0.0613368 0.6832874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4312 4313 -0.157157 -0.179231 -0.058607 -0.1890516 -0.5991543 0.7244729 0.2835711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4313 4314 0.015455 0.047742 0.118271 -0.3840056 -0.0866053 -0.9157303 0.0804808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4314 4315 0.136122 -0.025229 0.100006 -0.7878527 0.1262514 0.0831807 0.5970173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4315 4316 -0.210338 -0.169275 0.085156 0.6489523 -0.5551846 0.4509507 0.2593733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4316 4317 0.019406 -0.244135 0.039454 -0.5212859 0.2147680 -0.7267314 0.3924247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4317 4318 0.164593 -0.107413 -0.019144 0.0406207 -0.3760514 0.3486997 0.8575219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4318 4319 -0.091395 -0.034464 0.022641 -0.4454549 0.4724426 -0.1454691 0.7464628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4319 4320 -0.030109 -0.142464 0.071402 0.1188349 -0.1179660 -0.0363879 0.9852097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4320 4321 0.060074 -0.143439 -0.007951 0.4890600 -0.6411504 0.1319644 0.5764823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4321 4322 0.048095 -0.126481 -0.005333 -0.5810414 0.5722015 -0.4320186 0.3851446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4322 4323 0.061195 -0.138018 0.016646 0.1921355 0.6535748 -0.2162805 0.6993902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4323 4324 -0.075980 0.024383 0.118057 0.0216969 -0.5110609 0.2675057 0.8165701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4324 4325 0.134979 -0.089249 0.029363 0.3744574 0.7142023 0.0110629 0.5912481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4325 4326 0.044599 0.046434 -0.071737 0.5111919 -0.6809377 -0.5094530 0.1243561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4326 4327 -0.171701 0.048995 0.031303 -0.2085719 -0.7703681 -0.4427080 0.4087057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4327 4328 -0.187857 0.046326 -0.010524 0.4919829 0.4957087 0.3435378 0.6278595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4328 4329 0.026417 0.021516 0.061512 -0.5426067 0.5107636 0.5368600 0.3955754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4329 4330 0.072515 -0.058862 0.141859 -0.7154283 -0.5362294 0.1466433 0.4232211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4330 4331 0.026844 -0.236457 -0.003892 0.8784929 0.1437308 -0.4232988 0.1685522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4331 4332 -0.153001 -0.089475 -0.044418 0.2638724 0.3921355 -0.5976840 0.6475917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4332 4333 0.072025 0.080969 -0.010733 -0.3343456 -0.2686295 0.0234194 0.9030519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4333 4334 0.068850 0.191472 -0.031190 -0.0782783 -0.0734278 -0.0975782 0.9894238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4334 4335 -0.089679 -0.058359 -0.256514 0.3913158 -0.5296461 0.3502491 0.6660875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4335 4336 0.007582 -0.070336 -0.131191 0.2636080 -0.2171466 0.5721353 0.7456671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4336 4337 -0.060816 0.024420 -0.092997 -0.5092042 0.5696021 -0.6401433 0.0805053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4337 4338 -0.143489 0.057221 0.074881 -0.1320588 0.3903399 -0.8255951 0.3854711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4338 4339 -0.121093 0.119444 -0.125294 -0.1208500 0.4757800 -0.1927540 0.8496320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4339 4340 0.027882 -0.106745 0.127570 -0.1828495 -0.5962577 -0.3393751 0.7041786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4340 4341 -0.140990 -0.030956 -0.004399 0.3590363 0.5901189 -0.3664722 0.6233384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4341 4342 0.195053 -0.092422 0.018612 -0.0743403 -0.0668554 0.9788961 0.1782311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4342 4343 0.156781 0.059816 -0.048003 0.4761188 -0.5565430 0.5479770 0.4040940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4343 4344 0.029340 0.073506 -0.072792 0.6673539 -0.0413465 -0.4158241 0.6164572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4344 4345 0.069794 -0.283857 -0.179833 0.1925186 0.9381412 0.1021587 0.2690563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4345 4346 -0.051126 -0.003350 -0.033674 -0.5755512 -0.3342245 -0.4842548 0.5679191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4346 4347 -0.062132 -0.087181 -0.126525 -0.1750137 -0.6674622 -0.1933120 0.6974918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4347 4348 -0.112042 0.246882 -0.001431 -0.3282069 0.1518933 -0.5038324 0.7844498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4348 4349 -0.167850 -0.031872 -0.012816 -0.1890270 0.2525047 -0.8716507 0.3751468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4349 4350 0.066809 -0.071137 -0.095418 -0.6324941 -0.0690588 0.6148414 0.4659958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4350 4351 0.103912 0.220679 -0.143583 -0.1652368 -0.1014802 0.3439714 0.9187395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4351 4352 0.044851 -0.056412 0.024776 0.2894069 0.3022081 0.9050730 0.0758735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4352 4353 -0.036608 -0.049115 0.018515 -0.1403759 0.7972018 0.3765091 0.4505605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4353 4354 0.082971 0.034199 0.005362 0.3541658 0.0305138 0.3025780 0.8843540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4354 4355 0.034787 -0.015870 -0.001068 0.1490783 -0.3732195 -0.5377477 0.7411547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4355 4356 0.118814 -0.099210 -0.037872 -0.3221693 -0.7321811 0.4317569 0.4167779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4356 4357 0.193034 0.024804 -0.018224 -0.0031023 0.8137385 -0.4819060 0.3249410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4357 4358 -0.020524 0.163388 -0.181912 -0.1907494 0.2319539 -0.3095366 0.9022190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4358 4359 0.158487 0.110794 -0.151185 0.2054799 -0.1355976 0.2872823 0.9256674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4359 4360 -0.207270 0.077975 -0.122774 -0.4271831 0.1671393 0.6525614 0.6031108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4360 4361 0.122838 0.069930 0.019323 -0.2199196 0.8023655 0.4257550 0.3557775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4361 4362 0.076549 0.155728 0.154502 0.0839326 0.4979360 0.8473241 0.1644896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4362 4363 0.121118 0.100011 -0.012699 0.4045903 0.4702985 -0.7667372 0.1650454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4363 4364 -0.065935 0.064356 -0.063454 -0.1100856 -0.4051462 -0.5516837 0.7206822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4364 4365 0.000010 0.050030 0.030890 0.1914616 -0.5085952 0.8391968 0.0205436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4365 4366 0.104218 -0.056895 0.031090 -0.2472217 -0.3669430 -0.2912124 0.8481920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4366 4367 0.010911 0.153166 0.107729 -0.3212933 -0.3268274 -0.8662076 0.1990953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4367 4368 -0.142576 -0.018844 0.000277 -0.1416986 -0.3677232 -0.8407698 0.3712240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4368 4369 -0.038594 0.072436 0.100551 -0.5681337 -0.1551919 0.7916735 0.1624581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4369 4370 -0.085007 -0.021909 -0.184860 -0.2889836 0.4438871 0.7763474 0.3416684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4370 4371 0.010807 0.130451 -0.194430 -0.7837938 0.3805889 0.4900573 0.0257539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4371 4372 0.036284 -0.005538 0.056408 -0.2943137 -0.5257837 0.7619166 0.2375164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4372 4373 -0.081747 0.092770 0.071427 0.1911732 -0.1847940 -0.1773122 0.9475571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4373 4374 0.089739 -0.078232 -0.039627 0.0800142 0.3513922 -0.8960276 0.2593371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4374 4375 -0.015266 0.013986 0.079181 0.2679880 0.4371644 -0.4346850 0.7403504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4375 4376 0.125694 -0.020214 0.216757 0.3057369 -0.4934082 0.7496246 0.3180193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4376 4377 0.057799 -0.148505 0.041729 -0.4507710 -0.2032408 -0.8098652 0.3156217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4377 4378 0.154138 0.036548 0.050682 -0.7334184 -0.1611566 -0.6219450 0.2220596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4378 4379 0.121573 -0.154467 -0.028250 0.2365440 0.1566407 0.1356766 0.9492642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4379 4380 0.212921 0.116494 0.127278 0.0463960 0.6018023 -0.5074278 0.6149784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4380 4381 -0.147272 -0.136569 0.091415 -0.1120811 0.6896909 0.7065780 0.1118566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4381 4382 -0.021072 0.040477 0.046874 0.0235791 0.2527039 0.8618772 0.4390358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4382 4383 -0.125156 0.081652 -0.021146 0.6103670 -0.1905705 0.1001212 0.7623062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4383 4384 0.041515 -0.103103 0.061541 0.1161697 -0.2499775 0.7429687 0.6099290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4384 4385 0.021600 0.026910 0.110415 0.7395680 -0.2588876 0.3194211 0.5329038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4385 4386 0.157825 -0.018214 0.071031 -0.0826319 0.5851097 0.2656367 0.7617452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4386 4387 0.138175 0.032279 0.106396 -0.0470897 -0.0124847 0.7588748 0.6494119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4387 4388 0.084313 0.212790 0.042821 -0.1393117 -0.4840471 -0.8144636 0.2879926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4388 4389 -0.058300 0.001467 0.027944 0.0329816 -0.0402066 0.6358896 0.7700260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4389 4390 0.082911 -0.031455 -0.092588 0.4540300 0.0647128 0.8057659 0.3747137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4390 4391 0.065903 0.133929 -0.028254 0.0405038 0.2085513 -0.4452996 0.8698126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4391 4392 -0.025393 0.048620 0.077903 -0.2231335 -0.6101090 -0.2429351 0.7203895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4392 4393 -0.092017 -0.039801 0.046097 -0.4160202 -0.2161478 -0.7072268 0.5291858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4393 4394 -0.056670 -0.135925 -0.081841 -0.6228303 0.5986299 -0.3297212 0.3807999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4394 4395 -0.001331 -0.131586 0.177259 0.6977074 0.0259504 0.3253318 0.6377227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4395 4396 0.039991 0.091515 0.148420 0.1832739 0.1792272 -0.9044577 0.3409467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4396 4397 -0.011136 -0.156372 0.035313 0.2674855 -0.2040460 -0.9170276 0.2141893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4397 4398 0.086627 -0.008461 -0.000177 0.0385918 -0.9717485 -0.2320028 0.0197527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4398 4399 0.035829 -0.071006 -0.082970 -0.3793647 0.3378780 0.4326757 0.7447904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4399 4400 -0.107335 0.073121 0.087537 -0.4367370 0.0740294 -0.6474305 0.6201727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4400 4401 -0.018444 -0.112121 -0.065806 -0.2882785 0.0530302 0.2283101 0.9284168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4401 4402 -0.075253 -0.080943 -0.030064 -0.3744488 -0.2296201 0.5373809 0.7199198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4402 4403 0.034310 0.006498 0.198170 -0.2485526 -0.3940411 -0.1552220 0.8711253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4403 4404 0.017965 0.054566 -0.064737 0.4709535 0.1881855 0.7068694 0.4930768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4404 4405 -0.214860 -0.146710 0.013355 0.0782201 0.3093180 0.6328397 0.7054913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4405 4406 -0.049656 -0.017109 0.043371 0.0248350 0.4717640 -0.6337527 0.6125189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4406 4407 -0.023612 0.111191 0.009927 0.3304095 -0.6829801 0.3738007 0.5335173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4407 4408 -0.111808 -0.053483 0.054515 -0.3575222 0.2685391 -0.0934694 0.8895662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4408 4409 0.043394 -0.035748 -0.155926 -0.1843426 0.2746958 0.7516201 0.5706376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4409 4410 0.186147 0.000535 0.243201 -0.2596340 -0.5227580 0.5238077 0.6204351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4410 4411 -0.009842 -0.157527 -0.095765 0.0932828 -0.0585347 0.8413317 0.5291814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4411 4412 -0.129030 -0.002522 -0.057973 0.3528236 -0.1634871 -0.4783772 0.7873644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4412 4413 -0.072044 -0.117947 -0.040105 -0.4265387 -0.3637547 0.8021933 0.2055072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4413 4414 0.047832 -0.043320 -0.083694 0.3429326 0.1133732 -0.1987819 0.9110595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4414 4415 -0.024366 0.101988 0.106789 -0.1234699 -0.3900231 0.8796028 0.2427677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4415 4416 0.134759 -0.042378 0.012520 0.7483633 0.2009045 -0.1455659 0.6151426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4416 4417 0.062347 0.064330 -0.001032 0.4704412 -0.4479380 -0.5998503 0.4671361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4417 4418 -0.110166 -0.006869 0.013834 0.2072348 -0.2850967 0.9231962 0.1532395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4418 4419 0.246025 -0.064509 -0.106195 -0.4291187 0.6944179 -0.4581209 0.3518042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4419 4420 0.239139 -0.106631 0.110389 -0.2027274 -0.0800717 -0.8452076 0.4879695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4420 4421 0.082094 -0.100771 0.029122 -0.6547207 0.2313265 -0.7188247 0.0334660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4421 4422 -0.071670 0.043933 -0.078303 0.2569145 0.4844522 0.2417876 0.8005247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4422 4423 0.103101 -0.029930 0.148239 0.2972626 0.3814163 -0.5966108 0.6404780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4423 4424 -0.167661 0.033415 -0.110583 -0.0630775 0.4720619 -0.5676249 0.6715510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4424 4425 -0.089779 0.081228 -0.163385 0.4471274 0.5565359 0.4354231 0.5484082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4425 4426 0.106826 -0.243341 0.045012 -0.1556239 -0.2667172 0.4228784 0.8519490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4426 4427 0.001104 -0.104509 0.014573 -0.2873122 0.1576428 -0.3047549 0.8942734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4427 4428 -0.049698 -0.106334 0.032848 0.8824498 0.0234680 -0.4549760 0.1171680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4428 4429 -0.040257 -0.040398 -0.053866 -0.8931720 -0.3628195 0.1324747 0.2303392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4429 4430 0.128263 -0.146778 -0.132107 -0.0265761 -0.0711114 -0.4814815 0.8731623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4430 4431 0.029800 -0.030836 -0.256708 -0.0864087 0.9176889 -0.2485247 0.2976847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4431 4432 -0.011462 0.131358 -0.057252 0.7741873 -0.4274640 0.3937404 0.2507531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4432 4433 -0.024219 -0.106833 0.052738 -0.5886565 0.3643043 0.6317715 0.3487558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4433 4434 0.112168 0.077275 -0.030610 -0.4896288 -0.5296847 0.5226601 0.4544493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4434 4435 0.272414 -0.022447 -0.120997 -0.7235718 -0.3838628 0.5126506 0.2574542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4435 4436 0.222727 -0.040586 -0.046905 0.6999907 -0.0954634 0.0976758 0.7009702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4436 4437 0.088510 0.046552 -0.048360 -0.0020646 -0.4879268 -0.8662018 0.1077848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4437 4438 -0.040492 -0.128587 -0.175635 -0.4715856 0.5645981 -0.6772241 0.0142656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4438 4439 0.180895 0.150856 -0.004273 0.6737483 0.2040782 0.7040623 0.0933360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4439 4440 -0.104533 0.038451 -0.052984 0.3606900 -0.2680579 -0.8665870 0.2169668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4440 4441 0.123710 -0.035707 0.063117 0.7149021 -0.4855529 -0.4647380 0.1928004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4441 4442 -0.037683 -0.028755 -0.028541 -0.4293532 0.2422743 0.7579833 0.4271069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4442 4443 0.028831 0.147860 -0.185209 0.7557394 0.1204185 0.1429362 0.6276357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4443 4444 0.055242 -0.010708 0.055503 0.0225845 0.9103472 0.3874693 0.1436158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4444 4445 0.018650 -0.139620 0.024920 0.2844632 0.0032361 0.9578609 0.0396589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4445 4446 -0.033295 -0.015393 -0.112522 0.0068147 -0.0983845 0.7732376 0.6264006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4446 4447 -0.074261 -0.043938 0.001829 -0.5957625 -0.5531005 -0.0473617 0.5804342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4447 4448 -0.035182 -0.177507 -0.059435 0.7605276 -0.3080461 -0.1724630 0.5449421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4448 4449 0.133215 -0.029756 0.178206 0.3409832 0.5433643 0.7078059 0.2957980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4449 4450 -0.037761 -0.074983 -0.174781 0.0989278 -0.3619294 -0.7009449 0.6065449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4450 4451 -0.020787 0.114424 -0.061621 -0.7147347 0.2372010 -0.0019182 0.6579410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4451 4452 0.055865 0.098797 -0.150482 0.4007458 -0.6759251 0.1537785 0.5990661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4452 4453 -0.287362 -0.078970 0.008871 -0.7867696 0.3689724 -0.2284384 0.4389407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4453 4454 -0.146921 0.038238 0.045175 0.8490277 0.2293743 -0.3145259 0.3572293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4454 4455 0.031904 0.057956 0.004925 0.0500532 0.8976988 0.4027865 0.1714485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4455 4456 0.063295 -0.144357 -0.037379 -0.5278224 0.7585644 0.1155481 0.3641871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4456 4457 0.010854 -0.079988 -0.007294 0.1474092 -0.4928165 -0.6888185 0.5108146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4457 4458 -0.005066 -0.085917 -0.075163 -0.0067069 0.1156198 -0.9808493 0.1565944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4458 4459 0.041843 0.025431 -0.051678 -0.5524845 0.3236784 -0.7244919 0.2551562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4459 4460 -0.215214 -0.060553 0.049234 -0.4469432 0.7751818 -0.0119422 0.4463097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4460 4461 0.103918 -0.052201 0.081898 0.1386817 -0.3877935 0.7830511 0.4660628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4461 4462 0.060276 0.040168 -0.214625 -0.4458040 -0.1200620 0.1518436 0.8739493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4462 4463 -0.033299 0.021554 -0.160275 -0.1573468 -0.6487515 -0.1371376 0.7318174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4463 4464 0.032237 -0.087412 0.018779 0.5316191 -0.3605458 0.1130187 0.7580334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4464 4465 -0.024914 0.116080 0.015408 0.3512802 -0.7414679 0.5478539 0.1633514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4465 4466 -0.048259 0.014781 0.139511 0.1417366 -0.7168601 -0.0168244 0.6824509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4466 4467 -0.058391 -0.137713 0.162967 0.3080717 -0.3277010 0.8903291 0.0708371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4467 4468 0.078884 -0.062600 -0.039639 -0.5617943 0.4962135 -0.1421830 0.6464853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4468 4469 -0.125201 0.130259 0.050345 0.1484662 -0.1895365 0.7768343 0.5818610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4469 4470 0.011414 0.019006 0.010262 -0.0813241 -0.6141382 -0.5101205 0.5966555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4470 4471 -0.081036 0.040075 0.096329 -0.0511626 -0.4044445 0.1935926 0.8923726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4471 4472 0.100514 0.085888 0.023432 -0.2706568 -0.0346469 0.7518094 0.6002725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4472 4473 -0.187961 0.143478 -0.149394 0.4787230 -0.8194502 0.1621880 0.2702233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4473 4474 0.150836 -0.131876 0.170033 0.7425497 0.2439555 0.6232452 0.0259059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4474 4475 -0.020543 0.086383 -0.112145 -0.3048585 0.4840545 0.0360265 0.8194233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4475 4476 0.105275 0.009618 -0.135083 0.5300426 -0.5191032 -0.4188273 0.5236128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4476 4477 0.001462 0.216041 0.026981 -0.7538692 -0.4989749 -0.2032479 0.3760261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4477 4478 -0.152409 0.103815 0.022288 -0.1032738 0.7798670 -0.3652507 0.4977288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4478 4479 -0.063927 -0.090228 0.080069 0.6017153 -0.4568986 -0.0199189 0.6548172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4479 4480 0.026561 0.078064 0.221012 0.5380436 -0.1653279 0.8015928 0.2015559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4480 4481 0.086460 -0.116298 0.057913 -0.5450216 0.6214957 -0.2874051 0.4838314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4481 4482 0.051791 -0.090790 0.045756 0.8466332 0.1028506 0.4992966 0.1527643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4482 4483 0.112523 0.185225 0.021340 -0.2135955 -0.3538978 -0.5781309 0.7034898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4483 4484 0.065104 -0.049470 -0.011089 0.0018832 0.6636429 0.6681250 0.3364277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4484 4485 -0.008588 -0.143722 0.135952 -0.8884663 -0.1038571 0.1566498 0.4186910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4485 4486 -0.033565 0.050753 0.075243 0.0458651 0.5299558 -0.2689517 0.8029372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4486 4487 -0.006970 -0.122554 0.035840 0.3932512 0.6715310 0.0605754 0.6250842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4487 4488 0.061301 -0.195677 -0.102350 0.4361762 -0.6508493 -0.6108971 0.1137987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4488 4489 -0.136674 -0.077126 0.075707 0.2638619 0.4442070 0.6162559 0.5943783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4489 4490 0.225749 -0.099540 -0.002311 -0.4935215 0.4854310 -0.5951105 0.4082117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4490 4491 0.064092 0.035085 0.192378 -0.2725207 -0.3272326 0.4575092 0.7806002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4491 4492 0.058837 -0.069269 0.095910 0.7008878 -0.1782730 -0.6863361 0.0769275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4492 4493 -0.073245 0.337613 -0.003080 -0.4296925 -0.2869933 0.5071647 0.6897704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4493 4494 0.156266 -0.063746 -0.003051 -0.6355647 0.2231531 -0.4061378 0.6175049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4494 4495 -0.083313 -0.100440 -0.249949 0.4467649 0.1699513 -0.3153717 0.8197916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4495 4496 0.025661 0.120888 0.146337 -0.6166925 0.5736471 -0.4128484 0.3466635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4496 4497 -0.071019 -0.004758 0.010311 0.3097699 -0.4927632 0.5781729 0.5717894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4497 4498 0.048276 0.103144 -0.042183 -0.5464506 -0.2852302 -0.7402432 0.2684689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4498 4499 -0.070000 -0.068917 -0.034893 -0.2392698 0.1657057 0.3366201 0.8955325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4499 4500 -0.071908 -0.115237 -0.113319 0.7118068 0.2378073 -0.6608389 0.0084104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4500 4501 -0.069830 -0.084621 -0.099338 -0.1959981 -0.1703878 0.2624544 0.9293387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4501 4502 0.155860 0.113011 -0.016297 -0.0378994 -0.3981699 -0.7281746 0.5565843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4502 4503 0.009251 -0.199060 -0.001061 -0.1870586 -0.1604563 -0.8093538 0.5331129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4503 4504 -0.094457 -0.040302 -0.047143 0.3141208 -0.2417303 0.9144339 0.0818850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4504 4505 -0.116747 0.070866 0.030799 -0.4100895 0.2648001 0.6892344 0.5354096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4505 4506 -0.014317 -0.205072 0.079932 0.2453492 -0.2655421 0.1524227 0.9198144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4506 4507 -0.014131 -0.013557 0.016729 -0.2478996 -0.6060906 0.5262459 0.5424622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4507 4508 -0.070141 -0.062251 -0.069770 0.4655326 0.3760773 0.3456523 0.7227515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4508 4509 0.034114 0.190076 0.126096 -0.0647627 -0.4111783 -0.8307365 0.3696148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4509 4510 0.176152 0.062642 0.052622 -0.0193203 0.1252031 0.3494303 0.9283584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4510 4511 0.011584 -0.134457 -0.070854 -0.1335731 0.0133131 -0.8310854 0.5397019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4511 4512 0.209912 0.141344 -0.016806 0.5484458 0.3637586 0.6149681 0.4343974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4512 4513 -0.103093 -0.182672 0.063081 -0.2928219 -0.8158100 -0.4843363 0.1188604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4513 4514 -0.000853 -0.185218 -0.139077 -0.1151907 -0.1593973 -0.0338038 0.9798882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4514 4515 -0.013404 -0.074791 0.014359 0.3407605 0.0113124 0.8733385 0.3478997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4515 4516 -0.110525 -0.049872 -0.010477 0.0649689 -0.1122543 0.9499069 0.2843500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4516 4517 -0.027693 0.111238 0.085637 -0.3784797 0.3957424 -0.8148451 0.1901803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4517 4518 0.068432 -0.071517 0.185317 0.1541211 -0.2248855 0.4639973 0.8428403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4518 4519 -0.199175 -0.025562 -0.015059 0.0528421 -0.1805290 0.6702990 0.7178553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4519 4520 -0.023343 -0.085830 -0.159011 -0.3626740 -0.1119009 -0.3481747 0.8571582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4520 4521 -0.081215 0.034576 -0.041711 0.6556092 0.2465716 0.2297244 0.6757261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4521 4522 0.081637 0.133013 -0.107815 -0.3818157 0.0348127 0.1929493 0.9032029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4522 4523 -0.078135 -0.032820 0.058709 -0.0395916 0.5182439 0.8314979 0.1961303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4523 4524 -0.046898 -0.119124 0.084494 0.2907848 0.3064071 0.0222708 0.9061252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4524 4525 -0.111986 0.034232 0.161712 -0.5903894 -0.4685697 -0.1820365 0.6314630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4525 4526 0.075676 0.125870 -0.186037 0.5497036 0.4362956 0.5521173 0.4501540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4526 4527 -0.008327 -0.066599 0.168089 -0.5695249 0.7343640 0.0845924 0.3594372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4527 4528 0.170659 -0.017554 -0.020669 0.4963904 -0.0448678 -0.8651001 0.0564374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4528 4529 -0.021415 -0.093501 0.110512 0.1281497 -0.1265701 0.6121089 0.7699873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4529 4530 0.035038 -0.053397 -0.150740 -0.6247977 0.5552915 0.0213201 0.5484749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4530 4531 -0.081905 0.122746 -0.139154 -0.3990196 -0.2045078 0.8403651 0.3045431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4531 4532 0.031992 -0.256686 -0.015110 -0.1813171 -0.6836283 0.4874269 0.5120464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4532 4533 0.154476 0.134521 -0.105374 -0.2452782 0.0359693 -0.5740046 0.7804253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4533 4534 0.024538 0.091978 -0.106427 -0.0259448 0.1134758 0.2585294 0.9589644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4534 4535 0.067666 0.099385 -0.159436 0.5918225 -0.1418927 0.7902375 0.0716746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4535 4536 0.033908 0.036703 -0.129057 -0.7693960 -0.0049784 -0.5468493 0.3300923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4536 4537 0.084688 -0.123492 -0.057131 0.0062717 0.4415511 0.1766754 0.8796471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4537 4538 -0.022631 0.045387 -0.052462 -0.4581796 0.4841031 0.2066227 0.7162560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4538 4539 0.006853 0.003514 -0.224088 0.5304829 -0.5130083 -0.5985758 0.3116366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4539 4540 -0.050785 0.070668 -0.101874 -0.4098151 0.3741058 -0.1064156 0.8250892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4540 4541 0.064514 -0.025656 -0.074428 -0.0629539 -0.1421648 -0.7857660 0.5986633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4541 4542 0.063997 0.100347 -0.058587 0.3724579 0.0482102 0.9117764 0.1661770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4542 4543 0.216302 -0.019424 0.033738 0.2293530 0.6754175 0.6271188 0.3129384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4543 4544 -0.006515 -0.082868 -0.017440 -0.0676098 0.0849139 0.3538548 0.9289808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4544 4545 0.053549 -0.087864 -0.050800 -0.2954924 0.0157819 0.7929966 0.5325332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4545 4546 0.011715 -0.094385 -0.028264 0.3878013 0.4142775 0.5719682 0.5923146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4546 4547 0.089423 0.115161 -0.027789 -0.0727750 0.4231419 0.4528297 0.7814090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4547 4548 -0.100547 0.053280 0.103670 -0.4721416 0.7609788 -0.1298509 0.4255964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4548 4549 0.127554 -0.148355 0.058320 -0.7954652 0.2460668 0.1675562 0.5278363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4549 4550 0.204858 0.073169 -0.003301 -0.8588435 -0.0096203 0.3170728 0.4021941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4550 4551 0.043579 -0.092817 0.102882 -0.3297337 -0.0198270 0.9355841 0.1247594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4551 4552 -0.120562 -0.146136 0.160836 -0.4854050 0.6069612 -0.1723901 0.6051956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4552 4553 -0.010671 -0.069440 0.079388 -0.0377875 -0.4890335 0.5707752 0.6585089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4553 4554 0.267180 -0.045330 0.008083 0.3170870 -0.3325781 -0.8519064 0.2512033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4554 4555 -0.181542 -0.114475 -0.026704 -0.2359514 -0.4737391 0.7765196 0.3419289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4555 4556 0.128657 0.125646 0.126212 0.1318738 0.3346450 0.5366035 0.7633339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4556 4557 0.146656 0.023876 0.222732 0.5639199 0.0647618 -0.8078011 0.1589265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4557 4558 0.068063 -0.113091 0.132310 -0.3409445 0.5058632 -0.5195695 0.5982531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4558 4559 0.114869 0.093177 0.001005 -0.1756929 -0.2199562 0.8250414 0.4899571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4559 4560 -0.110553 0.035404 -0.211567 0.0026900 -0.3701702 -0.7063766 0.6033232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4560 4561 -0.203258 -0.138975 -0.113442 0.2391726 0.3679482 0.8223221 0.3622112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4561 4562 0.038527 -0.099551 -0.025512 -0.1894749 0.5586943 0.7073473 0.3893837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4562 4563 0.003071 -0.129711 0.042207 0.1864890 0.4955900 0.2461015 0.8118167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4563 4564 -0.026185 -0.148645 0.069083 0.0739128 0.1462505 0.2097447 0.9639268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4564 4565 0.223364 -0.070131 0.221969 -0.2916587 0.0124392 -0.7174960 0.6324397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4565 4566 0.029455 0.088426 0.103840 0.4558708 -0.6808098 0.4777863 0.3168598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4566 4567 0.082660 -0.283454 -0.016664 -0.1661363 0.0065237 0.7383734 0.6535755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4567 4568 0.040758 0.057237 0.026693 0.2769878 0.0902322 -0.7551731 0.5872389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4568 4569 -0.068985 -0.059321 -0.185491 -0.3779643 -0.3380594 -0.8571166 0.0906089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4569 4570 0.059228 0.050778 0.201582 0.2715413 -0.4838014 -0.7950811 0.2450462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4570 4571 -0.068621 -0.030994 -0.042894 -0.3255138 0.5515093 0.0759430 0.7642715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4571 4572 0.050639 0.083637 0.137843 -0.5635191 -0.5757973 -0.2490326 0.5374817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4572 4573 0.030100 -0.103549 0.142157 -0.0869774 -0.1962942 -0.9758213 0.0409435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4573 4574 0.142687 -0.028888 -0.006063 0.2136899 -0.5777213 -0.7805597 0.1063070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4574 4575 -0.164413 0.094763 -0.257908 -0.6215872 0.4575013 0.5013070 0.3911690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4575 4576 -0.137856 0.133771 -0.048173 -0.8884507 -0.3818686 0.2288487 0.1116241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4576 4577 0.023191 0.015316 -0.041054 0.6320806 -0.3943731 -0.1004382 0.6594363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4577 4578 -0.018563 -0.131204 0.045389 0.4130274 0.4051203 0.7378407 0.3476736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4578 4579 -0.278488 0.144973 0.203980 -0.7399225 0.3294391 0.1411432 0.5692655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4579 4580 -0.253997 -0.017610 0.244781 -0.2038772 0.0200478 0.6894169 0.6947925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4580 4581 0.193632 -0.046023 -0.112631 0.3967093 -0.2594704 0.3555270 0.8055417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4581 4582 0.029757 0.220264 -0.004341 -0.3225753 0.1161198 -0.8306137 0.4387963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4582 4583 -0.157449 -0.034022 0.036784 -0.8685339 -0.1977924 0.4465869 0.0841856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4583 4584 0.016653 -0.059815 0.036985 0.7472146 -0.4341319 -0.2711788 0.4238655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4584 4585 -0.116745 -0.049989 0.081989 0.6740956 -0.5090656 -0.3829333 0.3739111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4585 4586 -0.174096 -0.018803 0.083999 -0.5514630 -0.4970392 0.6569374 0.1314300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4586 4587 0.125674 0.048675 -0.019491 0.2072468 0.2017240 0.0781344 0.9540709 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4587 4588 -0.082272 -0.153459 0.014072 -0.4882286 -0.2476153 0.8183696 0.1749017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4588 4589 0.067590 0.021626 0.214939 -0.6659193 0.2100434 0.7044535 0.1271951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4589 4590 -0.180174 0.303636 0.137380 -0.4550765 0.1616513 0.7259752 0.4896267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4590 4591 -0.076349 0.002842 0.034052 0.4655192 -0.6971658 -0.4441732 0.3161675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4591 4592 0.043033 0.086792 -0.170351 -0.1847622 0.5804179 0.0421640 0.7919597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4592 4593 0.039749 -0.025526 0.090824 -0.2327100 -0.2672414 0.5212837 0.7763320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4593 4594 0.016923 0.064049 0.079161 -0.0988632 0.3235892 -0.9410168 0.0018805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4594 4595 -0.046196 -0.067292 -0.057723 0.6391409 -0.2186438 0.3205568 0.6640310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4595 4596 0.023412 -0.013655 -0.029577 -0.3550184 -0.8773589 -0.2240130 0.2324253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4596 4597 0.021935 -0.160181 0.009090 0.2456411 0.8422768 0.3261148 0.3519650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4597 4598 -0.159750 -0.175930 0.116770 0.2769229 -0.1281590 0.4047219 0.8620262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4598 4599 0.038654 -0.152574 -0.036796 0.0327970 -0.7964804 -0.5547292 0.2383671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4599 4600 -0.182313 0.057593 0.137865 0.0516930 -0.4572459 -0.8251868 0.3275983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4600 4601 -0.099989 -0.054564 -0.045093 0.1547986 -0.6107161 0.5648501 0.5329236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4601 4602 0.064967 -0.085136 -0.037229 0.1949875 0.5023873 0.3919432 0.7456322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4602 4603 -0.069357 -0.158835 0.026254 0.1173273 -0.0889003 0.7405095 0.6557261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4603 4604 0.144336 0.024487 0.083320 -0.2531258 0.6523898 0.1033580 0.7068465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4604 4605 0.054785 0.120267 -0.181156 0.7970443 -0.4257496 -0.4045630 0.1406641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4605 4606 -0.062694 -0.047389 -0.076083 -0.6594720 -0.3658184 0.6323938 0.1770638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4606 4607 -0.157951 0.213793 0.004398 0.2788952 0.0348922 0.5638513 0.7765769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4607 4608 0.192136 0.037212 0.020149 -0.0059554 -0.8296667 -0.4379679 0.3461241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4608 4609 -0.117954 -0.057931 -0.076404 -0.5794541 0.4035101 -0.6369045 0.3094597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4609 4610 -0.072786 -0.119131 0.147549 0.0708794 -0.6666892 0.1943941 0.7160395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4610 4611 0.155943 0.175871 -0.062880 0.6257127 0.0093462 0.6900830 0.3635680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4611 4612 -0.063319 0.076147 -0.013754 -0.0400998 -0.1652429 0.9781540 0.1195895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4612 4613 0.167839 0.086765 -0.057626 0.5290234 0.4862196 -0.6876857 0.1039857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4613 4614 0.033437 0.047266 -0.056803 0.4176558 -0.4306397 0.4257576 0.6773799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4614 4615 0.066676 0.020476 0.122724 -0.5350100 -0.1395141 -0.2093709 0.8065135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4615 4616 0.142685 0.055391 0.108989 -0.0439706 -0.3410884 -0.7192119 0.6037049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4616 4617 0.082619 0.046727 -0.118724 0.1484755 0.3544574 0.3067280 0.8707657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4617 4618 0.164849 -0.091140 0.172283 0.2310252 0.4530407 0.6425566 0.5731514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4618 4619 0.086291 -0.078719 -0.091388 -0.0391729 0.6831012 0.7119671 0.1579272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4619 4620 0.102070 0.021374 -0.011241 -0.8223134 0.2964618 0.4834709 0.0465499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4620 4621 0.102993 0.052621 -0.031059 0.0667722 0.2057956 -0.5797274 0.7855608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4621 4622 -0.028231 -0.027084 0.231362 0.1076011 -0.5366125 0.4589095 0.6999079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4622 4623 0.166603 0.039044 -0.075180 0.2030486 0.2905514 0.6192961 0.7005879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4623 4624 -0.076506 -0.015777 0.078803 -0.2676978 -0.2740539 0.8566101 0.3456174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4624 4625 -0.016698 0.070802 -0.120811 -0.1064383 0.2737210 0.9368043 0.1901192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4625 4626 -0.019705 -0.048677 0.123643 -0.5096974 0.1849588 0.6650807 0.5134847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4626 4627 0.018972 -0.010390 0.072620 0.2145522 0.3836051 0.7699421 0.4626053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4627 4628 0.059876 0.017376 0.014565 0.3044657 0.7533714 0.5303384 0.2418127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4628 4629 0.181352 -0.062741 -0.073406 -0.5311285 0.6940305 0.3484101 0.3388725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4629 4630 0.004258 -0.024910 0.023114 0.3641530 0.2338778 -0.4675009 0.7708027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4630 4631 0.133005 -0.145111 -0.046430 0.4991942 0.0481164 0.4225348 0.7549532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4631 4632 0.072967 -0.027337 0.119516 -0.5875533 -0.5451885 0.5358844 0.2652895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4632 4633 0.125078 -0.065167 0.011121 0.4429003 0.4670984 0.7293368 0.2317889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4633 4634 0.096187 0.022541 -0.152623 -0.8597656 0.0842514 0.0306126 0.5027601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4634 4635 0.034791 0.052959 0.200382 0.4776852 -0.5253270 0.2301453 0.6654934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4635 4636 -0.152990 0.138644 0.104008 0.2802722 -0.1150493 -0.4589941 0.8351859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4636 4637 -0.102257 -0.226175 -0.238263 -0.5220110 -0.2911117 0.6154311 0.5138123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4637 4638 0.141802 0.173032 -0.124726 0.5497215 -0.0779887 0.7861573 0.2714419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4638 4639 -0.018024 -0.256428 -0.112315 0.0805476 -0.2020507 -0.9758312 0.0210034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4639 4640 -0.068258 -0.123912 -0.097336 -0.4437143 -0.2114300 -0.0660346 0.8683631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4640 4641 0.120289 0.237413 0.058825 0.7206082 0.0430085 -0.0742314 0.6880144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4641 4642 -0.042598 -0.101308 -0.070127 -0.2920551 -0.2783571 0.5858048 0.7028897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4642 4643 0.040877 -0.084498 0.065230 0.5442016 0.7137597 -0.0551957 0.4374301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4643 4644 0.036096 -0.139068 0.036112 0.0619926 -0.0842017 0.5021685 0.8584252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4644 4645 0.052987 -0.031941 0.061726 -0.3811402 -0.4978425 -0.3963773 0.6706490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4645 4646 0.002329 -0.269204 0.129762 -0.4063903 0.2446506 0.6876320 0.5496864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4646 4647 0.010904 -0.033375 -0.161758 0.6463008 0.2157842 0.4704936 0.5606855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4647 4648 -0.135195 -0.224367 0.146910 -0.0226916 -0.5588943 -0.2107689 0.8016849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4648 4649 0.082501 0.077346 0.078192 -0.1485934 0.2302230 0.9405214 0.2008404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4649 4650 0.063416 0.018397 0.033379 0.1947346 0.7485000 -0.6324547 0.0427456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4650 4651 0.120166 -0.003079 -0.180876 0.7303654 -0.4183397 -0.2461867 0.4805729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4651 4652 -0.153211 -0.005411 -0.013378 0.2221992 0.0849538 0.6617780 0.7109573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4652 4653 0.092805 -0.122015 -0.079129 -0.3590219 0.2313572 0.8700430 0.2461753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4653 4654 0.092643 -0.035869 -0.001778 0.6524083 -0.5979429 -0.3228011 0.3355996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4654 4655 -0.077983 0.207526 -0.084537 -0.6406628 0.3360202 0.1286093 0.6783076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4655 4656 -0.132166 0.027765 0.006494 -0.4671263 -0.0671133 0.8681479 0.1536491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4656 4657 0.090880 -0.239627 -0.143176 -0.1693671 -0.4663046 -0.8067303 0.3210312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4657 4658 -0.155689 0.117916 0.017958 0.5302731 0.4767438 -0.5657628 0.4140510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4658 4659 0.142995 -0.138773 0.021077 -0.5306755 -0.2608532 0.5630665 0.5773172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4659 4660 0.141316 -0.012636 -0.071467 -0.1300397 0.4200495 -0.8287615 0.3461249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4660 4661 -0.101065 0.136385 -0.047307 -0.5117291 0.0547637 0.7990341 0.3109320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4661 4662 0.039965 0.100738 0.069040 -0.5470086 -0.3316037 -0.0469813 0.7672114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4662 4663 -0.099803 0.072054 -0.008091 0.1928462 0.8655552 -0.4578558 0.0631873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4663 4664 -0.231454 0.024028 0.025524 0.8156614 0.4482749 -0.3028117 0.2050639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4664 4665 0.003828 -0.213887 -0.015282 0.3748221 -0.1099417 0.0641677 0.9183157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4665 4666 -0.036108 -0.182583 0.073206 -0.5648757 -0.3710469 -0.6551221 0.3377198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4666 4667 0.006775 0.133782 0.033405 0.5705904 0.5064368 0.4317883 0.4811520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4667 4668 0.020796 -0.060863 -0.098861 -0.1696546 -0.7020535 -0.0245430 0.6911844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4668 4669 -0.063145 -0.052153 -0.060845 -0.2861781 0.1685256 0.9065772 0.2604208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4669 4670 0.174783 0.008674 -0.123682 0.1214702 -0.5574956 0.5771909 0.5842041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4670 4671 0.019548 -0.070734 -0.087208 -0.4173698 -0.1604508 -0.6113006 0.6529698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4671 4672 -0.134223 0.197882 -0.038122 -0.1072181 -0.2669398 0.1201341 0.9501659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4672 4673 -0.143845 0.121849 0.046898 0.0300913 -0.0669847 -0.1930060 0.9784458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4673 4674 0.049646 0.037714 -0.054378 0.5315079 0.2085171 0.7659357 0.2955715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4674 4675 0.153284 0.204620 0.123099 -0.4782044 0.3073449 0.4181227 0.7085429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4675 4676 -0.040287 -0.044474 -0.143546 0.5355744 0.2766864 -0.6635706 0.4430335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4676 4677 0.116519 0.062003 -0.033416 0.2110046 0.5359675 0.5648744 0.5908746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4677 4678 0.033899 0.157023 0.081450 -0.1818331 0.0103716 -0.9220589 0.3415210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4678 4679 0.034907 -0.005676 0.169204 0.5987470 -0.0080153 -0.0581799 0.7987821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4679 4680 -0.081418 0.025778 -0.020270 -0.3805369 -0.1710772 0.1824487 0.8903015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4680 4681 -0.026395 -0.012739 -0.042930 0.1380969 0.7585780 -0.6313324 0.0831145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4681 4682 -0.057791 0.068306 0.055544 0.2533642 0.4159858 -0.8145013 0.3151985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4682 4683 -0.098232 -0.094021 0.081272 -0.4889355 -0.5781519 0.5662538 0.3256365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4683 4684 -0.028114 -0.092904 -0.023043 -0.5112763 -0.7232455 0.3720384 0.2776688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4684 4685 -0.075356 0.013808 -0.027149 0.1194992 -0.7139387 -0.3597318 0.5887312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4685 4686 0.138961 -0.143806 0.228838 0.2777336 0.7636201 0.5455756 0.2051723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4686 4687 0.028717 0.113541 -0.079319 -0.6584726 -0.1979758 0.7022206 0.1846772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4687 4688 -0.023428 0.182931 -0.018978 -0.5847424 0.6789015 -0.4439196 0.0102254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4688 4689 0.170277 -0.020480 -0.021595 0.4204397 0.1874804 0.7187385 0.5210533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4689 4690 -0.103744 0.066206 0.035355 0.1907371 -0.1486711 0.1369498 0.9606045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4690 4691 0.072988 0.032687 0.013891 0.0558505 -0.2885592 -0.2126183 0.9318840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4691 4692 -0.016789 0.150127 -0.043618 -0.5434799 0.0716380 0.8314898 0.0901239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4692 4693 -0.029768 -0.078824 0.214321 -0.7034527 -0.6047721 0.1199819 0.3535666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4693 4694 -0.178771 -0.159308 -0.164904 0.6853826 -0.0725922 -0.0078037 0.7245137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4694 4695 -0.067138 0.098782 0.272129 0.6725363 -0.1559124 -0.5109385 0.5121797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4695 4696 0.054235 -0.166463 0.070875 -0.0648761 0.6609646 0.6846736 0.3002315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4696 4697 0.108948 0.140714 0.153823 0.0943049 0.4389727 0.5203818 0.7263693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4697 4698 0.107909 -0.101140 0.092389 0.4298702 -0.0888408 -0.8889816 0.1305018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4698 4699 0.039570 0.043672 -0.146228 0.3313582 0.5318193 -0.7775012 0.0534962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4699 4700 -0.118715 -0.032904 0.075915 -0.6010200 0.5242757 -0.5803606 0.1645951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4700 4701 0.113560 -0.133180 0.159904 -0.0808154 0.1000831 -0.1299691 0.9831380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4701 4702 0.063201 -0.060353 -0.024826 -0.6014261 0.1917670 -0.7177744 0.2937890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4702 4703 -0.062750 0.151238 0.092553 0.6696231 -0.1413607 -0.2437248 0.6871828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4703 4704 0.014079 -0.031917 -0.116360 -0.1782140 -0.0630942 -0.3975856 0.8978778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4704 4705 0.018686 0.103710 0.174771 -0.8297621 -0.4495460 -0.1604216 0.2892544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4705 4706 -0.030803 -0.077902 -0.000350 0.2525652 0.0858181 0.9191575 0.2898198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4706 4707 -0.030179 0.071072 0.045018 -0.2335726 -0.6301970 -0.5391130 0.5075950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4707 4708 0.131115 0.272912 0.136217 0.5905348 -0.0006682 0.5051741 0.6293388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4708 4709 -0.029878 0.174323 0.033835 -0.0562590 -0.0008501 -0.9941089 0.0926371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4709 4710 0.025529 -0.089678 0.064200 -0.1511657 -0.1104712 -0.5879447 0.7869346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4710 4711 -0.001879 -0.068178 -0.072476 0.0379453 0.2188053 0.6987042 0.6800712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4711 4712 -0.182647 -0.110611 0.056324 -0.4449263 -0.5616004 0.2460480 0.6527680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4712 4713 0.055863 0.026928 0.172114 -0.0957623 -0.4068641 0.5842921 0.6956248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4713 4714 -0.104100 -0.036142 -0.120345 0.3074558 -0.6584913 -0.0538061 0.6848103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4714 4715 0.028058 0.048646 0.050279 -0.1729858 -0.0227059 -0.6564928 0.7338785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4715 4716 0.081286 0.013518 0.038237 -0.0792728 -0.1230450 -0.7936214 0.5905429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4716 4717 -0.000832 0.068657 -0.047432 0.0446882 -0.8070420 0.2149882 0.5481479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4717 4718 0.048458 -0.035308 0.004884 0.1729144 0.3730221 0.3074893 0.8581407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4718 4719 -0.072497 -0.243849 0.071314 0.6560220 0.5915094 0.4553267 0.1114870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4719 4720 -0.158960 -0.002144 -0.147498 0.4001696 -0.1934247 -0.8894377 0.1065443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4720 4721 -0.076318 0.058142 0.025295 0.9553023 0.1145058 -0.1274348 0.2409282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4721 4722 0.019306 -0.121177 -0.147312 0.2401181 -0.4845519 -0.6846271 0.4887111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4722 4723 -0.065748 0.041028 -0.074629 -0.2602138 0.3280728 -0.8029127 0.4242501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4723 4724 0.006019 -0.201217 -0.155795 0.1679598 -0.5391218 0.7580794 0.3262711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4724 4725 -0.073488 0.004227 0.037882 0.3898469 0.4358838 -0.7517150 0.3048758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4725 4726 -0.049227 -0.227900 -0.013566 -0.0402383 0.4722375 -0.8636851 0.1715243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4726 4727 0.053963 0.089707 -0.146646 -0.0359425 -0.0168415 0.9987365 0.0308217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4727 4728 -0.058514 0.095673 -0.037193 -0.1196744 0.5170897 0.5840811 0.6141218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4728 4729 0.012365 -0.048368 0.105473 -0.5148983 0.4556924 0.0143106 0.7259610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4729 4730 -0.057375 0.091018 0.044888 0.5523470 0.3102861 0.0079884 0.7736740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4730 4731 0.004672 0.040101 -0.022575 -0.1155450 0.4502545 0.8265309 0.3174380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4731 4732 0.096853 -0.030503 -0.006876 -0.6998653 0.1010563 -0.2385551 0.6656333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4732 4733 0.069001 0.062364 -0.152896 -0.5335431 0.2411787 -0.4553148 0.6707108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4733 4734 -0.106392 0.040484 0.044970 0.4019126 0.2435318 -0.6475197 0.5998973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4734 4735 -0.122056 -0.039999 0.038380 -0.9390182 0.1557589 0.1317537 0.2768121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4735 4736 0.130085 0.045380 -0.037241 0.5495829 -0.3728712 0.1140976 0.7388555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4736 4737 -0.024909 0.116187 0.098714 -0.7588151 0.3102324 0.2221956 0.5278112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4737 4738 0.070663 0.022083 -0.057550 -0.7551560 0.2605329 0.6001075 0.0416298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4738 4739 0.036965 -0.165151 -0.164721 -0.3712741 -0.0727104 -0.2570374 0.8892697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4739 4740 -0.105755 -0.093000 0.006106 -0.3971856 -0.3647583 0.1571877 0.8273373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4740 4741 0.158380 0.015837 0.081049 0.2041698 0.6349187 0.4400265 0.6013066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4741 4742 0.134300 -0.245878 -0.184686 0.0076272 -0.2331153 -0.1753302 0.9564823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4742 4743 -0.091347 -0.115433 0.091717 -0.5702676 0.3041180 0.6515624 0.3972073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4743 4744 -0.009286 -0.017850 0.002623 0.5813067 -0.7086787 -0.2382145 0.3211088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4744 4745 0.095490 -0.021002 0.021372 -0.5087302 -0.4533936 -0.7314615 0.0243300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4745 4746 0.025454 0.189727 -0.250122 0.8224362 0.0677411 0.0406867 0.5633422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4746 4747 0.055626 -0.125810 0.015459 -0.3339191 -0.0381033 0.5316294 0.7774422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4747 4748 -0.053105 0.081630 -0.027020 0.1455863 0.2465671 -0.5295693 0.7984771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4748 4749 -0.092167 -0.007630 0.078132 -0.2967210 -0.3452063 -0.5474543 0.7021987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4749 4750 -0.009884 -0.165016 -0.160874 -0.3892653 0.5927211 -0.0916346 0.6991118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4750 4751 0.029344 0.068841 0.078285 0.1107732 0.3011126 -0.7929059 0.5180355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4751 4752 -0.112380 0.102978 -0.179429 0.6167662 -0.4324187 0.1332252 0.6440998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4752 4753 -0.144379 0.109449 -0.156930 -0.8422286 -0.1574630 -0.5121963 0.0592568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4753 4754 0.030308 -0.120462 -0.050913 0.2848148 0.2314538 -0.7072138 0.6042833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4754 4755 0.044105 -0.042358 -0.186869 -0.0056115 0.9274753 0.3186141 0.1955583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4755 4756 0.052364 -0.119074 -0.094372 0.3376430 0.7176226 0.2972422 0.5316598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4756 4757 0.059128 0.024355 -0.054582 0.0104778 -0.3503471 -0.1828448 0.9185395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4757 4758 -0.062524 0.064877 -0.115624 -0.2748829 0.1667933 -0.7746203 0.5445942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4758 4759 0.158705 0.010340 -0.058792 0.0737934 0.0196277 0.1950088 0.9778245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4759 4760 0.073566 0.033333 -0.113234 0.0446029 -0.5018198 -0.8404469 0.1995907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4760 4761 0.009965 0.164025 -0.007157 0.2771543 0.1601677 -0.1241047 0.9392177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4761 4762 0.021077 0.054782 -0.032791 0.5662418 0.4637943 0.5747786 0.3659161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4762 4763 0.177502 -0.139709 -0.128204 0.4075205 0.4564421 0.7192322 0.3290786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4763 4764 0.172616 -0.100023 -0.035708 -0.6197514 -0.3218110 0.4050724 0.5901375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4764 4765 0.092789 -0.080853 -0.048369 0.7116792 0.4186760 0.4778006 0.2998828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4765 4766 0.228517 0.079689 0.133317 -0.6830950 -0.3425807 0.5206696 0.3806872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4766 4767 -0.161366 0.003070 -0.167187 0.5855861 0.1248767 -0.7362899 0.3152330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4767 4768 0.085259 -0.034340 -0.218310 -0.5142040 -0.1736408 -0.3928415 0.7423737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4768 4769 -0.092282 -0.024120 -0.033008 0.0558783 -0.4257872 -0.0137705 0.9029913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4769 4770 -0.050715 0.086037 0.168140 0.0738634 -0.2585266 -0.8808251 0.3896862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4770 4771 -0.326580 0.114089 0.053494 -0.3578954 0.3458379 -0.0981201 0.8617885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4771 4772 0.033688 -0.080008 -0.195009 -0.3779905 0.3806851 0.4034874 0.7412152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4772 4773 0.104559 -0.106957 -0.183508 -0.0283182 -0.0164864 -0.9315698 0.3620828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4773 4774 0.077407 0.104991 -0.118496 0.3585030 0.7734690 -0.4819199 0.2024218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4774 4775 -0.003164 0.004546 -0.136995 0.7716393 0.0771481 -0.6306157 0.0307373 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4775 4776 -0.125679 -0.046917 -0.088726 0.3881027 -0.0564341 -0.5482135 0.7386836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4776 4777 -0.007964 -0.127825 -0.008739 0.3410943 -0.7336250 0.0875789 0.5811876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4777 4778 -0.032160 -0.021869 0.078730 0.3358861 0.1784814 0.8872466 0.2609949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4778 4779 -0.135272 -0.069763 -0.112517 -0.2769441 0.0793443 -0.7174614 0.6342363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4779 4780 0.142459 -0.167827 0.090416 -0.4691545 -0.1357468 -0.8450616 0.2175724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4780 4781 0.063349 0.100450 0.115856 -0.6608378 0.0510891 -0.2813634 0.6939149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4781 4782 0.175708 0.082106 0.085552 0.1663514 -0.5055209 0.7534059 0.3862064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4782 4783 0.068537 0.026178 0.112119 -0.0227602 -0.0060533 -0.7904537 0.6120688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4783 4784 0.081439 0.129152 -0.135439 0.1924892 0.0858463 0.0479515 0.9763601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4784 4785 0.048345 0.041947 0.075261 -0.6984565 -0.4142759 -0.5506388 0.1932120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4785 4786 0.176127 0.064854 0.090391 0.0148738 -0.1014489 -0.5933417 0.7983937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4786 4787 -0.002372 0.103793 -0.012399 -0.7651817 -0.1656533 -0.2943801 0.5480842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4787 4788 0.052126 -0.107907 -0.005337 -0.3573158 0.2816890 -0.0111300 0.8904229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4788 4789 0.175280 0.040554 0.113747 0.7200582 -0.2674476 -0.5131410 0.3829808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4789 4790 -0.134371 0.207934 0.049065 -0.1846083 0.1734293 -0.3074106 0.9172463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4790 4791 0.102609 0.122205 0.018443 -0.5152913 -0.3760533 -0.7696918 0.0251659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4791 4792 -0.061275 -0.056471 -0.042788 0.6556838 0.1481583 0.5704259 0.4719557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4792 4793 0.021669 -0.016116 0.211745 0.4168265 0.2483023 0.3130221 0.8164673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4793 4794 0.044700 -0.022031 0.137134 -0.5709818 -0.4956933 -0.6415903 0.1289571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4794 4795 -0.100970 -0.094670 0.191192 0.1739258 -0.1987880 0.8125247 0.5196506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4795 4796 0.010895 0.113846 0.081276 0.1732160 0.2084580 -0.9371920 0.2195739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4796 4797 0.241324 -0.008882 -0.124661 0.0041255 0.3983087 -0.1713026 0.9011041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4797 4798 0.142058 0.129264 0.134058 -0.5709496 -0.6552791 0.4787345 0.1242542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4798 4799 -0.093862 0.076435 0.071469 0.7786618 -0.2203399 -0.3361375 0.4818170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4799 4800 -0.003447 -0.145191 -0.150705 0.1410216 0.1056755 0.9224080 0.3436699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4800 4801 0.098457 -0.186357 -0.060431 0.6932392 -0.4369416 -0.3317323 0.4673917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4801 4802 0.001009 0.033287 0.230547 -0.6300766 0.7005913 -0.0145398 0.3346099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4802 4803 -0.136105 -0.106339 -0.041892 0.7110811 0.1871320 0.1586835 0.6589119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4803 4804 0.015799 0.099513 0.042611 -0.6626655 0.2989605 0.1791026 0.6628871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4804 4805 -0.058627 -0.023486 0.106055 -0.7426139 -0.2688944 0.4475794 0.4193961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4805 4806 0.132306 0.112325 0.056292 0.4105449 -0.7522343 0.5062641 0.0964007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4806 4807 0.150852 -0.007669 -0.089764 -0.7963098 -0.0869625 -0.4883075 0.3462428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4807 4808 -0.014060 0.192848 0.110513 0.0430689 -0.9726014 -0.2269094 0.0265253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4808 4809 -0.033875 -0.045704 0.066643 -0.5637501 0.0518986 0.8162947 0.1146963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4809 4810 -0.112206 0.006995 -0.038755 0.7117971 0.2655818 0.2431058 0.6030844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4810 4811 -0.075254 0.029497 -0.001955 0.6839795 0.2188065 0.6874124 0.1084439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4811 4812 0.164637 -0.018761 0.038005 0.3301337 0.0100327 0.7943342 0.5098473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4812 4813 -0.009275 0.147458 -0.042754 -0.4949407 -0.4376031 0.2907868 0.6920840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4813 4814 0.174432 0.096842 -0.090422 0.7895375 -0.1510489 0.1381797 0.5785509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4814 4815 -0.321768 0.213935 -0.010767 0.0897931 -0.1361940 0.0455564 0.9855521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4815 4816 -0.107563 -0.044778 -0.050690 -0.1380214 0.8411652 0.5090544 0.1193937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4816 4817 0.005646 0.008073 0.121202 -0.0919363 -0.1925089 0.2589012 0.9420500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4817 4818 -0.100351 -0.142495 0.028487 0.0413687 0.7900567 0.4092792 0.4545212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4818 4819 0.002633 -0.047408 -0.062105 0.2414678 -0.5431684 -0.5504337 0.5862458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4819 4820 -0.049173 0.019232 0.180422 -0.6297106 0.0357946 -0.3027537 0.7145092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4820 4821 0.100331 -0.050681 0.218428 0.3887119 0.2180553 0.6972208 0.5614606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4821 4822 -0.001465 0.037233 -0.094550 -0.9711706 0.2263033 0.0648541 0.0375302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4822 4823 -0.176590 -0.076395 0.039101 -0.2318951 -0.5230394 0.3436550 0.7446849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4823 4824 -0.146974 -0.043791 0.063404 0.3634319 -0.5679536 -0.5734330 0.4653176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4824 4825 0.060997 0.060843 -0.050943 -0.5054124 0.3837855 -0.4469841 0.6304540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4825 4826 -0.181269 0.137862 0.049491 0.7436312 0.1783372 -0.1191822 0.6332489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4826 4827 -0.006623 -0.217488 -0.155623 -0.1247065 0.4992982 0.6818488 0.5198383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4827 4828 0.002132 -0.273509 -0.134780 -0.5205465 -0.6543009 -0.4318742 0.3382401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4828 4829 -0.103908 -0.061705 0.065234 -0.6308391 0.0058458 -0.7653188 0.1276516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4829 4830 -0.007277 -0.087931 -0.224749 0.1745411 0.1707693 -0.0731082 0.9669687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4830 4831 0.297095 -0.147476 -0.250742 0.2129917 0.0699294 0.8324007 0.5068071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4831 4832 0.116840 0.047578 0.010523 -0.3036207 0.3022907 -0.7311178 0.5309440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4832 4833 -0.067101 0.260808 0.000594 -0.0256279 -0.0773606 -0.9018697 0.4242519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4833 4834 -0.201483 0.099601 -0.130041 -0.4516067 0.5697739 0.3916356 0.5639420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4834 4835 0.033113 0.089908 0.023268 0.1304194 0.0767211 0.6116290 0.7765402 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4835 4836 0.004261 0.016199 0.099856 0.1008328 -0.6114080 -0.5823412 0.5262050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4836 4837 0.050613 0.127305 -0.059851 0.2095690 -0.1405668 -0.5393122 0.8034078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4837 4838 -0.087779 0.079504 0.025386 0.0208270 -0.5289064 -0.6204519 0.5786742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4838 4839 -0.017502 -0.108596 0.031436 -0.5016582 -0.3032924 -0.2500410 0.7706051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4839 4840 0.065141 0.089238 -0.185388 0.4560672 0.7685443 -0.0421144 0.4467312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4840 4841 0.171681 0.112616 0.050920 0.0942055 -0.2575533 -0.6504351 0.7083260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4841 4842 0.242896 0.126012 -0.050813 -0.1865448 -0.9263303 0.3192036 0.0722651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4842 4843 0.065006 0.094005 -0.230039 0.3973544 -0.3827755 0.5833088 0.5961068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4843 4844 -0.041580 0.119199 0.048188 0.2041521 0.6033615 -0.1678499 0.7523983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4844 4845 0.125360 0.136904 0.097086 -0.2562728 0.0717966 0.7035394 0.6589400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4845 4846 -0.041837 -0.026991 -0.003097 -0.3599665 -0.1719330 0.8272305 0.3956675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4846 4847 -0.149254 0.231861 -0.035560 -0.1456435 0.2003321 0.6206933 0.7439051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4847 4848 0.119330 0.260298 -0.071532 -0.1029340 0.4252794 -0.8970693 0.0617145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4848 4849 -0.054575 -0.003810 -0.113191 -0.1494105 0.6304885 -0.3259185 0.6884314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4849 4850 -0.008751 -0.141172 0.046070 -0.2928188 -0.6229915 0.2882826 0.6656064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4850 4851 -0.047914 0.107368 -0.123563 0.6461542 0.0738292 -0.4825747 0.5866478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4851 4852 0.073108 0.020072 -0.059096 -0.7085634 -0.4053661 0.0528667 0.5751707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4852 4853 0.122798 0.058837 0.013843 0.5901138 0.1715046 -0.1887214 0.7659870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4853 4854 0.044053 -0.027854 -0.025543 0.2034516 0.0452144 0.9435245 0.2575358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4854 4855 -0.084539 0.139096 -0.173112 -0.1982695 0.6358755 -0.0704446 0.7425558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4855 4856 0.219159 0.087594 -0.043135 0.0520628 -0.0215399 -0.4391890 0.8966262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4856 4857 -0.002525 0.009182 -0.008817 0.1773215 0.7315349 -0.2073886 0.6248230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4857 4858 0.099097 0.060261 0.136759 -0.3267062 -0.0430213 0.7495350 0.5741162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4858 4859 0.136499 -0.151445 -0.102710 -0.2537710 -0.5953991 -0.0788830 0.7582069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4859 4860 -0.008782 -0.147602 -0.167899 0.2131757 -0.1358771 0.9318919 0.2601366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4860 4861 -0.114173 0.072534 -0.073059 0.0859840 -0.3196109 0.1463732 0.9322181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4861 4862 -0.043785 -0.153609 -0.147662 -0.0996338 0.5696748 -0.3224360 0.7493856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4862 4863 -0.081412 -0.069400 0.053647 -0.4688331 -0.3651028 0.6140167 0.5194987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4863 4864 -0.081919 0.043939 -0.083680 0.1357143 0.5986727 -0.6853883 0.3916830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4864 4865 -0.023342 0.053925 0.134890 -0.0800154 -0.1631002 0.9329679 0.3107519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4865 4866 0.050858 0.096509 0.047520 0.3247158 0.0775025 -0.6372547 0.6945930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4866 4867 -0.041916 0.103703 -0.157605 -0.1391971 -0.5750529 0.7635393 0.2587394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4867 4868 0.029948 0.004012 -0.128648 0.5056149 -0.1563119 -0.0160640 0.8483290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4868 4869 -0.077140 -0.002467 -0.039860 -0.4944435 -0.3693998 -0.3294898 0.7144970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4869 4870 -0.054388 0.042200 -0.120403 -0.0968228 0.1749324 0.9591063 0.2003476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4870 4871 0.020643 0.044071 -0.122985 -0.1203789 -0.1358810 -0.9768287 0.1133620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4871 4872 0.031286 0.142640 -0.042796 0.3636276 0.8897054 0.1237582 0.2467451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4872 4873 -0.026365 -0.116498 0.098143 -0.2717916 0.6251105 0.5903299 0.4322923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4873 4874 -0.058048 -0.049202 -0.075493 0.5133104 -0.0092586 -0.4966596 0.6998257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4874 4875 -0.007737 -0.011880 0.118573 -0.5861189 0.2834741 0.5935160 0.4731235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4875 4876 0.040521 -0.017380 0.020155 -0.3762974 0.2865102 0.6713643 0.5705981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4876 4877 0.115047 -0.020707 0.060120 0.5350612 -0.0075049 -0.5582476 0.6340448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4877 4878 -0.008554 -0.089773 -0.079899 0.2594836 -0.5583697 0.2655748 0.7418636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4878 4879 -0.036405 0.061032 0.085542 -0.6072925 -0.4274952 -0.6687708 0.0344867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4879 4880 0.069821 -0.089592 -0.082743 -0.7215001 0.0746190 -0.2140210 0.6542664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4880 4881 0.163658 0.187772 0.232601 0.2427903 -0.2064570 -0.7652140 0.5593532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4881 4882 0.108827 0.218195 0.210228 -0.7630110 -0.3276413 -0.5566892 0.0237164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4882 4883 0.036009 -0.025985 -0.179632 0.0819666 -0.1829735 -0.6009605 0.7737239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4883 4884 0.056566 -0.051766 -0.145843 -0.1839440 0.4678858 -0.3756355 0.7785534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4884 4885 0.033043 0.110019 0.233272 -0.0577889 -0.7537198 -0.5034196 0.4184922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4885 4886 0.173559 0.144893 -0.172909 0.0604645 -0.2801103 -0.1949410 0.9380193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4886 4887 0.070256 0.041403 -0.068892 -0.6723315 0.3780689 0.2126073 0.5998603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4887 4888 -0.000150 -0.055150 0.036947 -0.2476071 0.4228688 -0.6008369 0.6315597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4888 4889 0.232941 -0.071449 -0.020666 0.2381358 0.8619194 -0.1794895 0.4100851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4889 4890 -0.026780 0.033356 -0.050987 -0.3011630 0.0243236 0.8850852 0.3540245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4890 4891 -0.062385 0.121778 -0.134218 -0.5024042 -0.1526499 0.8493865 0.0532041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4891 4892 0.085540 -0.121128 0.011563 0.7803668 0.1471957 -0.4914756 0.3575093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4892 4893 0.086331 0.044647 0.028797 -0.5594619 -0.0928600 -0.7954455 0.2136489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4893 4894 0.188504 -0.170259 0.024057 0.2697940 0.1755398 0.8401386 0.4365364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4894 4895 -0.096885 0.025279 -0.041969 0.0680394 0.1043708 0.9876592 0.0949038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4895 4896 0.050502 -0.080919 -0.010161 0.2090400 0.5828157 0.7415045 0.2584552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4896 4897 -0.010941 -0.016955 0.010541 0.0717220 -0.0023947 -0.5748606 0.8150984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4897 4898 -0.037321 -0.143361 0.083884 -0.6504585 -0.4957760 0.3104468 0.4844923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4898 4899 -0.161090 0.155978 -0.025137 0.7710283 -0.5744952 -0.1546914 0.2270270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4899 4900 0.070886 -0.002059 -0.010687 -0.8984860 -0.3101213 -0.3088804 0.0337729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4900 4901 0.112541 0.141431 -0.015284 -0.2932744 -0.2627139 -0.6907845 0.6064556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4901 4902 0.068413 0.013976 0.240355 -0.7361649 0.2174790 -0.1313190 0.6273113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4902 4903 -0.023491 0.126058 0.048638 0.2191324 -0.2100746 0.9493400 0.0812606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4903 4904 0.100308 -0.074768 -0.114010 0.4154785 -0.0109109 -0.1429978 0.8982261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4904 4905 0.126271 0.121616 0.138941 -0.8870824 -0.0619868 -0.1987095 0.4120157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4905 4906 0.009219 -0.224842 -0.018092 -0.2592755 0.2943769 -0.6811914 0.6181398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4906 4907 0.053720 0.076238 0.008731 0.1564793 -0.1375411 0.5249349 0.8252515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4907 4908 0.007162 0.034658 0.052938 -0.1380535 0.0527593 0.3853985 0.9108379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4908 4909 -0.014646 -0.102937 0.218870 -0.5106306 -0.0040816 -0.8597664 0.0064447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4909 4910 0.145042 0.116331 -0.052984 -0.4538327 0.8711718 0.1697430 0.0792648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4910 4911 -0.012837 0.199432 -0.012964 -0.7565060 0.1572198 0.6132962 0.1638548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4911 4912 0.097848 0.109525 0.149453 -0.5012882 -0.1040390 -0.0617029 0.8567840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4912 4913 0.047892 -0.068841 0.100438 0.2206109 0.5368215 -0.2870455 0.7620751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4913 4914 -0.079814 0.020342 -0.009592 -0.2501273 -0.4281210 0.2898814 0.8186071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4914 4915 -0.034605 0.167066 0.045908 0.0544021 -0.3858497 -0.3962902 0.8313330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4915 4916 0.041875 -0.009389 0.079092 0.4023490 0.3817721 0.8073558 0.2013503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4916 4917 0.086866 0.145692 0.007218 -0.5033598 -0.6927795 -0.3825246 0.3469299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4917 4918 0.256495 0.016302 -0.027481 -0.4812160 0.6059294 -0.3555654 0.5242652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4918 4919 0.005827 0.186767 0.203792 -0.0621269 -0.5202717 0.7052659 0.4775538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4919 4920 -0.161281 -0.000891 -0.047045 0.0974791 0.0221558 0.9903399 0.0960930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4920 4921 0.014299 -0.060547 0.170458 0.4196318 0.8431013 0.3233320 0.0924435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4921 4922 0.093975 0.019534 0.078195 -0.5379326 -0.7006474 -0.4080330 0.2307181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4922 4923 0.020375 -0.034266 0.072919 0.3389809 0.1857938 -0.2865622 0.8766155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4923 4924 -0.134312 -0.101373 -0.043716 -0.4249477 0.3637973 0.7514742 0.3497964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4924 4925 0.163971 0.262668 0.011323 0.6412075 -0.2440349 -0.5248869 0.5037794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4925 4926 -0.025530 0.081166 -0.138736 -0.9196696 0.1566703 -0.3153081 0.1739054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4926 4927 -0.104399 0.044194 -0.012772 -0.0099815 -0.6715111 0.2113879 0.7101326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4927 4928 -0.035326 0.086982 0.104739 0.7821620 -0.3478734 0.4610986 0.2336553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4928 4929 0.027310 0.090250 0.118486 -0.6363951 0.0720610 0.1596125 0.7512205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4929 4930 -0.032214 0.011057 -0.031116 0.8957390 0.2009005 0.3644469 0.1564260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4930 4931 -0.093592 -0.059116 0.211900 0.5782801 0.6125477 0.4764073 0.2518203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4931 4932 0.131338 0.022549 0.066868 0.0720861 0.3311153 -0.1307196 0.9317074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4932 4933 0.053584 0.070335 -0.173971 -0.7446830 0.0600496 0.4921886 0.4467568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4933 4934 0.105977 0.001559 -0.094503 -0.1529290 0.2019039 -0.9672405 0.0171270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4934 4935 0.012318 -0.102748 -0.022931 0.2555969 0.3138401 0.8744157 0.2675290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4935 4936 -0.130218 0.070371 0.048344 0.4385423 0.1704059 -0.8574627 0.2083273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4936 4937 0.031010 0.069757 -0.055494 -0.6257009 -0.0974185 0.4306150 0.6431009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4937 4938 -0.240143 0.139174 -0.104560 0.6502472 -0.0545739 -0.6135718 0.4446684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4938 4939 -0.114868 -0.179421 -0.030548 -0.2788770 -0.1572001 -0.1353482 0.9376549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4939 4940 0.141085 -0.118940 -0.168835 0.1897284 0.4830215 -0.8530923 0.0541004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4940 4941 -0.022520 0.137698 -0.013985 0.1606779 0.4090070 0.6068205 0.6623178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4941 4942 0.132033 -0.038993 0.028982 0.7198113 -0.5235857 -0.4549850 0.0268019 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4942 4943 0.040737 -0.089484 0.001121 -0.6291414 -0.1163315 0.7586484 0.1228847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4943 4944 0.089795 -0.011078 0.008086 0.1908962 -0.5353816 -0.0520180 0.8211086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4944 4945 0.003121 0.009365 0.117247 -0.0914099 -0.6637325 0.7149104 0.2000163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4945 4946 0.072513 -0.066307 0.187438 0.2257985 0.1823461 0.0448968 0.9559023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4946 4947 0.077425 -0.041313 0.132759 0.8882802 -0.1892972 -0.1663693 0.3839872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4947 4948 -0.077781 0.132803 0.016792 -0.2952462 0.0369120 -0.6929715 0.6567021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4948 4949 -0.079598 0.026874 0.053530 0.6585708 0.3219719 0.3708709 0.5701521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4949 4950 0.023969 -0.051961 0.147141 -0.2152397 0.4246143 0.7855036 0.3954221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4950 4951 0.053049 -0.064476 -0.043527 0.1528645 -0.0093818 -0.5203186 0.8401268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4951 4952 0.249629 0.039889 -0.052908 -0.3265699 0.4712354 0.1720716 0.8010497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4952 4953 -0.092210 0.007117 0.085973 0.2203492 0.1770383 0.8575191 0.4298426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4953 4954 0.084262 -0.156733 -0.087745 -0.6511845 0.1814134 -0.2440341 0.6953383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4954 4955 0.061706 0.126089 -0.088103 0.7889033 0.0354231 0.4627398 0.4028009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4955 4956 -0.024312 -0.176042 -0.078657 0.5234983 0.0535153 0.8490115 0.0475938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4956 4957 -0.019030 0.181012 -0.301091 -0.0639935 0.5209868 -0.4361781 0.7309079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4957 4958 -0.060727 0.006101 0.033799 0.4160967 0.1934329 0.3464403 0.8181848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4958 4959 0.071427 -0.074644 -0.017162 -0.1264273 -0.7840379 -0.1719346 0.5828715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4959 4960 -0.030074 0.087401 -0.222799 0.4115722 0.3067265 0.0097950 0.8581557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4960 4961 -0.090727 -0.012175 -0.070072 0.0679239 0.1327081 -0.9226171 0.3557424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4961 4962 0.066608 -0.003391 -0.080559 0.2666444 -0.4983918 0.1892047 0.8029371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4962 4963 -0.023384 -0.079235 -0.002748 0.2635409 -0.6050846 -0.0703387 0.7479781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4963 4964 -0.054627 -0.174562 0.027163 0.3789506 0.3263864 0.6326930 0.5912427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4964 4965 0.093593 0.082519 -0.041771 0.1750807 0.1492715 0.9488650 0.2161482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4965 4966 0.110237 0.077745 -0.019597 0.1044069 -0.4192046 0.6878167 0.5833309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4966 4967 0.041428 0.092257 0.025612 -0.4844841 0.3917487 -0.6676751 0.4074530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4967 4968 0.254760 -0.167103 0.044210 0.0824392 0.2805676 0.1494906 0.9445307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4968 4969 0.047282 0.010628 -0.193325 0.1481268 -0.6406964 -0.6349952 0.4053983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4969 4970 0.007147 0.149476 -0.242382 -0.5873426 0.2651406 -0.4469198 0.6204771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4970 4971 -0.044197 0.041209 0.011665 -0.1114412 0.4511480 0.8474194 0.2567621 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4971 4972 0.042383 0.042683 0.004323 -0.9768447 -0.0036470 0.1218249 0.1758403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4972 4973 0.035680 -0.110467 -0.196317 -0.4633491 0.1786492 0.8642841 0.0800314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4973 4974 -0.094876 -0.044403 0.040147 -0.7319090 0.2343511 0.5237965 0.3674588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4974 4975 0.078156 0.125832 0.187240 0.4115594 -0.0678799 -0.6560472 0.6289780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4975 4976 0.053275 0.064340 0.192067 0.4041621 0.2228105 -0.4956607 0.7357506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4976 4977 -0.316413 0.002418 -0.284428 -0.3806115 0.8650873 0.3247699 0.0358242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4977 4978 0.059008 0.034382 -0.013848 0.1504610 -0.9149266 -0.3230205 0.1895483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4978 4979 -0.035959 -0.017707 -0.026882 0.0006763 -0.2537133 0.8609858 0.4408316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4979 4980 0.006075 0.098196 -0.281191 0.0604071 -0.0745881 0.2659222 0.9592044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4980 4981 -0.034320 0.113734 -0.047634 0.0268720 -0.1519057 0.9878891 0.0166632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4981 4982 -0.047952 -0.070826 0.083028 -0.2530073 -0.1521873 0.4947894 0.8173187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4982 4983 0.074660 0.050917 -0.047195 -0.7368104 0.0229762 -0.3249179 0.5924617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4983 4984 0.065844 -0.228691 0.060805 0.2480147 -0.3170541 0.7316225 0.5501763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4984 4985 0.104025 -0.116983 -0.001527 0.5381420 0.4645827 0.3304449 0.6207835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4985 4986 0.189919 -0.026771 0.306816 -0.5401880 -0.3961196 -0.7409700 0.0474306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4986 4987 0.024431 -0.107285 -0.027180 -0.0937689 0.3224523 -0.8150041 0.4722290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4987 4988 -0.022497 -0.034669 0.083135 -0.5383108 0.1720535 -0.7887008 0.2420129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4988 4989 0.023627 0.092419 0.077515 0.3340003 -0.8894409 0.3093384 0.0406012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4989 4990 -0.003845 -0.106555 0.052237 0.1026691 0.3044383 0.9155120 0.2421037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4990 4991 -0.126359 0.032360 -0.048915 -0.5771548 -0.3211815 0.3731524 0.6515305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4991 4992 0.148936 -0.093361 0.056784 0.1645154 -0.3920193 -0.3547176 0.8327251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4992 4993 0.268154 -0.033506 -0.030818 0.3427585 -0.0827551 0.6067206 0.7124313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4993 4994 -0.062687 -0.087892 -0.044331 0.4494334 -0.1293496 0.1650991 0.8683436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4994 4995 -0.002487 -0.015344 0.139185 0.3193495 -0.0111330 0.9311770 0.1755034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4995 4996 -0.129291 -0.036482 0.026701 -0.6247952 0.2009531 0.7469879 0.1061034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4996 4997 -0.016673 0.039674 0.115100 -0.0860330 0.0468117 0.5910456 0.8006698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4997 4998 -0.145375 0.184622 0.191548 -0.6491348 0.0207909 -0.3930866 0.6509030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4998 4999 -0.017659 0.093243 -0.052088 0.2289274 -0.3327878 0.1334216 0.9050101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 0 100 -0.054401 0.773077 0.080261 0.1481157 -0.4183582 0.8467221 0.2934276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1 101 0.583523 -0.392303 -0.456300 0.0519179 0.5659412 -0.3046158 0.7643457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2 102 -0.592502 0.243632 0.514289 0.7219122 -0.0126575 0.5040023 0.4739876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3 103 -0.033545 -0.682774 -0.243680 -0.0417996 0.1163506 -0.9852522 0.1182942 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4 104 -0.717097 -0.084699 -0.246363 -0.1489531 0.0685810 0.7898211 0.5910095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 5 105 -0.410064 0.452427 0.599928 0.1985215 0.5236471 0.3317635 0.7591548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 6 106 0.331780 0.699777 -0.180267 0.2543010 0.2575604 -0.2201080 0.9058400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 7 107 -0.178808 -0.695030 0.095186 -0.1659341 0.1112463 -0.7001743 0.6854532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 8 108 0.621927 0.218346 -0.229799 0.2452647 -0.0621721 0.9034886 0.3459599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 9 109 0.012832 0.788532 0.125019 0.4562436 -0.8378700 -0.2579680 0.1525392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 10 110 -0.545887 -0.007498 -0.445215 -0.4004540 -0.4726081 0.7352741 0.2750457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 11 111 0.012824 0.729114 -0.530927 -0.6092654 0.3065494 0.4937256 0.5394980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 13 113 0.433606 -0.135149 -0.704332 0.4454902 0.5823688 -0.0087037 0.6799333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 14 114 0.008167 0.570179 0.400598 0.1077047 0.5876240 -0.2253139 0.7696306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 15 115 0.314215 -0.334017 0.392252 -0.3466408 -0.7749210 0.2880745 0.4431147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 16 116 0.096827 0.171426 -0.659819 -0.5705179 -0.4719916 0.6697023 0.0568519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 18 118 -0.497757 -0.129271 0.304588 -0.4436547 0.3133365 -0.5855540 0.6017618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 19 119 0.277503 0.475037 0.486903 0.0599892 -0.8039867 0.5826005 0.1028751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 20 120 -0.389255 0.662215 -0.553646 -0.6363842 0.1358137 0.7159535 0.2529433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 21 121 0.612790 0.185693 0.104983 -0.3742096 -0.9146470 0.0705284 0.1356974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 22 122 -0.229119 0.620939 0.105912 -0.6162640 0.3287691 0.6894382 0.1918448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 24 124 0.376886 -0.380423 -0.308704 -0.3539886 0.6926673 -0.6011097 0.1832244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 25 125 0.353919 -0.345987 0.326064 0.2137955 -0.7622012 0.2059853 0.5752485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 27 127 -0.545745 -0.255633 0.524489 -0.4469499 0.6607198 -0.5674254 0.2042389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 28 128 0.389342 -0.374900 0.018115 -0.1805558 -0.6299567 -0.2092989 0.7257741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 30 130 0.384243 -0.338779 -0.667373 0.0122612 -0.0316453 -0.0635724 0.9974000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 31 131 0.385878 0.147400 -0.379718 -0.9091333 -0.1610229 -0.2115466 0.3206186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 32 132 0.060143 -0.603361 -0.563027 0.8660855 -0.1779499 0.2987421 0.3591418 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 33 133 -0.110352 -0.140477 0.389955 -0.6244975 -0.1617286 0.5808969 0.4963925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 34 134 -0.454583 0.120601 -0.203698 0.0495420 -0.1809924 0.9460856 0.2640255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 35 135 0.203421 -0.345303 0.519116 -0.1198547 -0.7958398 0.0085686 0.5934647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 36 136 0.236732 -0.058271 0.534617 -0.2966649 -0.2444606 0.7939240 0.4710770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 37 137 0.106874 -0.476143 0.154565 -0.6617657 0.1231535 0.7142840 0.1915665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 38 138 0.406364 0.086840 0.296661 -0.1518218 -0.5727913 0.4851302 0.6430466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 40 140 -0.367577 -0.523593 -0.037059 0.4134818 0.2595042 0.7289130 0.4799752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 41 141 0.340685 -0.393313 -0.276472 -0.7302029 0.1197536 -0.6705917 0.0526268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 43 143 -0.353884 -0.241245 -0.233160 0.1873264 -0.1512048 -0.4294445 0.8704156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 44 144 -0.293424 0.056780 -0.453946 -0.4495574 0.5653886 0.0652932 0.6884552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 45 145 -0.259335 0.280340 -0.288154 0.0064025 0.0189725 0.5259715 0.8502664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 46 146 -0.074996 0.205107 -0.536275 -0.6658629 0.0212005 -0.6871135 0.2899175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 47 147 0.194831 -0.322632 -0.258407 0.5163604 0.2038222 0.7776067 0.2952225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 48 148 0.258230 0.279156 -0.025336 0.2712817 0.4873616 0.2236544 0.7992894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 49 149 0.323557 0.413834 -0.210628 -0.3417284 0.1474078 -0.7293109 0.5741065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 50 150 -0.317717 0.230812 0.305402 -0.4426217 0.6088801 -0.5072075 0.4196328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 51 151 -0.643341 0.126739 -0.040977 -0.1738198 0.1133964 -0.0540051 0.9767351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 53 153 0.183464 0.414661 0.138568 -0.0143502 -0.0981316 0.4113386 0.9060711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 54 154 -0.372610 -0.109950 0.377698 0.1515149 -0.2422241 0.4614875 0.8398809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 56 156 -0.628148 0.145288 0.002449 -0.5014908 0.4217732 0.2083003 0.7261029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 59 159 -0.467492 0.516191 -0.089461 -0.6532622 -0.6213237 0.1427669 0.4084397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 62 162 -0.553485 0.096632 -0.121362 -0.3755237 -0.3523632 0.8408623 0.1666513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 63 163 0.187559 -0.113269 -0.362635 -0.2437822 -0.9368057 -0.1524525 0.1993078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 65 165 0.103158 -0.179341 0.536821 -0.0432329 0.0761219 0.9421678 0.3235062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 67 167 0.296302 0.146066 -0.562329 -0.0121798 -0.1196922 -0.9914721 0.0500845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 68 168 0.236431 0.559187 0.490751 -0.3285568 -0.5536721 0.7309194 0.2263945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 69 169 -0.149340 0.631904 -0.503964 -0.7212276 0.1129350 -0.4346560 0.5273999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 70 170 -0.236901 0.191530 -0.418087 -0.0015511 0.7760001 -0.3098558 0.5493731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 73 173 0.011684 0.090859 -0.461170 0.2791033 -0.5220280 -0.7989846 0.1058855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 74 174 0.439745 -0.137839 -0.189459 -0.2402383 -0.2851805 -0.6875755 0.6230551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 75 175 0.504276 0.010429 0.148059 -0.4431916 -0.0843478 -0.1837269 0.8733333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 76 176 0.530843 0.333592 0.310101 0.4671271 -0.1524583 0.0582117 0.8689995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 77 177 0.788944 0.083748 0.072614 -0.6060580 -0.6113652 -0.1054011 0.4978122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 78 178 0.032097 0.708140 0.269611 0.1288002 -0.2925076 -0.7405708 0.5911047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 79 179 0.452635 0.225413 -0.415538 -0.0052659 -0.4037811 0.8381009 0.3667696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 80 180 -0.156171 0.303555 0.568633 0.7828998 -0.2203057 0.5811611 0.0280209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 81 181 -0.311743 0.724006 0.160778 -0.0057071 -0.6056514 0.7701976 0.1998736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 82 182 -0.013426 0.590932 0.379948 -0.0040617 0.5794690 -0.6793126 0.4502595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 83 183 0.023922 0.659011 0.529860 0.6409794 0.4589428 0.4533765 0.4158927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 84 184 0.593812 -0.603128 0.015010 -0.2484688 -0.8417349 -0.3508084 0.3266176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 85 185 0.301294 -0.578049 0.399084 -0.2400835 -0.1600535 -0.8075552 0.5143903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 86 186 -0.137604 -0.088331 -0.749923 -0.4129843 -0.8151297 -0.1793963 0.3644509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 87 187 0.613211 0.229028 -0.556605 -0.2021862 0.8732406 -0.3948425 0.2016706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 88 188 0.035177 -0.625331 0.596227 -0.5887207 0.0193020 -0.0365700 0.8072782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 89 189 0.200976 -0.100399 -0.641178 -0.1401688 0.2325009 0.6161334 0.7393752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 90 190 0.517007 -0.112849 -0.387954 -0.3942597 -0.2279410 0.8326438 0.3151295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 91 191 -0.624022 -0.344097 0.150548 0.2445777 -0.6181069 0.4687303 0.5817366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 93 193 0.350565 0.650392 -0.261033 0.4756398 0.2956103 0.1785110 0.8090211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 94 194 -0.304464 0.514907 -0.331446 -0.4874745 0.2884549 -0.8090202 0.1569990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 96 196 0.529659 -0.637806 -0.130096 0.2929524 -0.3610617 0.8714219 0.1563243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 97 197 -0.000019 -0.179991 0.756082 -0.9758209 -0.1401395 -0.1231540 0.1138757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 98 198 -0.195685 -0.169949 -0.649858 0.9744373 0.1032452 0.1017691 0.1716256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 99 199 0.288433 0.389660 0.380507 0.3170824 -0.4396834 0.2200938 0.8109846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 100 200 0.369818 -0.367451 -0.463284 -0.0645909 -0.2377923 -0.9535291 0.1733928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 101 201 0.591836 0.162033 0.483907 0.1303563 -0.4524690 0.0187234 0.8820026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 102 202 0.263608 0.561905 -0.484848 0.6553680 0.0676537 0.6644802 0.3526779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 103 203 0.469257 0.505891 -0.267224 0.0765806 0.2616370 0.9483352 0.1623014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 104 204 0.042832 0.670605 -0.178791 0.3325383 0.0957150 -0.7029121 0.6214270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 106 206 -0.063630 0.445549 -0.405028 -0.7379755 -0.4901848 0.2453137 0.3936143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 107 207 0.588829 -0.181159 0.188032 0.1738559 -0.2828868 0.9078194 0.2561505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 108 208 -0.122338 -0.799543 -0.148998 0.6754760 -0.1118462 -0.2662483 0.6784796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 109 209 -0.698330 0.030970 0.122154 0.4075078 0.8693962 0.2613210 0.0989899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 110 210 0.353934 0.333593 0.402385 -0.1803776 -0.2223021 -0.1680418 0.9432962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 111 211 0.450752 0.013805 0.615303 -0.2382771 -0.5821437 -0.5184325 0.5792758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 113 213 0.491001 -0.212125 0.255187 0.3230830 0.5254852 0.7350551 0.2813835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 115 215 -0.355485 -0.616478 -0.513627 0.6473623 0.2395400 -0.5309380 0.4915765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 116 216 0.653380 0.506311 0.243425 -0.4602604 0.3111183 -0.7844003 0.2758294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 117 217 -0.729769 0.235165 -0.073692 0.1027133 -0.7021234 0.5694624 0.4149521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 119 219 -0.106773 -0.418003 -0.571965 0.4809034 -0.2354904 -0.3225165 0.7805506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 120 220 0.536068 -0.149997 0.331080 0.5479877 -0.6861372 0.3787845 0.2923141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 121 221 -0.435716 0.535047 -0.366741 0.3608788 0.4313205 0.4561737 0.6896627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 122 222 -0.115954 -0.100503 0.583589 -0.2632689 -0.7407424 -0.6179006 0.0137514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 123 223 0.230941 0.232201 0.402795 0.4165006 -0.6583028 0.4548857 0.4315596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 124 224 -0.127065 0.229618 0.479823 0.2542624 -0.8410268 0.4657092 0.1055436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 125 225 0.100626 -0.523630 0.049020 0.4620903 0.3348158 -0.2738756 0.7741854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 127 227 0.411651 -0.273361 -0.340450 0.4754459 0.4002692 -0.7826991 0.0334352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 128 228 0.188172 0.264100 -0.568475 0.4811701 -0.4385246 0.6533212 0.3864490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 129 229 -0.270747 0.341710 0.402218 0.0359087 0.4655763 0.7598255 0.4523432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 130 230 0.272178 -0.081013 -0.639894 0.1194247 0.1779995 0.3513878 0.9113619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 132 232 -0.318956 -0.087921 0.428989 0.0317179 0.6236474 0.2457953 0.7413788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 133 233 -0.633822 -0.115213 0.089478 0.2521739 0.3435191 0.3103597 0.8497528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 135 235 0.218790 -0.118130 -0.246619 -0.2314697 0.3795676 0.8952654 0.0291571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 136 236 -0.235022 -0.394837 0.158309 -0.6348798 -0.5388014 -0.2002602 0.5162524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 137 237 -0.368802 0.161140 -0.268053 -0.2049810 -0.3721261 -0.6795167 0.5981321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 138 238 0.217265 -0.321056 -0.374650 0.2237329 -0.2037834 0.2596501 0.9170593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 139 239 0.093415 -0.434717 -0.121787 0.1757897 -0.3208501 0.1410627 0.9199209 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 140 240 -0.751789 0.254455 -0.317171 -0.3888812 0.0636913 0.7038499 0.5910246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 142 242 0.178815 -0.120701 -0.564970 0.2853576 0.5615620 0.4575508 0.6275877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 143 243 -0.358791 -0.550265 -0.106013 -0.4059247 0.3878591 0.1533503 0.8131877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 144 244 0.148650 0.401017 -0.161520 0.0786688 -0.5406610 -0.0121084 0.8374666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 145 245 0.028762 0.513481 -0.197438 -0.3775636 -0.2093832 -0.2795321 0.8575933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 147 247 -0.531595 -0.049394 0.058699 0.3721393 -0.0600402 0.9127710 0.1573423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 148 248 0.434447 0.253807 -0.037676 0.1240451 -0.6400773 -0.3428007 0.6763147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 151 251 -0.391318 0.167907 -0.227875 0.2233864 -0.1887620 -0.8682319 0.4008002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 152 252 -0.469988 0.019469 -0.133896 -0.2469110 -0.1361275 0.0668352 0.9570984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 153 253 0.276998 0.128649 0.003462 0.3037911 -0.7295827 -0.3492805 0.5034116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 154 254 -0.077979 0.180151 0.278661 -0.3048303 -0.3158966 0.2773520 0.8546132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 155 255 -0.180962 0.328123 0.296820 0.0048423 -0.2259017 0.5338817 0.8148100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 156 256 -0.222106 0.465354 -0.289285 0.2400738 -0.4453660 0.0962373 0.8571768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 157 257 0.291911 0.256749 0.264937 0.6209697 -0.3601541 -0.5165793 0.4667242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 158 258 0.337971 -0.123719 -0.328342 -0.5057802 -0.0251254 -0.4217430 0.7521223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 159 259 0.185520 -0.068336 0.456413 -0.4667680 0.0716110 0.8731727 0.1207017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 160 260 0.438437 -0.018603 0.011001 0.4263300 -0.2631376 -0.4108323 0.7617205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 161 261 0.231185 -0.055154 -0.436315 0.5236940 -0.5593237 0.3303341 0.5511633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 162 262 0.200671 -0.080173 0.400543 0.3038639 -0.0551172 0.8783385 0.3648977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 163 263 -0.399247 -0.091516 0.372251 -0.0176290 0.7394006 0.4656760 0.4859237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 165 265 -0.283957 -0.005557 0.336951 0.6033607 0.2886744 0.2886211 0.6850699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 166 266 0.178528 0.072741 -0.647738 0.3223895 0.7196569 -0.3388920 0.5131385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 168 268 0.016050 -0.445794 -0.181914 -0.8064341 -0.2849088 0.2323095 0.4631666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 169 269 -0.402990 0.011657 0.259921 0.6903530 0.4041087 0.2014564 0.5652647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 170 270 0.265655 0.464336 -0.316302 -0.6976020 -0.6968220 0.0088195 0.1664713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 171 271 -0.463039 0.128278 0.460391 -0.3278819 0.6098676 -0.7115561 0.1193434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 172 272 -0.318172 0.441317 0.360181 0.2040231 -0.0789727 -0.0455615 0.9747113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 173 273 0.284428 -0.572004 0.040187 -0.0536290 -0.4513580 -0.6140591 0.6452374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 174 274 -0.156493 0.568076 -0.412512 -0.0826626 -0.6911933 -0.7178048 0.0132308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 175 275 0.687373 -0.052435 0.312673 0.1702307 0.3609580 0.2652095 0.8777213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 176 276 0.280357 0.398528 -0.247241 0.0320745 0.0925058 0.4804383 0.8715463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 177 277 0.375365 0.559086 -0.150002 0.2901338 0.7546108 -0.0965189 0.5805765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 178 278 -0.352397 -0.279709 0.226328 -0.1485567 0.3942024 -0.9069084 0.0072420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 179 279 -0.359453 -0.056368 -0.648778 -0.4077418 -0.0216074 0.9072259 0.1010987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 180 280 0.394472 -0.392421 -0.478043 0.0806203 0.8150195 -0.2418389 0.5203437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 181 281 0.535886 -0.156557 -0.509538 0.0531874 0.3795990 -0.0670173 0.9211864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 183 283 0.366201 0.382134 -0.337374 -0.4576373 -0.4459528 -0.0350284 0.7684186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 184 284 -0.332374 0.042586 -0.505159 -0.7789727 -0.5350445 -0.1216194 0.3035419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 185 285 0.333663 0.615881 0.186179 0.0934056 0.0498519 0.9127424 0.3945777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 186 286 -0.223488 -0.119785 0.464585 0.7567927 0.0418302 0.6168274 0.2122239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 187 287 -0.394897 0.360860 0.244983 -0.9800898 -0.1544745 0.1068648 0.0643546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 188 288 0.048489 -0.723661 -0.405727 0.7269844 -0.0405980 -0.2645866 0.6323286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 189 289 0.722497 -0.216043 -0.362321 0.5765700 -0.4524127 0.3387143 0.5900528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 190 290 -0.028526 -0.105150 -0.953812 0.5279497 -0.5445845 0.6402750 0.1214282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 191 291 0.324881 0.157655 0.417578 -0.2953058 0.4509176 -0.3481972 0.7669592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 192 292 0.121833 0.761654 -0.275995 -0.4486332 -0.4595291 0.7637690 0.0649471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 193 293 0.517287 -0.131691 -0.389062 0.0909598 -0.6579180 -0.6604685 0.3502166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 195 295 0.415337 0.210556 0.337735 0.2370665 -0.6774885 0.5244473 0.4579998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 196 296 -0.263879 0.246729 0.680770 0.2763051 0.0986082 -0.0382952 0.9552305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 197 297 0.023358 0.059273 -0.675151 0.8983487 -0.1411966 0.1714284 0.3790059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 199 299 0.450230 0.284967 -0.309042 -0.6223588 0.2729096 0.7050028 0.2028818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 200 300 -0.577046 0.024688 -0.440536 -0.7759228 -0.3560217 -0.5146520 0.0795338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 201 301 0.753624 0.192016 -0.135310 -0.2386910 -0.2609101 0.6797261 0.6425924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 202 302 0.138145 -0.835847 -0.404121 -0.6426674 0.2402826 -0.7143750 0.1375181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 203 303 -0.021396 -0.663209 0.309505 0.4247641 -0.7860112 -0.2041837 0.4000887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 205 305 -0.547137 -0.289975 0.371016 -0.0830777 -0.6104592 -0.7262671 0.3049160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 206 306 0.657345 0.330257 0.562100 0.9104148 0.1586843 -0.1798221 0.3370878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 207 307 -0.618371 -0.187368 0.475034 -0.4905701 -0.1731236 0.7147377 0.4674603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 208 308 0.442552 -0.213827 0.608226 -0.4419590 0.8836875 0.1221750 0.0940317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 209 309 0.380952 -0.363059 -0.204664 -0.9321136 0.1208039 -0.0635174 0.3354641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 210 310 0.643511 0.405461 0.562731 0.4397835 -0.4910677 0.0397701 0.7509070 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 211 311 0.264701 0.493336 0.054436 0.0489828 -0.4706853 0.6780622 0.5623945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 212 312 0.053974 0.690039 -0.258725 0.1140566 -0.0667085 0.4405574 0.8879472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 213 313 -0.464344 0.164016 0.443232 -0.1424381 0.0113278 -0.7309182 0.6673393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 214 314 -0.169281 0.573421 0.341291 0.3465855 -0.2970758 -0.7129283 0.5323135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 215 315 0.541679 -0.260574 0.548092 -0.1285341 -0.7909469 -0.5854315 0.1230934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 217 317 0.570017 0.519418 0.334185 0.7512638 0.6293733 0.1117938 0.1642989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 218 318 -0.325542 -0.683009 0.074123 -0.4664708 -0.7832424 -0.3463460 0.2213160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 219 319 0.164538 -0.681474 0.062738 -0.1318512 0.2695707 -0.9539103 0.0014018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 220 320 0.153042 -0.680695 -0.171287 -0.5288381 -0.0258655 0.3711847 0.7628127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 221 321 0.414891 0.155682 -0.412134 -0.0430791 -0.1029014 0.7948490 0.5964650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 222 322 0.244646 0.568380 -0.376667 -0.4039936 0.6068082 0.1871696 0.6584379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 224 324 0.343592 -0.147275 -0.357492 0.7221095 0.1045745 -0.4836422 0.4834380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 226 326 0.479821 -0.383861 0.361272 0.1164866 -0.4675449 0.8415666 0.2441275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 227 327 -0.120803 0.444358 -0.301213 0.1040230 0.4179560 0.2983858 0.8517382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 229 329 0.282237 0.411863 0.304270 -0.4609671 -0.2714574 0.5532173 0.6385694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 230 330 0.250801 -0.374437 -0.596334 0.1703055 0.2079001 0.8098385 0.5214740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 233 333 -0.581029 -0.123067 -0.310554 0.8017529 -0.1612165 -0.5673193 0.0966975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 234 334 0.422631 0.391389 0.203540 0.2050634 -0.2760237 0.6281559 0.6979829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 236 336 -0.188574 -0.292945 -0.383177 0.6433495 0.5851522 0.4751301 0.1339765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 237 337 -0.436363 -0.534536 -0.066784 -0.1071671 -0.3310595 0.8600987 0.3730215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 239 339 -0.369110 -0.636666 -0.304100 0.0579302 0.2978617 -0.7748113 0.5546079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 240 340 0.147235 0.318363 0.326414 0.2131713 -0.1402848 -0.1230986 0.9590229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 241 341 0.403554 -0.145387 -0.439330 -0.2453394 0.4459050 -0.5762643 0.6394503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 242 342 0.333205 -0.392736 0.260811 -0.2149212 -0.5431151 0.7912809 0.1808575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 244 344 -0.204219 0.564292 -0.315954 -0.4256388 -0.0014034 0.2260559 0.8762011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 245 345 -0.368200 0.529717 0.074280 0.0327619 -0.5847212 -0.7549035 0.2952092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 246 346 0.484439 0.280936 -0.219725 -0.4522402 -0.6689910 -0.1344388 0.5743310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 247 347 0.325708 0.321890 -0.119721 -0.6213106 0.5891271 -0.0762185 0.5109728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 249 349 0.306590 -0.118950 0.294523 -0.3951635 -0.5557361 -0.2777314 0.6766598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 250 350 0.352627 -0.272252 0.207308 -0.0475284 -0.6033548 -0.6780374 0.4170963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 251 351 0.304428 -0.478542 0.014039 -0.4560274 -0.5864089 -0.5396259 0.3961912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 253 353 -0.514118 -0.013712 -0.312494 -0.8699405 0.4615352 -0.0689728 0.1594726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 255 355 0.377222 0.246034 0.205792 0.7484883 0.4950273 0.2455257 0.3666475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 256 356 -0.194162 0.420702 0.209049 0.3605520 0.3968078 -0.3016988 0.7883677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 258 358 0.174785 0.458593 -0.152950 -0.3698931 0.6235309 -0.3639768 0.5847301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 259 359 -0.553934 0.017767 0.223933 0.1020241 -0.3265234 -0.5436910 0.7664031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 260 360 0.470314 0.398523 -0.222912 -0.1793966 -0.0899297 0.4729255 0.8579458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 261 361 -0.348510 -0.361863 -0.057108 -0.0463247 0.1632343 0.7062037 0.6873753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 262 362 0.112002 -0.156571 0.432460 -0.9290103 -0.0794902 0.0070860 0.3613461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 263 363 -0.380196 0.598269 -0.237748 -0.1431210 -0.5768389 -0.4097214 0.6920272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 264 364 -0.252819 -0.379199 0.042713 -0.1237985 -0.4283627 -0.5446008 0.7103445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 268 368 -0.379190 0.303336 -0.200589 0.5525876 -0.7947316 -0.1960923 0.1568324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 269 369 -0.311890 0.074612 -0.196424 -0.2801995 -0.3211183 -0.8093874 0.4040587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 270 370 0.281995 0.364422 0.425931 -0.5515650 0.4862820 -0.6723273 0.0853344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 271 371 0.377115 -0.248603 -0.442137 0.1862275 -0.3312469 0.9148529 0.1365244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 272 372 -0.452128 0.516975 0.298421 -0.3854301 -0.0080314 0.4435959 0.8090746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 273 373 0.515013 0.150153 -0.508377 -0.2448560 0.2130760 0.4754192 0.8176924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 274 374 0.350980 -0.468148 0.473235 -0.3466448 0.5874893 0.7311285 0.0120363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 275 375 0.414923 0.189725 0.541579 0.4845772 -0.1434480 -0.7644558 0.4002686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 276 376 0.702514 -0.060440 -0.246085 -0.3571057 -0.4735928 -0.3438691 0.7279694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 277 377 0.288968 0.623335 -0.045773 -0.5145191 -0.0453711 0.2112128 0.8298197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 278 378 0.479433 0.214835 0.100245 0.4614295 -0.6022545 0.6173973 0.2078292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 279 379 0.651054 0.381170 -0.233608 0.3047502 0.2762455 -0.9090973 0.0660144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 280 380 0.442482 -0.023330 0.585377 0.5544301 -0.6093743 -0.5205184 0.2243453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 281 381 0.915432 -0.047836 0.147079 0.1605133 0.4880219 0.3610896 0.7782573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 282 382 0.759331 -0.235273 0.270726 -0.4351390 -0.2556244 0.7479658 0.4311117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 283 383 0.333055 0.757040 -0.028490 0.4392027 0.1788024 -0.1317258 0.8705050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 284 384 -0.384228 -0.371105 0.538107 0.2647688 0.5215658 -0.7160913 0.3808935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 286 386 0.375414 0.514588 -0.393846 0.3106342 -0.3338864 0.5642296 0.6882378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 287 387 -0.287526 -0.487490 0.032885 -0.4288274 -0.3737675 0.4515214 0.6874106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 288 388 0.594130 -0.213835 0.410956 -0.4599958 -0.0922572 -0.3611192 0.8059066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 289 389 -0.274984 -0.635238 0.141362 0.2846559 -0.2169527 0.7441807 0.5640015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 290 390 -0.696208 0.421990 0.358473 -0.4410476 0.5558188 0.3499376 0.6116258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 291 391 -0.272286 -0.305976 0.517355 0.0312628 -0.5124703 0.7998224 0.3109357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 293 393 -0.437766 -0.142672 -0.148425 0.0554623 0.1161399 0.8851740 0.4471045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 294 394 -0.272860 0.611821 -0.104682 -0.1984925 -0.0518228 0.9787145 0.0057506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 296 396 -0.383982 0.457819 0.131350 -0.6102135 0.1707858 -0.7602333 0.1432378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 298 398 0.343349 0.407195 -0.024207 -0.1006425 -0.4891222 -0.5450835 0.6734349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 299 399 0.311550 -0.643845 -0.173450 0.2199021 -0.2314678 -0.9417102 0.1060548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 301 401 0.197407 -0.552226 -0.466763 0.6636017 -0.0801136 0.1854563 0.7202919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 303 403 0.816872 -0.182408 -0.446104 0.2978461 0.5191975 0.7901920 0.1315990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 304 404 0.323802 -0.084324 -0.541217 0.8383988 0.0562430 -0.3594426 0.4058635 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 306 406 0.413637 0.390543 -0.666598 -0.1948142 -0.4962581 -0.8076361 0.2519907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 308 408 -0.293653 -0.321379 -0.583839 0.8083956 -0.0870318 -0.5680727 0.1273396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 309 409 0.664521 0.423076 0.308901 0.3666695 0.0012713 0.1719007 0.9143315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 310 410 0.456359 0.274125 -0.457775 -0.6192736 -0.1002416 -0.7586769 0.1756733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 312 412 0.455441 0.486388 -0.479860 0.4125394 0.5223237 0.1292319 0.7350430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 313 413 0.213955 -0.607494 0.318687 -0.2650735 -0.1115461 -0.8037157 0.5208978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 314 414 -0.531018 -0.059821 0.313986 -0.1347316 0.8002415 -0.3831901 0.4411647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 318 418 0.112030 -0.441241 -0.669002 0.6531252 0.4120767 0.5288299 0.3520784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 320 420 0.167107 -0.171412 -0.724724 0.5974486 -0.2221311 -0.3907309 0.6641101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 321 421 0.133311 -0.360762 -0.622370 0.0211016 0.2313013 0.9369170 0.2612299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 322 422 -0.108261 0.225545 0.646637 0.7244832 -0.4217402 0.5315581 0.1212653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 323 423 0.154303 0.404008 0.395076 -0.5995105 -0.2861977 0.6375384 0.3901575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 324 424 0.709409 -0.054393 -0.098802 0.1102804 -0.1469224 0.9097712 0.3722479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 325 425 0.441284 -0.552565 -0.097191 -0.6726515 0.3604396 -0.6438051 0.0560195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 326 426 -0.210559 -0.508176 0.315772 -0.5196936 0.5271497 -0.0901249 0.6662651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 328 428 -0.349896 0.093395 0.334219 -0.1869117 0.6660859 -0.6848202 0.2289428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 330 430 -0.290629 -0.221105 -0.391058 0.2340556 -0.1834338 0.9334318 0.2006866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 331 431 -0.257080 -0.401293 0.353235 -0.1536859 -0.4368166 -0.7590541 0.4576119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 332 432 0.649605 -0.161303 0.087377 -0.1060310 -0.4917958 -0.6478616 0.5719875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 333 433 0.352815 0.134135 0.567544 -0.0431567 -0.8159222 -0.2466836 0.5211100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 334 434 0.369493 -0.248710 -0.510978 -0.0228347 0.0614331 0.6933694 0.7175956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 335 435 -0.064590 -0.369002 -0.427023 -0.3426179 -0.1296487 0.6606880 0.6552065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 337 437 0.113211 0.456836 0.111046 0.5883828 -0.1015056 0.3604461 0.7166455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 338 438 -0.318277 0.161434 0.355238 0.3446731 0.1234267 0.6301359 0.6847591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 339 439 0.530471 -0.010382 -0.087732 0.0234857 0.6442905 0.6397403 0.4184143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 340 440 0.021382 0.498096 0.236015 -0.1570936 0.2778096 -0.4709205 0.8224216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 341 441 0.209905 0.413569 -0.052389 -0.1669545 -0.3698495 0.1719293 0.8976513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 342 442 -0.459765 -0.245784 0.080849 0.0142048 -0.0878069 -0.0756782 0.9931571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 343 443 0.337779 -0.396700 0.169816 -0.3547279 -0.4705263 -0.0308941 0.8073529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 344 444 -0.053632 0.578616 0.148461 -0.6601100 0.4192614 -0.5058878 0.3640773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 345 445 0.084895 -0.214981 0.354833 -0.5507195 0.4992243 0.4881095 0.4574191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 346 446 -0.119721 0.257662 0.268644 0.0392465 -0.2788701 -0.9441435 0.1711262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 347 447 0.051985 0.036418 0.553237 -0.2841492 0.8359336 -0.1474497 0.4457947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 348 448 0.326162 0.426336 -0.206256 0.0266575 -0.5225522 -0.3994407 0.7527786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 349 449 0.388979 0.037064 -0.398612 0.4657785 0.3902054 -0.6945660 0.3851858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 352 452 0.445269 -0.326848 0.110123 0.6109227 -0.1948265 0.5447007 0.5404787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 353 453 -0.348081 0.303638 0.276991 0.0896180 -0.9439434 0.0983628 0.3020997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 354 454 -0.183985 -0.505238 -0.065753 -0.4766275 0.0183619 -0.0788897 0.8753659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 355 455 0.431941 0.470412 0.226504 0.3664496 -0.2111160 -0.7230974 0.5461455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 356 456 -0.403867 0.027873 -0.360002 0.0748865 -0.3836782 -0.6926364 0.6061665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 358 458 -0.401727 0.354926 0.049361 0.1963566 0.0276748 0.9056665 0.3747617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 359 459 0.210083 -0.248039 0.528689 -0.3270544 -0.4406397 0.2467352 0.7987451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 360 460 0.370408 0.018986 -0.263415 -0.2803920 0.5699328 0.6776043 0.3706877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 361 461 -0.283022 0.347173 -0.291811 -0.3778386 -0.8277774 0.3789268 0.1686327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 362 462 0.286368 -0.053104 -0.475240 0.7103530 -0.1632633 -0.0100329 0.6845751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 363 463 -0.551106 0.056978 0.526782 -0.0993201 0.5502627 0.7362951 0.3810721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 364 464 0.284581 -0.374622 -0.214223 -0.4645059 -0.2434222 0.7132066 0.4650980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 366 466 -0.453672 0.148418 0.340568 -0.0765668 -0.5091501 -0.8543606 0.0705107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 367 467 -0.586659 0.309070 -0.199320 -0.6955945 0.4218521 -0.1075682 0.5715052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 368 468 -0.224938 0.340665 0.509014 -0.0263177 0.1450383 -0.7871648 0.5988680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 369 469 -0.152316 -0.419146 -0.363013 -0.0480449 0.2766335 -0.9597567 0.0057101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 370 470 -0.003597 -0.638361 -0.095312 -0.1882549 0.1760240 0.9644317 0.0587119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 371 471 -0.559498 0.136093 0.145302 0.0331623 0.3756236 -0.8549578 0.3561661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 372 472 -0.154974 0.114123 0.705623 0.5741480 0.5155441 -0.5411470 0.3342577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 373 473 0.354402 -0.234878 -0.121611 0.1840156 -0.6239618 0.7544306 0.0874326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 374 474 -0.359883 0.370988 -0.402573 0.5434156 -0.0778495 -0.3787207 0.7451239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 375 475 -0.613687 0.482358 -0.134425 -0.0395104 0.2618315 0.7336013 0.6258693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 376 476 -0.145816 0.547090 -0.176989 -0.6106114 -0.1348494 0.3891983 0.6763830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 377 477 0.384712 0.311039 0.361538 0.0342324 0.2604947 0.6407898 0.7213592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 379 479 -0.274364 -0.107108 -0.449024 -0.3953734 -0.1680882 0.2573807 0.8655527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 381 481 0.067807 -0.467074 0.650350 -0.8709790 -0.0291516 -0.3310609 0.3618626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 382 482 -0.506384 -0.460385 -0.335625 -0.3472623 0.2957990 -0.8860527 0.0825978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 383 483 0.044135 0.553318 -0.609755 -0.4493175 -0.0454898 0.6417087 0.6198826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 386 486 0.091330 -0.271932 -0.743313 0.0059269 -0.4536543 0.7178747 0.5280327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 387 487 -0.707758 -0.124287 0.135238 -0.0587186 0.5606030 -0.6424976 0.5191081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 388 488 0.729395 0.089571 0.153063 -0.4725363 0.6474117 0.5772337 0.1561053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 389 489 -0.628384 0.373558 0.301785 0.5569244 0.3520899 -0.7490963 0.0687210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 390 490 -0.388431 0.617336 0.111996 -0.0399120 0.3053946 0.9359878 0.1704934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 391 491 0.427901 -0.002357 0.582796 -0.4285296 -0.4299186 0.1579308 0.7788391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 392 492 -0.415984 0.192655 -0.466810 0.0389361 0.4367528 0.8542635 0.2792219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 393 493 0.161643 0.652035 -0.135804 -0.3132371 -0.0500752 -0.4242242 0.8481797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 395 495 -0.077727 0.705588 0.390051 -0.3013046 0.0187750 0.6337848 0.7121656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 398 498 -0.265529 0.641759 0.024174 -0.7962592 0.1983979 0.2721872 0.5025174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 399 499 -0.056129 0.626263 -0.332156 -0.0821320 0.6643876 0.2439372 0.7016680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 400 500 0.528322 0.115286 -0.359932 0.4123508 0.1107665 -0.1675761 0.8886033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 401 501 0.254589 -0.720041 0.626974 -0.2613883 -0.3381517 -0.8121810 0.3971040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 402 502 0.471990 -0.582112 0.111640 0.7070018 -0.2772202 0.3800000 0.5281074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 403 503 -0.418034 -0.301759 0.441041 -0.4066542 0.1442178 -0.7514143 0.4992095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 405 505 -0.563993 0.601326 -0.066987 0.0232077 0.0779245 0.9958986 0.0396883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 406 506 -0.613528 -0.368982 0.069994 0.5579164 -0.1123657 -0.0395390 0.8213038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 407 507 -0.748253 0.176641 -0.177558 -0.2707604 0.0588744 -0.9298200 0.2421929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 408 508 0.402210 0.178862 0.617562 0.8200363 0.2235069 -0.2326639 0.4727078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 409 509 0.725511 0.397562 0.031640 -0.0286256 -0.1735558 0.1303698 0.9757370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 410 510 -0.635126 -0.182397 0.518697 0.4007599 0.3444008 0.6787545 0.5099724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 411 511 0.536813 0.108958 -0.072650 -0.3736468 -0.1920417 0.7596522 0.4964237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 412 512 0.494152 -0.023777 0.037083 0.0017741 -0.3791102 -0.4623788 0.8015474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 413 513 0.580593 0.156739 0.348232 0.2808136 -0.2643554 0.2095627 0.8985229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 415 515 0.164114 0.238078 0.669024 0.5519199 0.0726730 0.2004489 0.8061782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 417 517 0.023276 -0.266455 -0.592220 0.4492973 -0.5531275 0.0098451 0.7014877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 420 520 0.285984 -0.656367 -0.088307 0.3731147 0.1197234 0.5327411 0.7500924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 421 521 -0.132342 0.049153 -0.515940 -0.6225855 0.6212816 0.3557998 0.3159161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 424 524 -0.404121 -0.387731 0.040465 0.4427444 0.6066558 -0.2918895 0.5922386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 425 525 -0.015786 0.157436 0.534939 -0.0698703 -0.5503229 0.8311389 0.0383541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 426 526 -0.011291 -0.328160 -0.267823 0.4344354 -0.2517983 -0.7272195 0.4679906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 427 527 0.605061 0.182448 0.093896 -0.4651426 0.5086461 0.2516046 0.6794238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 428 528 0.195464 -0.341214 -0.504634 0.0556939 0.7709465 -0.0989090 0.6267030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 429 529 -0.446510 -0.189756 -0.133058 -0.3129900 0.5338602 -0.5964760 0.5111232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 430 530 0.050377 0.457214 -0.181571 0.4954611 0.6013002 0.5295549 0.3354519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 432 532 -0.021739 0.629261 -0.042190 0.0270247 -0.5635222 -0.8054886 0.1813849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 433 533 0.400238 0.386550 -0.346698 -0.4579149 -0.0964126 -0.0154700 0.8836171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 434 534 -0.164160 -0.481278 -0.437238 -0.8692462 -0.0759807 -0.4675711 0.1414755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 435 535 -0.150688 0.054468 -0.397023 -0.3869760 -0.4511202 0.0789902 0.8003129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 436 536 -0.014123 0.394422 -0.194007 0.2697426 0.4785596 0.4255447 0.7191185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 437 537 0.314564 0.280445 -0.267679 0.1348453 -0.1084588 -0.2664745 0.9481797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 438 538 0.001846 0.393480 -0.320728 0.3046525 -0.2635677 -0.0689760 0.9126671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 439 539 -0.314600 -0.333164 0.313625 -0.5427522 0.2827965 -0.1539689 0.7757188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 440 540 -0.419677 0.263884 -0.017879 0.2155449 -0.4835006 0.8046867 0.2687879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 441 541 0.270051 0.423005 -0.019361 0.5642765 0.2874412 0.1411804 0.7609452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 442 542 -0.351621 -0.414707 0.135617 -0.2487444 0.2332703 0.3894907 0.8555748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 443 543 0.190757 -0.079293 -0.430534 0.5115860 -0.4189703 0.5722172 0.4850888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 444 544 -0.255169 -0.319782 -0.052359 0.2380077 0.1055277 -0.9369486 0.2331171 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 445 545 -0.583788 -0.027325 -0.166867 -0.2001255 -0.6657989 0.6292289 0.3474660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 446 546 0.090738 -0.236366 0.382626 -0.0837978 -0.0518966 -0.7756095 0.6234698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 448 548 -0.232540 0.348170 -0.284536 0.4664384 -0.1592449 -0.5876251 0.6416954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 449 549 0.309751 0.461876 -0.205778 -0.1006097 -0.0493850 -0.8134701 0.5707058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 450 550 0.393564 0.186313 -0.339826 0.3297801 0.7459201 -0.2618899 0.5160057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 451 551 0.359281 0.069749 -0.505834 -0.1885946 0.0453725 0.2065605 0.9590131 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 452 552 0.201614 -0.063196 0.491791 -0.1181832 0.2242868 0.6635533 0.7038645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 453 553 0.124493 0.354037 -0.101268 0.3584816 0.6049886 -0.0189791 0.7107176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 454 554 -0.067876 -0.476823 -0.300147 -0.2129114 -0.4306596 0.1799510 0.8583814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 455 555 -0.468694 0.158246 -0.206105 0.2764502 -0.7026317 0.0147979 0.6554883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 456 556 0.056054 -0.532043 -0.055206 0.1101226 -0.1078438 -0.9136141 0.3762341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 457 557 0.501224 -0.128324 0.434511 -0.9589470 0.1747289 0.0485498 0.2180216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 458 558 0.367560 0.118423 -0.071435 -0.4155906 -0.0388407 -0.4688469 0.7784333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 460 560 -0.035503 -0.588650 0.064326 0.0139044 -0.6188645 0.7849158 0.0268456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 461 561 0.377861 0.180514 0.044420 -0.0043407 -0.2084862 -0.0965349 0.9732398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 462 562 0.201388 -0.616586 -0.041595 -0.1040019 0.6267052 0.3522177 0.6872895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 466 566 0.439734 0.439506 0.278472 0.5208073 0.4081678 -0.7445829 0.0880632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 467 567 -0.540855 0.279249 -0.269875 0.6868499 -0.1038720 -0.6197944 0.3651064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 468 568 -0.148392 -0.404891 0.476986 -0.1032847 -0.6609735 -0.7053611 0.2343332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 469 569 -0.018494 0.600674 0.109853 -0.4494308 -0.1334937 0.8192350 0.3302203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 470 570 0.122385 0.700588 -0.191227 -0.2556289 -0.4257491 0.7894165 0.3608506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 471 571 0.194824 -0.392409 -0.109015 -0.1036040 0.4686460 0.7435552 0.4655779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 472 572 -0.515598 -0.242278 0.104036 0.2759678 0.0791737 0.7135774 0.6390466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 473 573 -0.432600 -0.143013 0.449186 -0.0549852 0.6071866 0.3066788 0.7309235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 474 574 -0.403667 -0.536330 -0.076367 -0.2002783 -0.6390057 0.6246892 0.4016513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 475 575 0.389990 0.429346 -0.135201 0.3032346 0.5935641 0.6196054 0.4145112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 476 576 0.545191 0.362010 0.335090 0.8745413 -0.2875627 0.2780469 0.2741810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 477 577 0.074447 -0.285285 0.463613 -0.4562970 0.1252909 0.7067612 0.5259123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 478 578 0.681858 0.100977 0.082778 -0.2772639 0.4504048 -0.3446576 0.7755459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 479 579 -0.372283 0.438104 -0.461993 -0.2499773 -0.3539920 0.5192503 0.7366004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 480 580 0.657690 0.746007 0.074880 -0.2401555 0.3871801 0.1110662 0.8832221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 481 581 0.462462 -0.062411 -0.436154 -0.0820409 0.4847198 -0.7546463 0.4345400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 482 582 0.342157 0.639436 -0.219653 -0.1409765 0.1564388 0.8071200 0.5515523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 485 585 0.306089 -0.506823 0.321808 -0.7401718 0.1723144 0.1631785 0.6291472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 486 586 -0.334741 0.446065 -0.564412 0.1808758 0.1192696 -0.7900507 0.5734794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 487 587 0.185249 -0.454246 -0.326757 0.2776430 -0.2599887 -0.9038452 0.1959185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 488 588 -0.422088 -0.546061 -0.124686 -0.6549752 -0.0169999 0.0579975 0.7532296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 489 589 -0.081725 -0.613223 0.352572 0.5372084 -0.0813273 0.0410989 0.8385129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 490 590 0.531829 -0.001658 0.478711 -0.6916088 -0.4932143 -0.4676280 0.2444198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 491 591 0.708889 -0.154934 0.088191 0.0293540 -0.9505259 0.2886656 0.1109554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 493 593 -0.784668 0.505692 0.104764 -0.2359271 -0.4891275 -0.3661374 0.7556693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 494 594 0.776439 -0.415145 -0.096441 0.8206346 0.1531653 -0.3521632 0.4231788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 495 595 0.381133 -0.157136 0.606441 -0.0605292 -0.4781816 0.1301414 0.8664536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 496 596 -0.354863 -0.482739 0.522543 0.3096613 0.0460871 -0.8504858 0.4226816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 497 597 0.322140 0.525400 -0.369856 -0.0058329 -0.1325037 -0.3104082 0.9413052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 498 598 -0.426305 -0.123167 0.467390 0.2280650 0.7438036 -0.6277970 0.0247685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 499 599 0.584615 0.446326 0.051427 -0.1081095 -0.2125539 0.1109277 0.9647944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 500 600 0.596088 0.087796 -0.195850 0.0860888 -0.7255164 -0.6121324 0.3025039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 501 601 0.573275 0.511654 0.020884 0.5493279 -0.7183726 0.3605954 0.2283651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 502 602 0.513441 0.224628 0.602740 -0.4883839 0.5304762 -0.0513589 0.6909692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 503 603 0.574563 -0.410014 -0.406752 -0.4931872 0.4808877 -0.5349074 0.4892724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 504 604 0.475049 0.170501 0.661242 0.1761037 0.0598683 -0.9601456 0.2086234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 505 605 0.528741 -0.372370 -0.087589 -0.4511115 -0.3246244 0.3397914 0.7587221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 506 606 -0.424604 -0.001827 0.343669 0.3301458 0.6148801 0.5247957 0.4873559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 507 607 0.430773 -0.512727 -0.554528 0.1788658 0.0587672 0.8515858 0.4892393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 508 608 -0.141788 0.411903 -0.631713 -0.1757728 0.0574377 -0.8974768 0.4004251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 509 609 0.653037 0.053055 -0.122840 0.7311879 -0.0428945 0.6805617 0.0189736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 510 610 0.164819 0.649599 -0.233299 -0.6744991 -0.3923025 -0.5734409 0.2496303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 511 611 0.061865 -0.450120 -0.583722 0.3587052 0.4117316 -0.1973465 0.8141634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 512 612 0.026910 0.651867 -0.227380 -0.2183309 0.2945180 -0.8885754 0.2757253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 513 613 0.564696 0.269344 -0.314421 -0.3552531 -0.3289863 0.8745558 0.0267475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 514 614 -0.350879 0.413167 0.465330 -0.4736787 0.0912925 0.8326000 0.2721606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 516 616 -0.042300 0.431129 0.482199 -0.6974659 -0.1843620 0.6060050 0.3351267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 517 617 -0.101330 -0.681589 0.205175 0.0711748 0.1368341 0.7075416 0.6896343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 518 618 -0.503376 -0.435048 0.221371 0.6504295 0.4923473 -0.0848086 0.5721391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 521 621 0.477046 0.336725 0.221895 0.1138733 -0.2000429 0.8185358 0.5263220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 523 623 0.502120 -0.508862 0.012900 -0.0192083 -0.1335462 0.3163708 0.9389920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 524 624 0.051602 -0.400119 0.245890 0.0091853 -0.1487611 -0.4676316 0.8712671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 526 626 0.430649 -0.093972 -0.247420 -0.3142268 0.0115130 -0.6331132 0.7073165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 527 627 -0.031299 -0.286939 0.452397 0.1779741 -0.2041990 -0.2284258 0.9351201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 528 628 0.457671 -0.359079 0.402584 -0.0422276 -0.8877888 0.3371842 0.3104104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 529 629 0.507380 -0.146658 -0.105343 0.4653045 -0.6863499 0.3863499 0.4039174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 530 630 0.424130 -0.111515 0.335029 -0.2983288 0.0982929 -0.4217075 0.8505888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 533 633 0.159392 0.565399 0.007261 -0.2453217 0.5240658 0.2023068 0.7900913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 535 635 -0.319566 0.233259 0.122910 0.0843362 -0.0499393 -0.5648117 0.8193786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 536 636 0.280527 -0.034556 -0.313692 -0.0941708 -0.0855419 0.9724280 0.1954435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 537 637 -0.085568 0.315233 -0.769183 -0.3517226 -0.3913332 -0.4566737 0.7173553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 538 638 -0.230488 0.226892 -0.610698 -0.4065789 -0.2977795 -0.2823138 0.8162842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 539 639 0.008835 -0.377075 -0.239098 -0.4473802 -0.0673010 0.1419841 0.8804329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 540 640 0.465569 0.327809 -0.333337 0.7577331 -0.3626803 0.4107129 0.3544270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 541 641 0.564621 0.056490 -0.073740 -0.5567582 0.0838469 -0.5324434 0.6320554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 542 642 -0.358691 -0.070368 -0.158811 0.0460751 -0.4217279 -0.0684951 0.9029569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 543 643 -0.482450 -0.157941 -0.083603 0.2095027 0.9299996 -0.2556700 0.1607554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 545 645 0.297994 0.130117 0.450693 0.0638033 -0.8374591 0.4728830 0.2664075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 546 646 0.341517 -0.118283 0.232253 0.7355907 -0.4159072 0.2355103 0.4800651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 547 647 -0.392861 0.440353 -0.106908 0.4190968 0.6558353 0.1305086 0.6141705 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 550 650 0.230588 0.525918 0.009798 0.1969020 0.2212121 -0.7158919 0.6322924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 551 651 0.325422 -0.024832 -0.090587 0.6177256 0.0730168 0.7069456 0.3366177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 552 652 -0.444645 -0.101253 0.400384 -0.6644749 0.1379440 -0.5945567 0.4312156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 553 653 0.071073 0.421484 -0.028331 0.0381972 -0.0173751 0.8592291 0.5098671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 554 654 -0.484498 0.051558 -0.023902 0.5581591 -0.2394066 -0.1800622 0.7737703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 556 656 0.184047 0.551634 -0.031211 -0.2058620 -0.2602595 -0.5724248 0.7498104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 557 657 0.485514 -0.119865 -0.411462 0.8008188 -0.0206792 0.1471068 0.5801907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 558 658 -0.044087 0.450150 -0.084743 0.1202306 0.6491799 -0.7364683 0.1473925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 559 659 -0.057856 0.205755 -0.541022 -0.8322843 0.3427852 0.2814903 0.3325122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 560 660 -0.043900 -0.002299 0.615649 0.3136130 0.6905591 -0.5166488 0.3973023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 561 661 0.250157 0.420315 -0.088505 0.6871184 0.5844093 0.0236872 0.4310140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 562 662 -0.329029 -0.354938 0.037409 -0.6257253 0.1707631 -0.0694195 0.7579503 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 564 664 -0.232998 0.171901 -0.393019 -0.5504408 -0.3084007 -0.2215544 0.7435170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 565 665 0.373853 0.343284 0.539963 -0.8362379 -0.0117700 0.1228012 0.5343102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 566 666 0.073841 0.024995 -0.667946 -0.2990370 -0.2374957 0.6458210 0.6611262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 567 667 0.108821 -0.531878 0.641814 -0.3708440 0.6884083 0.2234670 0.5819203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 568 668 0.506328 0.315004 -0.303920 -0.7297954 -0.0348601 -0.6798141 0.0635308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 569 669 0.265143 -0.602601 0.097992 -0.5362453 -0.4537739 -0.0843363 0.7066948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 570 670 0.398833 -0.011084 -0.449457 -0.2069313 0.6175125 -0.7106864 0.2660499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 571 671 -0.450856 -0.206406 -0.369582 -0.1710328 -0.5900228 0.3458492 0.7092314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 572 672 -0.293537 0.558653 -0.217618 -0.6800622 -0.3222862 -0.4992506 0.4294133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 573 673 -0.373787 0.207950 -0.387795 -0.5949064 -0.6609650 0.4189779 0.1834914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 574 674 -0.238652 0.256079 0.440231 0.1216655 0.1657652 -0.9772779 0.0514518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 577 677 -0.694607 -0.419055 0.260142 0.2306806 0.2717329 -0.5292552 0.7699589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 578 678 0.085141 0.122468 0.820599 0.5387813 0.2529499 0.3475925 0.7245071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 579 679 0.191925 0.808524 -0.086411 -0.1448302 -0.0484987 -0.1361187 0.9788482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 580 680 0.237407 0.215470 0.675605 0.4915608 0.5001860 -0.4223509 0.5742836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 582 682 0.370828 -0.569129 -0.046621 -0.5700153 -0.7929233 0.0892026 0.1959544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 583 683 -0.081806 -0.581425 0.321355 -0.5038613 0.5692597 -0.2907494 0.5809750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 584 684 -0.284281 -0.297629 -0.546320 -0.3824589 -0.6772056 0.1375687 0.6133454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 585 685 0.343060 -0.377847 -0.803473 0.5928628 -0.2062688 -0.1917500 0.7544527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 586 686 0.289304 -0.463026 -0.560313 0.5351229 -0.1719709 -0.3922278 0.7281668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 587 687 0.362896 0.563969 -0.557778 -0.8689580 0.1353651 -0.4701279 0.0746198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 588 688 -0.695090 -0.055973 -0.450539 0.1354005 -0.4216539 -0.3595974 0.8213187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 589 689 0.043823 0.064177 0.615400 -0.2891109 -0.2422372 0.0692376 0.9235487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 590 690 0.347407 0.680220 0.059586 -0.6254444 0.4350146 -0.3004382 0.5738628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 592 692 -0.461511 0.709087 -0.233789 0.1765571 0.4295175 0.8816179 0.0842155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 593 693 -0.132074 -0.308321 0.662203 0.6582123 0.4914447 0.2943607 0.4884571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 594 694 0.502842 0.492811 0.029669 -0.0555138 0.5200266 -0.8518377 0.0293778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 596 696 0.137063 -0.196461 0.624605 -0.2043657 0.0881661 0.8164111 0.5328548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 598 698 0.087755 -0.613092 0.186560 -0.0669435 -0.0281041 -0.1405458 0.9874085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 599 699 0.571179 0.380608 0.077521 -0.0930346 -0.6095280 0.4581828 0.6402255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 600 700 -0.671578 -0.286915 -0.303794 0.1291758 0.3896590 0.7388528 0.5343931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 601 701 -0.439894 -0.514752 -0.464637 0.6546621 -0.3803364 0.6364899 0.1471133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 602 702 0.080856 -0.580707 0.575043 0.0444592 0.4037869 0.9051081 0.1255343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 603 703 0.314319 0.462836 0.723902 0.1791574 -0.3984517 0.6456424 0.6263265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 604 704 -0.722122 0.009353 0.476713 -0.6299586 0.3480497 0.6940122 0.0189905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 605 705 -0.107921 -0.029923 -0.811243 0.3431157 -0.0533717 0.8648630 0.3625398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 606 706 -0.020868 0.572052 -0.625415 0.1174038 0.1375643 0.7778482 0.6018676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 607 707 -0.714467 -0.398132 -0.235804 -0.2460531 -0.0997961 -0.8471492 0.4602574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 608 708 -0.466798 -0.157118 -0.685476 -0.0102512 0.5846014 -0.7577989 0.2896152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 609 709 0.130186 -0.428669 0.615215 -0.2064001 0.2706616 -0.1797290 0.9229511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 610 710 0.170580 -0.483842 0.524865 0.6152055 0.3173340 0.7117289 0.1194289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 611 711 0.312024 -0.406730 0.291549 -0.3211658 -0.0850571 0.0033126 0.9431897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 613 713 -0.168273 0.059685 -0.634218 0.6067267 -0.2493559 0.5756901 0.4881447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 614 714 -0.138931 -0.223189 0.647084 -0.7796195 -0.5629322 -0.1101078 0.2513506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 615 715 -0.091623 0.666061 0.216297 -0.0457955 0.1283147 0.7341467 0.6651817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 616 716 0.007124 -0.627327 0.267778 0.0402595 -0.7302153 -0.0529478 0.6799715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 617 717 -0.620912 -0.029275 -0.061573 0.1263844 -0.0462466 0.7177092 0.6832142 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 618 718 -0.439197 -0.495443 -0.018734 -0.5119536 0.0706645 -0.6213149 0.5889634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 619 719 0.426087 -0.243618 -0.582670 0.2486483 0.4283209 0.6551985 0.5704648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 620 720 -0.452703 -0.426817 -0.306790 0.5043680 0.5374257 0.6017375 0.3077312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 621 721 0.196829 -0.516689 0.006867 -0.0991449 0.6097093 0.3820197 0.6873760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 623 723 -0.077533 -0.694553 0.005558 -0.1224049 0.3396437 0.9305867 0.0605611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 624 724 0.744376 -0.345360 0.210132 0.1963725 0.1709663 -0.0931424 0.9610062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 625 725 -0.042925 -0.037635 0.716545 0.0237058 0.8958515 -0.4360273 0.0822695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 627 727 0.330308 0.123679 0.455584 0.7822613 -0.4314690 -0.4029789 0.1987706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 628 728 -0.131730 -0.531266 -0.164990 0.7257649 -0.5253111 0.4333959 0.0973732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 629 729 -0.257108 -0.476803 0.040318 -0.5840748 -0.4237615 -0.6707948 0.1712225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 630 730 0.597278 0.345070 0.297318 0.2128272 -0.3996823 -0.0939051 0.8866456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 631 731 0.171603 -0.097036 0.320143 -0.1524123 -0.4922553 -0.1631270 0.8413352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 632 732 0.416320 -0.255850 -0.321218 0.5120959 0.7707674 0.3672160 0.0939560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 633 733 -0.108016 0.262509 0.540500 0.1892458 0.6265732 -0.6137000 0.4415476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 634 734 -0.299758 -0.339933 -0.095211 0.2618950 -0.7185000 -0.1225728 0.6325699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 636 736 -0.410524 -0.195065 -0.468027 -0.5873965 -0.2033863 0.7590133 0.1936444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 638 738 -0.595244 0.176638 0.031310 -0.0031742 -0.1826843 -0.9822488 0.0424700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 639 739 -0.149019 -0.164939 -0.594836 -0.0001045 0.2097902 0.9758686 0.0605692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 642 742 -0.518350 -0.086992 0.205630 0.0611285 -0.7376368 0.2512307 0.6237294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 643 743 0.295717 -0.408167 0.119540 0.7293241 -0.5887216 -0.3474449 0.0278435 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 644 744 -0.349887 -0.029071 -0.244768 0.0954185 -0.2255894 -0.6877347 0.6833928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 645 745 0.468166 -0.274710 -0.469072 -0.3991181 0.3616415 -0.8255791 0.1683430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 647 747 0.371387 -0.053810 -0.354453 -0.2788505 0.7665708 -0.0291829 0.5777196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 648 748 -0.326905 0.230336 -0.507483 0.2612473 0.6123368 -0.7318442 0.1455939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 649 749 -0.335220 -0.544349 0.178303 -0.3783531 -0.6676742 -0.0979656 0.6336109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 650 750 -0.368149 0.103176 -0.121890 0.6371733 0.5893737 -0.4950814 0.0392844 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 651 751 -0.346566 -0.364685 0.374869 0.2578124 0.5683996 0.7661077 0.1534071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 652 752 0.141565 -0.229577 -0.372078 0.2213215 -0.6344670 0.7035733 0.2311991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 653 753 0.292421 -0.227567 0.088015 0.0370182 0.6815973 -0.6820928 0.2623057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 654 754 -0.102368 -0.276573 0.382251 0.1988593 0.3239019 0.8905247 0.2500166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 655 755 0.008050 0.276996 0.382556 0.4249470 -0.3487604 -0.8111559 0.1995304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 656 756 -0.295849 0.303695 0.381851 -0.5598009 -0.0748455 -0.8174753 0.1129393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 658 758 -0.170733 0.061656 -0.400204 0.0374540 -0.7874812 0.5695073 0.2326628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 660 760 -0.481692 -0.287559 0.187838 0.1216032 0.0787912 -0.8893991 0.4335595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 661 761 0.502338 0.378417 -0.358818 -0.7011682 0.5315295 0.4432460 0.1713842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 662 762 -0.108731 -0.093707 -0.565451 0.1002962 -0.3577775 0.2992155 0.8788663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 663 763 0.043315 0.476338 0.183025 0.2550373 0.5570464 -0.6058138 0.5075874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 664 764 -0.596716 -0.047778 -0.041844 0.0410508 -0.1933094 0.9755979 0.0956815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 665 765 0.264029 -0.627392 0.035751 0.6082010 -0.4972302 -0.2828661 0.5503094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 666 766 -0.195903 0.566800 -0.256749 0.7216231 -0.3228770 -0.2767263 0.5462903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 667 767 -0.288233 -0.361739 -0.197471 0.0204375 -0.0705368 0.7611911 0.6443563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 668 768 -0.185726 -0.258974 0.428794 0.5945256 -0.2203804 0.6089705 0.4765782 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 669 769 0.401661 -0.164010 -0.768432 0.0569340 -0.7160386 0.5573407 0.4164356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 670 770 -0.273319 0.468750 0.317529 -0.6501719 -0.1071230 0.7318438 0.1737980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 671 771 -0.580140 0.187967 0.241156 0.2026158 0.0247773 -0.7045795 0.6796327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 672 772 -0.314223 -0.659074 0.204569 -0.1303049 0.0013705 -0.6382645 0.7587076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 674 774 0.112760 -0.282021 0.523746 -0.0552808 0.1470812 -0.5637574 0.8108568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 675 775 0.178492 0.483460 -0.256043 -0.3948353 -0.3543261 -0.0439344 0.8465388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 676 776 0.663203 -0.376706 0.070511 0.0963806 -0.4578287 0.2012958 0.8605717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 677 777 0.065708 -0.693162 0.189058 0.0241942 -0.5921514 -0.1431574 0.7926395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 679 779 -0.017037 0.527862 -0.000264 -0.1601396 0.2969918 0.8703828 0.3585875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 681 781 -0.171455 0.583782 -0.385702 0.1101037 -0.8418371 -0.4386820 0.2945260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 682 782 -0.601231 -0.091709 -0.488855 0.5941621 -0.2265797 0.6504636 0.4153674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 683 783 0.386778 -0.436784 -0.033466 0.2486309 0.1758809 0.3800495 0.8733905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 684 784 -0.618160 -0.025254 0.098772 0.5042713 -0.2428073 -0.0949747 0.8232466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 685 785 0.303070 -0.558465 -0.260603 0.5252149 0.1542575 0.1897890 0.8150669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 686 786 0.509206 -0.501166 -0.117447 0.5494916 0.1141194 0.6458596 0.5175917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 688 788 -0.285903 -0.548186 0.101515 0.0883334 0.3732382 0.9012582 0.2015544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 689 789 0.703839 -0.343471 0.489488 -0.3084452 -0.5684371 0.4385345 0.6240419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 690 790 -0.308960 -0.200390 0.911793 -0.1540779 0.5630082 -0.6127028 0.5328012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 691 791 -0.585263 0.356466 0.004883 0.4151765 0.8544577 0.2913765 0.1123848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 692 792 0.640681 -0.386988 0.278935 -0.8383985 -0.1232506 -0.5306465 0.0176487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 694 794 -0.392595 -0.281108 -0.498253 0.5600371 0.4833603 0.5136689 0.4345866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 695 795 -0.254001 -0.674183 -0.166423 -0.2194793 -0.0757467 -0.0659697 0.9704325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 696 796 -0.401674 -0.264191 0.436691 0.4920648 0.5950649 0.5833937 0.2518369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 697 797 0.526837 -0.392887 0.547286 0.1042259 -0.7814945 0.0349734 0.6141500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 698 798 0.457434 -0.570353 0.296316 0.1646428 0.1910755 -0.5013864 0.8276440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 699 799 0.288187 -0.105944 -0.841033 -0.5037698 -0.3787186 -0.7669033 0.1210271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 702 802 -0.293530 0.814465 -0.006877 0.7614292 0.3271256 0.3727870 0.4174257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 703 803 0.801082 -0.520291 -0.148192 -0.1284258 -0.2001728 -0.8906018 0.3876416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 705 805 -0.594897 -0.000287 -0.510205 0.4442476 -0.4262505 0.6427653 0.4558589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 706 806 0.627634 -0.227154 -0.391886 0.1654935 -0.0445065 0.5869689 0.7912639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 707 807 0.261119 -0.421097 -0.602628 -0.1103759 0.6648309 -0.7122137 0.1963892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 709 809 -0.154989 -0.631687 0.367897 -0.0784291 -0.1306050 -0.9874584 0.0414379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 710 810 0.022043 0.651944 -0.033711 0.5235569 -0.0121946 -0.0633696 0.8495433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 711 811 0.522359 -0.278026 0.170509 -0.6720069 0.1049615 0.6955657 0.2314695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 713 813 -0.558997 0.128095 -0.276047 -0.8491347 0.2654554 -0.1062991 0.4440769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 715 815 0.551863 0.238472 0.469111 -0.2084812 -0.6716161 0.6238030 0.3410823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 716 816 0.318334 -0.474915 0.113386 0.3792230 0.1001593 0.6246435 0.6752618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 719 819 -0.124726 -0.822269 -0.076240 0.5627449 -0.2805199 -0.7487022 0.2099330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 720 820 -0.356143 -0.323521 -0.411576 -0.2785243 0.7666865 0.5553754 0.1617841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 721 821 -0.205745 -0.704629 -0.049470 -0.3684280 -0.0524749 0.1256033 0.9196364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 722 822 -0.541473 0.221714 0.124116 -0.2453891 0.8067244 0.5256712 0.1124713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 724 824 0.568754 0.041425 0.248691 0.4051374 -0.7373645 -0.0433053 0.5387781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 725 825 0.091365 -0.607101 -0.236070 0.5149955 -0.1937223 -0.5085814 0.6622660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 726 826 0.417869 0.113504 0.313455 -0.1132880 -0.4444457 -0.0217834 0.8883464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 727 827 -0.280201 -0.155795 -0.495855 -0.6536381 -0.2114771 0.1477227 0.7114862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 728 828 -0.028321 0.443078 0.435053 0.1487456 0.7894183 0.2100880 0.5572760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 729 829 -0.020111 0.136398 -0.640517 -0.4507932 -0.2247590 0.0966410 0.8584459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 730 830 0.419540 0.187615 -0.205938 -0.4233261 0.4960633 0.5619633 0.5088353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 731 831 0.519835 -0.035671 0.380040 0.0202087 0.6231981 -0.6966658 0.3547851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 732 832 -0.237083 0.241778 0.301306 0.1946319 0.5608579 0.0366611 0.8038736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 733 833 -0.612848 -0.380919 -0.108035 0.5097191 0.2947307 0.2509477 0.7683394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 735 835 -0.650509 0.005175 -0.013872 0.4135280 0.3263665 -0.8478423 0.0603563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 736 836 0.434717 0.406689 0.210436 0.0320759 -0.8473095 0.0275061 0.5294159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 737 837 -0.012187 0.098318 0.610991 0.5018666 -0.0927578 -0.3405323 0.7896605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 740 840 0.341406 -0.315715 0.415906 0.1259466 -0.1105632 0.7407039 0.6505927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 741 841 0.283494 -0.366556 -0.060282 0.4829433 0.2388921 -0.6366933 0.5516502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 742 842 0.171138 0.210032 0.385833 0.6187642 0.3257349 0.5188298 0.4917757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 743 843 0.312202 -0.024606 -0.213102 0.5237802 0.6051523 0.5785750 0.1571495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 744 844 0.343453 -0.491669 -0.255511 0.3941257 -0.3530594 -0.8476986 0.0376964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 746 846 -0.603631 -0.104364 0.086129 0.2242500 0.2647734 0.7618733 0.5469517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 747 847 0.104272 -0.096270 0.386463 -0.3284308 -0.6888128 -0.5617071 0.3196174 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 748 848 0.442233 0.163199 -0.181655 0.2823746 0.3052777 0.1964169 0.8879699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 751 851 0.194552 0.161526 -0.406673 0.7390122 0.1327419 -0.6563831 0.0734969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 752 852 -0.354947 -0.078100 0.036881 -0.1224918 0.9276265 -0.3083291 0.1715752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 753 853 -0.235324 0.148379 0.443574 0.2130572 0.0670378 -0.9747262 0.0046229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 754 854 0.101200 0.458350 -0.202333 -0.0470439 0.6307398 0.7682953 0.0983695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 755 855 -0.125525 0.060770 0.380536 -0.4080515 -0.4436947 -0.7896093 0.1146567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 756 856 0.370568 -0.238516 -0.136969 -0.2628620 -0.4656843 0.8424395 0.0658585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 757 857 -0.215441 -0.075018 0.436156 -0.9040745 -0.3812316 -0.1536420 0.1170720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 759 859 -0.435145 -0.261789 -0.321742 -0.0493651 0.9150470 -0.3986310 0.0366792 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 760 860 0.570627 0.012691 0.281416 0.6756030 -0.0416141 -0.4757699 0.5616688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 761 861 -0.087720 -0.330201 0.014888 0.1086357 0.0771407 0.1564012 0.9786655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 762 862 -0.273908 -0.020904 -0.346721 -0.3683648 0.0303905 0.5696934 0.7340526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 763 863 -0.424068 -0.247002 -0.401968 -0.9260549 -0.3288114 0.1392194 0.1221610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 764 864 0.457932 0.203505 0.235156 0.5095525 -0.5824832 -0.5647113 0.2866542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 765 865 0.676306 0.010327 -0.235519 0.5662754 0.1214967 0.4473583 0.6814993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 767 867 -0.412794 0.446226 -0.094858 -0.3985985 -0.5203346 -0.6035686 0.4539559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 768 868 0.483751 0.382983 0.435782 -0.7137420 -0.3777157 -0.5761359 0.1263751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 769 869 -0.693550 0.056571 -0.011772 0.6881223 0.0134648 0.4431640 0.5743797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 770 870 0.125971 -0.207641 0.344771 0.7517569 0.1112176 -0.6180022 0.2014088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 771 871 -0.127728 -0.505491 0.384443 -0.1030531 -0.0242283 0.9794192 0.1718463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 772 872 0.573511 -0.305084 0.184808 -0.4073247 0.5156304 -0.5793804 0.4822138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 773 873 0.314804 0.331473 0.333181 0.1814760 -0.3573606 0.2591679 0.8787445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 774 874 0.220240 0.110905 0.454754 -0.7333615 0.1642866 0.6133043 0.2429992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 775 875 0.049369 0.780722 0.072292 -0.0887521 -0.2059355 0.2295862 0.9471028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 776 876 0.036417 -0.572884 -0.315122 0.2744014 -0.7163748 0.5230274 0.3714206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 777 877 0.431914 -0.477699 -0.003272 -0.0227205 0.4821224 -0.6313374 0.6070048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 778 878 -0.227201 -0.161001 0.491758 0.7607694 -0.4276840 0.4621052 0.1574011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 779 879 0.491865 -0.111139 0.560534 0.2018396 0.3139568 0.8883259 0.2675239 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 780 880 0.381940 0.534356 -0.210273 0.0481110 -0.2163499 0.7789611 0.5865984 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 782 882 -0.330286 0.429369 -0.448224 -0.7421638 -0.2189768 -0.1698279 0.6102462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 784 884 -0.580685 0.301981 0.588627 -0.0255571 -0.4642196 0.8476943 0.2554631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 785 885 -0.016874 -0.308520 0.610984 -0.0914004 0.2099634 0.9658141 0.1215089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 786 886 -0.509566 -0.084163 0.508410 0.1736921 0.6912742 0.3124714 0.6279592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 787 887 0.682879 -0.143454 0.496126 -0.0850332 0.5459356 0.5919859 0.5867506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 788 888 -0.021399 0.689941 -0.392812 0.2719104 -0.5753403 -0.6882348 0.3483979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 789 889 -0.046142 -0.347214 -0.575357 -0.0342429 0.8447005 -0.5038075 0.1774445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 790 890 -0.007517 -0.634227 -0.061722 0.4776689 -0.1497001 0.0488991 0.8643096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 792 892 -0.002461 0.550825 0.322376 0.6700161 -0.1719872 0.3311573 0.6417426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 793 893 -0.635601 0.342515 0.419499 0.0422643 -0.4378962 0.7373935 0.5125538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 794 894 -0.449029 -0.687181 -0.309643 -0.0117350 -0.4988293 0.8655269 0.0435299 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 795 895 -0.259723 -0.584955 -0.056055 -0.3513189 -0.1283839 -0.8405950 0.3917814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 796 896 -0.061388 0.260777 -0.614494 -0.6554185 -0.4787114 0.3649476 0.4561526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 798 898 0.396334 0.400494 0.615771 -0.1568763 -0.2794814 -0.5445628 0.7750686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 799 899 -0.714833 -0.342452 0.233135 -0.6810553 0.6427202 0.3456352 0.0600896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 800 900 0.511147 0.599382 -0.000815 -0.5626000 0.1923053 0.3974188 0.6989694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 801 901 0.683612 0.248935 -0.140588 -0.3526034 0.3132389 -0.2847668 0.8345419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 802 902 0.537092 -0.082729 -0.745205 0.1044627 0.5228246 0.8156064 0.2247847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 803 903 -0.094005 0.661939 0.077774 0.0714776 -0.1941411 -0.5533191 0.8068693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 805 905 -0.361168 0.693431 0.013764 -0.7290830 -0.1354986 -0.5648485 0.3619728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 806 906 0.345200 -0.729742 -0.198020 0.4611587 0.1479899 0.4637300 0.7418801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 807 907 -0.120365 0.395508 0.436642 -0.1608115 0.1860915 -0.2398170 0.9391472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 808 908 -0.355005 0.742052 0.147987 0.0182261 0.3975592 0.8528067 0.3381348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 810 910 0.122374 0.340182 -0.516863 -0.8946954 0.0330088 -0.1414714 0.4223937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 811 911 -0.083503 0.339441 -0.631550 -0.2985156 0.1054754 -0.2404297 0.9175821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 812 912 -0.469445 0.405918 -0.363694 0.0497558 0.2749207 -0.2420475 0.9291695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 813 913 -0.543588 0.481575 -0.136521 -0.6652605 0.1924692 0.7156884 0.0904115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 814 914 0.518866 0.201308 -0.474696 0.4275574 0.2902409 0.1826324 0.8364211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 815 915 -0.137390 -0.499134 -0.412030 0.1992205 0.2970701 0.5963439 0.7186338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 816 916 -0.500167 -0.214599 0.609661 0.0817577 0.5211398 -0.0994276 0.8437080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 817 917 -0.149434 0.354498 0.453581 0.1018635 0.1275745 -0.1843123 0.9692149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 818 918 -0.051253 0.420847 -0.520111 -0.2320814 0.4189683 0.0899885 0.8732158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 819 919 0.395934 0.561516 -0.170984 -0.5903351 -0.4027451 0.6844576 0.1442866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 820 920 0.572222 -0.157159 -0.181303 -0.4655152 -0.3920137 -0.5822593 0.5390686 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 821 921 -0.416460 -0.346682 -0.463448 -0.0090126 0.3853369 -0.4387986 0.8117204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 822 922 0.349344 0.365478 0.166856 0.4603214 -0.7059320 -0.4977804 0.2048874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 823 923 -0.709281 0.117177 -0.128790 0.2366863 0.8762928 0.2549375 0.3333129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 824 924 0.184191 -0.038731 -0.725866 -0.7913308 0.1142077 0.1537982 0.5806017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 825 925 0.581057 -0.100049 0.068162 -0.4274725 0.4393129 0.6515496 0.4469390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 826 926 0.684238 0.135995 -0.156154 0.4428980 0.0634670 -0.8654399 0.2254486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 827 927 -0.269174 0.589491 0.095284 0.0376004 -0.6477792 -0.5662382 0.5082742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 828 928 -0.184129 0.714831 -0.022284 -0.4103935 -0.5126596 0.3858131 0.6480013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 829 929 0.039073 0.381437 0.077540 -0.6396641 -0.5995110 -0.4372285 0.2006183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 831 931 -0.556347 -0.042251 0.215475 0.3511999 0.5093018 -0.6105682 0.4944459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 832 932 -0.421538 0.365704 0.167028 -0.5726071 -0.5210305 -0.1637180 0.6114285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 833 933 -0.521329 -0.321067 -0.135173 -0.1699643 0.2385289 -0.9349298 0.2003059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 835 935 0.411101 -0.155140 0.531287 -0.5679606 -0.6215182 0.4883723 0.2294088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 837 937 -0.342144 0.512322 0.113208 0.4279319 -0.2384867 0.7807753 0.3877993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 839 939 -0.377137 -0.404807 -0.124381 -0.0104617 0.4540604 -0.6180367 0.6416777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 840 940 -0.062776 -0.313553 0.493218 0.0160186 -0.2255066 0.9670457 0.1171018 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 841 941 0.303545 0.288655 0.266818 0.0429074 0.3971034 0.5695966 0.7183506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 842 942 0.179667 0.503248 0.277587 -0.8913784 0.0224376 0.4281324 0.1471178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 843 943 -0.152134 -0.222267 0.384852 0.5304327 0.3671496 0.4973125 0.5801058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 844 944 -0.084335 0.043940 -0.458860 0.1398072 0.6061076 0.6294698 0.4656772 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 845 945 -0.270337 0.631210 -0.135563 -0.7428366 0.0431416 0.2180335 0.6315013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 846 946 0.069551 0.532250 -0.475386 -0.1695850 -0.2693360 -0.2397957 0.9171680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 847 947 0.273035 0.283747 0.131928 -0.7421334 0.3091774 -0.5866800 0.0972319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 848 948 0.650596 0.212946 0.084398 0.6142802 -0.3211450 -0.4857269 0.5325365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 849 949 0.548040 0.072142 -0.106134 0.0362652 -0.2318197 0.5422816 0.8067684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 850 950 0.358517 0.003807 -0.049192 0.3936805 -0.3761376 0.4384787 0.7150333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 851 951 0.338805 -0.345259 -0.046410 0.9918303 -0.0701343 0.0536508 0.0920616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 854 954 -0.070959 -0.094842 0.580348 0.0605416 0.7193964 0.6187526 0.3097559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 855 955 0.571697 -0.000422 -0.085537 -0.0842287 0.1942976 -0.6164371 0.7583925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 857 957 0.003567 -0.230768 -0.288564 -0.5693244 0.4758267 -0.5284454 0.4125581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 858 958 0.138870 -0.216113 0.454428 -0.9358703 -0.1209428 -0.0916471 0.3179944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 860 960 0.191293 0.347644 -0.381990 -0.2142239 -0.7582234 -0.5019132 0.3567751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 861 961 -0.076371 -0.411150 0.310350 -0.4876067 0.5281691 0.6146567 0.3247679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 862 962 0.064046 0.684488 -0.192969 -0.4121498 0.3276020 0.8493619 0.0373321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 863 963 -0.233860 -0.125066 0.391600 0.6873055 0.6385937 -0.2657830 0.2217398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 864 964 -0.319344 -0.056208 -0.389950 -0.0702857 -0.4360140 -0.6889630 0.5747014 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 866 966 -0.383644 0.324172 0.566149 0.4154122 -0.2367603 -0.4905580 0.7285123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 868 968 0.573316 -0.074520 0.313230 -0.0768809 -0.4236728 -0.6166936 0.6589990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 869 969 -0.183918 0.199535 -0.297253 -0.7236890 0.5382806 -0.2166253 0.3736331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 871 971 -0.206687 0.235997 0.539577 -0.0251637 0.7185784 -0.6592266 0.2200731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 872 972 0.294886 0.009993 0.575042 0.6074288 0.2868853 -0.7368180 0.0763305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 873 973 0.536819 0.406186 -0.202395 0.4259540 -0.3269744 -0.8212653 0.1928064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 874 974 -0.700492 -0.319286 -0.108098 -0.0707791 0.1197455 0.4374935 0.8883978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 876 976 -0.448874 -0.272176 0.307717 0.2903242 -0.1925223 0.9119993 0.2165742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 877 977 0.332750 0.292107 0.377387 -0.8524365 -0.2364056 0.4142194 0.2142115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 878 978 0.365953 0.176277 -0.559934 -0.0307598 -0.2779890 0.3606114 0.8897951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 879 979 -0.389592 0.353342 0.508806 0.1306654 -0.2655323 -0.8325079 0.4683478 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 880 980 0.381253 -0.263407 -0.683316 0.5191842 0.4039285 0.3664809 0.6580132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 881 981 -0.667341 -0.128649 -0.073612 0.3322411 -0.5936056 0.1869696 0.7087247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 882 982 -0.419431 0.070509 0.302459 -0.4415243 0.2928533 -0.7946280 0.2964113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 883 983 -0.639899 -0.397891 -0.337113 0.6298007 0.6347144 -0.3961901 0.2086195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 885 985 -0.409139 0.869826 0.005508 0.2836469 -0.3295825 -0.8757108 0.2098817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 887 987 -0.338353 -0.501439 0.491713 -0.5265220 0.0160050 0.2083057 0.8240917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 888 988 -0.349934 -0.641563 0.155491 0.4039743 0.7351675 0.5402169 0.0670758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 891 991 0.289509 -0.515332 0.318370 -0.8531509 -0.1988234 -0.4585095 0.1495721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 892 992 0.578580 0.324905 -0.188582 0.3359384 0.5724799 -0.4036696 0.6296531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 893 993 0.457895 0.425237 0.392303 0.5072890 0.2436435 -0.6022494 0.5662079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 895 995 0.420660 0.223830 -0.621835 0.3702976 0.4761297 0.5209774 0.6039559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 897 997 -0.048145 -0.489030 0.402039 -0.8813401 0.2273061 -0.0264868 0.4133642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 898 998 0.113184 0.566584 0.654376 -0.3798559 0.4904415 -0.6701447 0.4075325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 899 999 0.268374 0.749341 0.025842 -0.8667986 -0.0589496 0.4785352 0.1272369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 900 1000 0.662374 -0.484453 0.463469 -0.3844642 -0.4705888 -0.1199866 0.7850711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 901 1001 0.172905 0.491788 0.686107 0.8367855 0.1336997 0.5309363 0.0045887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 902 1002 -0.412031 -0.381017 -0.153069 0.0738306 -0.1441110 -0.3237412 0.9321871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 903 1003 -0.716838 -0.139923 0.393229 -0.4128053 0.6508304 0.0588808 0.6344640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 904 1004 0.416130 0.594279 -0.322986 -0.0949679 -0.0292765 -0.9932563 0.0597157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 905 1005 -0.068004 -0.802969 0.235082 -0.0351136 0.6185410 0.7743174 0.1288668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 906 1006 -0.385208 -0.631868 0.290089 -0.1539175 0.6754876 0.6498728 0.3125561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 908 1008 0.581110 0.256256 0.555619 0.0812194 -0.3538892 0.1289050 0.9227943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 909 1009 -0.176807 -0.175680 -0.590058 0.1136173 -0.5338277 -0.7549519 0.3635473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 911 1011 -0.320002 0.458500 -0.598608 -0.4421764 -0.0735878 0.1360386 0.8834922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 912 1012 -0.180409 0.126561 -0.474796 0.3711330 -0.3331425 -0.7192829 0.4836408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 913 1013 0.366336 -0.268981 0.548354 -0.5548896 -0.1877502 -0.2171432 0.7808305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 914 1014 0.679291 -0.100092 -0.148804 0.2382031 0.6972056 0.6608465 0.1429879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 917 1017 -0.403714 0.289122 0.209573 0.0230879 0.4648347 0.0546342 0.8834086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 918 1018 0.093520 0.341058 -0.342018 0.5212234 0.7080484 -0.4763460 0.0093884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 919 1019 0.244606 0.033596 -0.539529 -0.0453804 0.0058953 0.9969425 0.0633363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 920 1020 -0.209608 0.523464 -0.231650 -0.0761313 0.6509098 0.5762851 0.4882785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 922 1022 -0.647553 -0.111918 -0.108342 0.1596794 -0.3344945 -0.8943625 0.2504628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 923 1023 0.373116 -0.001463 -0.358688 -0.1904288 0.1376195 -0.9296005 0.2839730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 924 1024 0.173584 0.531034 0.248316 0.1854853 -0.2634853 0.8145767 0.4823230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 925 1025 -0.346905 -0.660017 -0.267672 -0.2803331 0.1984977 0.9218159 0.1796313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 926 1026 -0.496143 0.249831 -0.556385 0.1753254 0.2022758 0.8118247 0.5189280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 927 1027 -0.260543 0.066935 0.565632 -0.4987331 0.2948401 -0.7251573 0.3721310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 928 1028 0.450201 0.585069 0.420030 -0.0584882 0.6889028 -0.2780428 0.6668465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 930 1030 0.088012 0.208932 0.428092 0.3256231 0.1654025 0.4438142 0.8183157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 931 1031 -0.050305 -0.511849 0.104086 -0.5057335 0.0293453 -0.2274355 0.8316523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 932 1032 -0.268751 -0.303910 0.451171 0.2759481 0.7830457 -0.2382059 0.5039346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 933 1033 0.545337 0.217392 0.082340 0.7679566 0.3300509 -0.4173875 0.3565063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 934 1034 -0.143425 -0.152964 -0.452246 0.0880168 -0.0440206 0.7560099 0.6471200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 936 1036 -0.477585 -0.102168 0.017498 -0.2083085 -0.7727077 0.5737207 0.1742840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 937 1037 0.351307 0.135310 -0.331389 -0.7891591 0.2657073 -0.5165570 0.1994904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 938 1038 0.090529 -0.365761 -0.304058 0.5240105 -0.2353873 0.0398523 0.8175681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 939 1039 0.476752 -0.324632 -0.091126 -0.6935004 0.2017943 -0.5100121 0.4671444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 940 1040 0.060310 0.082157 0.409006 0.5821690 0.6719266 -0.1190724 0.4420585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 941 1041 0.318918 0.097439 0.539475 -0.3771688 0.2564265 0.3329386 0.8253127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 943 1043 -0.393310 0.355882 -0.052386 0.1119151 -0.3257692 -0.8107193 0.4733747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 944 1044 0.402549 -0.223830 -0.000132 -0.0914145 -0.7320299 -0.5945454 0.3198302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 945 1045 0.163067 0.203329 0.397431 0.1059328 -0.0593092 -0.0772592 0.9895917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 946 1046 -0.170019 0.588698 0.063451 -0.1213981 0.4767194 -0.1093580 0.8637372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 947 1047 0.041920 -0.402350 -0.055528 -0.1032461 -0.2235003 0.9692195 0.0011950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 948 1048 0.005437 0.070074 -0.652518 -0.4416896 0.2551343 0.3125920 0.8013134 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 949 1049 0.240981 -0.587930 -0.351372 -0.1284869 -0.3005812 -0.5064284 0.7979175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 950 1050 0.225466 -0.443997 -0.175083 -0.0348630 0.4356285 -0.8254195 0.3573444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 951 1051 0.493415 0.140180 0.116539 -0.4430224 0.5879255 0.1264619 0.6648926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 952 1052 -0.621069 -0.084155 -0.265957 0.1066927 0.0353877 0.9691092 0.2195260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 955 1055 -0.227296 0.473171 0.197294 -0.2686006 -0.3783896 0.6926509 0.5521864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 956 1056 0.458836 -0.044152 0.445362 0.3657272 0.1897173 -0.6505186 0.6380255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 957 1057 -0.023700 0.389462 -0.057767 -0.5726322 -0.3455089 -0.5946116 0.4462656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 958 1058 0.343893 0.200699 -0.570369 -0.3654090 0.5257770 -0.1945921 0.7430805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 959 1059 -0.160280 -0.580763 0.050347 -0.3399384 -0.5657781 0.1624314 0.7334529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 960 1060 -0.355910 0.012102 0.384739 0.8038570 -0.2660856 0.5268514 0.0737563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 961 1061 -0.202376 0.346490 -0.327286 -0.2102559 0.5595143 0.7554418 0.2684100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 963 1063 -0.466816 -0.223001 -0.474905 0.2561440 -0.6718315 0.4411309 0.5370626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 964 1064 0.227739 -0.644403 -0.149836 0.0203154 -0.3499212 -0.1713809 0.9207448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 965 1065 0.092838 -0.437338 0.139297 0.3785531 0.0872638 0.6947418 0.6053234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 966 1066 -0.369937 0.182910 0.342939 0.1120972 0.5981991 0.0917434 0.7881467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 968 1068 0.028141 0.882805 0.042444 -0.8278557 -0.4162305 0.2505833 0.2803839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 969 1069 -0.415165 0.591614 0.088123 0.5125992 -0.8012268 -0.1000915 0.2919921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 970 1070 -0.421098 -0.507916 0.057405 -0.3262167 0.1644590 -0.3778190 0.8507577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 971 1071 0.065443 -0.579602 -0.391670 0.6981950 0.0501926 -0.2312329 0.6756744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 972 1072 -0.444274 0.003552 0.003629 -0.3712591 0.5005143 0.7521340 0.2143516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 973 1073 -0.382500 -0.293168 -0.347488 -0.4328016 -0.4706213 -0.7574415 0.1322147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 974 1074 -0.577950 0.279366 0.012587 -0.3849747 -0.0603329 0.2589635 0.8837943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 975 1075 0.125762 0.330103 -0.663819 -0.6444509 -0.1730123 0.5438560 0.5088914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 977 1077 0.036575 -0.246764 -0.379319 0.7500002 -0.0999454 -0.4769694 0.4472257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 978 1078 0.336455 0.035001 -0.532951 0.8582248 0.3557303 0.2082792 0.3058200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 979 1079 -0.001207 -0.026757 0.460056 -0.6814152 0.4799616 0.3382806 0.4368941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 980 1080 0.163858 -0.363237 0.376539 0.0019326 0.2806298 0.2052372 0.9376144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 981 1081 -0.116624 0.489323 0.435233 0.6301725 -0.5551997 0.5260444 0.1338400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 982 1082 0.199810 -0.421660 -0.477006 0.0267224 0.0218615 -0.1865414 0.9818403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 983 1083 -0.209454 -0.281339 0.605315 0.5847617 -0.6586523 -0.0472610 0.4711658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 986 1086 -0.161029 0.704828 0.412258 -0.6282561 -0.4196198 0.6306337 0.1775234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 987 1087 -0.511271 -0.325261 0.044643 -0.1027671 -0.1353919 0.8947760 0.4128969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 988 1088 -0.087660 -0.115384 -0.840069 -0.8097913 -0.0111685 -0.5713814 0.1328029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 989 1089 -0.250148 0.417603 -0.572125 -0.0001451 0.6383302 -0.0860037 0.7649431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 990 1090 0.726006 0.209601 0.058960 -0.4675507 0.3666328 -0.7280811 0.3418694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 991 1091 0.294255 0.563358 -0.201999 0.3642163 0.5643559 -0.5226798 0.5250283 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 992 1092 0.327557 0.712279 -0.115043 -0.4262646 -0.4882030 0.2251774 0.7274967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 993 1093 -0.535505 0.549204 -0.377560 -0.0769842 0.1107612 -0.4906294 0.8608648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 994 1094 0.392594 0.610794 -0.471587 -0.6102973 0.7044671 -0.3620392 0.0138199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 995 1095 0.218830 -0.578869 0.249543 -0.8482282 -0.1595858 0.4742287 0.1736332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 996 1096 0.041208 0.642852 0.424821 0.4721812 -0.1857215 -0.8615158 0.0185199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 998 1098 -0.308275 -0.556841 0.196051 0.2658615 -0.1162223 -0.8398332 0.4587922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 999 1099 0.313532 -0.668786 0.386764 0.5885532 -0.3275663 -0.7053280 0.2209476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1000 1100 0.655892 -0.201221 -0.386396 0.4869967 -0.4744727 -0.2628612 0.6845537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1001 1101 0.748088 -0.169775 -0.026591 -0.7152077 -0.0684980 -0.5556097 0.4184301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1002 1102 0.205113 -0.927698 0.120228 -0.3324284 -0.3910177 -0.5923260 0.6210849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1003 1103 -0.477130 0.223941 -0.553336 -0.2404547 0.4696086 0.3754230 0.7620412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1004 1104 -0.501251 -0.347413 -0.038326 -0.3911104 -0.0733083 0.0769912 0.9141832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1005 1105 -0.137547 0.190560 -0.642567 -0.2319850 -0.9128142 -0.1552445 0.2980812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1006 1106 -0.213582 0.482787 -0.689625 -0.6216478 0.0675038 0.7793090 0.0409251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1007 1107 -0.506755 -0.301049 -0.463141 0.7324355 0.0245432 -0.2099278 0.6471987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1008 1108 0.740220 -0.045570 -0.039226 0.1601722 0.2348988 -0.9563798 0.0671194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1009 1109 0.268936 -0.762652 -0.283407 -0.6892651 0.0921335 -0.5459742 0.4672657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1010 1110 -0.414657 -0.179091 0.590533 0.2908781 0.2641502 0.8958459 0.2075443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1011 1111 -0.117330 0.731368 -0.057048 -0.1298472 0.3145611 -0.9036734 0.2599334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1012 1112 0.224006 -0.604237 -0.028627 0.3209461 0.0232165 -0.8696020 0.3744957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1013 1113 0.673357 -0.345230 0.063510 0.5358530 -0.3926204 -0.6853473 0.2983453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1015 1115 -0.169474 0.485997 -0.387435 -0.0927047 0.4647583 0.1365727 0.8699158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1016 1116 -0.181245 0.361026 0.559634 0.1381679 0.1208381 -0.6507730 0.7367511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1017 1117 -0.425144 0.218500 -0.476268 0.3973619 -0.2119275 -0.5461476 0.7063378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1020 1120 0.744395 0.200489 0.297238 -0.3596410 0.4164967 0.5590055 0.6202433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1021 1121 -0.059020 -0.626020 0.211701 0.5867878 0.0775480 0.5255687 0.6111006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1022 1122 0.594877 -0.214223 0.217243 0.0863362 -0.6098134 0.4906293 0.6164061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1023 1123 -0.528715 0.547794 -0.190550 0.4908691 0.7916193 -0.3498196 0.1000629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1024 1124 0.443179 -0.490689 -0.268388 -0.3566072 -0.4533534 0.8103698 0.1029696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1025 1125 0.108985 0.630958 -0.268361 0.2043187 0.5543425 -0.3283931 0.7369642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1027 1127 0.351281 -0.560390 -0.045226 -0.5679296 -0.2036636 0.7789781 0.1707929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1028 1128 -0.376285 0.367189 -0.047328 0.1987076 -0.4426383 -0.2823688 0.8275593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1030 1130 0.191123 0.301030 0.169561 0.3138967 -0.4444958 -0.5870224 0.5994139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1033 1133 0.051505 0.169195 -0.683741 0.0640260 -0.0113719 0.0015557 0.9978822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1034 1134 -0.431795 0.436067 -0.347906 -0.4003861 -0.6874270 -0.1567983 0.5852771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1035 1135 -0.298466 0.628561 0.197443 -0.3421774 0.4558518 -0.2699597 0.7760384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1036 1136 0.548526 -0.271062 0.322363 0.7166786 -0.5105478 -0.1407765 0.4537563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1037 1137 -0.294007 0.005682 0.602721 0.7460965 0.5444966 0.3829468 0.0146701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1040 1140 -0.465401 -0.055701 -0.207810 0.0325280 0.3096917 -0.5835490 0.7500023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1042 1142 -0.542348 0.299538 0.213050 0.3909168 0.3070597 0.8207854 0.2814422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1044 1144 -0.229362 -0.031965 -0.554378 -0.3873011 -0.3757838 0.8405568 0.0474203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1046 1146 -0.501956 0.179354 -0.052567 -0.6357269 -0.1639248 0.3753068 0.6543125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1047 1147 0.378053 0.497225 0.113682 -0.2925488 -0.7600539 0.2255439 0.5346618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1048 1148 0.331979 0.316428 -0.381969 -0.3056193 0.2407882 0.2133626 0.8961553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1049 1149 0.018289 -0.235421 -0.519317 -0.2973869 0.6319404 -0.6902594 0.1890882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1050 1150 0.011029 0.525767 0.050315 0.3470348 -0.1056646 0.2205568 0.9054041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1051 1151 0.016796 -0.193527 0.582285 0.4340246 -0.0712162 -0.8840132 0.1583399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1052 1152 0.301855 0.384850 -0.297972 0.0826773 0.4014361 0.0197040 0.9119349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1053 1153 -0.438190 -0.012737 0.268594 -0.3922860 -0.4274133 -0.7815711 0.2292948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1054 1154 0.491046 0.106554 0.256272 0.6355945 -0.2299955 -0.6621428 0.3235563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1055 1155 0.424428 -0.012712 0.155113 -0.0518247 -0.2608178 0.5942574 0.7590431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1056 1156 -0.059232 0.501344 0.170925 0.2857766 -0.2220221 -0.9150196 0.1782613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1057 1157 0.078642 -0.213577 0.667470 -0.2640835 0.6916683 0.5191531 0.4270069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1060 1160 0.169292 -0.015396 -0.426762 -0.1668901 0.2561658 -0.9110811 0.2765104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1061 1161 0.404508 0.114983 0.169211 -0.0819622 0.0811663 -0.6842291 0.7200866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1063 1163 -0.456936 0.135414 0.484259 0.6603752 0.5718075 0.4580698 0.1646596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1064 1164 0.115431 -0.420892 -0.194631 -0.0098168 -0.1035381 -0.9936531 0.0428604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1066 1166 -0.390908 0.218256 -0.243202 -0.4980688 0.1680344 0.3233416 0.7868559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1067 1167 0.125727 0.209956 -0.402396 -0.4434444 0.2778232 0.0210897 0.8518958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1068 1168 0.424876 0.073702 0.314565 0.3930718 -0.1299535 -0.2549255 0.8738533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1069 1169 -0.398887 0.260550 0.356451 0.6609295 -0.0908314 0.5936773 0.4499657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1070 1170 0.351433 -0.393520 -0.389586 -0.1172131 0.2302469 -0.4376345 0.8612337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1071 1171 0.126653 -0.253895 0.737114 -0.5663073 -0.7157254 0.3940729 0.1083499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1072 1172 0.319847 0.422359 -0.055289 -0.7327217 -0.1018073 0.6182695 0.2655129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1074 1174 -0.406970 0.443677 0.332712 0.2214447 0.7874819 0.5691392 0.0831571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1075 1175 0.575158 0.434712 0.274650 0.1773823 0.3807060 0.7642367 0.4894290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1076 1176 -0.270216 0.264599 0.500448 0.5962312 0.1079288 -0.5238460 0.5987028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1077 1177 0.585243 -0.188777 0.344493 0.0428838 -0.4947442 0.7905148 0.3584349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1078 1178 0.497778 -0.443661 0.531253 -0.7345149 -0.2982493 -0.5369283 0.2885189 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1079 1179 -0.526370 -0.352148 -0.397690 -0.5539160 0.0617452 0.5927561 0.5813817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1080 1180 -0.317516 -0.468270 0.141042 -0.0523657 0.0325940 0.7072425 0.7042752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1081 1181 0.524247 -0.318276 -0.585555 -0.3178962 0.3080169 -0.8965362 0.0170419 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1082 1182 0.368204 -0.355087 -0.651171 0.0653037 0.2518064 0.1853343 0.9476181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1083 1183 0.554136 0.274615 -0.292264 0.4591457 -0.7334120 -0.3619369 0.3468339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1086 1186 0.442704 -0.571099 -0.298102 -0.6911418 -0.2339798 0.5515443 0.4041972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1087 1187 -0.007806 0.724558 0.144527 0.1275475 0.1147403 0.0713781 0.9825841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1088 1188 -0.618496 -0.037195 0.094179 -0.2612389 0.3083689 -0.8921109 0.2019924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1089 1189 0.691345 0.537336 -0.377659 -0.5738825 -0.2463603 -0.7794757 0.0488178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1090 1190 -0.388003 0.028785 0.529948 -0.0536908 0.6979486 0.2568664 0.6663368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1091 1191 0.045139 0.379051 -0.655254 0.0788463 -0.2045692 -0.6900954 0.6897123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1092 1192 0.403589 0.578173 -0.007092 -0.4987360 0.0105831 0.1200684 0.8583321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1093 1193 -0.379275 0.101360 -0.832103 0.3904304 0.2759367 -0.7628677 0.4352653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1094 1194 -0.711253 -0.278423 0.069542 0.4143191 -0.8296287 0.3397093 0.1570143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1095 1195 -0.376572 0.278634 -0.724485 0.3624705 -0.5988678 -0.7109568 0.0671785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1096 1196 -0.446557 -0.672369 0.528075 -0.5689215 -0.2821456 -0.5620537 0.5299225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1097 1197 0.819542 -0.180175 -0.003550 0.2567739 0.1206310 -0.9273622 0.2439562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1098 1198 0.629318 0.153251 0.268103 0.3282763 -0.3698242 -0.6392711 0.5888949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1099 1199 0.158379 0.626375 -0.286886 -0.5192159 0.0520404 0.8311645 0.1920215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1100 1200 0.325423 -0.321394 -0.537658 -0.3141390 0.7998166 -0.3217698 0.3975857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1101 1201 0.084708 0.840201 0.341931 -0.2937490 -0.1675619 0.2178584 0.9155175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1102 1202 0.203674 0.238527 -0.595158 0.1382371 0.8095873 -0.4021106 0.4046801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1103 1203 0.493235 0.523230 -0.376181 0.1743442 -0.1393171 -0.9219371 0.3165862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1105 1205 -0.146032 -0.131428 0.567083 0.3879148 0.1719285 0.6907501 0.5855143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1106 1206 0.821502 -0.377434 0.022541 -0.4302836 -0.6728285 0.1142201 0.5908567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1108 1208 -0.584319 0.203647 -0.296265 0.9603748 -0.1419341 0.1252415 0.2045715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1109 1209 0.473835 0.774363 -0.026140 -0.1062770 0.7444583 -0.6571202 0.0517694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1110 1210 0.432054 0.510274 -0.030955 0.3494061 -0.3046157 -0.4770168 0.7467126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1111 1211 -0.186544 -0.643653 -0.437104 0.6256282 -0.2795841 0.5671367 0.4569224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1112 1212 0.420818 0.624204 -0.019700 0.0825628 -0.4022327 -0.3866750 0.8257571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1113 1213 -0.143313 -0.062163 -0.739323 -0.8529727 -0.4798179 -0.1609059 0.1277560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1114 1214 0.450175 0.263608 -0.548030 0.1736608 0.3237424 0.2423641 0.8979379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1115 1215 0.113774 0.529321 -0.366871 0.1006825 0.2078435 -0.9037139 0.3605071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1116 1216 -0.434814 -0.190757 0.527268 -0.0321521 -0.2200762 0.2145837 0.9510450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1117 1217 -0.343142 -0.571193 0.057238 -0.4818223 0.5423061 0.2365132 0.6463845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1118 1218 0.381183 0.367895 -0.063300 0.1757368 0.0136314 0.8393011 0.5143000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1119 1219 0.466789 0.226002 -0.632517 0.3266854 -0.2859498 -0.8811582 0.1872687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1120 1220 -0.064951 -0.464719 0.381274 -0.5861996 0.6475771 0.3860633 0.2965959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1121 1221 -0.283393 0.166408 0.498618 0.3933502 0.8244625 0.3084576 0.2653132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1122 1222 0.074152 -0.660920 -0.518684 0.8166945 0.1836782 0.5362802 0.1080557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1123 1223 0.629711 -0.061476 -0.014567 0.1565975 -0.9081658 -0.1039741 0.3740340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1125 1225 -0.022343 0.383927 -0.368655 -0.6035192 -0.3543885 0.3643856 0.6143260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1128 1228 -0.459423 0.027852 0.357627 0.0242485 0.8057390 -0.5854517 0.0862726 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1129 1229 0.203488 -0.054353 0.346998 0.4784546 0.4916076 0.7113878 0.1527434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1130 1230 -0.474836 0.512030 0.204088 -0.7039923 0.5519503 -0.4256339 0.1363138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1131 1231 0.113243 0.285390 0.301071 -0.6750928 -0.5011297 0.4959160 0.2172236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1132 1232 -0.676735 0.125650 0.020689 -0.3456282 -0.5805488 0.4050529 0.6159841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1133 1233 0.092296 0.174284 -0.433885 -0.6450415 0.4099282 0.1005756 0.6369968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1134 1234 -0.117315 0.165880 0.609700 0.5479734 0.6406120 0.5066292 0.1807436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1135 1235 -0.486797 0.211307 -0.059539 -0.2693294 0.3678282 -0.5687921 0.6845727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1136 1236 0.513311 0.150915 -0.334373 -0.5372012 0.0528837 0.2127475 0.8144671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1137 1237 0.057194 0.173671 -0.479264 0.1910263 -0.4771279 -0.8429257 0.1591672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1138 1238 -0.206750 0.237536 0.595806 -0.1045149 -0.1915662 0.8078240 0.5475394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1139 1239 -0.283206 -0.365124 0.070731 -0.4155865 0.3137641 0.5578383 0.6462634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1140 1240 -0.045713 -0.220339 -0.418523 0.7126895 -0.1329238 -0.4993485 0.4744007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1141 1241 0.024436 -0.222254 -0.582972 -0.2964797 0.0753797 0.7005231 0.6447365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1142 1242 0.460738 -0.035144 -0.279291 -0.8755067 -0.2202932 -0.4290614 0.0294149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1143 1243 -0.243990 0.403396 0.060676 -0.2781277 0.1139107 0.9108143 0.2829958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1144 1244 0.277730 0.199783 0.100515 0.2772418 -0.0178974 0.1692945 0.9455982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1145 1245 0.088901 0.385600 0.065126 0.1065494 0.1662454 0.6637248 0.7214423 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1146 1246 -0.162190 0.303489 0.327137 0.0273460 0.1861386 0.2776768 0.9420723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1147 1247 0.408253 0.096473 -0.067169 0.0241955 0.2291819 0.9551725 0.1858377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1148 1248 0.284936 0.379315 0.053809 0.0661942 -0.2901385 0.7042140 0.6446089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1149 1249 -0.156142 0.441030 -0.002298 -0.8688248 -0.0181329 0.4928596 0.0436358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1150 1250 0.199300 0.482822 -0.376663 -0.3578843 -0.3544672 -0.6247740 0.5965981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1152 1252 0.407831 0.300211 -0.076160 0.5853525 -0.2237748 -0.5299798 0.5713219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1153 1253 0.486165 -0.322278 -0.168984 0.2788840 0.5773762 0.7624787 0.0865259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1154 1254 -0.432895 0.046180 -0.341732 -0.8992256 0.2466086 0.2738903 0.2357151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1155 1255 0.379099 -0.508560 -0.155828 0.4157799 0.1194820 0.8837481 0.1784391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1157 1257 -0.337073 -0.077980 -0.608351 -0.0293916 -0.0552165 0.9083288 0.4135530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1159 1259 -0.424572 0.279573 0.395756 0.4257045 0.5552900 -0.4144901 0.5819164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1160 1260 -0.647810 0.079178 -0.326792 -0.8916889 -0.0737357 0.0705013 0.4410030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1161 1261 -0.069703 0.441806 0.310953 0.1860385 0.2125531 -0.7303944 0.6218802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1162 1262 -0.389642 0.160868 -0.110836 0.6342991 -0.0896292 -0.7639719 0.0773187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1163 1263 0.185632 0.129407 -0.281153 0.1910723 0.7064425 0.1666764 0.6607944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1164 1264 -0.289283 0.532914 -0.307284 -0.2811619 0.2898564 0.8467825 0.3462523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1166 1266 -0.315944 0.636584 0.172685 -0.0135373 -0.3382800 0.8666601 0.3664472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1167 1267 0.409539 0.554773 -0.095986 -0.2118306 -0.5252057 -0.4160170 0.7114890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1168 1268 0.423446 0.415669 0.074003 0.6746750 0.4442327 -0.0573262 0.5866725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1169 1269 0.333048 0.081724 -0.401407 -0.8280999 0.0239247 -0.5152058 0.2196385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1170 1270 0.562343 0.247350 -0.166436 -0.4261029 0.5275329 0.7248482 0.1214102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1171 1271 -0.393470 -0.159968 -0.541377 0.3963057 0.8067695 -0.4201122 0.1247820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1172 1272 0.336169 -0.427809 -0.197646 0.5911758 -0.2333803 0.4434744 0.6319614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1173 1273 -0.433586 0.498450 -0.414227 0.0608334 -0.1380132 -0.9584734 0.2420337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1174 1274 0.466032 0.124241 -0.088380 -0.2936254 -0.7262953 -0.5377145 0.3116768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1175 1275 -0.104695 -0.205198 0.608580 -0.6972313 -0.1410907 0.0871298 0.6974026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1176 1276 -0.742748 0.007613 0.283232 0.2364509 0.7079920 0.3235591 0.5815047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1177 1277 -0.413587 -0.571937 -0.139884 0.1016177 0.3718307 -0.8933033 0.2311386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1178 1278 0.577382 0.451646 -0.043703 0.6779102 -0.1547874 -0.1558865 0.7015540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1179 1279 -0.231804 0.605753 -0.159637 -0.5398389 -0.0119336 0.2185675 0.8128098 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1180 1280 -0.571140 0.113638 0.213915 0.0824463 -0.2065144 0.8804694 0.4187219 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1181 1281 -0.448579 0.123720 -0.065517 0.2398177 -0.3355262 0.4073777 0.8148332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1182 1282 0.585706 -0.425749 -0.292562 0.2356603 -0.3549911 -0.3549115 0.8321558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1184 1284 -0.050374 -0.525405 0.210980 -0.3859941 -0.0091197 -0.6189209 0.6840045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1185 1285 -0.040555 -0.202561 0.703147 -0.5548134 -0.7301705 0.3924026 0.0710866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1186 1286 -0.224056 0.322908 -0.623079 0.2970184 -0.8163231 -0.1864530 0.4589465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1187 1287 -0.065315 0.766518 0.102564 0.4558873 -0.3233385 0.5794783 0.5931474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1188 1288 0.783733 -0.180444 -0.438149 0.2091325 0.4106989 0.3339865 0.8222184 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1189 1289 -0.474283 -0.428900 0.391190 0.0765620 0.5813065 -0.8098849 0.0175371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1190 1290 -0.567304 0.253119 -0.367283 0.5706808 -0.6013160 -0.4355149 0.3508124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1191 1291 -0.469051 -0.526018 -0.586090 0.3207788 -0.7262235 0.4693073 0.3865889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1192 1292 0.560988 0.124741 0.600619 0.1587184 -0.0991684 0.8263868 0.5310922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1193 1293 0.704341 -0.229889 0.240464 0.1388759 -0.0986724 -0.9371103 0.3046336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1194 1294 0.627783 0.639909 0.186493 0.0828874 -0.2264082 -0.8738163 0.4222724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1196 1296 0.368007 -0.379230 -0.549119 0.7149308 0.1384110 0.5895972 0.3494160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1197 1297 -0.526108 0.329416 -0.573129 -0.4532600 -0.0106235 0.8845446 0.1096512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1198 1298 -0.379020 0.534254 -0.322322 -0.5628737 0.1403777 -0.5940921 0.5572450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1199 1299 0.277678 -0.413572 -0.248941 0.4698170 -0.4832655 0.3683123 0.6403690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1201 1301 0.335756 0.258343 0.643897 0.6456155 0.0812551 0.7072484 0.2763657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1202 1302 0.213702 0.684707 0.239669 -0.2140889 -0.6398614 0.6123757 0.4119943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1204 1304 0.365507 0.441323 0.401742 0.3160017 -0.0080929 0.9432552 0.1017203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1205 1305 0.251459 0.579728 0.234225 -0.2373630 0.6479486 -0.7097238 0.1418225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1206 1306 0.013179 -0.208924 -0.655262 0.0392788 -0.5851084 0.8033731 0.1034262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1207 1307 -0.362729 -0.091291 0.452279 -0.3472794 -0.6384824 -0.4652536 0.5052488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1208 1308 -0.677143 -0.173905 0.346222 -0.7305766 0.2646928 -0.2257428 0.5875677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1209 1309 -0.434019 -0.196280 -0.451130 -0.1976121 0.1342025 0.9710181 0.0079430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1211 1311 -0.705258 0.194027 0.377069 -0.3616169 0.0442173 0.2908214 0.8847039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1212 1312 -0.582240 0.375672 -0.386884 0.5018157 -0.3486552 -0.6113622 0.5028488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1214 1314 0.567624 0.071527 -0.218289 -0.2212975 0.1303574 -0.6217642 0.7398944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1215 1315 -0.445246 -0.125330 -0.443240 0.2295993 0.3718888 -0.6216872 0.6499907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1217 1317 -0.211294 -0.011063 -0.588480 -0.4903722 -0.6523400 -0.5014320 0.2873213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1218 1318 0.306836 -0.685593 0.058223 -0.3261446 0.2902802 -0.4499454 0.7790483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1219 1319 -0.161892 -0.590723 -0.345443 0.4436081 -0.2876041 0.2155437 0.8209973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1222 1322 -0.443373 0.366446 0.244162 -0.4960990 -0.4223762 -0.0926638 0.7529260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1223 1323 -0.152652 -0.230046 -0.619852 0.1354191 0.5266422 0.0470545 0.8379114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1224 1324 0.363350 -0.444714 -0.398597 0.3485862 -0.2764703 0.6406017 0.6258444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1228 1328 0.426084 -0.462858 -0.323574 0.0445315 -0.1488815 -0.9757696 0.1540289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1230 1330 -0.309835 -0.051305 -0.320770 0.4904687 0.2781326 -0.0801468 0.8219849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1231 1331 -0.039615 -0.363625 -0.432084 0.2455025 -0.1311245 -0.9589981 0.0534563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1233 1333 0.177988 0.167107 0.328222 -0.4815552 -0.4984850 0.0798379 0.7164100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1234 1334 0.208362 0.303969 -0.294555 0.8241704 0.2899805 0.4825041 0.0620021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1235 1335 -0.294438 -0.227414 -0.492262 0.4683466 0.4757683 -0.5312512 0.5216016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1236 1336 0.590201 0.194896 0.120000 0.0794912 0.0619227 -0.9712164 0.2158365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1238 1338 0.048895 -0.021818 0.522386 0.5244936 0.1375354 -0.8183353 0.1905722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1239 1339 -0.011659 0.163039 -0.572508 -0.4307206 0.0185963 0.8745485 0.2220335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1240 1340 0.507122 -0.143862 -0.118141 -0.5198057 -0.5161889 -0.6135713 0.2947564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1241 1341 -0.112900 0.036002 -0.461980 0.2061153 -0.5254627 0.3205265 0.7607025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1242 1342 -0.052465 0.055036 0.635112 0.2569579 0.4477609 0.4859912 0.7051917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1244 1344 0.462749 0.126968 -0.159433 0.4144399 0.7042955 -0.3046202 0.4892994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1245 1345 0.521654 -0.001486 0.205340 -0.2425921 0.0328193 0.1354174 0.9600698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1246 1346 -0.390888 0.206744 0.317024 -0.7472331 -0.4577006 0.4800814 0.0409249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1248 1348 0.162018 -0.438022 -0.168671 0.1409152 0.5277823 -0.4640347 0.6973238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1249 1349 -0.167973 -0.511561 0.104561 -0.4521149 0.0214636 -0.8034507 0.3867795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1252 1352 -0.172117 0.307772 -0.438258 -0.0946283 -0.1047541 -0.8034604 0.5783800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1253 1353 -0.538572 0.105028 0.149368 0.0691468 -0.8049009 -0.4904288 0.3268531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1254 1354 -0.293138 0.266940 0.389278 0.1217663 0.8920212 -0.3541603 0.2530646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1256 1356 -0.387666 0.006536 0.556977 0.3246957 -0.2452998 -0.7413131 0.5337186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1257 1357 0.257625 0.376756 -0.541833 -0.6019429 -0.1020349 -0.7154386 0.3397076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1258 1358 -0.118531 -0.412061 0.301601 0.0919868 0.5550620 -0.3739452 0.7372989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1260 1360 -0.477112 0.053858 0.334070 -0.4588341 0.5016368 -0.4710047 0.5621267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1261 1361 -0.437785 -0.026344 -0.099736 0.7878787 0.2366141 -0.4800380 0.3046710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1262 1362 0.402057 -0.353053 0.488875 0.0981078 -0.4079266 0.8739935 0.2451656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1263 1363 0.450936 -0.153724 0.286582 -0.6519097 -0.3340417 0.3699569 0.5714558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1264 1364 0.566141 -0.005481 0.172595 0.3099728 -0.0956560 -0.9268692 0.1888924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1265 1365 0.502581 -0.190290 -0.045293 -0.3532413 0.7833364 0.4410734 0.2589574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1266 1366 0.534201 -0.100031 -0.130688 -0.7010241 -0.0454766 -0.1721750 0.6905453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1268 1368 0.438798 0.604024 -0.123122 -0.1034144 -0.9110648 -0.0053774 0.3990456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1269 1369 -0.250414 0.089803 0.462018 -0.4001826 0.3376668 0.8509666 0.0411206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1270 1370 -0.141137 -0.561919 -0.117238 -0.7369591 0.2299961 0.5040529 0.3872000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1271 1371 0.488934 0.013027 0.440246 0.5810213 -0.2666390 -0.6586807 0.3968092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1272 1372 -0.001907 -0.219373 0.655764 -0.6911442 0.3089385 -0.1212907 0.6420010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1273 1373 -0.084902 -0.690805 -0.115114 0.1882175 -0.4131841 -0.8178351 0.3535517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1275 1375 0.076721 -0.568356 -0.323803 -0.1329067 0.2715933 0.8665138 0.3971482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1276 1376 0.009965 0.447266 -0.569838 -0.0050983 -0.8350169 -0.4971306 0.2357580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1277 1377 0.634144 0.239662 0.330353 -0.5177064 0.3149875 0.7755743 0.1767693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1278 1378 0.279594 -0.125506 -0.817355 -0.6103259 -0.5481932 -0.4654985 0.3321110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1279 1379 -0.011431 0.239228 0.385640 0.0466048 0.1693697 -0.7788479 0.6021112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1281 1381 0.025952 0.728766 0.155286 0.0256389 -0.5653056 -0.8244703 0.0045809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1282 1382 0.520856 0.073562 -0.452956 -0.2941644 0.7726615 0.2365555 0.5103949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1283 1383 -0.460578 -0.236883 0.481035 0.0022785 0.7415272 -0.6616207 0.1113117 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1284 1384 0.426537 -0.195434 -0.268069 -0.0455803 0.2743489 -0.9261610 0.2547172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1285 1385 -0.407148 -0.538547 -0.204961 0.2379046 0.3694914 -0.2913895 0.8496880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1287 1387 0.195200 -0.013147 -0.693016 -0.0212889 0.7888946 0.1612757 0.5926063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1289 1389 0.225843 -0.262800 0.607757 -0.5364797 0.0038746 0.4144321 0.7351330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1290 1390 -0.124828 -0.171070 0.709576 0.3283667 0.7497858 0.5566097 0.1420639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1291 1391 -0.068287 0.493998 0.464464 -0.6739071 0.3465819 -0.4195026 0.4997477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1292 1392 0.041580 -0.530623 0.431137 0.4054277 -0.5514326 0.2115147 0.6977191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1293 1393 -0.493086 0.490669 -0.521385 -0.2186112 -0.5515346 -0.5424564 0.5947771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1294 1394 -0.644870 0.140502 0.179497 -0.5892495 -0.7876409 -0.0183797 0.1790785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1295 1395 -0.209470 -0.342618 -0.566188 0.7548323 0.1433731 0.3316932 0.5474047 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1296 1396 -0.195729 -0.503160 0.419306 -0.1794489 -0.6339047 -0.6759272 0.3302808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1297 1397 0.816704 -0.128236 0.145172 0.0542322 -0.7084135 -0.2469581 0.6589544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1298 1398 -0.734742 0.046923 -0.390512 -0.0156554 0.7305047 -0.6636130 0.1604232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1299 1399 0.105095 -0.740156 0.355181 0.1486462 0.3908430 0.9039094 0.0899658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1301 1401 0.776373 -0.036036 0.429083 0.0488284 0.6042591 0.0894012 0.7902494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1302 1402 0.457902 -0.223965 -0.436419 0.1513797 -0.6338668 0.7215041 0.2339422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1303 1403 -0.010289 0.284803 0.775618 0.6858397 -0.1400176 -0.6289906 0.3382156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1307 1407 0.422117 -0.409231 -0.187231 -0.2435654 -0.4618083 -0.7465436 0.4124095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1308 1408 -0.367445 -0.126558 -0.492930 0.3800854 -0.4651301 -0.7218207 0.3437498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1309 1409 0.495728 0.200790 -0.264161 -0.3030355 -0.0110464 0.9435054 0.1335849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1310 1410 -0.403060 0.475378 0.252961 0.0002351 0.3199205 0.9317757 0.1715949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1311 1411 -0.444722 0.276201 0.179539 0.0135666 0.6661717 -0.5321987 0.5222986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1312 1412 -0.289670 -0.656575 0.349328 0.0609594 -0.8775914 -0.4673069 0.0879865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1316 1416 -0.348034 -0.039292 0.755903 -0.1701032 0.3414975 -0.8133114 0.4392822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1317 1417 -0.311023 -0.555599 -0.050991 -0.6913431 -0.0455955 -0.7167606 0.0788679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1318 1418 0.579060 -0.116159 0.144436 0.4956824 -0.1405850 0.3209778 0.7946748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1320 1420 -0.471166 0.323956 -0.344651 -0.0197955 0.1632549 0.9809716 0.1032025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1321 1421 0.423985 -0.142281 -0.414674 -0.8779663 0.2290009 -0.3010847 0.2933971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1322 1422 0.017641 -0.305951 0.495374 -0.1138192 -0.1839920 -0.5495825 0.8069394 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1323 1423 0.348971 -0.320852 -0.465397 -0.2283308 -0.3857217 0.2425561 0.8603780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1324 1424 -0.407620 -0.343393 -0.011309 0.6401623 0.1626632 0.3277984 0.6754858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1325 1425 0.574524 0.442358 -0.154940 0.6879969 -0.6391253 -0.3228703 0.1180424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1327 1427 -0.320484 0.530000 0.282810 -0.5953128 0.2313098 -0.3726310 0.6732345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1328 1428 -0.334249 0.382159 -0.136732 0.1413860 0.7159442 0.6304471 0.2645191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1330 1430 0.013045 -0.252491 -0.096305 0.1230142 -0.6942683 0.6408242 0.3036501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1331 1431 0.142001 0.393783 -0.276559 -0.4759524 -0.0444896 0.2256954 0.8488531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1332 1432 0.122596 0.414807 0.405516 -0.6603267 0.4950714 -0.5422695 0.1575333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1333 1433 0.647017 0.131049 0.180665 0.4441000 0.1200571 0.8488042 0.2605627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1334 1434 0.036772 -0.354901 0.458886 -0.0360532 0.5367642 -0.4210443 0.7302781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1335 1435 0.645232 0.109566 0.304097 -0.7642651 0.0218289 0.5999892 0.2354471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1336 1436 -0.500737 0.067231 -0.059211 -0.7822088 0.2722170 0.3613968 0.4282986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1337 1437 0.156837 0.344434 0.303017 0.6358730 -0.4759951 -0.3021967 0.5270403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1338 1438 -0.313691 -0.190875 0.004470 -0.2255211 0.4130637 -0.5352363 0.7014561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1340 1440 -0.356161 0.442007 -0.154648 -0.2554338 -0.2054042 0.3202846 0.8888084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1341 1441 -0.441885 -0.053935 0.131846 -0.7029923 -0.6174623 -0.3126821 0.1636216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1342 1442 -0.103575 0.182238 0.178998 -0.3595902 -0.8365878 0.3860114 0.1476854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1343 1443 -0.399379 -0.030361 -0.168440 -0.2688696 0.1655541 0.1621072 0.9348916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1344 1444 0.146796 0.657789 -0.051173 -0.0048937 -0.8110555 0.3871907 0.4384614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1345 1445 0.583140 0.135651 0.011763 -0.3879624 0.2334178 -0.8108514 0.3708386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1346 1446 -0.030429 -0.466036 0.035206 0.0591026 0.6759238 -0.7144685 0.1707882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1347 1447 0.392794 -0.425032 -0.366621 0.2848990 0.8140402 -0.3671723 0.3483612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1348 1448 0.525380 -0.043856 0.115897 0.2606404 -0.6385228 0.0208322 0.7238240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1349 1449 0.550402 0.041764 0.093189 0.3686855 -0.8576768 0.3446691 0.0983094 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1350 1450 0.167452 -0.254862 0.162295 0.2053875 -0.1348423 0.0091820 0.9693035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1351 1451 0.211169 0.208746 0.515143 -0.5351099 -0.7417664 -0.3397656 0.2190875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1352 1452 -0.131330 -0.254298 -0.587860 0.3081830 -0.0480060 0.8472845 0.4299158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1353 1453 0.356945 -0.021397 0.333433 -0.5735312 0.3104242 0.5554437 0.5159274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1354 1454 0.002519 -0.144270 -0.565768 -0.2577449 0.7027323 -0.0691781 0.6595069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1355 1455 -0.318044 0.528899 0.002941 -0.1850446 -0.5804581 -0.5968767 0.5220777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1356 1456 -0.134592 0.016633 0.310256 -0.4813008 0.4900412 0.4845147 0.5417146 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1357 1457 -0.595049 -0.121906 0.524620 -0.2715659 0.7598571 -0.1807121 0.5623276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1358 1458 -0.032459 -0.227134 0.288481 0.7040418 -0.1566129 -0.6553630 0.2242698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1359 1459 -0.334691 -0.426386 0.190890 -0.7915446 -0.4110658 0.4365937 0.1177625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1360 1460 0.122999 -0.406744 -0.414088 0.2139786 -0.3058594 0.3096512 0.8745166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1361 1461 -0.188287 -0.155819 0.316038 0.0286132 -0.3854838 -0.1402296 0.9115477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1362 1462 -0.080638 -0.354046 0.508038 0.5530830 0.6577835 0.3048273 0.4104880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1364 1464 -0.570637 0.361583 -0.211210 -0.0354164 0.0332195 -0.0163043 0.9986873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1365 1465 -0.075520 -0.556244 -0.083466 0.3516424 -0.5315786 0.1411216 0.7575332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1366 1466 0.423900 0.461977 -0.017386 0.9106607 0.1935798 -0.2094798 0.2989015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1367 1467 -0.174408 0.297322 -0.437774 -0.1689108 -0.1761772 -0.9692456 0.0315218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1368 1468 -0.386995 0.524400 0.069965 0.5116767 0.3493189 0.7468214 0.2417044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1369 1469 -0.267643 0.328167 0.222467 0.4242621 -0.1172642 -0.8402767 0.3165214 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1370 1470 -0.126946 0.597824 -0.331436 0.7106730 -0.1343651 -0.6895250 0.0380166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1371 1471 -0.479387 0.547737 -0.147408 -0.1501622 -0.5226190 0.8154413 0.1984344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1373 1473 0.344835 0.239788 -0.371006 -0.2536500 -0.4490693 -0.4685049 0.7172877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1374 1474 0.417471 -0.131258 0.146649 -0.8331951 0.1795173 -0.1969421 0.4845341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1375 1475 -0.286853 0.240158 -0.482081 0.1078184 0.7836473 0.3800125 0.4794399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1376 1476 -0.208495 -0.387788 0.387044 0.0813997 -0.3681383 -0.5385641 0.7535231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1378 1478 -0.561732 0.284385 0.429339 -0.3776303 0.4605660 -0.6301426 0.4981914 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1379 1479 -0.509818 -0.464272 0.339299 -0.7218649 0.3136984 -0.5673628 0.2420825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1380 1480 -0.544672 -0.068747 -0.229178 0.0927813 0.1136944 -0.9888199 0.0264656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1381 1481 0.284444 -0.266998 0.674228 0.1040128 0.5773263 0.7560761 0.2902147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1383 1483 0.415074 -0.312181 0.260092 -0.2659764 -0.0669064 -0.7198350 0.6376658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1384 1484 -0.467321 0.759159 -0.031159 -0.1444706 0.1626557 0.7211025 0.6577861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1385 1485 0.262747 -0.551959 -0.088488 0.2281832 -0.5020060 0.5252973 0.6480626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1386 1486 -0.378758 -0.540290 -0.501337 0.0884580 0.3007072 0.8567451 0.4095586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1387 1487 0.524041 0.021486 0.498949 0.3925883 -0.2822674 0.3708628 0.7928810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1388 1488 0.509362 -0.454288 0.478772 0.4276679 -0.3595885 -0.2909741 0.7766147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1389 1489 -0.050514 -0.753744 -0.109463 0.1990105 0.1656937 0.1601493 0.9525191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1391 1491 -0.467198 -0.585400 -0.201363 -0.1865419 0.0603115 -0.7839226 0.5890925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1393 1493 -0.346599 -0.345545 0.504488 0.7004611 -0.2224580 0.6235551 0.2665441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1394 1494 0.338631 -0.625461 -0.033295 -0.0179848 0.0913280 -0.2630357 0.9602854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1395 1495 -0.707821 -0.283194 0.211619 -0.4368634 -0.2923518 0.5323099 0.6635714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1396 1496 0.892458 0.445624 -0.505678 -0.4997344 0.4620990 -0.4556971 0.5736464 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1397 1497 -0.096997 0.027276 -0.796710 0.6939374 0.1858004 0.6438845 0.2633285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1398 1498 0.769334 0.368714 -0.051769 0.4372101 -0.3221094 0.7534819 0.3706183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1400 1500 -0.333415 -0.468071 -0.600124 0.2483328 -0.7453250 0.3694314 0.4963285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1402 1502 -0.619845 0.096435 -0.034270 0.8502764 -0.0092074 -0.4821529 0.2108880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1403 1503 -0.575126 0.329707 0.210284 -0.5623042 -0.6235379 -0.3111340 0.4452080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1404 1504 0.214653 -0.219038 0.744799 0.2221399 -0.1342911 0.1146561 0.9588919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1405 1505 -0.614868 -0.181549 0.118787 0.3285113 0.2031480 -0.2770747 0.8797959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1406 1506 0.324114 0.741988 -0.039349 -0.2986375 -0.3514431 0.0305131 0.8867764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1408 1508 0.644855 -0.575403 0.146357 -0.4581433 0.0129242 0.1580407 0.8746204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1409 1509 -0.128838 -0.348328 -0.536689 0.1674114 -0.8222490 0.5433357 0.0258125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1410 1510 0.632379 -0.212505 0.547371 0.4562635 -0.0719448 -0.5057385 0.7286125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1411 1511 0.069156 -0.478876 -0.503973 0.3184443 0.6940754 -0.5346379 0.3619599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1412 1512 0.325141 0.042774 -0.510636 -0.1366172 -0.2298930 -0.6306087 0.7285723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1413 1513 -0.297661 -0.254138 0.396749 0.6911526 -0.4142327 0.5349024 0.2541629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1414 1514 0.583366 0.144829 0.309109 0.0093682 0.2380470 -0.3815421 0.8931246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1415 1515 0.571127 0.056898 0.417777 0.1184722 0.6942042 -0.7099188 0.0077554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1416 1516 0.011101 -0.637301 0.151685 0.0963273 -0.3080835 -0.8043914 0.4987586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1418 1518 0.623602 -0.276342 0.281354 0.2954162 0.2287641 -0.2872002 0.8819934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1419 1519 -0.569701 0.445277 -0.221184 -0.0906221 0.1982524 -0.6885668 0.6916353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1420 1520 0.658882 -0.368170 -0.167895 0.1018451 0.3221778 -0.2341146 0.9116026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1421 1521 0.235951 0.253397 0.649957 0.5511237 -0.0100991 -0.4381634 0.7100518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1422 1522 0.470573 0.171498 0.516382 0.1764797 -0.6611333 -0.7286238 0.0294113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1423 1523 -0.355506 -0.335563 -0.678037 0.1346569 0.2821421 0.1796901 0.9327244 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1424 1524 -0.570591 0.251131 -0.135574 -0.0639294 -0.3176355 0.1187028 0.9385789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1425 1525 -0.317548 -0.244840 -0.029616 -0.9049408 -0.1071169 0.0300464 0.4107376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1426 1526 0.197158 0.273778 0.528973 0.5204994 0.5442772 -0.5275058 0.3931671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1427 1527 -0.687561 -0.306764 0.081916 0.2952301 0.6779823 -0.6478785 0.1828460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1430 1530 -0.383202 -0.091831 0.460397 -0.0055851 0.8469218 -0.5205584 0.1082188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1431 1531 0.444393 0.488370 0.129423 0.9011550 -0.0110775 0.4328641 0.0206306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1432 1532 -0.315164 -0.448387 0.063320 0.3337008 -0.3862727 -0.5954717 0.6203633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1435 1535 -0.072258 -0.275608 -0.576781 0.4518735 -0.4340433 0.6690632 0.3997139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1436 1536 -0.232917 0.485647 -0.041241 0.1150454 -0.6437222 -0.4917764 0.5749280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1437 1537 -0.270025 0.415613 -0.283731 -0.3066860 -0.2816631 -0.8332303 0.3637813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1439 1539 0.234055 0.230068 -0.525206 -0.6309064 0.4848658 -0.5714126 0.2008728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1440 1540 0.177480 0.530705 0.238739 0.4469844 -0.5337562 0.2645788 0.6673135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1441 1541 0.002319 -0.680986 -0.101089 -0.4956049 0.7374169 -0.2914019 0.3545096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1442 1542 0.582030 -0.013175 -0.222591 -0.0382773 -0.4106436 0.9093500 0.0546737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1443 1543 -0.381234 0.079127 -0.268343 -0.4194396 -0.3760882 -0.5783135 0.5900691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1444 1544 0.434268 0.378810 -0.237744 -0.7366406 -0.2899864 -0.3828676 0.4761102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1445 1545 -0.137618 0.030647 0.352411 0.5064013 0.1092218 0.7969225 0.3107135 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1446 1546 0.040322 0.014077 0.452319 0.3435333 0.1622795 0.9025700 0.2025280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1448 1548 0.236256 0.137258 -0.415290 -0.8684671 0.1743892 0.0696652 0.4588029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1449 1549 -0.410510 -0.391309 -0.157191 0.8082319 0.4502158 0.0605628 0.3746986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1450 1550 0.352744 -0.178148 0.229746 0.3001866 -0.0529893 -0.5975859 0.7416004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1452 1552 -0.217731 0.188114 -0.246545 -0.8128417 0.2658148 -0.3051823 0.4189207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1453 1553 -0.121190 -0.453438 -0.162824 0.4791713 0.4332757 -0.6081633 0.4613073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1454 1554 0.609008 0.353262 0.188272 -0.2705108 0.6150193 -0.2579536 0.6942875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1456 1556 -0.503974 -0.123325 -0.028404 -0.2039855 0.1322221 0.8074386 0.5375409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1457 1557 -0.007625 -0.399278 -0.568275 -0.0984115 0.0644397 -0.1199367 0.9857880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1458 1558 -0.078014 0.471810 0.041467 0.8107677 -0.2810871 -0.2338079 0.4571430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1459 1559 -0.457809 0.116255 0.247159 -0.2932217 -0.2037909 0.9064583 0.2254408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1460 1560 -0.400498 -0.407276 -0.123950 -0.2770300 0.0407997 -0.8207880 0.4978923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1461 1561 0.387667 -0.123686 0.413503 -0.1343804 0.2059266 0.1881769 0.9508552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1463 1563 -0.157952 0.527789 -0.058397 0.8074221 -0.1078973 -0.2371653 0.5293206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1465 1565 0.207898 -0.385679 0.438792 0.0426539 -0.8461841 -0.5073796 0.1572229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1466 1566 0.570192 0.194742 -0.317685 0.0423895 0.8775706 0.3700787 0.3018523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1468 1568 0.494765 -0.132709 -0.178455 -0.2169772 0.5391071 -0.8036211 0.1283650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1469 1569 -0.254726 -0.535291 0.337068 0.3654116 0.6228190 0.1343499 0.6786170 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1470 1570 0.592023 -0.426748 0.186218 0.2374489 0.1051820 0.7756144 0.5753060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1471 1571 0.436566 0.333752 -0.159083 -0.4997081 0.6797037 -0.4335091 0.3168036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1472 1572 0.511932 -0.122884 0.053043 0.5125761 0.6760255 -0.4488790 0.2806473 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1473 1573 -0.395972 0.404116 -0.199412 0.2258344 0.9033109 0.3636541 0.0279988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1474 1574 0.707863 -0.189449 0.078809 -0.3174579 -0.1494926 0.5871539 0.7294675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1475 1575 0.462470 -0.177952 -0.017258 -0.6390348 -0.0546890 -0.1563950 0.7511220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1476 1576 0.590793 0.011887 0.371032 -0.0736593 -0.1120286 -0.3445762 0.9291346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1477 1577 -0.598102 -0.346771 -0.020036 0.4950881 0.2598139 0.8221713 0.1068592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1478 1578 -0.096616 -0.517441 -0.379933 0.0996087 -0.6207449 -0.3462026 0.6963459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1479 1579 0.251511 0.035069 -0.434980 0.7038868 0.2424991 0.3895751 0.5421889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1482 1582 0.447438 0.455375 0.383433 0.8772457 0.0761654 -0.3150607 0.3540842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1483 1583 0.259984 0.388064 0.253390 0.0348250 -0.2226047 0.9098440 0.3484514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1484 1584 0.592949 0.366354 0.148466 -0.0488268 -0.7224984 -0.6372373 0.2637054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1485 1585 -0.437606 -0.284131 0.584850 0.0730158 -0.8771805 0.3678187 0.2998874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1487 1587 0.781713 -0.388842 0.004817 -0.6429483 -0.5481923 -0.4765558 0.2428937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1488 1588 0.648254 0.300961 0.060069 -0.4065307 -0.2110547 0.6881783 0.5626717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1489 1589 -0.221834 -0.739070 0.132627 -0.4604053 0.1228605 0.3235198 0.8174761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1490 1590 -0.454855 0.531495 -0.044082 0.3422173 -0.7115822 -0.5251481 0.3174233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1491 1591 0.760063 -0.106533 -0.291062 0.4377895 0.0094877 0.8178963 0.3732237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1492 1592 -0.585429 -0.176094 0.396323 0.2736283 0.1903503 0.8969104 0.2905959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1494 1594 0.518778 -0.111929 -0.177831 -0.5877099 -0.0103301 -0.3824266 0.7129097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1495 1595 -0.435317 0.085395 0.698449 0.6846220 0.6623535 0.2585021 0.1604908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1496 1596 0.061262 0.464736 0.598319 0.3582741 0.0043558 -0.7538901 0.5507000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1497 1597 -0.333813 -0.724920 -0.183069 0.6019199 0.5893636 0.5042508 0.1899317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1499 1599 0.145676 0.386006 -0.473571 0.2808395 0.6930437 0.3816330 0.5433009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1500 1600 -0.297348 0.135923 0.562776 0.5359129 0.0878675 -0.2117975 0.8125383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1502 1602 -0.259432 -0.184929 0.669724 -0.5484901 -0.3431092 -0.2618861 0.7161357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1503 1603 0.273391 -0.622923 0.375539 -0.2166059 0.7921326 0.2539357 0.5110034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1504 1604 0.432796 -0.006879 0.663299 0.6507531 -0.0644659 -0.7556768 0.0362925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1505 1605 -0.655098 -0.375725 0.003211 0.3240909 0.2452750 0.1863434 0.8944727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1506 1606 0.409346 0.674583 0.306761 0.1914781 0.7399988 0.0141892 0.6446213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1507 1607 -0.454824 -0.393452 0.173322 -0.0274558 -0.0883141 -0.7024221 0.7057266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1508 1608 0.503496 -0.470898 -0.490640 0.0094308 0.5176744 0.7472557 0.4165732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1509 1609 -0.011382 0.396006 0.528511 0.4415796 -0.6864816 0.4506439 0.3614839 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1511 1611 0.373727 0.257495 0.388744 -0.0919936 0.2305612 0.9685043 0.0194447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1512 1612 -0.332562 0.189805 -0.524015 -0.2130807 -0.1480079 0.1015895 0.9604009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1514 1614 -0.151960 0.418121 0.638129 0.5261953 0.0228641 -0.0675214 0.8473704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1515 1615 -0.654712 -0.372159 -0.169411 0.1897826 0.0657695 0.5637010 0.8011855 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1516 1616 0.189041 0.549139 -0.247621 -0.2095630 -0.4370117 0.5224188 0.7015573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1517 1617 0.240211 0.581036 -0.014078 -0.0731401 0.4481603 0.8735135 0.1754337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1518 1618 0.275857 0.349475 0.579560 0.2538040 -0.1084161 0.1098033 0.9548679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1520 1620 0.530937 -0.168472 0.328656 0.4407645 0.2304001 -0.5676159 0.6560903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1521 1621 -0.246537 0.550075 -0.139139 -0.8917530 0.2145367 -0.3068101 0.2542009 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1522 1622 -0.669456 0.444523 -0.193683 -0.2038998 0.1574067 -0.9266972 0.2736428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1523 1623 0.040366 -0.213369 -0.487749 0.4886455 0.0092865 -0.8239963 0.2866522 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1524 1624 -0.588109 0.104425 0.266381 -0.2630322 0.7688252 -0.1779985 0.5550120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1526 1626 -0.494196 0.111465 -0.285643 0.1958837 -0.9341822 0.0948390 0.2827343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1527 1627 0.316905 -0.559337 0.544937 -0.0205456 -0.4498477 0.7599824 0.4686595 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1529 1629 -0.673989 -0.086005 -0.174035 -0.2157069 0.5850107 -0.7668330 0.1523159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1530 1630 0.071501 -0.390652 -0.392209 0.0917354 -0.9804426 0.1740920 0.0029769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1531 1631 0.158954 -0.572878 0.232981 0.2296598 0.1418245 0.9505967 0.1533238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1532 1632 0.534819 -0.175351 0.211321 -0.6915913 -0.6171400 -0.3320493 0.1748801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1535 1635 -0.490971 0.125087 0.309103 0.1421751 -0.2086522 -0.9412687 0.2241959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1536 1636 -0.309037 0.255482 0.405230 0.2617282 0.4077529 -0.8567767 0.1765490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1537 1637 -0.064404 -0.479230 -0.110265 0.5811445 -0.0637223 0.4324174 0.6864588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1538 1638 -0.247782 -0.183871 0.575542 0.7340600 0.0552563 -0.0865908 0.6712710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1541 1641 0.309696 -0.048009 0.385754 0.2263316 -0.4504399 0.8570013 0.1068959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1542 1642 -0.459233 0.079669 -0.259741 0.4206830 -0.2948625 -0.5032019 0.6948883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1543 1643 -0.351586 -0.386618 -0.160747 0.5011728 -0.2176573 0.0505430 0.8360003 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1544 1644 -0.210153 0.078634 0.378615 -0.0600101 0.7768641 -0.2698310 0.5657493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1546 1646 0.297055 0.173234 0.260432 -0.4212610 -0.2040936 -0.2152836 0.8570519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1547 1647 -0.357961 0.291982 0.339114 -0.2379661 0.0611488 -0.8250984 0.5087687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1548 1648 0.402554 0.278491 0.342913 0.5884143 0.2345705 -0.3107765 0.7086348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1550 1650 0.042928 0.394692 0.165559 -0.1392363 0.1135075 0.8655482 0.4674994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1552 1652 -0.476945 0.219745 -0.144627 0.6627127 -0.6124783 0.3451453 0.2579865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1553 1653 0.222946 0.043304 0.384457 0.5398999 -0.1528067 0.4108800 0.7185652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1554 1654 -0.200817 0.081881 0.437159 0.2151990 -0.8060505 0.4146813 0.3633338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1555 1655 0.310614 0.287249 0.229663 -0.3340549 -0.5435723 -0.5478410 0.5411162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1556 1656 0.141194 0.360402 0.121347 -0.7354968 0.3447325 0.5831038 0.0139263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1557 1657 0.155548 -0.085456 -0.400448 0.7102584 -0.0985931 0.6792708 0.1562166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1558 1658 -0.286643 -0.180290 -0.276246 -0.4896343 -0.4632662 -0.7091362 0.2068054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1559 1659 0.499647 -0.046495 0.337900 0.1605517 0.7817909 0.4881418 0.3531908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1560 1660 0.177291 -0.010609 -0.466996 0.0811246 0.1038563 0.6519822 0.7466940 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1561 1661 -0.033575 -0.294568 0.456915 0.7558964 -0.4257040 -0.2181255 0.4470101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1562 1662 -0.237907 -0.362752 0.315392 -0.5355617 0.4395567 -0.7132575 0.1059589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1563 1663 -0.370974 -0.152544 -0.298548 -0.1364406 -0.0239244 0.8390452 0.5261318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1564 1664 -0.480331 0.149897 0.262119 0.5819431 0.4158528 0.6986317 0.0179571 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1565 1665 0.252110 0.302820 -0.612631 -0.1552568 0.8122257 0.2946914 0.4788963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1567 1667 0.304883 -0.107399 0.417755 -0.3815320 -0.1381398 0.5733147 0.7118013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1568 1668 -0.534135 0.005087 0.155976 0.6656521 -0.2248257 0.6729080 0.2314206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1569 1669 -0.631144 0.032078 0.068158 -0.5220517 -0.1236214 -0.3878192 0.7495172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1570 1670 -0.451873 -0.286640 0.289416 0.0072487 -0.0514248 -0.8481213 0.5272507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1571 1671 -0.251414 -0.107206 0.747348 0.8935943 0.1840848 -0.1464407 0.3823050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1572 1672 -0.034491 0.630101 -0.060479 -0.1171019 0.1693544 0.9565893 0.2062600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1573 1673 0.628487 0.077240 0.227571 0.3696155 -0.7257805 -0.4057909 0.4146815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1574 1674 -0.062896 -0.743601 -0.350636 0.1514280 -0.1937974 -0.9687251 0.0329206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1575 1675 0.567238 0.516857 0.086085 -0.1169918 0.3207210 0.7708314 0.5378382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1577 1677 0.135310 0.297688 -0.656054 -0.8449856 0.1770367 -0.4901566 0.1200162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1578 1678 -0.033559 -0.328130 -0.281140 0.2220030 -0.0059494 0.5492396 0.8056148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1579 1679 0.233320 -0.688940 -0.064674 0.3008557 0.2738632 0.8203756 0.4018317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1580 1680 0.618940 0.231824 0.372855 0.5740076 0.0248738 -0.5529387 0.6034529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1581 1681 -0.316172 -0.212977 -0.563953 -0.6969434 -0.0112967 0.0936461 0.7108957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1582 1682 0.019366 -0.084363 -0.736004 0.0453277 0.8319574 0.3671129 0.4135461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1583 1683 0.019805 -0.872433 0.235861 0.1143763 -0.7856046 -0.1838246 0.5796137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1584 1684 -0.677824 0.294486 0.243124 -0.0341026 0.6611147 0.6081436 0.4380931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1585 1685 0.549003 -0.327251 0.389425 0.1953855 -0.0749756 0.9755119 0.0676739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1586 1686 0.680300 0.020946 0.061856 0.2927478 0.8788109 -0.2358450 0.2938832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1587 1687 -0.352708 0.636957 -0.091845 -0.5170802 0.0314515 -0.2789587 0.8085919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1589 1689 -0.427961 -0.378794 -0.183603 -0.4007710 0.5341209 0.3041775 0.6793920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1591 1691 -0.545276 -0.496859 0.106843 -0.0786717 0.0753589 0.9863874 0.1231736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1593 1693 -0.095743 0.185642 0.523517 0.7937435 -0.1860080 0.5317476 0.2293834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1594 1694 0.625089 0.388288 -0.007855 0.2331622 -0.1251585 0.5370493 0.8009674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1595 1695 0.136922 0.066043 -0.941479 -0.1020999 0.2134103 0.9369194 0.2573201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1596 1696 -0.569384 -0.168850 0.325046 -0.5754701 0.5436012 -0.4617585 0.4001387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1597 1697 -0.485919 -0.347502 -0.596262 -0.1402323 -0.6913864 0.0908454 0.7028989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1598 1698 0.613635 -0.059669 0.429088 0.1809749 -0.5770891 0.3076751 0.7345422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1599 1699 0.752459 0.004413 0.531171 0.1904843 0.1140684 -0.9415993 0.2531695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1600 1700 -0.697370 0.181794 0.219562 -0.6275271 0.4646082 -0.2745491 0.5612235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1601 1701 -0.641421 -0.079002 0.651064 -0.0359753 -0.1828165 0.9062049 0.3795742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1602 1702 0.421574 -0.467835 -0.277548 0.1413550 0.2747668 -0.9509384 0.0154311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1603 1703 -0.079636 -0.698440 -0.180401 -0.6633792 0.0099258 0.0133612 0.7480982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1604 1704 -0.709664 0.052484 -0.345443 -0.1321254 0.7219326 -0.5781833 0.3564552 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1605 1705 -0.489775 -0.341628 0.041516 -0.6097058 0.0535019 0.7550534 0.2351399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1606 1706 -0.237691 0.578471 0.194998 -0.0191127 -0.0542397 -0.0647661 0.9962420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1607 1707 0.597381 -0.552076 0.030526 -0.1787724 -0.3127358 -0.9157763 0.1777374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1608 1708 -0.357531 -0.594514 -0.199161 -0.2240876 -0.3028563 -0.5641783 0.7346874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1610 1710 -0.249877 0.679698 0.333868 0.4211056 0.1880961 -0.2796998 0.8420558 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1611 1711 -0.475951 -0.038717 0.687037 0.0007884 -0.8111632 -0.5449845 0.2121453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1612 1712 -0.484709 0.659141 -0.421354 -0.6886834 -0.1720903 -0.4955132 0.5005664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1614 1714 -0.122995 0.495333 -0.275051 -0.5873140 -0.2429133 0.6996445 0.3264246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1615 1715 -0.383926 0.203642 -0.237887 0.6034930 -0.1603637 -0.1505446 0.7664307 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1616 1716 0.401021 0.185450 -0.589703 -0.1977334 0.2517125 0.6365780 0.7016487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1618 1718 0.247007 0.472013 0.164836 0.7299444 -0.5814144 -0.3417742 0.1110353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1619 1719 0.195105 -0.363825 -0.610857 -0.0129268 0.4103240 -0.5569293 0.7220089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1620 1720 -0.074389 0.764567 0.029458 0.1250608 -0.3044963 -0.3255653 0.8863684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1621 1721 -0.554588 -0.184149 0.155145 0.2625159 -0.5962816 0.7073666 0.2741643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1622 1722 0.376631 -0.036446 -0.345034 -0.0141840 -0.1312810 0.9230063 0.3614187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1623 1723 0.405556 0.093133 -0.245919 -0.6043830 0.4028639 0.2581027 0.6370281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1625 1725 0.566812 0.428056 -0.073016 -0.3374163 0.2155909 -0.8136061 0.4215637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1626 1726 0.106210 0.073191 0.569569 0.1444230 -0.1480993 0.4380691 0.8748166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1627 1727 -0.219440 -0.574962 0.320224 -0.5695045 -0.1930077 -0.5104215 0.6147215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1628 1728 -0.431057 0.126901 -0.230815 -0.1782843 -0.5311426 0.1723924 0.8101747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1629 1729 0.407894 0.291282 -0.375131 -0.5604390 0.7642376 -0.2793661 0.1542841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1630 1730 -0.324962 -0.457723 0.353281 0.1651072 -0.7693340 0.4878268 0.3780078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1632 1732 0.045872 0.560013 -0.030511 -0.3744462 0.6324270 0.4871954 0.4716638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1633 1733 -0.542192 -0.070632 0.043810 0.3284833 0.3398792 0.8442385 0.2526703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1634 1734 0.498046 0.195913 -0.267100 0.0288104 0.5145311 -0.3099099 0.7989891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1635 1735 0.231719 -0.116846 0.474092 0.7287481 -0.2525636 0.2641793 0.5790917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1636 1736 -0.248212 -0.469277 0.226506 0.6320518 -0.5999838 -0.4276945 0.2400152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1637 1737 -0.586478 -0.042321 0.614239 0.5333522 0.3941908 0.5349976 0.5233799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1638 1738 -0.339541 0.335144 0.166624 0.2120305 0.6482474 0.5893944 0.4329349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1639 1739 0.417503 0.506329 0.196511 0.3071291 -0.0646590 0.3719396 0.8735856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1640 1740 0.029594 -0.084091 -0.524293 0.4824526 0.0513895 0.6414539 0.5942521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1641 1741 -0.021262 -0.164905 0.093750 0.2817322 0.1052272 -0.6633071 0.6852576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1642 1742 -0.137209 -0.186967 0.195231 -0.1732305 -0.6796492 0.0666667 0.7096645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1643 1743 -0.306758 -0.182171 0.295292 0.6146325 -0.5438328 0.2777954 0.4993021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1644 1744 -0.421602 -0.088044 -0.174898 -0.4657438 -0.3254131 -0.0946096 0.8174583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1646 1746 0.465905 0.143345 0.225654 -0.3443139 0.4311208 -0.6807699 0.4818041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1647 1747 0.205291 -0.457888 0.305058 0.0870038 -0.1334585 -0.9800956 0.1184556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1649 1749 -0.244906 -0.309479 0.142385 0.2915421 -0.5614746 0.0522257 0.7726720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1650 1750 0.198724 -0.233733 0.335916 0.4360546 -0.2372654 -0.8590367 0.1249700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1651 1751 -0.340577 0.310022 0.168434 -0.0510943 -0.0031094 0.7417825 0.6686841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1652 1752 -0.178784 0.420927 -0.020295 -0.7552405 0.0150499 0.2378420 0.6105870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1653 1753 0.439702 0.274195 0.139468 0.2824606 0.0506370 -0.7569922 0.5870390 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1654 1754 0.546642 0.026063 0.065807 0.6762204 0.3692354 -0.6163361 0.1628526 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1655 1755 -0.114435 0.704759 0.194435 0.5978224 -0.2876122 0.4098443 0.6260314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1656 1756 -0.134725 -0.488551 0.167212 -0.5129360 -0.4364010 0.7386673 0.0286611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1657 1757 -0.426937 -0.106105 0.328472 -0.9134945 0.3482523 -0.0322236 0.2078696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1658 1758 0.055826 -0.299786 -0.305425 0.2080580 0.0577553 -0.7575802 0.6159939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1659 1759 -0.403552 0.182548 0.257807 -0.4955721 -0.7255772 -0.2854780 0.3826856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1660 1760 0.147062 -0.329986 -0.356520 -0.3562225 0.3411715 -0.3778687 0.7835322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1661 1761 0.088482 0.442367 -0.199101 -0.2566673 0.0491525 -0.0880633 0.9612236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1663 1763 -0.234120 0.702513 0.159254 -0.0115269 -0.0923395 0.7588938 0.6445314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1664 1764 0.548101 -0.262511 -0.187358 -0.6904048 -0.0914015 -0.1878162 0.6926125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1665 1765 0.418909 0.101393 0.320506 -0.2495878 0.8379167 0.4052069 0.2672243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1666 1766 -0.105645 0.491180 0.078332 0.3194055 -0.0405047 -0.1015241 0.9412929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1667 1767 -0.305794 -0.531454 0.205975 -0.6580931 -0.1958865 0.1794333 0.7045180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1668 1768 0.097411 0.047104 -0.524934 -0.5878007 0.1348156 -0.7824065 0.1554193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1670 1770 0.589720 0.092600 0.427463 0.2324022 -0.5270523 0.1302128 0.8070005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1672 1772 0.595648 -0.389919 0.258513 0.3433499 0.4834739 0.0134818 0.8050975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1676 1776 0.365621 -0.337953 -0.465824 -0.0467141 -0.3089116 0.8242650 0.4722062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1677 1777 -0.593269 -0.103477 0.209433 0.1084606 0.2200289 0.5758749 0.7798665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1680 1780 -0.154488 0.387408 -0.388301 -0.5260857 -0.2821961 -0.0341746 0.8015181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1681 1781 -0.271100 0.534705 -0.375361 0.1552482 -0.0888333 -0.5415457 0.8214225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1682 1782 0.523556 -0.266024 0.417548 -0.6605067 -0.3313649 -0.1000731 0.6662684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1683 1783 0.739414 -0.259874 -0.182927 0.2943159 0.7154307 0.4084986 0.4844234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1684 1784 0.268093 0.598769 -0.096458 -0.0663037 -0.1038343 0.9445652 0.3043333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1685 1785 -0.424089 0.199029 0.822496 0.4170393 0.4047751 0.5817317 0.5690550 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1686 1786 -0.450127 0.650153 0.061510 0.0307472 0.5984610 -0.6579456 0.4560775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1687 1787 -0.771423 0.273099 0.386256 -0.2971395 0.1983984 0.5176381 0.7774297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1688 1788 0.007033 -0.592225 0.005497 -0.3667831 0.7030857 0.4348599 0.4266587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1689 1789 0.215845 0.180159 -0.708030 -0.8129152 0.1435162 0.5610440 0.0616570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1690 1790 0.505260 -0.264260 -0.373564 -0.2326763 -0.0545191 0.4015992 0.8840857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1691 1791 0.038878 0.707078 0.027950 0.7176911 -0.6251744 -0.2606907 0.1616068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1692 1792 -0.077860 0.231942 0.598393 -0.1091813 0.3184729 -0.9412842 0.0252667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1694 1794 0.672225 -0.215773 -0.361533 0.5262351 0.5671297 0.5306787 0.3461512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1695 1795 0.170037 -0.313578 -0.682628 0.0851751 -0.1047993 -0.3212967 0.9372997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1696 1796 0.287984 -0.073955 -0.783416 0.8170290 0.0187343 0.4170362 0.3977354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1697 1797 -0.465816 -0.007653 0.602673 0.0206917 -0.5825991 -0.5179274 0.6260202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1698 1798 0.750371 -0.316279 -0.262849 0.0065192 -0.1206435 -0.5531872 0.8242491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1699 1799 -0.781391 0.135762 0.181351 0.8490503 0.1913959 -0.3634794 0.3322106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1700 1800 -0.625158 -0.143936 -0.587741 0.6050442 0.0824653 0.4302252 0.6648514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1701 1801 0.328619 0.008167 0.646129 0.4711979 0.2009101 0.2873456 0.8093455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1704 1804 0.716142 0.045230 -0.588901 -0.1872877 0.0576448 0.9784558 0.0649977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1705 1805 0.073693 0.534221 0.548287 -0.1468183 0.1568021 0.5639452 0.7973853 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1706 1806 -0.494010 0.638403 0.166033 -0.0447626 -0.1759152 -0.4340301 0.8824217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1707 1807 -0.484245 0.440421 -0.176581 0.7850154 -0.0224322 -0.3147673 0.5330752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1708 1808 0.266776 -0.569248 -0.366199 0.6293026 -0.2900117 0.1055766 0.7132496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1710 1810 -0.570738 0.461505 -0.410344 -0.1565762 0.1430014 -0.3265015 0.9211033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1711 1811 0.675407 0.377995 -0.371756 -0.6179293 0.3851044 0.5465665 0.4136702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1712 1812 -0.411213 -0.505109 -0.115663 -0.4180265 0.4381925 -0.7764719 0.1741624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1713 1813 0.581899 -0.273800 0.233047 -0.0394034 0.3055762 -0.7635269 0.5675362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1714 1814 0.624781 -0.302854 0.047917 0.6919344 0.0689735 -0.7097526 0.1127863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1715 1815 -0.655811 -0.238774 0.087658 0.4144088 -0.6527311 -0.2723178 0.5727570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1716 1816 0.725022 -0.330344 -0.057480 0.2793010 0.5221745 -0.1594044 0.7898829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1717 1817 0.331648 0.560890 0.035432 0.7624239 0.0860877 0.1405583 0.6257332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1718 1818 -0.550140 -0.523887 -0.092360 0.3338913 -0.5989749 -0.3379154 0.6446386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1719 1819 0.500551 0.276930 -0.154986 0.3128658 0.5940034 0.5841766 0.4560841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1720 1820 -0.663922 0.374909 0.267710 0.1783583 0.2286471 -0.9196632 0.2648176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1721 1821 0.504862 0.469389 0.212084 0.1173788 -0.1526794 0.4860011 0.8524753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1722 1822 -0.559542 -0.032181 -0.375014 0.3310061 0.2530258 -0.4218147 0.8052858 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1723 1823 0.562756 -0.053724 0.227622 0.8270769 -0.4596283 -0.1883014 0.2631124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1725 1825 -0.540264 0.455045 0.449827 0.8105994 -0.4789024 -0.2202988 0.2550480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1726 1826 0.077587 0.329397 0.557478 0.4737993 -0.2129093 0.5392134 0.6628973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1727 1827 0.185874 -0.181541 -0.534479 -0.7939338 0.2781506 0.0428521 0.5389481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1728 1828 -0.409530 -0.080545 0.523397 -0.4219252 0.3745051 0.3994880 0.7225887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1729 1829 -0.397598 -0.231581 0.523775 0.3744352 -0.4537399 0.3268824 0.7396393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1730 1830 0.286264 0.096202 0.358175 -0.2257876 -0.3768115 0.7561831 0.4849951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1731 1831 0.205181 0.356701 0.770015 -0.5302401 0.0580864 0.2816082 0.7976016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1732 1832 -0.045863 0.093227 0.331052 0.2071781 -0.5132587 0.6710226 0.4933269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1733 1833 0.233427 0.282970 -0.228176 0.3773857 0.3020662 0.2315503 0.8442278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1734 1834 0.408320 0.527783 0.266294 0.1777528 -0.5685362 0.3406603 0.7274071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1736 1836 0.358116 0.382237 -0.072675 -0.6132890 -0.2558945 -0.6557882 0.3582407 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1737 1837 -0.199623 0.449421 -0.285469 -0.5662014 -0.0158442 0.1500919 0.8103316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1738 1838 0.219804 0.169078 -0.148360 0.5063204 -0.0775025 -0.8281863 0.2274654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1739 1839 0.497080 0.379816 0.064422 -0.1528478 0.4407148 0.0056722 0.8845201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1740 1840 -0.327942 -0.306541 -0.370493 0.6563346 -0.2324140 0.2388819 0.6768634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1741 1841 0.264941 -0.226100 0.503632 0.1464107 -0.1354656 -0.6091603 0.7675524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1742 1842 0.108420 -0.514734 -0.102761 -0.1406795 -0.6746089 -0.6933686 0.2105994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1744 1844 -0.373261 -0.308183 -0.337529 0.6559793 -0.0700712 0.4509918 0.6011553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1746 1846 -0.279071 -0.212248 0.414569 0.3605128 -0.8082029 0.4609886 0.0657889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1748 1848 -0.135241 -0.382509 -0.307414 0.0697609 -0.6828592 0.2629653 0.6780015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1750 1850 -0.423800 0.199478 -0.118920 0.3663943 -0.4361243 -0.1505060 0.8080215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1751 1851 -0.032879 0.360023 0.259550 0.4052332 0.7536922 0.0904050 0.5094713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1752 1852 -0.057416 -0.112668 0.417455 0.5287965 0.0857530 0.8280810 0.1652345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1753 1853 -0.459836 0.318779 -0.180063 0.3708512 -0.7131520 0.4309440 0.4100864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1754 1854 -0.051802 0.480424 -0.336152 0.0028355 -0.2112418 0.8488265 0.4846261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1755 1855 0.117574 0.173415 -0.336666 0.3854883 0.5056080 0.7554601 0.1582382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1756 1856 -0.417148 0.330538 0.619488 0.8814238 -0.2568394 -0.1308990 0.3741537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1757 1857 -0.252969 0.071420 -0.208983 -0.0992882 -0.6382969 0.3048437 0.6998494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1758 1858 0.459900 -0.056315 -0.221925 0.0039728 -0.1991609 0.9372783 0.2860568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1759 1859 0.546236 -0.111029 0.030527 -0.1773649 -0.1491144 -0.4683187 0.8526337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1760 1860 0.440363 0.313467 -0.149894 0.0624262 0.5007751 -0.0332642 0.8626823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1761 1861 0.213089 0.589974 -0.023468 0.4874658 -0.1159482 -0.6869886 0.5262887 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1762 1862 -0.340583 -0.159979 0.386849 -0.8850491 0.1905727 0.4237185 0.0288570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1763 1863 0.612677 0.142830 0.013948 0.8217964 0.1454216 -0.3407622 0.4328791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1765 1865 -0.477447 -0.383458 0.220562 0.5191773 0.2679163 -0.8078079 0.0782444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1766 1866 -0.236408 0.473108 -0.412172 0.0889553 0.1931231 0.8084644 0.5487948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1767 1867 -0.307312 -0.234223 -0.398557 0.2331768 -0.3163769 -0.6866872 0.6115513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1768 1868 -0.739748 -0.038850 0.102370 0.5674217 0.0771556 -0.8105889 0.1225778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1769 1869 -0.484241 0.047693 0.279746 0.1845721 -0.0016434 -0.0583463 0.9810842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1770 1870 0.634136 0.005368 -0.181599 -0.0744920 -0.1887238 0.6685322 0.7154712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1772 1872 0.172709 0.155275 0.490280 -0.9327652 -0.0356232 -0.0619262 0.3533345 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1773 1873 -0.593481 0.349659 -0.026216 0.0942230 -0.7442597 -0.2776426 0.6000951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1775 1875 -0.204346 -0.109150 0.580374 0.0543081 0.8443584 0.5328337 0.0140620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1776 1876 -0.470692 0.099303 -0.588497 -0.0366971 -0.5684536 0.2772148 0.7737350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1777 1877 -0.218168 0.460538 0.036126 -0.1622725 -0.0392296 0.4111736 0.8961389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1778 1878 -0.449972 0.053361 0.013300 -0.4832123 -0.0360147 0.1566168 0.8606277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1779 1879 0.304928 0.097092 0.585534 0.8558937 -0.2135771 -0.4445647 0.1555411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1781 1881 -0.515539 -0.184304 -0.230806 0.5317639 0.1801820 -0.5043227 0.6560641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1782 1882 0.525758 0.095414 -0.566410 0.6311962 -0.5449056 0.3288163 0.4433386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1783 1883 -0.315118 -0.305779 0.390848 -0.7983065 -0.1644245 -0.0120553 0.5792461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1784 1884 0.181997 -0.548166 -0.273622 -0.5568939 -0.0062407 -0.0463722 0.8292647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1785 1885 0.199547 0.661037 0.054686 -0.0031192 0.3688094 0.6369020 0.6769976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1786 1886 0.168600 -0.341695 -0.569892 0.5326412 -0.4623179 0.0461220 0.7074096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1787 1887 -0.521121 0.592784 0.141292 -0.6278675 0.0754386 0.6118871 0.4750638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1788 1888 0.247992 -0.521978 -0.399749 0.1673648 0.0466890 0.0459408 0.9837167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1789 1889 0.639424 -0.353015 0.130570 0.6697955 -0.0635962 0.3580433 0.6474060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1790 1890 -0.082460 -0.162320 -0.668984 0.8751921 0.0280356 -0.1690072 0.4524262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1792 1892 0.286303 -0.631426 0.106685 0.1300023 0.8672459 0.2383007 0.4173688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1793 1893 0.322769 -0.260881 -0.467260 0.1233349 0.9220338 -0.1239091 0.3453821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1794 1894 -0.163969 -0.311097 0.326923 -0.7925263 -0.0075300 -0.5119160 0.3313417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1795 1895 0.248309 -0.180599 -0.559912 0.2988808 0.5485873 0.4675487 0.6253962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1796 1896 -0.229854 -0.717661 0.480538 0.0863387 0.1960384 -0.6845758 0.6967572 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1797 1897 0.808694 -0.061928 0.289384 -0.3743502 -0.1512619 0.3592833 0.8413663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1798 1898 0.248521 0.496907 -0.356658 -0.2579104 -0.2856230 -0.6791170 0.6250614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1799 1899 -0.377504 -0.491252 -0.014309 -0.0176152 -0.4237644 -0.6843727 0.5930831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1800 1900 -0.470806 -0.330711 -0.328605 -0.8014103 -0.3011231 0.3930079 0.3355760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1801 1901 0.266120 0.598487 0.309488 -0.0607547 0.5472304 -0.0792346 0.8310052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1803 1903 -0.051253 -0.775871 0.000297 -0.1306385 0.6777259 0.0225997 0.7232638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1804 1904 -0.291002 -0.368571 -0.536547 0.0733568 -0.1936883 -0.6385456 0.7411903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1805 1905 0.263404 0.329724 0.606374 0.0156243 0.6756470 0.7362561 0.0344082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1807 1907 -0.558040 -0.500314 -0.067911 -0.0772702 0.1795895 0.0764177 0.9777204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1808 1908 0.227526 -0.642715 0.366716 0.0944863 0.2756898 -0.9321773 0.2147391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1809 1909 0.447409 -0.285052 -0.717000 -0.0999409 0.8682383 -0.2728429 0.4021576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1811 1911 0.412221 -0.509434 0.265247 0.1687980 0.4299444 -0.6264473 0.6278685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1812 1912 0.657708 0.246330 -0.152283 0.1879558 0.3469976 -0.7122931 0.5804342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1814 1914 -0.075699 0.150954 -0.647181 0.0721670 0.0048118 0.6356775 0.7685590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1815 1915 0.470674 -0.077168 0.777816 -0.5199690 -0.1316093 -0.1096449 0.8368328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1817 1917 0.401516 0.015786 -0.614094 0.5327432 -0.0805733 -0.8424250 0.0035633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1818 1918 0.321375 -0.262325 0.437141 -0.1822211 0.0083610 -0.9232375 0.3381687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1819 1919 0.277332 -0.181927 0.626515 -0.1227670 0.0367852 0.9818310 0.1399393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1820 1920 0.426497 -0.512180 0.346508 0.3981739 -0.8538008 -0.0146395 0.3350634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1821 1921 0.576065 0.091154 -0.022770 0.1785636 -0.3647173 -0.8719420 0.2735204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1823 1923 0.209641 -0.056190 -0.442988 -0.5427077 -0.4294502 -0.6355036 0.3423099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1825 1925 -0.574509 0.297219 0.064317 0.3140236 0.0711875 0.1471495 0.9352372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1828 1928 -0.539227 0.042705 0.225376 0.6356699 0.0471466 -0.7112728 0.2962971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1829 1929 -0.036425 0.563247 0.454747 -0.1377404 -0.6981347 0.6219708 0.3267842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1830 1930 -0.208415 -0.409918 -0.077597 -0.0335415 0.0262820 -0.7581644 0.6506696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1831 1931 0.131048 -0.448796 0.226621 -0.5987245 0.2342967 0.7257544 0.2447745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1832 1932 0.782132 -0.063842 -0.089744 -0.8230864 -0.0181478 -0.3852231 0.4168964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1833 1933 0.577250 -0.216111 -0.025154 -0.2652191 -0.5427999 0.1844097 0.7752549 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1835 1935 -0.057630 0.006923 -0.536912 0.3652245 0.2550245 -0.6406928 0.6253690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1836 1936 -0.209546 0.068358 0.488398 0.4303626 0.7744119 -0.0067458 0.4637120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1837 1937 -0.062878 0.320744 0.385700 -0.0709361 -0.6850087 0.7204019 0.0821718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1838 1938 -0.316233 -0.166897 -0.389618 -0.1614177 -0.9117878 0.2464863 0.2860625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1839 1939 0.504998 0.186822 0.365408 -0.6665150 0.3048177 0.4341428 0.5237976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1841 1941 0.151372 0.403381 0.285046 0.4314280 -0.3952706 -0.5673715 0.5794141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1842 1942 -0.333589 -0.015582 -0.445078 0.0781981 -0.3922514 -0.6383563 0.6576664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1843 1943 0.592086 -0.276131 -0.156716 -0.4709118 0.6276558 0.3360865 0.5208994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1844 1944 -0.524712 0.284624 -0.112202 -0.5027576 -0.1317411 -0.1277324 0.8447269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1845 1945 -0.188994 0.326027 -0.162886 0.2040864 -0.3298824 -0.8872940 0.2494707 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1846 1946 0.652645 -0.192941 -0.146083 0.1000686 -0.0417764 0.5808639 0.8067454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1847 1947 -0.345231 -0.446544 0.068771 0.2020611 -0.1054083 -0.2884727 0.9299698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1848 1948 -0.528553 -0.151229 0.341474 0.5198056 0.3804305 -0.2193333 0.7327808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1849 1949 -0.167544 0.134793 0.476193 0.2074631 0.8366711 0.1949004 0.4679256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1850 1950 -0.419760 0.132390 0.134103 -0.0565898 -0.9557717 -0.2753578 0.0864647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1853 1953 -0.088272 0.387945 -0.071787 -0.3751407 0.2968106 -0.5176814 0.7093510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1854 1954 0.226936 0.047755 -0.367717 0.4395786 0.1226225 0.3619940 0.8128313 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1855 1955 -0.092623 -0.277579 0.265398 -0.1094530 0.3765936 -0.1916396 0.8997064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1856 1956 -0.119036 0.522628 -0.411859 -0.4119078 0.6641338 -0.2692273 0.5628276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1858 1958 -0.624322 -0.083443 -0.435852 0.7126064 0.5740903 -0.2365400 0.3265903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1860 1960 0.373566 0.270234 0.141811 -0.5242863 0.3906659 0.7217521 0.2271076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1861 1961 -0.295849 -0.260094 -0.372791 0.5696160 -0.3822508 0.2404898 0.6867216 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1862 1962 -0.515011 0.018062 -0.218402 0.8679892 -0.3364927 -0.2637015 0.2526438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1863 1963 0.404847 0.221514 -0.470252 -0.6950147 -0.1607859 -0.6305362 0.3058211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1864 1964 -0.301493 0.028689 -0.334576 0.2867150 -0.4702471 0.5754821 0.6045515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1865 1965 0.072786 -0.232778 0.549139 0.5013717 0.7927987 -0.3174497 0.1390050 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1866 1966 0.521366 0.036901 -0.316248 -0.7826629 0.4743031 -0.3773197 0.1417930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1867 1967 0.235376 -0.416433 0.101564 0.0151026 0.4727582 -0.2083451 0.8560747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1868 1968 0.458688 -0.183971 0.337973 -0.5788645 0.6733586 0.1621319 0.4303688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1869 1969 -0.389445 -0.174925 0.223773 0.0431462 0.6889708 -0.6051144 0.3966033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1870 1970 0.024894 -0.534193 -0.471470 0.8243251 0.3705346 0.1251330 0.4093093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1871 1971 0.228511 0.575709 0.158063 0.3160883 0.1991139 0.2759284 0.8856102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1872 1972 0.283410 -0.496744 -0.199013 0.1940142 0.3239012 -0.3248398 0.8671365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1874 1974 0.058515 -0.486289 -0.092657 -0.2547390 0.0690480 0.7988065 0.5406002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1877 1977 0.235793 0.627580 0.063044 0.6461978 0.0365941 -0.4678187 0.6018596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1878 1978 -0.629603 -0.044285 0.248313 0.7669586 -0.2394779 0.2085626 0.5576078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1879 1979 -0.338786 0.126582 -0.435568 -0.0021572 0.9279946 -0.3659768 0.0698735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1880 1980 -0.514202 -0.175591 0.362444 0.5489661 -0.1942697 0.4956812 0.6443567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1881 1981 0.144177 -0.626342 0.170722 0.4566880 -0.2028286 0.4490533 0.7407076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1882 1982 -0.418887 -0.427716 0.157940 0.5171538 0.1160252 -0.2486140 0.8107288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1883 1983 -0.099670 -0.456906 -0.424511 0.1679102 0.6696501 0.0682648 0.7202186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1884 1984 0.389283 0.028600 -0.606011 -0.6991993 0.4781278 -0.4951857 0.1931459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1885 1985 0.544369 0.201211 0.406476 0.0336134 0.0541112 -0.9978939 0.0122444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1886 1986 -0.304664 -0.652035 0.099344 0.7647516 -0.3629024 0.5146156 0.1364832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1887 1987 0.231603 0.092158 0.649802 -0.0652927 0.6435565 0.6741050 0.3565871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1889 1989 0.683803 -0.151860 0.402247 -0.6744952 -0.3071978 0.3791840 0.5539903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1890 1990 0.409956 -0.351798 0.412179 -0.8074123 0.4176893 -0.2159709 0.3563392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1891 1991 -0.096466 0.638458 0.547234 0.0265406 -0.4517376 0.8758210 0.1678282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1892 1992 -0.643320 -0.568720 0.091615 -0.8020524 -0.2648527 -0.1676308 0.5083944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1893 1993 0.181249 -0.254704 0.609161 -0.0748342 0.4589131 0.6001174 0.6508899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1894 1994 0.584461 -0.253891 -0.415100 0.1281594 0.5057938 -0.3697865 0.7687689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1895 1995 0.169786 -0.607144 0.469100 0.4462187 -0.1333406 -0.0486853 0.8835943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1896 1996 0.352659 -0.144124 0.519999 0.0133929 -0.2045605 -0.6237347 0.7542750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1897 1997 0.325310 -0.646359 -0.237875 0.1229664 0.3410620 0.0732724 0.9290786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1898 1998 -0.782339 0.289775 0.158563 -0.4355993 -0.3869004 -0.2977183 0.7562573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1899 1999 0.798157 -0.324876 0.106877 0.5071625 0.4975522 0.1230826 0.6928771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1900 2000 -0.626200 0.318930 0.629234 -0.2374015 -0.2113565 0.0706796 0.9455016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1902 2002 -0.417114 0.596845 -0.117411 0.7192449 -0.2850117 -0.3333981 0.5387957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1903 2003 0.000644 -0.808381 -0.297286 0.2860319 0.3299566 -0.8608652 0.2612002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1904 2004 0.510443 -0.502193 -0.279786 0.6390777 0.5325894 -0.4949139 0.2509751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1905 2005 -0.428876 0.311230 0.478534 -0.3372128 -0.0067597 -0.6304769 0.6990999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1906 2006 0.719779 -0.419895 -0.144929 0.6480702 -0.2729373 -0.3723391 0.6057011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1907 2007 -0.608515 -0.354234 -0.415745 -0.8079443 0.0888061 0.2404678 0.5305795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1908 2008 -0.210042 0.484824 0.576635 -0.0968883 -0.9132326 0.3103350 0.2455830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1909 2009 0.026778 0.165275 0.644667 -0.0418566 -0.5040741 0.8616463 0.0415086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1910 2010 0.651921 -0.318968 -0.110073 0.7012451 0.5809604 -0.3706190 0.1827071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1914 2014 -0.124278 0.270340 -0.782696 0.4591236 0.4007507 0.3220600 0.7244872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1915 2015 0.606853 -0.342851 0.261817 -0.5222060 -0.4104065 0.7386145 0.1153952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1916 2016 -0.206376 -0.222113 -0.546509 0.2095952 -0.6552096 0.6778376 0.2594349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1917 2017 0.506283 -0.231188 -0.465886 0.8709725 -0.3277646 0.3278670 0.1627282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1918 2018 -0.114268 0.245290 0.521493 0.7897087 0.0066725 -0.2049761 0.5781872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1919 2019 -0.507735 -0.004372 0.526519 0.1741155 0.4061563 -0.8336811 0.3312049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1921 2021 -0.559135 0.189969 -0.114993 0.0936990 -0.8637249 -0.4933651 0.0423164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1923 2023 -0.558495 0.141578 0.043004 0.5353988 0.1374387 0.7453241 0.3727609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1924 2024 -0.675910 -0.297076 -0.084470 -0.3491479 -0.4035008 0.8101937 0.2426292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1925 2025 -0.354292 0.309131 -0.210600 0.2312485 0.2764182 0.9303112 0.0681038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1926 2026 0.166829 -0.428160 -0.424754 -0.2902223 0.6215540 -0.7245178 0.0671983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1927 2027 -0.343046 -0.121433 -0.364481 -0.0034503 -0.0809034 -0.9307643 0.3565397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1928 2028 -0.081654 -0.145247 0.505620 0.0396982 0.6723551 0.4489538 0.5871995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1929 2029 0.213915 -0.248278 -0.328270 -0.5360558 -0.6313291 0.3480228 0.4392583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1932 2032 0.490115 0.330176 0.455433 -0.1569744 0.0509862 0.5720701 0.8034272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1933 2033 0.020802 -0.024720 -0.525712 0.2284032 -0.1885772 0.0824891 0.9515599 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1934 2034 0.109564 0.535482 -0.417041 0.3256177 0.8145835 0.2126111 0.4303758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1935 2035 0.435068 0.249863 -0.094883 -0.5533157 0.0810268 -0.8122831 0.1657486 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1936 2036 -0.408790 -0.040456 -0.544827 0.0885605 -0.7541610 -0.2285904 0.6092164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1937 2037 0.161077 -0.389309 -0.388834 0.4793087 0.2697594 -0.8127668 0.1921017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1938 2038 -0.170539 -0.017402 0.477611 -0.4461463 0.2460148 -0.7197493 0.4715836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1939 2039 -0.047938 -0.531726 -0.052286 0.1519633 0.0007322 -0.7841116 0.6017272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1940 2040 0.303358 0.610757 -0.146210 0.2174633 -0.5170560 -0.2576043 0.7867673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1941 2041 -0.477861 0.290370 -0.161958 -0.7193084 -0.1840241 -0.2491130 0.6218306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1942 2042 -0.122989 -0.463306 -0.145571 -0.5245573 0.4274297 0.6279037 0.3845523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1943 2043 0.109383 -0.457862 0.190854 -0.1881422 0.4418319 0.7587959 0.4400181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1944 2044 -0.492785 -0.155228 0.210331 -0.2909072 0.2385374 -0.2782250 0.8837781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1945 2045 0.204109 -0.565096 -0.017631 0.5237837 0.3676057 0.5676809 0.5179335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1947 2047 0.241641 -0.417352 0.429810 -0.4443566 -0.1432548 -0.3931369 0.7921292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1950 2050 0.442361 0.158162 0.049321 0.0049547 -0.9751346 -0.2192256 0.0320634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1951 2051 0.286572 -0.228656 0.254706 0.7679031 -0.2513155 -0.0752623 0.5843808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1952 2052 -0.319021 0.486567 0.030173 -0.1471585 0.7621504 0.2437720 0.5814176 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1953 2053 -0.529491 0.060558 -0.040985 -0.0218523 -0.2848660 0.1044044 0.9526141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1954 2054 0.157860 -0.428043 -0.119757 0.6078583 0.0058414 0.7937938 0.0191199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1955 2055 -0.162199 -0.432541 0.143574 -0.6799941 -0.1538964 0.1090062 0.7085489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1956 2056 -0.339253 0.420804 -0.110524 -0.3932606 -0.6901096 -0.2191200 0.5666403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1957 2057 -0.461781 -0.056639 -0.233509 -0.6699144 -0.2423994 -0.6175829 0.3332395 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1958 2058 -0.006239 -0.462719 0.201467 0.4249987 0.1276044 -0.0968800 0.8909026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1960 2060 -0.243640 -0.419523 0.187499 0.2002113 -0.0769762 -0.9479786 0.2352163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1961 2061 -0.497303 -0.040526 0.251678 -0.5797886 -0.1017893 -0.0241642 0.8080224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1963 2063 -0.339691 -0.097458 0.156299 0.4256276 0.5670066 0.5950678 0.3784693 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1964 2064 -0.306957 0.457938 -0.103131 -0.3050077 0.0807407 0.7717802 0.5520929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1965 2065 -0.413283 -0.135900 -0.506633 0.8976151 -0.1462536 0.1548571 0.3858968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1966 2066 0.207691 -0.071639 0.460100 0.0087344 -0.1025592 -0.0456906 0.9936386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1967 2067 0.418455 -0.343401 0.409785 -0.0686462 0.1347097 0.8277619 0.5403251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1968 2068 -0.316835 -0.408996 -0.058217 0.3402371 -0.3771119 -0.5405274 0.6707127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1969 2069 0.184671 -0.490155 0.000466 -0.1614299 0.0114215 0.7771748 0.6081194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1970 2070 -0.331910 -0.155914 0.613881 -0.7362979 0.4311454 0.0737038 0.5162817 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1971 2071 0.495143 0.440718 -0.205275 -0.3616077 -0.2064944 -0.0304399 0.9086657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1973 2073 -0.384255 0.032177 0.403354 0.6864370 0.1860758 0.6721028 0.2060534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1974 2074 -0.354238 0.258899 -0.325956 -0.5432664 -0.3146758 0.1235930 0.7684826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1975 2075 0.258164 0.541415 0.228925 0.2391694 -0.0450513 -0.8836171 0.3999866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1978 2078 -0.397298 0.519325 -0.091864 -0.3585842 -0.1287122 -0.8608870 0.3372300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1979 2079 0.246340 0.446228 0.498109 0.4473466 0.0969321 0.8493928 0.2627112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1980 2080 -0.259290 0.506965 0.075468 0.0653227 0.4407812 0.8543606 0.2674190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1981 2081 0.054019 -0.097555 0.595707 -0.1918911 -0.0789623 -0.6048392 0.7688383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1982 2082 -0.258965 -0.481499 0.598431 -0.2316204 -0.0976257 -0.3559658 0.9000609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1983 2083 0.467590 -0.590547 0.014628 0.5336269 0.6604830 -0.5101422 0.1369654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1984 2084 -0.242719 0.246548 0.613308 0.6326515 0.5410037 0.5377604 0.1337193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1985 2085 -0.478487 -0.182723 0.368171 0.5217632 -0.1247945 0.7789783 0.3246264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1987 2087 -0.520799 0.512405 0.213744 0.0067810 0.9126678 -0.0525412 0.4052542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1988 2088 -0.026449 0.935246 0.030206 -0.3830926 -0.4318568 -0.1330502 0.8056286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1990 2090 0.710047 -0.227811 0.149503 0.3737136 -0.2821513 -0.1116222 0.8765097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1991 2091 0.497088 -0.696894 -0.056357 0.7303249 0.4304259 0.5297965 0.0259755 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1992 2092 -0.298667 -0.242278 -0.431473 0.0024501 0.8685575 -0.3546646 0.3461430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1993 2093 -0.472147 0.295333 0.457891 -0.7691149 -0.4157045 -0.4479627 0.1870333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1996 2096 0.035324 0.529086 0.560071 0.0852567 0.4153604 -0.8690429 0.2548951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1997 2097 0.383523 -0.573967 0.055247 0.0671815 -0.0719591 0.5139518 0.8521514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1998 2098 -0.398522 -0.715790 0.299349 -0.1696868 0.8873458 -0.1985854 0.3799837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 1999 2099 0.361120 0.364593 0.813867 0.2305465 -0.8507772 -0.4707558 0.0376222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2000 2100 -0.059539 0.021323 0.609437 0.3393491 -0.7471737 0.2881730 0.4934876 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2003 2103 -0.036285 0.601042 0.308931 0.3500587 0.1890636 -0.3573491 0.8449944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2004 2104 0.061418 0.506551 0.681254 0.2907200 -0.5025009 -0.7846741 0.2173966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2005 2105 -0.201321 -0.610309 0.354773 -0.6898787 0.3785192 -0.3370093 0.5169288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2006 2106 0.466226 -0.239459 -0.258576 -0.1913170 -0.1286623 0.7352440 0.6373854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2007 2107 -0.396964 0.529778 -0.127885 0.0964418 -0.2815488 0.3735535 0.8785710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2008 2108 0.754551 0.125281 -0.581732 -0.2286653 -0.3830181 0.7012419 0.5561197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2009 2109 0.059966 -0.869444 0.078044 0.3968611 -0.2102987 -0.5755624 0.6833767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2010 2110 -0.236285 0.735994 -0.265979 -0.4670719 -0.0689477 0.5918779 0.6532768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2011 2111 -0.665277 0.317953 0.402988 -0.4087659 -0.8312045 -0.3298073 0.1823093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2012 2112 0.008025 0.766779 -0.155520 0.3125688 0.1906905 0.7344866 0.5713732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2013 2113 -0.098426 0.104222 -0.752597 0.3068138 -0.6667576 -0.6397243 0.2281501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2014 2114 0.378903 -0.583758 -0.331670 -0.7514205 -0.5206035 -0.3839642 0.1300414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2015 2115 -0.536519 0.160045 -0.388040 0.2138695 -0.3398867 0.9112377 0.0915566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2016 2116 -0.289553 0.383501 0.554162 -0.1440280 -0.1243814 0.8635855 0.4669104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2017 2117 0.053506 -0.206423 0.609088 -0.5106526 0.4517041 0.7308923 0.0315259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2019 2119 0.112600 -0.637245 0.334869 -0.1583112 -0.4667792 0.8034255 0.3340092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2021 2121 0.579581 -0.017983 0.150590 -0.1465533 -0.0347048 0.6324164 0.7598468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2023 2123 0.158704 0.128412 -0.627376 0.2919668 0.3747099 -0.0119069 0.8798898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2024 2124 0.187535 0.393617 0.505181 -0.3683738 -0.8104464 0.3776884 0.2546151 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2025 2125 0.331076 -0.634326 0.002174 0.6075451 0.0064617 -0.7579386 0.2374370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2026 2126 -0.182825 0.627292 0.150475 0.2784618 0.3831929 -0.8273447 0.3018658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2028 2128 -0.382254 0.175622 -0.189292 0.4059292 0.5730475 0.3926040 0.5938857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2029 2129 -0.443858 0.487994 -0.294177 0.0854514 0.0603499 -0.8552850 0.5074874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2030 2130 -0.672726 0.175588 0.070359 0.1739223 0.1737216 0.0051722 0.9693013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2031 2131 -0.390594 -0.428363 -0.056125 -0.1136956 0.3781917 0.9144124 0.0888500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2035 2135 -0.575181 -0.146271 0.304210 -0.2891624 0.2147764 -0.9233364 0.1330640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2036 2136 -0.273985 -0.478564 0.479993 -0.1189002 -0.7270248 -0.6641705 0.1271819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2037 2137 0.306118 0.547010 0.095983 0.4405459 0.2127897 -0.8294960 0.2693998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2038 2138 0.115673 -0.413079 -0.081598 -0.0731304 0.1155177 0.8302282 0.5403968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2039 2139 0.378809 0.035723 0.242752 -0.1867199 0.0928912 -0.9652301 0.1576000 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2041 2141 -0.328141 -0.163995 0.412093 -0.7141282 -0.1365957 -0.6846039 0.0517694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2042 2142 0.063118 0.284521 -0.368500 -0.3333800 0.2628607 0.7814110 0.4573389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2043 2143 -0.489417 -0.076615 -0.157672 0.0773049 0.8570223 0.4974742 0.1098010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2045 2145 -0.443508 0.184573 0.215058 -0.7935937 -0.4200005 -0.3868069 0.2102120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2046 2146 0.180628 0.494928 -0.173420 -0.1120583 0.6469814 0.6368373 0.4040992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2047 2147 0.379401 -0.158937 -0.224040 -0.4448288 0.1423673 0.7938023 0.3895340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2048 2148 0.320458 0.361442 -0.265110 0.7521548 0.0833859 0.1297313 0.6406870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2050 2150 -0.424377 0.071892 0.174853 0.2960833 0.3729187 0.3099125 0.8229342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2052 2152 -0.062273 0.586623 -0.139062 0.0353003 -0.1901275 0.5263188 0.8280060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2053 2153 -0.499343 0.191214 0.081864 0.3180166 -0.1821445 -0.9242726 0.1068126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2054 2154 -0.129566 0.522142 0.287310 -0.1904038 -0.1687010 -0.0366447 0.9664075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2055 2155 -0.145593 -0.245001 -0.507704 0.6413521 -0.7488828 -0.0762033 0.1484421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2056 2156 -0.125365 -0.222634 0.517733 0.5101752 0.3925758 -0.0252027 0.7648336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2057 2157 -0.150593 -0.204378 -0.331147 0.2288977 0.2051377 0.5385916 0.7845021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2059 2159 -0.071055 -0.423848 0.261310 -0.4771746 -0.5898892 -0.4542643 0.4668822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2060 2160 0.325805 0.326156 0.310763 -0.3971310 0.5579851 -0.6979436 0.2093188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2061 2161 -0.230201 -0.511530 0.111479 0.4727700 0.0649217 -0.5129298 0.7135662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2062 2162 -0.017793 -0.519543 0.314731 0.4990022 -0.0618781 -0.7567635 0.4177043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2063 2163 0.192430 0.358068 -0.563814 0.7891768 -0.2413081 -0.4510015 0.3399529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2064 2164 0.232672 0.234039 0.317742 -0.7417774 -0.4790623 0.3139389 0.3488667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2065 2165 -0.260002 -0.095747 0.348819 -0.4643244 0.0390937 0.4006879 0.7888750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2066 2166 0.006510 -0.013254 0.458147 -0.3592680 -0.7770287 0.4388635 0.2730415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2068 2168 0.386190 -0.426954 0.322298 0.1723376 0.5209812 0.7552190 0.3585005 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2069 2169 -0.524007 -0.172063 -0.231371 0.2550961 -0.4922691 -0.4424077 0.7048919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2070 2170 -0.514535 -0.134787 -0.310572 0.4044326 0.6370898 -0.5626704 0.3375690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2071 2171 0.275143 0.435327 -0.064416 -0.5089312 0.1882271 0.4121984 0.7318825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2072 2172 0.264574 -0.151755 -0.658677 0.2074782 0.2827720 0.6285181 0.6942318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2074 2174 -0.343783 0.257719 0.440871 0.1651531 -0.4505679 0.0725133 0.8743311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2075 2175 -0.574781 -0.129777 -0.087046 0.1406977 -0.2281370 -0.9489123 0.1665024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2076 2176 -0.570479 -0.191659 0.358354 0.3715961 0.7985095 -0.0312171 0.4725722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2077 2177 0.573798 -0.265533 -0.059702 0.7736889 -0.5403496 -0.0165636 0.3303837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2078 2178 -0.130648 -0.645141 -0.001993 -0.1981086 0.3922363 0.4090555 0.7997358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2079 2179 0.720246 -0.134513 0.502610 -0.4145918 -0.2181951 -0.0128333 0.8833685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2080 2180 0.664002 -0.041905 0.348758 -0.6548320 0.2459830 0.0414571 0.7134204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2081 2181 0.319956 -0.194828 0.535268 -0.4944557 0.3831715 0.5567353 0.5465702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2082 2182 0.167331 -0.638664 0.229961 -0.0928207 -0.2070837 -0.9703734 0.0829227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2083 2183 -0.471544 0.290269 0.330223 -0.2847277 -0.1781234 -0.3878816 0.8583414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2084 2184 0.352681 -0.022433 -0.501143 -0.4055509 0.7528131 0.4884522 0.1738254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2085 2185 0.576465 0.477166 0.133679 0.6512888 -0.0890640 0.3266159 0.6791263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2086 2186 -0.054137 0.083999 0.852525 0.3125079 0.0101124 -0.9321927 0.1823551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2087 2187 0.092686 0.427656 -0.778550 -0.2337562 0.6953015 0.5131020 0.4456908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2088 2188 -0.096248 0.346548 0.519436 -0.2692272 0.1719873 0.1214168 0.9397846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2089 2189 -0.449136 0.834379 0.331574 -0.3454637 -0.4175977 0.7932993 0.2773863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2092 2192 0.765553 0.286971 0.177975 0.2947437 0.4485170 -0.4405783 0.7196175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2093 2193 0.248305 -0.554846 -0.515409 -0.1977834 0.7870782 -0.3844138 0.4400178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2094 2194 0.236098 0.119127 -0.603646 0.5618796 0.5273330 -0.0397580 0.6361058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2095 2195 -0.412052 0.306683 -0.341476 -0.2366723 -0.9566450 0.1690006 0.0159824 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2096 2196 -0.434719 -0.513582 -0.149107 0.5216013 -0.2194620 -0.7366642 0.3702627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2097 2197 -0.281180 -0.780543 0.372788 -0.3494899 -0.1329574 -0.8178117 0.4374507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2098 2198 0.305133 -0.515084 -0.346503 0.4467392 -0.2017575 -0.2369285 0.8387985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2099 2199 -0.386414 0.438588 -0.221121 -0.3639268 0.0349135 -0.8329787 0.4153129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2100 2200 0.869318 0.075398 -0.099071 0.2527105 -0.5297589 0.8095432 0.0115226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2102 2202 -0.424249 0.509983 0.420726 0.4040360 -0.1674907 -0.0137117 0.8991739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2104 2204 -0.415012 0.268063 0.498151 -0.0407883 -0.6781443 -0.6725092 0.2935778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2105 2205 0.549393 -0.377785 -0.484252 0.6055296 -0.3499499 -0.1550571 0.6977294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2106 2206 -0.148104 -0.399010 -0.704526 0.4725362 -0.0043280 0.8561445 0.2090631 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2107 2207 -0.127239 0.676291 -0.168755 0.3879216 0.2445019 -0.5324797 0.7114780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2108 2208 -0.058250 -0.093756 -0.710926 0.2758211 -0.3377347 0.8995193 0.0268888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2109 2209 0.621008 -0.027244 0.401490 -0.4557913 0.7201832 0.2973171 0.4303405 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2110 2210 0.447111 0.285716 0.412686 -0.5792216 -0.0349059 -0.2401806 0.7782013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2111 2211 0.758182 -0.203322 -0.311715 0.4543377 0.5926311 0.6103491 0.2642718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2112 2212 0.570381 -0.084826 -0.188693 -0.5829403 -0.6825239 -0.1566817 0.4120590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2113 2213 0.130000 -0.824472 0.208135 -0.0733826 -0.2553807 0.5812288 0.7691351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2114 2214 -0.428828 0.438116 0.251587 -0.3547281 -0.2052886 -0.6922834 0.5939430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2115 2215 0.237227 0.105660 -0.640342 -0.1316466 0.5761303 0.5433215 0.5962758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2116 2216 0.438283 -0.072759 0.339120 0.0285981 0.2317478 0.0132233 0.9722655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2118 2218 -0.487195 -0.116998 0.430156 0.6767773 0.3752477 -0.4244245 0.4701336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2119 2219 -0.576493 0.006792 0.479281 0.9040980 -0.3057572 -0.2580537 0.1500922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2120 2220 -0.442576 -0.070267 -0.477785 -0.0401542 -0.7058335 0.6833854 0.1821293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2121 2221 0.187900 -0.727169 -0.095362 -0.7352903 0.2114610 -0.5415264 0.3483986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2127 2227 -0.654687 -0.228526 0.263237 -0.5025992 0.0703091 -0.8272547 0.2410401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2128 2228 0.259408 -0.045232 -0.641593 -0.1408112 0.1494030 -0.9332707 0.2947147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2129 2229 0.142987 -0.629316 -0.542945 0.3885263 -0.4557538 0.3165524 0.7356157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2130 2230 -0.359487 0.357424 -0.294450 -0.2980835 0.2113098 0.9115448 0.1886279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2131 2231 0.049007 0.280299 -0.257614 0.3070844 -0.0003124 0.5263111 0.7929033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2132 2232 0.567741 -0.186659 -0.430723 0.0519962 -0.2940615 0.8045508 0.5133441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2133 2233 -0.127086 0.070713 0.507039 -0.0556737 0.0234804 -0.0141711 0.9980723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2134 2234 -0.703581 0.225590 0.120059 -0.4884972 0.2761089 -0.2058315 0.8017280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2135 2235 0.440211 -0.048492 -0.062649 0.1579467 -0.3957022 -0.1621789 0.8900397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2137 2237 -0.278498 -0.368038 -0.353492 -0.0182908 0.1182717 -0.1764001 0.9770160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2138 2238 -0.363961 -0.257958 -0.182498 -0.0973247 0.2429470 -0.8850012 0.3850682 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2141 2241 0.008579 0.246431 -0.452552 -0.8108944 -0.3629453 0.0784006 0.4522989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2142 2242 0.479445 -0.099594 0.006946 0.4026057 0.7661885 0.4057719 0.2936204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2143 2243 0.518022 -0.301023 -0.003809 -0.1222107 0.6834784 0.5191157 0.4984383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2144 2244 -0.186067 -0.534542 -0.130068 -0.1328198 -0.3363411 0.9318573 0.0295891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2145 2245 0.122596 -0.450995 -0.350995 0.4986406 0.0817736 -0.4116307 0.7584397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2146 2246 0.200754 -0.145006 0.425596 -0.5125695 -0.1574197 -0.6235703 0.5689039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2147 2247 -0.095453 -0.170585 -0.462610 0.2430934 -0.6219014 0.3716852 0.6449762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2148 2248 0.298774 -0.349838 0.058849 -0.2590580 0.0976238 0.5097950 0.8145352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2149 2249 0.267367 0.441425 -0.014680 -0.0725811 0.5013610 0.0847525 0.8580129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2150 2250 -0.442681 0.328588 -0.123850 0.2170488 0.8255007 0.3939761 0.3409124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2152 2252 0.391216 0.243041 -0.281704 -0.5407180 0.1253131 0.8036383 0.2146770 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2153 2253 0.238804 -0.025961 0.665386 -0.5984377 0.0806364 0.7676015 0.2148442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2154 2254 -0.265197 0.144911 0.397007 -0.7125523 0.2862837 -0.2866370 0.5728438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2155 2255 0.178126 -0.195608 0.481392 -0.3977601 0.2037360 -0.8930091 0.0530406 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2156 2256 -0.584293 0.282831 0.089130 0.4009660 -0.3654804 -0.6065131 0.5811990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2157 2257 -0.212475 -0.409828 -0.481463 -0.3223146 -0.5291108 0.5305524 0.5785060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2159 2259 0.298053 0.211592 -0.254263 0.5162352 -0.0745929 -0.4561400 0.7210225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2160 2260 -0.270380 -0.465204 0.087905 0.4878594 0.5711339 0.6434274 0.1476495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2161 2261 -0.099392 -0.240414 0.418340 -0.7933830 0.1508393 0.5897358 0.0015836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2163 2263 0.096976 -0.473957 -0.110592 -0.1916664 0.0122703 0.0943637 0.9768362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2164 2264 0.514932 -0.202410 -0.462044 0.2734584 -0.4730669 0.4874465 0.6810463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2165 2265 -0.491249 -0.061863 0.177597 -0.4468922 0.0378813 -0.4993845 0.7412608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2166 2266 -0.130098 -0.503922 -0.371792 -0.2568421 -0.8095375 0.4403194 0.2912043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2167 2267 -0.217001 0.306927 0.245270 0.5465618 0.1265155 -0.7660463 0.3137468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2168 2268 -0.644825 -0.039243 0.199153 -0.5426150 0.5996969 0.5390555 0.2352696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2169 2269 0.015071 -0.269980 0.538123 -0.8683334 -0.2987366 -0.0001976 0.3959211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2170 2270 0.516517 -0.009939 0.320082 0.5383277 -0.0904419 -0.5111632 0.6638793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2171 2271 0.333132 -0.191678 0.318602 0.2777769 -0.0823201 -0.9326734 0.2149039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2172 2272 0.114825 -0.535297 -0.234115 0.1936607 -0.4285385 0.7415901 0.4784291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2173 2273 -0.212103 0.550419 0.172429 0.4979979 0.2546424 0.1490352 0.8154408 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2174 2274 0.025322 0.498717 0.398085 -0.2965169 0.4347503 -0.8145750 0.2440030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2175 2275 0.601827 0.324152 -0.090280 -0.1540626 -0.3909322 0.8081999 0.4126133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2177 2277 0.583514 -0.331532 -0.306871 -0.1925329 0.0288864 0.8315564 0.5202025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2178 2278 -0.458965 -0.305006 -0.279225 -0.4719345 0.7736478 0.4002106 0.1363026 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2179 2279 0.558966 -0.187654 0.066749 0.7140504 -0.1262066 0.2424877 0.6445181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2180 2280 0.458093 -0.491721 0.198882 -0.7082776 -0.5408823 0.4071807 0.1999825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2181 2281 -0.627912 -0.287411 -0.264411 -0.4591500 -0.5204010 0.2134736 0.6875995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2183 2283 -0.469083 -0.232634 0.641833 0.8514636 -0.0438524 0.4290238 0.2983711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2184 2284 -0.192705 -0.637155 0.397514 -0.7107053 0.3922675 0.5820667 0.0471449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2185 2285 0.360675 -0.025306 -0.418316 -0.2000814 0.5953756 0.3754651 0.6815580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2186 2286 -0.535924 0.247037 0.509794 -0.6712622 -0.2119673 -0.6377059 0.3127429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2187 2287 0.712034 -0.251968 0.463260 -0.4843180 -0.1926389 -0.6133739 0.5933791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2188 2288 -0.431288 0.292039 0.695537 -0.3211885 0.5732309 -0.7105344 0.2517641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2189 2289 0.540152 -0.442869 0.039245 0.3676175 -0.3715427 -0.7207798 0.4552909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2191 2291 0.696778 -0.189542 0.224045 -0.0288482 -0.3154744 0.7481941 0.5829660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2192 2292 -0.434126 0.679448 0.099791 -0.4064153 0.4802832 0.7651733 0.1366180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2193 2293 0.304060 0.106224 0.596067 -0.3895284 -0.4688219 0.7021748 0.3680002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2195 2295 0.485144 -0.022061 0.698636 -0.1784334 0.6808694 -0.2971278 0.6452081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2196 2296 0.638533 0.020396 0.433944 -0.0878480 -0.4961627 -0.0634943 0.8614370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2197 2297 0.481104 0.252903 -0.369651 0.1003141 0.5712635 0.2737278 0.7672472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2198 2298 0.822193 -0.182706 0.064123 0.0525884 -0.4341948 -0.7188519 0.5403344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2199 2299 -0.280441 -0.648989 -0.410058 -0.3807804 0.1894739 -0.5501077 0.7186706 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2200 2300 -0.791484 -0.211366 -0.022346 0.5923033 -0.0504778 -0.6100120 0.5239410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2201 2301 0.515421 -0.388786 0.499988 0.6041068 -0.2693445 -0.2359986 0.7119081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2202 2302 -0.421189 0.657571 -0.349045 -0.7320389 -0.2271819 0.5859089 0.2630934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2203 2303 0.141726 -0.232303 0.794511 0.3130356 -0.3512873 -0.3706831 0.8007497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2204 2304 0.551897 0.403660 0.173289 -0.0121399 -0.8795548 -0.3095780 0.3611059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2205 2305 0.604013 -0.442173 -0.258960 0.6416761 0.0458884 0.2719456 0.7156756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2206 2306 -0.400217 0.169603 -0.481624 -0.2022700 0.2434491 0.5994025 0.7352116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2208 2308 -0.460235 0.390205 -0.362137 0.4868679 0.5912345 0.3082288 0.5642662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2210 2310 0.400285 -0.057842 0.526185 0.1972558 -0.0257827 -0.4208833 0.8850326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2211 2311 -0.363837 -0.049134 0.556617 -0.2215984 -0.2062121 -0.3049049 0.9029971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2212 2312 -0.334771 0.584736 -0.094482 0.0477920 0.3711502 -0.9246903 0.0700802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2213 2313 -0.661843 -0.513459 0.200121 0.5513021 -0.0497341 0.8323500 0.0280372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2214 2314 -0.015201 -0.689552 0.534283 0.1988307 -0.1417695 -0.4168619 0.8755535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2216 2316 0.279688 -0.105987 0.503423 0.1068417 -0.3156446 -0.1956913 0.9223114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2217 2317 0.624813 0.277300 -0.234372 -0.3306721 0.4271443 -0.0308912 0.8409812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2218 2318 -0.398975 -0.276985 0.173289 -0.7179252 -0.3887273 0.1443849 0.5591310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2219 2319 -0.330894 0.514310 0.042294 0.0940502 0.5399253 0.8214426 0.1576936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2221 2321 0.368609 0.554046 -0.007874 -0.5953176 0.3631960 -0.1931229 0.6902095 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2222 2322 -0.495806 -0.051136 -0.315795 0.1667207 -0.4966975 -0.1560175 0.8373496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2223 2323 -0.043453 0.688002 0.245086 -0.2863748 0.4600310 0.8390755 0.0480960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2225 2325 0.518553 -0.141177 -0.392177 0.5527537 -0.2353505 0.7915340 0.1120156 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2226 2326 0.451120 0.118691 -0.175041 -0.5432501 -0.2536658 0.0152133 0.8001884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2227 2327 0.318305 -0.182717 -0.382137 0.5248135 0.1473338 -0.4368243 0.7155753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2228 2328 -0.442622 0.220400 -0.329795 -0.1732238 -0.2121765 -0.4495386 0.8502292 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2229 2329 -0.180470 -0.573696 0.276211 0.0037652 -0.6872242 0.5824840 0.4340750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2230 2330 0.597016 -0.106377 0.271258 0.1044838 0.1923378 -0.6175842 0.7554331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2231 2331 0.366816 -0.231511 -0.416400 -0.3036714 0.6461405 0.2108421 0.6677064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2232 2332 -0.461497 -0.423532 -0.405797 0.3111048 0.0945933 -0.8001053 0.5040807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2233 2333 -0.139078 -0.037283 0.600696 -0.0881140 0.6136042 -0.7822693 0.0614859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2234 2334 -0.408309 -0.091085 -0.225938 -0.2295278 -0.6106038 0.5382942 0.5335910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2235 2335 0.436688 0.134922 -0.417927 -0.0672672 -0.3838134 -0.7496702 0.5349364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2236 2336 -0.633952 -0.363204 -0.055137 0.2516090 -0.4591413 0.1374601 0.8408251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2237 2337 0.055091 -0.232005 -0.238606 0.0532200 -0.4349342 0.8885199 0.1361331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2238 2338 0.374474 0.088574 -0.192903 -0.3802570 0.3266198 0.6335096 0.5893978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2239 2339 -0.455007 0.072867 0.385683 -0.4089278 0.5563218 0.7228640 0.0274179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2240 2340 -0.225946 -0.750988 -0.076999 -0.2828971 -0.8182778 0.2954764 0.4038370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2241 2341 0.054547 0.452957 0.195356 0.6349466 -0.1737472 0.7526160 0.0149613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2243 2343 -0.254957 -0.594420 0.086079 -0.1867301 -0.5546703 0.7952192 0.1584268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2244 2344 0.059385 0.506277 0.357081 0.1333095 -0.1977503 0.6687514 0.7041981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2245 2345 0.380478 -0.238343 0.163517 -0.1181961 0.1016213 -0.0176463 0.9876191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2246 2346 0.356240 0.051099 0.149575 0.4140741 0.1106199 -0.0222177 0.9032233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2247 2347 -0.568711 -0.215617 0.118326 0.1067177 -0.0157151 -0.4538935 0.8845027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2248 2348 0.149786 -0.465644 -0.282739 0.1933989 0.6506240 0.3766058 0.6304389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2249 2349 0.053211 0.504554 0.191588 -0.2896106 0.1416831 0.2813685 0.9038160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2252 2352 0.014821 -0.493043 -0.055149 -0.4012128 -0.6173933 0.5842028 0.3414101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2253 2353 -0.588142 -0.250535 -0.131354 0.6346667 0.0969738 0.2336328 0.7302123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2254 2354 -0.239097 -0.514040 -0.373934 0.4719017 0.7072991 0.4052246 0.3359015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2255 2355 0.113002 0.037463 0.492836 0.0229143 0.2649611 -0.9639798 0.0036778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2256 2356 -0.299889 -0.164023 0.518040 -0.3804995 0.5805466 -0.0610265 0.7172597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2257 2357 -0.373824 0.295782 0.398830 -0.2915558 -0.4010698 0.8655396 0.0705654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2258 2358 -0.227201 -0.188125 -0.153940 -0.4723398 -0.5762068 -0.0501702 0.6651043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2259 2359 0.253492 -0.105635 -0.373017 0.1187876 0.2993070 0.7157922 0.6196341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2261 2361 -0.448537 0.277456 -0.434721 0.6221582 -0.7449979 0.1321459 0.2010837 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2262 2362 -0.433270 -0.269983 0.005668 0.0461276 0.2878416 -0.8564983 0.4259461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2263 2363 -0.219924 -0.415229 -0.365301 0.2166032 -0.1820535 -0.2102859 0.9357988 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2265 2365 -0.064027 -0.520127 -0.297082 0.2776302 0.5755464 -0.5103469 0.5755118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2266 2366 -0.345821 0.127483 0.393463 0.1762720 -0.2234168 0.8751363 0.3913433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2268 2368 -0.187165 0.548951 0.164089 0.7580968 -0.2738295 -0.0367318 0.5907262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2269 2369 0.021873 -0.206995 -0.530139 0.1504695 0.3322887 0.2714071 0.8906634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2270 2370 0.088556 0.755424 -0.143382 0.1232150 0.4267046 -0.6585476 0.6075001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2273 2373 0.142042 0.402850 -0.394051 0.4939784 0.3052979 0.1679617 0.7965974 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2274 2374 -0.199684 -0.693781 0.084028 0.1389589 0.1099018 -0.6673527 0.7233619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2275 2375 -0.297073 -0.472093 -0.354298 -0.2183585 -0.6922611 0.6050952 0.3270382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2276 2376 0.158004 0.038016 -0.849329 -0.8058149 0.2787131 0.2829260 0.4392429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2278 2378 0.793228 0.206583 -0.218693 -0.6888544 0.4090256 0.5679673 0.1886553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2279 2379 0.721996 -0.368507 0.250704 -0.6775490 0.1153095 0.6406990 0.3422512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2280 2380 -0.621050 0.177357 -0.609400 -0.2419860 0.3454624 0.9064401 0.0215604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2281 2381 -0.450774 -0.091283 0.451465 0.5749186 0.1348481 0.6135731 0.5242258 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2284 2384 -0.185117 0.571456 -0.550172 -0.4977428 -0.6299115 -0.1223024 0.5835287 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2285 2385 0.616433 -0.459496 0.471116 -0.0644097 -0.1920815 -0.2812010 0.9380203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2286 2386 0.628689 -0.240548 -0.245555 0.6424964 0.3105960 0.4292094 0.5536315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2287 2387 0.676679 0.361668 0.326800 0.2042115 0.6327614 -0.7174326 0.2078487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2288 2388 0.220525 -0.710852 -0.291953 0.2228908 0.1264257 -0.9103414 0.3249842 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2291 2391 -0.319139 -0.739607 0.062996 -0.2800827 0.5092232 0.5227263 0.6237008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2294 2394 0.452910 -0.432278 0.239318 0.5306031 0.1142471 -0.7031042 0.4594045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2295 2395 -0.385008 -0.313361 0.365107 0.4510804 -0.4932178 0.0287274 0.7432613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2296 2396 0.638588 0.396326 -0.185538 0.1541384 -0.0754769 -0.2217092 0.9598904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2297 2397 0.683721 -0.083794 0.295184 -0.0038906 -0.2343110 -0.1479786 0.9608255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2298 2398 -0.241137 0.525759 -0.453160 0.3117433 0.1944899 0.8809577 0.2981666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2299 2399 0.653547 -0.111097 -0.622031 -0.3803070 0.1971537 -0.7430159 0.5142222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2300 2400 0.004304 -0.200045 0.648737 0.3747152 -0.5924039 -0.3034185 0.6454327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2301 2401 0.570462 0.433452 -0.100603 -0.3906801 -0.3572618 0.7767675 0.3411237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2304 2404 -0.265787 0.626634 -0.416795 -0.8415309 0.1330031 -0.2161528 0.4768794 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2305 2405 0.225578 -0.419609 0.682877 -0.6122683 0.4737885 0.4088345 0.4832250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2306 2406 0.213817 0.712522 -0.240127 -0.5092078 -0.0905422 -0.5149282 0.6836362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2309 2409 -0.674024 0.166565 -0.283438 -0.0491153 -0.6368567 0.0305603 0.7688090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2310 2410 0.131051 0.445702 0.656760 0.1003484 0.6657692 -0.3746925 0.6374066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2311 2411 0.061555 -0.681866 0.422665 0.0069794 0.2468471 0.9607642 0.1262929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2313 2413 0.398048 0.665504 -0.208557 -0.0581700 -0.1398808 0.1668412 0.9742760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2314 2414 0.506313 -0.332948 0.277117 0.0204230 0.0734338 -0.6851364 0.7244160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2315 2415 0.196091 -0.582773 -0.263320 0.0918697 0.2529321 -0.7854185 0.5574075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2316 2416 0.521129 0.192938 0.448238 0.9123100 0.1430984 -0.2440091 0.2960961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2318 2418 -0.736406 -0.373235 -0.101126 0.4897598 0.0393770 0.8608977 0.1320605 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2319 2419 0.669319 -0.015440 0.225391 -0.3504331 -0.4145727 0.7939782 0.2737236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2320 2420 0.079324 0.625794 -0.120550 -0.6362480 -0.3086458 -0.4793147 0.5197920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2321 2421 -0.137217 -0.028428 0.663243 0.1322897 0.9068158 -0.2284206 0.3286466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2322 2422 -0.345783 -0.292469 0.397185 0.2594454 0.2898001 -0.9082113 0.1544543 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2323 2423 0.014182 -0.135150 0.560942 0.4606703 0.4297959 0.7669202 0.1220317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2324 2424 -0.532482 -0.534250 -0.057177 -0.3369111 -0.1568639 -0.6888650 0.6223742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2325 2425 -0.456686 -0.120995 0.491682 -0.7352692 0.3225805 0.5556550 0.2157975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2326 2426 0.426968 0.230468 0.001557 -0.3482764 -0.1942896 -0.7941614 0.4585442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2327 2427 0.579769 0.066629 -0.079318 -0.4927835 0.0473848 -0.8304742 0.2554048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2328 2428 -0.627176 -0.035702 -0.040540 0.0037173 -0.8171930 0.2339467 0.5267360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2329 2429 0.374867 0.092136 0.610476 0.4578841 -0.7171932 0.5196964 0.0767574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2331 2431 0.470875 -0.430247 0.178601 0.2025345 -0.0817838 -0.6767338 0.7030807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2332 2432 0.338140 -0.172809 0.335731 0.3366798 -0.4941879 -0.7977569 0.0775173 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2333 2433 0.391311 -0.257113 0.158191 0.0471024 0.6190609 0.7755694 0.1141801 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2334 2434 -0.027226 0.262897 0.546480 0.5031787 0.2301516 0.0513267 0.8313886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2335 2435 -0.384304 0.240159 -0.157049 -0.6522571 -0.0461201 0.3839188 0.6519508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2336 2436 -0.415944 -0.055381 0.301623 0.4004697 -0.3169590 0.2254228 0.8296660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2337 2437 -0.054076 0.426831 0.261910 -0.3161288 0.0087135 -0.4779536 0.8194797 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2338 2438 0.006418 -0.408425 -0.419747 0.1104733 -0.1938219 0.9617011 0.1592474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2339 2439 -0.252639 0.770857 0.226675 -0.0506645 0.7144325 -0.6241329 0.3122138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2340 2440 -0.381771 -0.256593 0.158528 0.6867868 -0.3561550 0.4275702 0.4676123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2341 2441 0.352481 -0.495219 0.088851 -0.1702418 -0.4681840 -0.8670568 0.0058277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2342 2442 0.469742 -0.084396 0.309103 -0.4033518 -0.5583212 0.0207752 0.7246745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2343 2443 -0.136295 -0.096723 0.477839 0.2609555 0.7184369 -0.0561271 0.6423398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2344 2444 0.381702 0.014494 0.220329 -0.4450729 -0.1590557 -0.8789750 0.0633593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2345 2445 0.561870 -0.108009 0.034294 -0.0967012 0.1630125 -0.5170348 0.8347160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2347 2447 -0.036534 -0.546569 0.044386 -0.2170925 -0.4688427 -0.4850537 0.7055354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2349 2449 0.082702 0.346402 0.591316 0.4550840 -0.3492720 -0.7048943 0.4171710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2350 2450 -0.518633 -0.286694 0.097835 -0.1676932 0.0247022 -0.9852848 0.0219699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2351 2451 -0.365141 -0.074364 0.435816 -0.8861384 -0.0811979 0.3443117 0.2993579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2352 2452 -0.483513 0.146310 0.003661 -0.4949622 0.5284179 -0.6882205 0.0462560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2353 2453 -0.462199 0.031635 0.027518 -0.7994505 -0.1770122 0.3257548 0.4726831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2354 2454 -0.140726 -0.448918 -0.165367 -0.7470467 0.0075485 0.0706234 0.6609664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2356 2456 -0.225344 -0.333770 -0.097738 -0.4333542 -0.2866583 0.3690199 0.7706202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2357 2457 0.180825 -0.367899 0.344263 0.7056545 -0.1489144 -0.5718822 0.3909309 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2358 2458 -0.321847 -0.194896 0.055577 -0.6991393 -0.1925600 -0.6783941 0.1179253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2359 2459 0.053669 -0.519513 -0.198894 -0.0052539 0.3379820 0.4177769 0.8433285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2360 2460 0.310973 0.489773 -0.007868 -0.5599243 0.2328319 -0.5806125 0.5432892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2361 2461 -0.446691 0.310539 0.249913 0.1439232 0.0880378 0.0386576 0.9849066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2362 2462 0.285633 0.052451 0.351792 0.3277177 0.0268460 0.7117193 0.6207544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2363 2463 0.206723 -0.578838 -0.051851 -0.4079503 -0.4959560 0.7013458 0.3093836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2364 2464 0.253060 -0.099569 0.347023 -0.1502688 0.3311100 0.9201841 0.1450744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2365 2465 0.439123 0.059382 0.361800 0.6344312 0.5479913 -0.5040513 0.2076891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2366 2466 0.417020 0.360954 0.160323 0.4580331 -0.6221854 0.0350445 0.6339266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2368 2468 -0.397668 0.176414 -0.235886 -0.4897070 0.2025013 -0.2061022 0.8226191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2369 2469 0.318742 -0.387670 -0.429500 0.8396755 0.3231953 -0.4349351 0.0363500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2370 2470 -0.489333 0.090688 -0.611346 0.3425832 -0.0366466 -0.9387457 0.0070982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2371 2471 -0.039753 0.480941 0.542074 -0.9365237 0.1965638 0.2762244 0.0893652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2372 2472 0.215605 -0.695758 -0.005239 0.5021276 -0.4572636 0.3834595 0.6258888 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2373 2473 0.381660 -0.193576 -0.617827 -0.3511110 0.6594718 0.0693459 0.6610667 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2374 2474 0.630384 -0.100995 0.066958 0.1773079 -0.3812986 0.6623452 0.6200582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2375 2475 -0.287469 0.485009 0.389374 0.9203627 -0.2982705 -0.2496051 0.0407979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2376 2476 0.334530 0.218472 0.357393 -0.5491130 0.0663662 -0.8065079 0.2088430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2377 2477 -0.568070 -0.198141 -0.285658 0.3746302 -0.8677593 0.2100679 0.2500349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2378 2478 0.241366 -0.439359 -0.038948 0.2753150 0.2901363 0.8000101 0.4472208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2379 2479 -0.078766 -0.267510 -0.529067 0.4190294 0.0987796 0.2803865 0.8579279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2380 2480 0.634452 -0.486234 -0.030012 -0.9240173 -0.1806296 -0.3349533 0.0370310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2381 2481 -0.429638 0.755467 -0.134584 -0.2210002 -0.4477585 -0.8566657 0.1295957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2382 2482 0.658932 0.129305 0.351178 -0.1560613 0.3983389 0.7427669 0.5150420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2383 2483 -0.094916 0.733515 0.234185 0.2598415 -0.3927206 -0.1557448 0.8683297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2384 2484 -0.465978 0.297869 0.572904 0.7355443 0.2203086 -0.4424287 0.4633525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2385 2485 0.742975 -0.103477 0.149694 0.4146386 0.3343488 -0.6955313 0.4822052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2386 2486 0.039858 -0.099719 0.691173 -0.2424923 -0.6600189 0.2197682 0.6762207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2387 2487 -0.418167 -0.096080 -0.489085 0.3003001 -0.3985004 0.8557531 0.1367625 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2388 2488 0.256190 0.680769 -0.176649 -0.3702310 -0.6402575 -0.5881845 0.3271672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2389 2489 -0.364587 0.321860 0.099164 -0.4792931 0.0213671 0.1356125 0.8668511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2390 2490 0.402356 -0.116796 -0.603790 0.7224881 0.3215266 -0.4355055 0.4300773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2391 2491 -0.493213 0.027830 -0.689746 -0.5421256 -0.7637999 -0.2707219 0.2223046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2394 2494 -0.277834 0.697668 0.248653 0.5600681 0.2378370 -0.2644783 0.7482035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2395 2495 0.067086 0.316345 0.861435 0.4059353 0.1525066 0.6101206 0.6631071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2396 2496 0.221523 0.381143 -0.329600 0.3254736 0.1278747 0.2876864 0.8916006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2397 2497 0.696499 0.083019 0.007388 0.1860665 -0.2070735 0.8850749 0.3730178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2398 2498 0.408446 -0.555761 -0.277009 0.5981255 -0.3142560 -0.6243691 0.3919851 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2399 2499 -0.367849 0.853652 0.088042 -0.5480880 0.5252467 0.3843638 0.5253380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2400 2500 0.495697 0.445836 -0.176059 0.5234807 -0.7264352 -0.2577098 0.3631053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2401 2501 0.092203 -0.549268 -0.386801 0.6708264 0.0751350 -0.1000200 0.7309874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2403 2503 -0.115935 -0.782031 -0.230090 0.1662251 0.3031896 -0.6690268 0.6579121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2404 2504 -0.523634 -0.319355 0.388039 0.4844525 0.2086510 0.5694840 0.6304432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2405 2505 -0.454885 -0.396606 -0.679891 0.6181851 -0.2290962 0.2912607 0.6932022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2406 2506 -0.651246 0.103342 0.371363 0.4192218 -0.0781853 -0.8377509 0.3410477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2408 2508 -0.622136 -0.661755 0.019752 -0.2210391 0.1041973 0.8630060 0.4421597 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2409 2509 -0.432257 0.045733 0.787361 -0.5074979 0.7433540 -0.4336119 0.0430273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2411 2511 -0.159727 0.621806 0.136600 -0.0166199 -0.9023095 0.1792748 0.3916912 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2412 2512 0.325968 0.618230 0.164214 0.4469141 -0.2864113 -0.6086837 0.5896953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2413 2513 0.179827 0.441289 -0.367982 -0.0037512 0.4294478 -0.0003143 0.9030838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2414 2514 0.110455 0.626402 0.292967 0.5786875 0.4558974 -0.5360791 0.4121864 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2415 2515 0.487530 0.489599 -0.021995 -0.1078363 -0.0824176 -0.6286810 0.7657277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2416 2516 0.136882 0.262579 -0.770851 -0.3311782 -0.2993562 0.6737685 0.5888488 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2417 2517 -0.239150 -0.601741 0.102207 0.0711872 -0.5824202 0.7253920 0.3598966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2418 2518 0.035348 0.635778 -0.458199 0.2539257 -0.1142991 0.4394982 0.8539899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2420 2520 -0.349927 0.125281 0.440714 0.2571475 -0.5739389 0.2834399 0.7239690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2421 2521 -0.281493 -0.376239 -0.445281 0.1119011 -0.2241086 -0.4461341 0.8591960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2422 2522 0.364334 -0.041579 0.394137 0.2535533 -0.6592148 -0.5696525 0.4202886 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2423 2523 0.227036 0.599174 -0.039232 -0.5564633 0.5649070 -0.2692864 0.5465468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2425 2525 -0.572196 0.413765 0.057614 0.4777611 -0.7828447 0.3027288 0.2593334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2426 2526 -0.257495 0.165778 0.586355 -0.4649774 -0.4316158 -0.4752077 0.6096569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2427 2527 -0.285136 0.027218 0.210108 -0.0591111 0.0630803 -0.9587024 0.2709548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2429 2529 0.390240 -0.630931 -0.106937 0.1431702 0.5948223 -0.2388892 0.7540694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2430 2530 -0.173371 0.383594 0.275431 -0.1054435 -0.2026899 -0.4975045 0.8368320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2431 2531 0.035550 0.607160 0.101380 0.6492634 -0.0558751 0.2788751 0.7053819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2432 2532 -0.404376 0.495688 -0.125653 -0.6187296 -0.0085327 -0.5997820 0.5073091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2433 2533 -0.450660 0.197661 -0.229456 -0.6955030 0.1937101 0.6853833 0.0948773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2434 2534 -0.322473 0.559832 -0.118887 0.3780346 -0.0093833 0.4671056 0.7992585 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2435 2535 -0.272947 0.423565 0.335808 0.4641976 0.4150731 -0.3425476 0.7034884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2437 2537 -0.481585 -0.252770 0.205974 0.1560952 0.3741240 0.8290819 0.3850827 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2438 2538 -0.221652 0.283959 0.008465 -0.2555590 0.1057555 -0.8342621 0.4769822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2439 2539 0.057022 -0.102672 -0.584134 -0.4462294 -0.4788072 0.7560424 0.0047835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2440 2540 -0.047189 0.398725 0.324018 0.2008045 -0.1735846 0.5862032 0.7654487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2442 2542 0.504381 -0.025230 -0.349089 -0.0581977 -0.1491218 0.2361638 0.9584375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2443 2543 -0.244601 0.151316 -0.186118 0.3412746 -0.4073532 -0.8240203 0.1964322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2444 2544 -0.291190 -0.017013 0.357385 0.4300661 -0.0936592 0.8689632 0.2262169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2445 2545 0.239295 0.254045 -0.083977 0.1702968 -0.6473642 0.0002988 0.7429122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2447 2547 0.356395 -0.042192 -0.343771 -0.2042731 0.6107977 0.4760818 0.5987861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2448 2548 0.497014 0.294486 0.056574 0.3050475 -0.7093203 -0.6022903 0.2026257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2449 2549 -0.567275 0.154329 -0.031377 -0.6899217 -0.0674705 0.2470043 0.6770854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2450 2550 0.434278 0.188671 -0.199738 -0.2629685 0.4348750 0.2138696 0.8342608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2451 2551 -0.735221 -0.197792 0.203089 0.2703754 0.2222832 0.1123651 0.9299793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2452 2552 0.343310 0.344917 -0.397209 0.6990069 0.2792926 -0.2691335 0.6007929 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2455 2555 -0.450009 -0.394905 -0.010639 0.2797165 -0.8245506 0.4172700 0.2603091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2456 2556 -0.472610 0.115390 -0.005784 -0.1117552 -0.2918451 -0.5562187 0.7700377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2457 2557 0.263168 0.460785 -0.227389 0.2800933 0.3056776 0.7081229 0.5715513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2459 2559 -0.333950 -0.442459 -0.293297 0.0939611 -0.0492316 -0.8280642 0.5505063 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2460 2560 -0.316840 -0.275565 0.568248 -0.3525018 0.1582172 0.1339447 0.9125616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2461 2561 -0.464276 0.350255 -0.022813 -0.2675677 0.4251760 0.8328009 0.2325415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2462 2562 0.054116 -0.406625 0.339241 -0.2464716 0.1541898 0.6914883 0.6613027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2463 2563 -0.613332 0.284534 -0.139818 -0.3458280 0.1841924 -0.4837594 0.7825938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2464 2564 -0.525990 0.336750 0.175825 -0.6268193 -0.0766630 0.0298009 0.7748111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2465 2565 -0.342919 0.289102 -0.462442 0.5140109 -0.4706779 0.0351849 0.7162521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2466 2566 0.064149 0.063209 -0.740204 -0.1283511 0.7260670 0.3565320 0.5737924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2467 2567 -0.169565 -0.487102 -0.344612 0.1681333 0.2350838 -0.1266085 0.9489136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2468 2568 -0.528653 0.259762 -0.237155 -0.2287926 -0.3068838 -0.3635339 0.8493052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2469 2569 0.122594 0.556888 0.228151 0.1963415 -0.1622057 -0.9065645 0.3365713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2471 2571 -0.539717 -0.383002 -0.220839 -0.7877994 0.0131757 -0.0287104 0.6151213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2473 2573 0.502384 -0.215491 0.130612 -0.0910165 -0.8670489 -0.2311181 0.4318872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2475 2575 -0.485642 -0.292506 -0.241374 -0.1919738 -0.3372699 0.4424515 0.8084750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2476 2576 0.091531 -0.028507 0.633040 0.0847456 0.4694867 0.8714577 0.1138505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2477 2577 0.207020 0.365657 0.410004 0.3750478 0.4031656 0.6071465 0.5728611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2478 2578 -0.794349 0.032102 -0.240307 -0.5684728 0.0018901 0.5072187 0.6477378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2479 2579 -0.411285 -0.625005 -0.275019 0.1109310 0.0953610 -0.5047289 0.8507933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2480 2580 0.220226 0.520211 0.488032 0.4642381 -0.1518246 0.0339612 0.8719397 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2481 2581 0.246361 -0.647384 0.262376 -0.0062014 0.2401172 -0.9659226 0.0964306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2482 2582 -0.249464 -0.511962 0.201915 -0.1200624 0.0330598 0.9699981 0.2087960 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2484 2584 -0.579978 -0.315791 -0.177260 -0.8498560 0.2388505 -0.0530379 0.4667786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2485 2585 -0.179428 0.626011 -0.287275 0.1804745 -0.6574037 -0.2999348 0.6672994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2486 2586 0.503058 -0.688031 0.070483 0.2283360 0.5091514 0.4238443 0.7134308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2487 2587 -0.140347 0.557452 -0.343325 0.3754446 0.2083343 0.7345246 0.5254634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2488 2588 -0.335541 0.110686 0.555229 -0.3887103 0.7598384 -0.3886964 0.3470808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2489 2589 -0.459409 0.464831 0.182924 0.3987191 0.2884451 -0.2077304 0.8453819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2490 2590 0.660285 0.311025 -0.120037 -0.6073227 -0.5064043 0.5159553 0.3293994 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2493 2593 -0.237891 0.844915 0.324136 0.5950872 0.2607676 -0.7342854 0.1967140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2494 2594 -0.408658 0.211942 -0.719994 -0.2590759 0.0609034 -0.6934556 0.6695445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2495 2595 0.280463 0.427371 0.263206 -0.2030708 -0.6841409 0.2896739 0.6378107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2497 2597 -0.271460 -0.677377 -0.116710 0.1419540 0.1051371 0.1996171 0.9638196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2498 2598 0.642537 0.014366 -0.421142 -0.5454786 0.3568709 -0.1852763 0.7353699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2499 2599 -0.142408 0.293197 0.506805 -0.0365652 0.3377083 -0.9378229 0.0714441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2500 2600 -0.551648 -0.109713 -0.056476 0.0560262 0.2753936 0.6868936 0.6702213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2501 2601 0.466283 -0.503352 0.453684 0.3215125 -0.3087991 -0.1093711 0.8884316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2502 2602 0.557851 0.404567 0.478934 0.4170733 -0.5665480 -0.4108630 0.5798835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2504 2604 -0.297436 0.533866 -0.315145 0.0652227 -0.8301276 -0.3260783 0.4475568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2505 2605 -0.764881 -0.203241 0.276106 0.0844309 0.2037093 -0.6390648 0.7368651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2506 2606 0.138334 -0.351216 0.455270 -0.1241957 0.4771462 0.5907578 0.6386800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2507 2607 -0.586594 -0.619400 -0.126992 -0.1447478 -0.1417089 -0.6434822 0.7381716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2508 2608 -0.267030 0.649353 -0.234453 -0.5039802 -0.5360705 0.5993427 0.3153105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2509 2609 0.591266 0.041593 -0.374949 0.5481276 0.0494420 -0.3135346 0.7738266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2511 2611 0.274107 0.590624 -0.055698 0.7010531 -0.2541026 0.6568786 0.1116554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2512 2612 -0.675867 0.317813 -0.250741 0.1648668 -0.5623565 -0.8099775 0.0225938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2513 2613 0.372678 0.519814 -0.098307 0.0014265 -0.2406750 -0.7326346 0.6366475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2515 2615 -0.142906 0.723483 0.075287 -0.3230678 -0.2997467 -0.2267932 0.8685298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2516 2616 -0.027102 0.494886 -0.571592 0.5885503 -0.2754268 0.6548234 0.3859469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2517 2617 -0.256114 0.015186 0.899708 0.2204006 0.1383184 -0.9437321 0.2041111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2518 2618 0.044565 0.366581 -0.631412 -0.3105285 0.4150661 0.7295558 0.4461396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2519 2619 -0.402888 0.479797 -0.243714 -0.2441316 -0.2980948 0.1540801 0.9098344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2520 2620 0.530177 0.288663 0.386840 -0.4416281 0.2812584 -0.8471076 0.0909234 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2521 2621 0.136597 -0.559380 -0.385458 0.1805365 -0.1005269 0.3318945 0.9204059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2522 2622 -0.224256 0.556722 -0.370066 -0.7044997 -0.4313360 -0.4839609 0.2888101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2523 2623 -0.251617 0.043303 0.427303 -0.0272848 0.1847685 -0.9797113 0.0726773 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2524 2624 0.462750 0.052449 0.381952 -0.3880524 0.1197021 -0.5942719 0.6942101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2525 2625 -0.388249 0.612090 0.014240 -0.0198695 0.2194174 -0.5518213 0.8043348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2526 2626 0.490714 -0.227926 0.191531 -0.3985789 0.0312949 -0.9158242 0.0377024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2527 2627 0.413714 -0.340724 0.273392 -0.0531260 -0.3028692 0.5893477 0.7470724 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2528 2628 -0.526154 0.112117 0.342147 0.1049128 0.0422059 -0.9789366 0.1699857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2529 2629 0.223648 -0.279506 0.427828 -0.1292447 0.0149365 0.4331398 0.8918871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2530 2630 -0.312390 0.010851 0.591481 0.2498582 0.1712830 0.1461133 0.9417451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2531 2631 0.255473 0.050673 -0.589538 0.0654756 0.9337439 -0.0789856 0.3429236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2532 2632 -0.568418 -0.111649 -0.137022 0.4313713 0.3274056 0.5647491 0.6227221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2533 2633 0.321767 -0.082133 0.610538 0.2291780 -0.0241329 -0.8256891 0.5149103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2534 2634 0.240774 0.204367 -0.518233 0.1679285 0.3649746 -0.6684931 0.6258679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2535 2635 -0.234759 0.036245 -0.480510 -0.2338741 0.5493224 0.7611301 0.2534340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2536 2636 -0.087239 -0.345355 -0.375019 0.2204033 -0.8041347 0.3773877 0.4029495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2537 2637 0.161066 0.652876 -0.181342 -0.3192869 0.0656526 -0.9294626 0.1727565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2538 2638 -0.029885 -0.370323 -0.142161 -0.0269323 0.2229538 -0.3014313 0.9266636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2539 2639 0.431020 0.591935 0.038353 -0.4676067 -0.0111594 0.2740832 0.8402963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2540 2640 0.420494 -0.015894 -0.065621 0.0987472 -0.4671459 0.5310743 0.6999884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2541 2641 0.458140 0.401622 0.221486 -0.4468333 -0.0679425 0.8891970 0.0710813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2542 2642 0.216926 -0.063867 -0.144197 0.6037204 0.2913632 -0.7246061 0.1599225 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2543 2643 0.400599 -0.266661 0.155736 -0.7951376 0.5172520 0.2876977 0.1320476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2545 2645 0.169597 0.388879 -0.405494 0.3847835 -0.1838656 -0.4502603 0.7844748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2546 2646 -0.362668 -0.131972 0.390842 0.4071079 -0.0550396 0.8907711 0.1943207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2548 2648 -0.640402 -0.161393 -0.025039 -0.0939018 -0.0903388 0.9113667 0.3904256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2549 2649 -0.226102 0.016944 0.374712 -0.3421330 -0.0508815 -0.6543310 0.6724634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2552 2652 0.402331 -0.149464 -0.367530 0.2863611 -0.1161814 0.8009570 0.5128032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2553 2653 0.656085 0.106719 -0.088770 0.5559690 -0.4929111 0.3034694 0.5965262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2555 2655 -0.126559 0.530508 0.418031 0.2525857 0.3194599 0.1565399 0.8998006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2557 2657 0.476323 -0.318448 0.015407 0.0229745 0.1174128 -0.2828529 0.9516725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2558 2658 -0.285289 -0.262785 0.440319 -0.1861705 0.2608546 -0.9067362 0.2740891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2559 2659 0.426941 0.187559 -0.389935 0.5607990 -0.1869771 0.5501709 0.5897933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2560 2660 -0.368664 -0.220329 0.099459 -0.5816433 0.5512391 -0.2641361 0.5367110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2561 2661 0.027205 0.180409 0.443284 0.3339588 -0.5441576 0.5808574 0.5049443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2562 2662 -0.259276 -0.374514 0.377152 0.4399623 0.1419435 0.8848955 0.0569671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2563 2663 -0.327745 -0.312889 -0.470250 0.7246860 -0.4705306 0.2320955 0.4467246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2564 2664 -0.278342 -0.223975 0.202798 -0.1182091 -0.1099339 -0.7333679 0.6603883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2565 2665 -0.582928 -0.207538 -0.066433 0.2934432 -0.3692757 0.5346754 0.7011767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2566 2666 0.497513 -0.071926 0.164396 -0.4140358 0.1434087 -0.0550499 0.8972056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2567 2667 0.206214 -0.341431 -0.129875 -0.3294141 -0.2218166 -0.3521201 0.8475230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2568 2668 -0.759170 -0.248814 0.047310 -0.4655531 0.5920800 -0.3053208 0.5826498 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2570 2670 -0.663678 0.257149 -0.161007 -0.3914140 0.3182633 -0.7681969 0.3941789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2571 2671 -0.658414 0.280991 -0.393084 -0.0704160 -0.4459870 -0.8852833 0.1114030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2572 2672 0.371028 0.341962 -0.240593 -0.0139663 0.1586932 -0.4444110 0.8815443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2573 2673 -0.233544 0.381680 -0.345336 0.4380741 0.7555116 0.1218870 0.4716321 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2574 2674 -0.324174 0.041654 -0.535231 0.1817326 0.0618709 -0.7639810 0.6160181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2575 2675 -0.490285 0.237591 0.308332 -0.6648443 -0.1545693 0.0022161 0.7308115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2576 2676 -0.187202 0.421910 0.095211 0.0226048 0.1451118 -0.7808987 0.6071481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2577 2677 0.320975 0.523408 0.447240 -0.5257914 -0.7842333 0.3022904 0.1309275 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2578 2678 -0.256718 0.334763 0.392031 -0.1073614 -0.4373340 0.8744010 0.1806530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2580 2680 0.169964 0.522173 -0.093924 0.1124479 -0.0015037 0.9013851 0.4181603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2582 2682 -0.140458 0.495395 0.416383 -0.4293080 -0.1506141 0.8459838 0.2780673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2584 2684 -0.420413 0.391067 -0.262326 -0.1191431 -0.4319221 0.6319087 0.6324078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2585 2685 -0.636629 0.315440 0.255086 -0.4885318 0.2755298 -0.3761434 0.7375203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2586 2686 -0.475808 -0.755498 0.527483 -0.1783476 0.0785418 -0.8230581 0.5334779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2587 2687 0.627883 -0.467667 -0.413035 -0.2615112 0.7226902 -0.4554012 0.4493779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2590 2690 0.162806 0.046209 -0.726969 0.4469118 0.5574570 0.1871030 0.6741691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2591 2691 0.405852 0.276391 -0.570744 -0.3181791 -0.5019894 -0.5363676 0.5992317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2592 2692 0.544525 0.376688 -0.252010 -0.9137916 0.2398943 -0.3181307 0.0789211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2594 2694 -0.193010 -0.157017 -0.819162 0.7532230 0.3364613 -0.5615337 0.0642557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2596 2696 -0.295734 -0.415762 -0.539161 -0.6725146 -0.0504780 0.6768652 0.2950076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2599 2699 0.302894 -0.657106 0.194251 -0.0756857 0.0269790 0.5754901 0.8138519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2600 2700 -0.254016 0.278048 -0.501103 0.1379207 0.3229439 -0.0870062 0.9322634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2601 2701 0.779393 -0.185337 0.176015 0.0764840 0.0045585 0.6089174 0.7895245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2602 2702 -0.547413 0.457165 -0.493884 -0.5165801 0.4370401 0.6231959 0.3921325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2603 2703 -0.478568 0.111108 -0.610408 0.0439836 0.1895572 -0.8836784 0.4257301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2605 2705 -0.081668 -0.587259 0.439914 -0.1967378 0.1644654 0.2644826 0.9296743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2606 2706 -0.978808 -0.074159 0.124577 -0.3554807 -0.3200626 -0.4891899 0.7293056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2607 2707 0.457953 -0.432788 -0.385285 0.1577138 -0.2055398 0.7112648 0.6534387 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2608 2708 0.644257 -0.013502 0.146700 -0.3876074 0.5235032 -0.7555067 0.0701033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2609 2709 0.599084 -0.031003 -0.634125 0.5317251 -0.3458769 0.7706916 0.0605982 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2610 2710 -0.218543 0.472522 -0.620928 -0.4351295 -0.5812743 -0.0535236 0.6855054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2611 2711 -0.060681 -0.801293 0.111319 -0.4708617 -0.0250078 0.6926737 0.5457719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2612 2712 0.657105 -0.162140 0.134817 0.2955534 -0.3506337 -0.8842935 0.0879162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2613 2713 -0.695150 0.211433 0.042447 -0.4027933 -0.1472206 0.7877027 0.4422761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2615 2715 -0.432597 -0.057759 0.589588 0.4508407 0.6964188 0.4479711 0.3332646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2616 2716 -0.220308 -0.482547 -0.449830 0.2725900 0.7946161 0.0333854 0.5414475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2617 2717 -0.248242 -0.258262 0.549508 -0.2013242 -0.0878486 0.9465204 0.2363267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2618 2718 0.518158 -0.274060 -0.254582 0.1262138 0.2032654 0.6354621 0.7341261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2619 2719 -0.298466 0.417271 0.035486 -0.1305745 0.4633568 -0.6074160 0.6318993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2620 2720 0.015368 -0.544984 0.467997 -0.3347768 -0.1106655 -0.5700400 0.7421132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2621 2721 -0.119975 -0.463517 -0.186906 0.3081626 0.2594428 -0.2551293 0.8789962 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2622 2722 0.102437 -0.405176 0.594297 0.3821540 0.2020071 0.5390866 0.7228672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2624 2724 0.327185 0.316262 0.496974 0.2182372 0.4365012 -0.6623583 0.5684371 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2625 2725 -0.624981 -0.029102 -0.226742 -0.0996721 0.3586562 0.0391645 0.9273065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2626 2726 -0.150488 0.271053 0.327916 -0.2629541 -0.1865557 -0.8374197 0.4413392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2627 2727 -0.090996 -0.835545 0.158503 0.3652883 -0.3777332 0.4764937 0.7048658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2628 2728 0.228244 -0.117818 0.432629 0.1881381 -0.8459287 -0.4639701 0.1836856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2630 2730 -0.330683 0.314126 0.387609 -0.2149278 0.7830909 -0.0645734 0.5800043 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2631 2731 0.180602 0.340964 0.477473 0.8330273 -0.5191138 -0.1802213 0.0640833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2632 2732 -0.158082 -0.052344 -0.646625 -0.0718695 0.2186916 -0.9041092 0.3599934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2633 2733 -0.401928 0.376389 0.398120 0.3031527 -0.2568073 0.8461838 0.3551359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2634 2734 0.068777 0.367633 -0.552439 -0.1060737 -0.6748221 -0.4702389 0.5587834 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2635 2735 0.441238 0.004786 -0.116661 -0.5633460 0.5376560 -0.4176242 0.4681424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2636 2736 -0.015243 -0.061345 0.502659 0.3842487 0.1112982 -0.6528484 0.6432376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2637 2737 -0.192905 -0.543577 -0.103314 -0.2161758 0.1574672 -0.1281748 0.9550096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2638 2738 0.334498 -0.510130 0.158800 0.3062904 -0.2070041 -0.1605567 0.9151814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2639 2739 0.573710 -0.167330 0.119997 -0.5416758 0.4486561 0.6090047 0.3666175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2640 2740 0.215428 -0.375701 -0.111346 -0.0361577 -0.3213610 0.0441342 0.9452364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2641 2741 -0.262234 -0.484521 -0.255007 -0.4767446 0.1711708 0.7552034 0.4160323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2642 2742 0.033348 0.457704 -0.252347 -0.3628301 0.4883833 0.6007122 0.5186336 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2643 2743 0.008496 -0.173371 -0.246640 0.0266896 -0.8541743 0.5009998 0.1366495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2644 2744 -0.220439 -0.420642 -0.031225 0.5213248 -0.4803208 0.1721454 0.6840163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2645 2745 -0.388076 -0.035680 -0.327000 -0.7513972 -0.1948733 0.3390652 0.5314710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2646 2746 0.246353 0.146314 0.102001 0.1332831 0.3775672 0.9149732 0.0500270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2647 2747 -0.440565 -0.396345 0.112900 0.2435442 -0.3604984 -0.3735631 0.8192544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2648 2748 0.604851 0.439075 0.030708 0.2117519 0.3275136 0.8455850 0.3645298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2650 2750 -0.187780 -0.472933 0.473304 0.4096993 -0.5324029 -0.7406060 0.0140102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2651 2751 -0.381640 -0.225835 -0.336895 0.2285410 -0.1155804 -0.6020938 0.7562363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2652 2752 -0.424384 -0.372065 -0.288114 0.7144377 0.2126037 -0.4988905 0.4421388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2654 2754 -0.276903 0.252437 0.314257 -0.2339650 -0.2543460 -0.0159490 0.9382506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2655 2755 -0.215077 0.590682 0.221531 0.0179074 0.1007792 0.5556581 0.8250860 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2656 2756 0.140287 -0.017640 -0.521908 -0.0495293 0.3857222 -0.0386607 0.9204730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2657 2757 0.414558 0.112589 0.224014 0.0154235 0.0801642 -0.9511245 0.2978223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2659 2759 -0.098231 -0.580555 -0.001347 0.3229973 -0.2096623 -0.2344314 0.8926121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2660 2760 0.226452 0.010672 -0.575021 -0.2419042 0.9041522 0.0467376 0.3490081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2661 2761 0.450883 0.024761 -0.109858 0.0585088 -0.2183530 0.9338445 0.2771878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2662 2762 0.237122 0.442003 -0.026280 -0.6188567 0.1098674 -0.7636335 0.1476803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2663 2763 -0.416735 0.162294 0.349349 0.7410135 0.2895767 0.4077626 0.4480781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2664 2764 0.564539 -0.514910 0.060652 -0.0081956 -0.0482680 -0.7350279 0.6762670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2665 2765 -0.255015 0.443432 0.194748 -0.0710264 -0.2472211 0.8889645 0.3789182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2666 2766 0.349018 -0.137781 0.026879 -0.3270456 -0.5157552 -0.3738563 0.6980467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2668 2768 0.130037 -0.207366 -0.638138 -0.1203917 0.5515708 -0.3545689 0.7453565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2670 2770 -0.048975 -0.209174 -0.355936 -0.0994779 0.7211686 -0.5631205 0.3910439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2671 2771 0.206403 -0.532470 0.115654 -0.6689345 0.7261325 -0.1586402 0.0095715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2672 2772 -0.054050 0.509630 -0.346014 -0.4327434 -0.3476434 0.0454853 0.8305470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2673 2773 0.892186 0.091635 0.099220 0.6380142 0.2297015 0.7238067 0.1275892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2674 2774 0.564414 -0.143086 -0.332046 0.2724996 -0.4027569 -0.3587946 0.7967417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2676 2776 -0.333574 -0.533517 0.042765 -0.3268002 -0.3240381 -0.8654558 0.1979578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2677 2777 0.175326 0.130237 -0.630791 -0.3386958 0.3482079 -0.8387892 0.2459045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2678 2778 0.437588 -0.485147 0.172639 0.1504923 0.4375446 -0.3278523 0.8236623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2679 2779 0.310596 -0.205431 -0.089843 0.4824012 -0.0025300 -0.7987483 0.3595606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2680 2780 0.327611 -0.439992 -0.098645 -0.3659279 -0.5039087 -0.3414563 0.7039747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2681 2781 0.229120 0.508696 0.541237 0.7177580 0.3531374 -0.5871676 0.1239013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2682 2782 0.292146 -0.667052 0.336672 -0.0759553 0.0663828 -0.6930579 0.7137891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2683 2783 0.489553 0.344027 -0.482194 -0.2724594 0.5865023 -0.0633328 0.7601118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2684 2784 0.241123 0.627198 0.180800 0.2814507 0.5647446 -0.7268282 0.2712375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2685 2785 -0.527432 -0.356591 -0.180715 -0.3806766 -0.1602883 0.6773054 0.6088106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2686 2786 0.619418 -0.120633 0.217443 -0.4905214 -0.5359957 0.2990018 0.6186237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2687 2787 0.463218 0.296681 0.542854 0.2120926 0.4791152 -0.7904045 0.3173736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2688 2788 0.171087 0.558725 -0.051341 0.4267171 -0.4044739 -0.0520801 0.8072181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2689 2789 0.693351 0.468855 0.326109 0.0981028 0.0449466 -0.9938375 0.0253491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2690 2790 0.664835 -0.364700 0.172199 -0.3240308 -0.4398610 -0.6515882 0.5262691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2691 2791 -0.659062 0.380047 -0.055777 -0.6371635 0.2240353 0.6350654 0.3748637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2692 2792 0.179583 -0.313171 0.516872 0.3272707 -0.2219159 0.8689358 0.2976537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2693 2793 -0.529925 0.400291 0.413308 -0.1879155 -0.1157899 0.9033393 0.3677753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2695 2795 0.538557 -0.018063 -0.213707 0.5362340 0.4638805 -0.6547072 0.2619665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2696 2796 0.196747 0.635504 0.302479 0.5044464 0.1825264 -0.7702565 0.3448518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2697 2797 -0.433742 -0.336190 0.646866 -0.2411430 0.7441778 0.5846226 0.2150949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2699 2799 -0.377546 -0.701930 -0.044174 0.2791917 -0.2287095 0.7700696 0.5260577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2700 2800 0.056831 0.321353 -0.671466 -0.3745829 -0.2572087 0.0718131 0.8879044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2701 2801 0.283907 -0.812071 0.041352 -0.7333736 -0.4312222 -0.4847378 0.2030761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2703 2803 0.284832 -0.362194 -0.629475 0.1440272 0.3209281 -0.7310366 0.5846767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2704 2804 0.257241 -0.072965 -0.595706 -0.8575320 0.2261880 -0.4533050 0.0893999 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2705 2805 -0.354538 -0.651316 0.016416 0.1326615 -0.6233755 -0.5345870 0.5549961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2706 2806 -0.185917 -0.619928 -0.046611 -0.1152979 0.2378817 -0.4636585 0.8456592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2707 2807 -0.450788 -0.594761 -0.136962 0.2959550 -0.1102228 -0.7390317 0.5950577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2708 2808 -0.372536 -0.598450 0.488957 0.0316383 0.6933908 0.3553428 0.6260509 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2709 2809 -0.587687 0.048179 0.330672 0.3138921 0.7638132 -0.5096815 0.2414249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2711 2811 -0.503751 0.423180 -0.375022 0.0127221 -0.1459673 0.9556550 0.2554510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2712 2812 -0.624056 0.124063 -0.338250 -0.5930121 -0.1335170 0.7565179 0.2412272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2713 2813 0.278009 0.282701 0.413040 0.3919755 -0.0360334 -0.8853679 0.2473469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2714 2814 -0.456367 -0.612221 -0.065492 0.6309823 0.1048693 0.0617866 0.7661894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2715 2815 -0.005243 0.536108 -0.486295 -0.4735115 -0.2742781 0.3484207 0.7610266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2716 2816 0.349381 -0.569757 0.151724 -0.0994763 -0.4614871 0.1479475 0.8690487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2717 2817 -0.193833 0.107988 0.536431 -0.0918433 0.3399525 -0.6284913 0.6935386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2718 2818 -0.145450 -0.640267 0.084202 -0.1780237 -0.5589143 -0.7117871 0.3863697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2720 2820 0.466536 -0.363387 -0.213968 -0.0105560 0.0995412 0.5340508 0.8395057 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2721 2821 0.218446 -0.692649 0.265703 -0.0856234 0.3767807 -0.8968239 0.2154342 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2722 2822 -0.169625 0.434070 0.555936 -0.4141467 0.7858064 -0.2682026 0.3729051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2723 2823 -0.284514 -0.165411 0.546584 -0.2748063 -0.6437601 -0.6395097 0.3179337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2725 2825 -0.320090 0.108087 -0.522811 -0.8440550 0.1750643 0.2285654 0.4524175 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2726 2826 0.526189 -0.527606 0.270551 -0.0777790 0.8550607 0.5062152 0.0810416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2727 2827 -0.084403 -0.152065 0.642391 0.0088169 0.9081292 -0.3756325 0.1847264 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2728 2828 -0.162871 0.321139 -0.424360 -0.2792411 -0.1805561 0.4241226 0.8423443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2729 2829 0.521678 -0.108579 -0.234375 -0.4539747 -0.4891580 -0.4442644 0.5977128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2731 2831 -0.467215 -0.167719 -0.415670 -0.4909181 0.8155783 0.2779955 0.1286469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2733 2833 0.670441 0.074878 -0.170904 0.5492293 0.3659395 -0.1945659 0.7256580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2734 2834 -0.544759 -0.230347 0.460760 -0.6239974 0.4177105 -0.4183249 0.5110278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2735 2835 0.207246 -0.053920 0.545055 -0.5616785 -0.6406564 0.2613508 0.4536215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2736 2836 -0.490914 -0.071970 0.397266 0.6315342 -0.4629174 0.4901977 0.3828553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2737 2837 -0.047745 -0.374367 -0.337236 0.3969353 0.5991670 0.4411675 0.5374128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2738 2838 0.595998 -0.260811 0.085679 0.2139195 -0.7111986 -0.6202472 0.2524447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2739 2839 -0.200301 -0.281531 -0.209490 -0.4725523 -0.1690004 0.8641665 0.0367347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2741 2841 -0.027691 0.433481 -0.019554 0.1904014 -0.3500982 -0.0171740 0.9169971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2742 2842 0.290710 -0.199838 0.343394 -0.1927827 -0.3899732 0.8713791 0.2268352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2743 2843 -0.371807 0.026988 0.352807 -0.6500522 0.2981946 -0.6933749 0.0879964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2744 2844 0.031025 -0.291482 0.412589 -0.0202547 -0.3793176 -0.8978066 0.2228256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2746 2846 -0.331884 -0.249913 0.377250 -0.3665465 0.6671234 0.4079514 0.5041485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2748 2848 0.429639 -0.289696 0.397390 -0.1048484 -0.2680551 0.3742309 0.8815353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2750 2850 0.066041 0.244424 0.000625 -0.0097722 0.4409909 -0.8743936 0.2021568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2752 2852 0.190100 -0.171926 0.478680 0.4207445 0.7856376 0.1922058 0.4108584 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2753 2853 0.368088 0.303082 0.352047 0.4088399 -0.3987557 0.7314077 0.3726749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2754 2854 -0.004322 0.127370 0.497896 0.2621097 -0.0325739 0.4373870 0.8596104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2755 2855 0.463395 0.318866 0.219479 0.1086873 -0.6021939 0.4560024 0.6462286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2756 2856 0.475412 -0.118803 -0.224711 0.8016181 0.5050415 -0.0674810 0.3127105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2757 2857 -0.395768 0.153280 -0.081807 0.6263582 0.2423228 0.4042147 0.6209392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2761 2861 -0.560704 -0.013769 -0.028291 0.8966870 0.2089091 -0.2178335 0.3238179 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2763 2863 0.043100 0.387805 -0.705931 -0.6079114 -0.0214405 -0.6650282 0.4332683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2766 2866 0.370419 0.336435 -0.196575 -0.5444307 0.2103562 -0.8118673 0.0147279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2768 2868 0.628650 0.300383 -0.255624 0.8136733 0.3329337 -0.3492045 0.3242641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2769 2869 0.441651 0.113496 -0.474864 0.7167569 0.1787234 0.4821256 0.4710334 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2771 2871 0.349161 -0.132929 0.071825 0.7639368 0.0488823 -0.3308602 0.5518538 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2772 2872 0.085874 0.508770 0.294414 0.5726806 -0.0110300 -0.5601485 0.5984555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2773 2873 -0.121996 -0.203688 0.584878 0.4936136 0.2316295 0.5972309 0.5882250 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2774 2874 0.245452 -0.276137 -0.516372 0.1056861 -0.1661832 -0.7091745 0.6769676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2775 2875 -0.413165 -0.175120 0.433986 -0.0956384 -0.1830532 -0.9353778 0.2870771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2776 2876 0.233428 0.016014 -0.525685 -0.7279553 0.2474451 0.2604026 0.5839884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2777 2877 -0.552753 0.408789 -0.060968 -0.3332237 -0.7881616 -0.3916403 0.3382027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2778 2878 0.073667 0.026521 0.620997 0.6428775 -0.0062623 -0.4564860 0.6150528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2779 2879 0.179756 0.431069 -0.536419 -0.4506065 -0.0131435 -0.8755918 0.1735510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2780 2880 0.076694 0.038048 -0.664748 0.1698156 -0.0517601 0.9275992 0.3286995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2781 2881 -0.405545 -0.404574 -0.671658 -0.3383233 -0.1060369 0.7427733 0.5679624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2782 2882 0.504758 0.080646 0.584063 -0.2717380 -0.4917765 0.4373865 0.7021448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2783 2883 0.276367 0.422002 0.401545 0.0959127 -0.5841317 0.1174818 0.7973638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2784 2884 -0.089319 -0.078552 -0.609535 -0.0486389 -0.2836531 0.2809914 0.9155430 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2785 2885 -0.314517 0.487998 0.100898 0.1762519 -0.6484256 0.1132772 0.7318796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2786 2886 0.322489 -0.032287 -0.698369 0.8461092 0.5074142 -0.0682233 0.1482421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2787 2887 -0.605067 -0.321205 -0.212359 -0.1887056 0.4858857 -0.3563124 0.7754655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2789 2889 -0.699264 -0.281430 0.212258 0.0904558 0.1820821 -0.3751605 0.9043884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2790 2890 0.083996 0.571569 -0.299777 -0.2670479 0.3612734 0.3972361 0.8002315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2791 2891 0.038627 0.231005 0.792062 0.7033976 -0.5267990 0.1253918 0.4604253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2792 2892 -0.030798 0.116624 0.693727 0.4331471 -0.5765417 0.5537268 0.4163771 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2793 2893 0.465560 0.310170 0.601149 0.1477884 0.1268501 0.9414461 0.2752215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2794 2894 0.455606 0.601556 -0.173035 -0.5194153 0.3382539 -0.7525252 0.2224813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2796 2896 -0.518548 -0.242047 -0.355521 -0.2286436 0.1833780 0.4606903 0.8377703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2797 2897 -0.062405 0.437733 -0.365096 0.4353466 -0.4837828 -0.5594226 0.5132970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2798 2898 -0.327658 0.320233 0.545127 0.0311496 0.4499671 0.3745701 0.8100966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2799 2899 -0.531135 0.535891 0.331220 -0.2028830 -0.0018873 -0.8411502 0.5012996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2800 2900 -0.178491 0.806692 0.071226 0.4283021 0.4466443 -0.4738823 0.6264996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2801 2901 -0.222880 0.556714 -0.592496 -0.1448634 0.4216468 -0.6405670 0.6252220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2802 2902 0.253902 0.455898 -0.764379 0.0768191 -0.0081218 -0.9222192 0.3788728 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2803 2903 0.489386 0.588207 -0.300935 0.1371400 0.5290511 -0.8338703 0.0771881 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2804 2904 -0.373982 0.433164 0.623036 -0.6436148 0.0757805 0.3067208 0.6970937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2805 2905 0.837093 -0.147823 -0.044680 -0.0942398 -0.2560074 -0.8638807 0.4234256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2806 2906 0.418958 -0.478440 -0.022504 -0.0715732 0.5003623 0.4035736 0.7626553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2808 2908 -0.461693 0.078441 -0.375528 0.2937084 -0.2156086 0.6945108 0.6204056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2809 2909 0.373744 -0.705698 -0.158557 0.6426262 0.3435416 -0.5159249 0.4503691 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2810 2910 -0.037322 0.412395 -0.022495 -0.0437631 0.6541711 0.1667808 0.7364300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2811 2911 0.623270 0.245139 -0.331731 -0.4478944 0.7482887 0.4878977 0.0375555 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2812 2912 0.470317 0.306661 0.436421 0.7772085 -0.0653914 -0.2802182 0.5595969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2813 2913 -0.607947 0.034848 -0.020212 -0.3954019 -0.5217792 -0.0018117 0.7559104 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2814 2914 -0.449550 -0.358016 0.481841 0.2513928 0.0491359 -0.9277295 0.2714870 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2816 2916 0.207884 -0.396650 -0.269908 0.0296398 -0.4892936 -0.6587372 0.5707701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2817 2917 -0.209455 -0.653187 0.202341 -0.1933649 0.4239462 -0.2986602 0.8328756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2818 2918 0.486818 0.221927 -0.340730 0.2066943 0.6238383 0.0957591 0.7476185 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2820 2920 0.047980 -0.531195 -0.227860 0.3700564 0.2402051 0.7961648 0.4141030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2821 2921 -0.031675 0.291732 0.226625 0.0046839 0.2179709 -0.7142932 0.6650202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2822 2922 -0.208304 -0.136504 -0.642164 0.0958105 -0.3451102 -0.4453958 0.8205742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2823 2923 0.590842 0.189421 -0.216269 0.2230768 -0.5908808 0.6719543 0.3867480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2824 2924 0.334040 -0.533404 0.432528 -0.2764458 -0.2260040 -0.2721549 0.8935500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2825 2925 -0.061347 0.623923 0.347836 0.2717296 -0.7711714 -0.3480907 0.4585745 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2826 2926 -0.429666 0.028935 -0.519442 0.1286976 -0.7953710 -0.2107168 0.5535524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2827 2927 0.070889 -0.614104 -0.375328 -0.0385986 -0.6841391 -0.4364788 0.5830524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2828 2928 -0.015991 0.492366 -0.070473 -0.0418753 0.0499615 -0.5036546 0.8614420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2829 2929 0.052325 0.504278 -0.171590 -0.3566181 0.2654432 -0.0728483 0.8927803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2830 2930 -0.401676 -0.071873 -0.206141 -0.2528384 -0.0089685 0.4037951 0.8791711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2831 2931 0.534902 0.003159 0.231549 -0.4630037 0.7647073 -0.0313349 0.4470665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2832 2932 0.548995 0.196737 0.366575 -0.3560299 -0.7626759 -0.0758143 0.5346217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2833 2933 0.574992 0.364264 -0.052865 -0.7110568 0.0249640 0.5313799 0.4597938 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2834 2934 -0.023000 -0.387336 -0.491375 0.3772923 0.8858016 -0.2241960 0.1508054 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2835 2935 0.386416 -0.592317 -0.335765 0.0431987 -0.3556579 -0.2973364 0.8850042 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2836 2936 0.156070 0.255038 -0.176196 0.2373943 0.4657536 -0.7193129 0.4575002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2837 2937 -0.261616 -0.637257 0.093236 -0.4776144 0.0314763 -0.4116419 0.7755286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2838 2938 -0.158518 0.256911 -0.450518 -0.6144149 0.5466490 -0.1054266 0.5590657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2841 2941 -0.405764 0.496961 -0.412112 -0.0044449 -0.0863380 -0.6003161 0.7950764 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2843 2943 0.327013 -0.065822 -0.499653 0.1354836 0.0434064 0.8662009 0.4790157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2844 2944 0.276390 0.457268 0.064400 -0.0432871 -0.3556557 0.9195512 0.1614340 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2845 2945 -0.181592 -0.078181 -0.366543 0.2743652 0.3479917 0.8942756 0.0624227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2846 2946 -0.291276 0.284197 -0.465736 0.1255430 0.2204952 -0.7248415 0.6404885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2847 2947 -0.359373 0.349887 -0.088064 0.7904090 -0.1619259 -0.0229287 0.5903456 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2849 2949 0.663805 -0.029474 0.122065 0.6156423 0.4846968 -0.2633252 0.5627730 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2850 2950 -0.119252 -0.223771 -0.521092 -0.6945296 -0.4356559 0.5331021 0.2088893 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2851 2951 -0.183554 0.219533 -0.336029 -0.0301828 -0.4635259 -0.5225556 0.7149604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2852 2952 -0.375168 0.375443 0.005790 -0.0274475 -0.1448191 -0.9804358 0.1304593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2854 2954 0.195001 0.452250 0.418895 0.2146421 -0.5210328 -0.7921956 0.2342641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2855 2955 0.218524 -0.063688 -0.528492 -0.0195532 0.1559781 -0.7144073 0.6818436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2856 2956 0.233646 0.411048 0.206703 0.1831530 -0.3118990 -0.2340085 0.9024489 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2857 2957 -0.012717 0.090634 -0.633633 -0.7406724 0.0968710 0.5071794 0.4298714 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2858 2958 0.480266 -0.003143 -0.458187 -0.0113143 0.2842056 -0.0563412 0.9570396 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2860 2960 0.124323 -0.102897 -0.554041 -0.0945696 -0.5031297 0.6994249 0.4987203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2861 2961 -0.263728 -0.398106 0.303234 -0.1826997 -0.3634626 -0.5882688 0.6988959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2862 2962 -0.155054 -0.551832 0.107283 0.4893499 -0.6925460 0.5298576 0.0129476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2863 2963 -0.485662 0.048844 0.228796 0.4878663 -0.6458465 0.5871734 0.0098038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2864 2964 0.378782 0.286803 0.299295 -0.8241182 -0.0959684 -0.0382037 0.5569199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2866 2966 -0.263374 -0.563166 0.196979 0.2424252 -0.6219123 -0.3088284 0.6775545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2867 2967 0.057179 -0.543024 -0.065278 -0.0199589 -0.0854985 -0.1013211 0.9909721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2868 2968 0.422733 0.050030 -0.490934 0.1889395 -0.6319355 -0.7255715 0.1962281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2869 2969 0.099964 -0.384427 0.254422 -0.1457332 0.3805960 0.7798682 0.4750939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2870 2970 -0.282622 -0.543697 -0.223167 0.1732267 0.0503896 -0.9770460 0.1132894 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2871 2971 0.085088 0.729565 -0.049386 -0.5698155 0.4319583 0.6985032 0.0285588 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2872 2972 -0.512859 -0.053210 -0.168026 0.1659373 -0.1108851 -0.8922118 0.4051265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2874 2974 0.150313 0.252003 -0.706956 -0.0494482 -0.7533779 -0.6526259 0.0636868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2876 2976 0.672013 0.187748 0.259142 -0.1066173 0.3480899 -0.5517578 0.7503529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2877 2977 0.285044 -0.038356 0.452093 0.1014617 0.3943398 0.8708452 0.2753729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2878 2978 -0.591426 0.549339 -0.077168 -0.3472586 -0.0114687 -0.9274142 0.1385021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2879 2979 -0.651906 -0.283669 -0.128311 0.7663029 0.3339462 -0.4427225 0.3244326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2880 2980 -0.244221 -0.256167 -0.606538 0.1422095 -0.4819525 -0.8425927 0.1937416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2881 2981 0.058231 0.580399 -0.255248 -0.0778602 0.2620299 -0.8787055 0.3913499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2882 2982 0.544371 -0.384598 -0.132179 0.0232369 0.2041177 -0.7378555 0.6429349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2883 2983 0.438351 0.461837 -0.346436 0.8655904 0.0424505 0.1478369 0.4765454 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2884 2984 -0.429729 -0.047522 -0.625239 0.4774913 -0.2729464 -0.0459856 0.8338991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2885 2985 0.174959 0.517447 0.064412 -0.3350523 0.1885374 -0.5973981 0.7037820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2886 2986 0.223006 0.378936 0.759210 0.1850125 -0.7160777 -0.5760644 0.3480702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2889 2989 -0.275050 -0.891262 0.234532 -0.1592783 0.5246384 -0.5162872 0.6579001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2890 2990 0.497250 0.543712 0.323431 0.5582106 -0.2840864 0.3292308 0.7066136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2891 2991 0.224615 0.364374 -0.498167 0.0387282 0.5352480 0.1186639 0.8354212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2892 2992 0.682395 -0.126898 -0.261689 0.1559883 -0.1283145 0.7414814 0.6398502 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2893 2993 -0.245207 -0.246241 0.813008 0.0821238 0.1437436 0.7104925 0.6839546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2894 2994 -0.759024 -0.491430 0.233296 -0.2359790 -0.1228240 0.0361345 0.9632873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2895 2995 0.569436 0.212457 -0.528138 -0.2471682 0.7361934 -0.5913103 0.2174380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2896 2996 -0.386019 0.347977 -0.407510 -0.3185406 -0.2504198 -0.5848734 0.7026699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2898 2998 -0.315254 0.604368 0.098466 0.3962717 -0.0471010 0.1941698 0.8961296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2899 2999 -0.137011 -0.778960 0.012651 -0.4904938 0.5330934 -0.6794333 0.1166090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2900 3000 -0.326899 -0.034838 -0.600580 -0.3500497 0.0331253 0.4304170 0.8313297 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2902 3002 -0.212356 -0.365651 -0.670899 0.7722126 -0.0173813 0.2403842 0.5878784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2903 3003 -0.043971 0.215786 -0.802869 0.3615336 -0.5919015 0.3250488 0.6428758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2905 3005 -0.497331 0.679310 -0.300736 0.0547117 0.2076189 0.4909191 0.8443337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2906 3006 -0.164266 -0.884873 0.154481 0.1479005 -0.8416358 -0.0729251 0.5142534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2907 3007 0.729034 -0.115883 -0.144274 0.3325094 -0.1815527 0.4451980 0.8113414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2908 3008 -0.192573 0.770094 -0.211981 0.8515298 -0.1091318 0.4597671 0.2271596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2909 3009 0.052536 0.636299 0.471826 -0.1374920 -0.4027945 -0.5625182 0.7088200 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2910 3010 -0.097585 0.490189 0.354585 -0.2261600 0.5532396 -0.7560131 0.2668742 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2911 3011 -0.149652 -0.492429 0.327093 0.4297956 -0.1460666 -0.7144144 0.5324963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2912 3012 0.147663 0.305137 -0.649319 0.5709791 -0.4700939 -0.4946975 0.4563650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2913 3013 -0.132132 -0.356814 0.540239 -0.1930593 0.3036801 0.5046654 0.7847416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2914 3014 0.397265 -0.111427 0.792624 0.1314359 -0.0707293 -0.1861378 0.9711203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2915 3015 -0.625780 -0.133111 -0.068410 0.1531645 -0.8043783 -0.5391673 0.1970148 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2917 3017 0.189526 -0.757504 -0.093754 0.4666429 0.1167767 0.8518553 0.2072442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2918 3018 0.543526 0.182593 0.502484 -0.1810391 -0.4863984 -0.3218080 0.7918845 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2919 3019 0.531093 0.141853 -0.421419 0.4210265 0.4938587 0.5318263 0.5440598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2920 3020 -0.527299 0.240347 -0.056277 -0.2844220 0.1702771 -0.7204042 0.6092025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2921 3021 -0.439964 -0.330663 0.449795 -0.2290690 0.3671397 -0.0461180 0.9003382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2922 3022 -0.245106 -0.534536 -0.113579 -0.7390549 0.5029954 -0.4450750 0.0519781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2923 3023 -0.391128 -0.424047 -0.530374 0.3998300 -0.7362245 0.2595798 0.4803412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2925 3025 -0.235230 0.508378 0.197925 0.3496056 -0.1755081 0.5688316 0.7234663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2926 3026 -0.178183 -0.296940 0.501156 -0.2461117 0.2346814 0.7758021 0.5314930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2928 3028 -0.435458 0.177448 -0.131398 -0.6853563 -0.3071508 0.4338107 0.4977484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2929 3029 -0.241634 0.631401 0.354663 0.1687939 -0.3573808 0.4885885 0.7778617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2930 3030 -0.316584 0.323946 -0.120707 0.1839104 0.1314673 0.6219014 0.7497546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2932 3032 0.163522 0.576136 -0.127259 -0.3345626 -0.4481683 -0.6849009 0.4670372 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2933 3033 0.299458 -0.416987 -0.009022 -0.0112375 0.3337562 -0.2147931 0.9177932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2934 3034 0.018255 0.258440 0.365826 0.3499909 0.5209423 -0.5595622 0.5413091 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2935 3035 0.262092 -0.329925 -0.254383 0.1777758 0.2327074 -0.5242741 0.7996122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2936 3036 -0.397829 0.205840 -0.257356 -0.3213983 -0.0700051 0.8326017 0.4456196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2937 3037 0.228601 -0.315106 -0.285165 0.3683553 0.6445323 -0.5929950 0.3118483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2938 3038 -0.143354 0.518358 -0.042691 -0.1124529 0.3088514 0.6363188 0.6978993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2939 3039 -0.206170 -0.405680 -0.195666 -0.3287546 -0.2446341 -0.8416618 0.3516816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2942 3042 -0.387460 -0.010807 -0.424100 -0.8517790 -0.2842048 0.4322207 0.0829783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2943 3043 -0.360880 -0.154530 -0.204859 0.3637584 0.0423858 -0.6157783 0.6976391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2945 3045 0.031789 -0.307400 -0.223897 0.5048025 -0.3861474 0.3628927 0.6814496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2946 3046 -0.006717 -0.272303 -0.600848 0.1361261 0.0035786 -0.9029092 0.4076910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2947 3047 -0.291817 0.143476 -0.054928 -0.8267257 -0.3163949 0.2917528 0.3623523 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2948 3048 -0.442265 0.024045 0.235947 -0.3336554 -0.7569342 -0.4908665 0.2734496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2951 3051 -0.295174 -0.364243 -0.025832 0.1499646 0.1897813 0.7130045 0.6581172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2952 3052 0.238190 -0.162765 -0.059777 -0.0198923 -0.5261201 -0.5166816 0.6751607 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2953 3053 -0.529567 -0.198351 -0.100446 0.1598473 0.6795465 -0.5389290 0.4714031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2954 3054 -0.191256 0.043935 0.368356 -0.1344814 0.6310371 0.7465267 0.1624957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2955 3055 0.077043 0.260669 -0.153878 -0.2577493 0.3657404 0.1971859 0.8723056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2959 3059 -0.311437 0.335019 0.001948 0.1052445 0.1876971 -0.7852408 0.5805948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2961 3061 0.438806 -0.350320 0.244262 -0.6613347 -0.3468197 0.6547872 0.1166459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2962 3062 0.385784 0.103860 0.394808 0.5355479 0.2016261 0.7636507 0.2989532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2963 3063 0.396097 0.487794 -0.235163 0.2616130 0.2565078 -0.9213311 0.1300440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2964 3064 0.543196 -0.175751 0.441274 -0.3263286 -0.5698734 -0.1941946 0.7287266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2965 3065 -0.112708 0.489091 0.073809 -0.3385761 -0.3830270 -0.0121536 0.8593654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2966 3066 0.411966 -0.056267 0.301809 0.0480098 -0.8394699 -0.2823256 0.4618199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2968 3068 -0.565981 -0.244803 0.000219 -0.3894178 0.2213661 0.8457817 0.2898346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2970 3070 0.434492 0.509808 0.094129 0.2142157 0.5464972 -0.6464068 0.4874533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2972 3072 0.603980 -0.229013 0.182035 0.0630929 0.2479558 0.9062254 0.3365897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2973 3073 -0.527025 0.372909 0.140129 -0.5007350 0.3316279 0.3143180 0.7351813 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2974 3074 -0.128840 -0.496612 0.333702 -0.8546600 -0.0925388 0.4917079 0.1386229 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2975 3075 0.022265 0.279884 0.655094 0.5516383 0.2578958 0.0361514 0.7923875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2976 3076 -0.048480 0.604746 0.546718 -0.4827526 0.6114571 -0.6264408 0.0253393 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2977 3077 -0.450803 0.301144 0.313770 0.3082272 -0.4536654 0.7812091 0.2981542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2978 3078 0.289019 -0.671874 -0.330159 0.2147102 0.4891378 0.4369874 0.7236613 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2980 3080 0.508879 -0.380887 -0.207233 -0.1556140 0.6362015 -0.7410798 0.1477589 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2981 3081 -0.494040 -0.317718 -0.428856 0.0899917 0.7644319 -0.6278789 0.1153841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2982 3082 0.303615 0.545819 0.413900 0.5638478 0.5429863 -0.1343996 0.6076004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2983 3083 0.334094 -0.366949 -0.140844 -0.6385176 0.0932062 0.2065902 0.7354783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2986 3086 -0.326649 0.648088 -0.008974 -0.1135201 0.0805228 0.1465176 0.9793681 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2988 3088 0.115011 -0.533358 0.529202 -0.0035038 -0.5533018 0.1118261 0.8254331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2989 3089 0.571122 -0.375464 0.380901 0.0839114 0.7585258 -0.6456060 0.0281152 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2990 3090 0.617705 0.132018 -0.203148 -0.6296623 0.3936623 0.2128874 0.6350074 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2992 3092 -0.188039 -0.589117 -0.047012 0.4665600 0.1689450 -0.1996875 0.8449285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2993 3093 -0.356269 0.477894 0.580611 0.6172495 0.7492176 0.1401568 0.1950183 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2994 3094 -0.623330 -0.463227 0.111131 0.8940918 -0.1757996 0.3970065 0.1099100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2995 3095 -0.520031 0.311605 0.195895 -0.1137872 0.1768658 -0.8376030 0.5041748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2996 3096 -0.848066 -0.491902 0.016377 -0.4643211 0.5496487 -0.6942559 0.0173477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2997 3097 -0.153865 -0.784924 -0.236193 0.4612155 -0.0223635 -0.6660818 0.5857603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 2998 3098 -0.195718 0.957135 -0.222499 0.2367460 -0.5154085 -0.5191041 0.6394031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3000 3100 -0.033778 0.450603 -0.417328 0.1174155 0.3546259 -0.8729808 0.3136217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3001 3101 0.770257 0.201961 -0.243615 0.3507214 -0.7833699 0.5130688 0.0092975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3003 3103 -0.797418 0.160593 0.035341 -0.1448627 0.4959612 0.8558362 0.0241182 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3004 3104 0.375851 -0.401764 -0.514068 0.3904690 -0.6763924 -0.2799561 0.5582579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3005 3105 0.402465 0.609098 -0.285381 -0.4270042 -0.4454165 0.0778404 0.7830788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3006 3106 0.402359 -0.792939 -0.023800 -0.0223167 0.4167059 -0.3387724 0.8432624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3007 3107 0.451816 -0.619178 -0.045243 -0.0692222 -0.4689913 -0.8743273 0.1039581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3008 3108 -0.474727 -0.401095 -0.407200 0.3955642 0.7659926 -0.3662503 0.3502071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3009 3109 -0.080722 0.505351 0.777851 0.5597103 -0.5481597 0.4173003 0.4605495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3010 3110 -0.312993 -0.434116 -0.461911 0.6270400 0.0880337 0.0485618 0.7724718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3011 3111 0.364240 0.305818 0.555672 -0.0286191 -0.4134442 -0.1315577 0.9005206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3012 3112 -0.079313 -0.756054 -0.228831 -0.3084256 -0.7364315 0.5840356 0.1464404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3014 3114 0.529668 0.386770 0.384740 0.2121373 0.0200372 -0.7641660 0.6088075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3015 3115 0.592947 -0.047857 0.105292 -0.8198700 0.3054846 0.2964385 0.3829055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3016 3116 0.208863 0.387247 0.486261 -0.5902347 0.4483236 -0.5575509 0.3738529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3018 3118 0.498944 0.537927 -0.128420 0.5617947 0.3876640 0.7298306 0.0380863 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3019 3119 0.240373 -0.697250 0.467485 -0.2377809 -0.5298559 -0.7799059 0.2333660 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3020 3120 0.005814 -0.545090 -0.292204 0.4130512 0.2322510 0.5169377 0.7128980 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3021 3121 -0.414695 -0.542561 -0.183697 0.3568497 0.3514718 0.4168995 0.7584989 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3022 3122 0.317658 0.501847 0.341482 0.6638579 0.6009495 0.3619128 0.2591746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3023 3123 -0.185263 0.330761 0.687335 0.1673919 0.5029767 0.0867077 0.8434905 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3024 3124 0.206574 0.226762 0.384676 0.0600321 0.3257264 -0.3673904 0.8690931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3025 3125 0.570132 0.340943 -0.263492 -0.4738234 0.7714068 -0.1276362 0.4051320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3026 3126 -0.617845 0.371833 0.232127 0.6534020 -0.0547526 0.6720416 0.3441339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3027 3127 -0.247944 -0.541230 0.563661 0.3415793 0.2290768 0.1014608 0.9058439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3028 3128 -0.130038 -0.147644 0.729336 0.0429624 0.0867781 -0.8546345 0.5101212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3030 3130 0.568059 0.408774 -0.113682 0.2541417 0.4972481 0.8145079 0.1572676 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3031 3131 0.129577 -0.445532 0.560004 -0.2292634 -0.5768278 -0.7770713 0.1042501 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3032 3132 -0.324487 -0.019096 0.505268 0.9130404 0.0348551 0.3995135 0.0743731 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3033 3133 0.307094 -0.396562 0.229899 0.5146646 0.2074105 -0.8295425 0.0629324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3034 3134 -0.513264 -0.197070 -0.132634 0.7088793 0.0761681 0.3079766 0.6299515 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3035 3135 0.311201 0.371343 -0.208486 -0.0729284 0.6398443 -0.6365194 0.4244099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3036 3136 0.543454 0.604945 -0.266802 -0.1608205 0.7058916 0.0018546 0.6898191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3037 3137 0.175170 0.505282 0.430564 0.2494482 0.3485728 0.7656070 0.4797066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3038 3138 0.434174 0.301480 0.350142 0.6888600 -0.0930947 -0.6303921 0.3455591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3039 3139 0.062196 0.227357 -0.503409 -0.0823517 -0.1651346 0.7101811 0.6794053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3040 3140 0.258322 0.356149 -0.419828 0.3646305 0.3633853 -0.2076721 0.8317861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3041 3141 0.248373 0.350052 0.305327 0.3482896 0.1695851 0.8134970 0.4337718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3042 3142 0.157775 -0.262676 0.323413 -0.0097168 0.0271119 0.0361843 0.9989300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3044 3144 0.180269 -0.277261 0.084965 -0.9768221 -0.0164481 -0.0326444 0.2109086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3045 3145 -0.341600 -0.246336 0.095593 -0.3747173 0.8096694 -0.2351751 0.3856360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3046 3146 0.312976 -0.099417 -0.622406 0.1215499 -0.2455808 -0.3941220 0.8772591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3047 3147 -0.244708 -0.151832 0.381985 0.4576513 0.4712927 -0.4987332 0.5654235 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3049 3149 -0.294140 0.061523 0.068240 -0.2377166 0.6009847 0.6339783 0.4247114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3050 3150 0.317658 -0.373817 -0.146101 -0.5645196 -0.4719538 0.4882321 0.4692619 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3051 3151 -0.489024 0.519104 0.011443 0.3055768 0.6754341 0.5949064 0.3106413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3052 3152 0.291224 0.253464 -0.454063 0.0971327 0.0670759 -0.0139334 0.9929108 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3053 3153 0.447752 -0.159518 -0.196748 -0.0236231 0.3354721 -0.4249009 0.8404520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3055 3155 0.467922 0.163383 0.061586 -0.3940326 0.0492825 -0.6342101 0.6633907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3056 3156 0.063550 -0.450566 0.224834 0.0551684 0.0729294 0.0175129 0.9956561 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3057 3157 0.529762 0.227339 0.156587 -0.4234984 -0.0539826 0.6595784 0.6186205 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3058 3158 0.148388 0.554629 -0.189246 0.2467779 -0.4380641 0.4793321 0.7193339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3059 3159 -0.317009 -0.387175 -0.111767 -0.5016764 -0.5036017 0.5289010 0.4636485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3061 3161 -0.350300 0.049168 -0.465154 -0.5325304 0.3352569 0.7703517 0.1028223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3062 3162 0.417162 -0.029516 0.313127 -0.4786466 0.1722873 -0.6124261 0.6051023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3063 3163 -0.259558 -0.033725 -0.520795 0.2096253 -0.7653249 -0.0985205 0.6005237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3064 3164 0.552267 0.157766 -0.400391 0.1243599 -0.4049398 0.2304566 0.8760411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3066 3166 0.007780 0.025010 -0.469929 -0.5147591 0.1101997 -0.1769954 0.8315959 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3067 3167 -0.335942 0.342896 -0.301432 -0.6099507 -0.4975046 -0.4137890 0.4574144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3068 3168 0.163739 0.495740 -0.363852 0.6087969 -0.1313328 -0.7282163 0.2860403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3069 3169 0.117870 -0.528045 -0.341200 -0.0115284 -0.5044783 -0.8471563 0.1664181 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3070 3170 -0.415176 0.278157 -0.424235 -0.7005968 -0.0513810 0.6937646 0.1587918 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3071 3171 -0.503620 -0.548238 0.172429 -0.1421065 0.4656006 0.4989507 0.7169868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3072 3172 -0.610519 -0.137606 0.135930 0.1405710 0.5066529 0.2510424 0.8127240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3074 3174 -0.621050 0.264093 -0.117003 -0.8279529 0.0203256 0.5567542 0.0640759 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3075 3175 0.009324 0.614673 -0.020780 0.0685584 0.1297850 -0.3644662 0.9195760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3078 3178 -0.288579 -0.607837 0.088347 -0.4059709 -0.2276605 0.8824248 0.0684457 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3079 3179 -0.002817 -0.471532 0.438210 0.1251529 0.7256532 0.6028652 0.3071119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3080 3180 -0.515694 0.459305 0.351009 -0.7202776 -0.0617126 0.6787111 0.1293950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3081 3181 0.411975 0.349161 0.458749 0.4381806 0.4695009 -0.7490726 0.1626560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3082 3182 0.159582 0.514461 -0.264071 -0.0925567 0.7418322 0.6512151 0.1305265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3083 3183 0.430936 0.101556 -0.525548 0.4720319 0.5883112 -0.0180553 0.6563154 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3084 3184 -0.079700 -0.058591 0.803645 -0.4643821 -0.1468255 -0.1453414 0.8612011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3085 3185 -0.193269 0.513828 -0.793953 -0.8745910 -0.0335798 0.4764336 0.0835111 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3087 3187 -0.263938 0.264827 0.612801 0.0840454 0.1293658 0.8382579 0.5229958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3088 3188 0.459063 -0.530375 0.306079 -0.5734329 0.1450457 -0.8030796 0.0721079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3090 3190 0.723920 -0.448644 0.372449 0.4983772 -0.0968961 0.1081254 0.8547165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3091 3191 -0.355941 -0.336470 0.625653 0.7510536 -0.2474091 -0.6020654 0.1105643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3092 3192 -0.081894 -0.598875 0.314948 -0.1844636 0.3780948 0.6820594 0.5981743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3093 3193 0.088808 0.200205 -0.775281 -0.3572184 0.1449396 0.8213606 0.4204215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3094 3194 -0.170389 0.608498 -0.286170 0.1788195 0.7602619 0.1515203 0.6058606 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3095 3195 -0.154337 -0.674285 0.062428 -0.1653332 -0.7015590 -0.5050739 0.4747422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3096 3196 0.752799 0.579383 0.052736 0.0805915 -0.8593547 0.3761576 0.3369272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3098 3198 -0.834681 0.145734 0.248543 -0.0229580 0.0792691 -0.8906882 0.4470615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3099 3199 0.085267 -0.647241 0.353017 -0.2080119 -0.5995964 -0.4848054 0.6018130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3100 3200 0.070339 -0.090557 -0.888440 0.7876889 0.1579722 0.2842078 0.5232752 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3102 3202 0.255546 0.552478 -0.063966 -0.3577081 0.3520640 -0.1823958 0.8454748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3103 3203 0.952827 0.188721 0.087087 0.3478225 -0.0991780 -0.1161945 0.9250308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3105 3205 0.134236 0.766626 0.278566 0.0736470 -0.1423263 -0.8877469 0.4315378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3106 3206 0.518122 -0.017717 0.332166 -0.4456549 -0.3023415 0.4914774 0.6844204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3107 3207 -0.390186 0.101192 -0.500723 -0.2393164 0.6094293 0.2109394 0.7258293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3108 3208 0.272212 -0.322861 0.652716 -0.2696166 -0.6621683 0.6111612 0.3395911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3109 3209 0.559975 0.112383 -0.373219 0.0843038 -0.2895047 0.5115045 0.8046385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3110 3210 -0.208206 -0.653595 0.158752 0.0504163 0.4612537 -0.7401814 0.4866567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3111 3211 0.596692 0.470630 0.166000 -0.2867103 0.0831120 -0.6542541 0.6948678 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3112 3212 -0.425197 0.101263 0.678656 0.3782742 -0.1488141 0.8872155 0.2182008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3114 3214 -0.551771 0.368213 0.233058 -0.1124218 0.7411109 -0.5281466 0.3989701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3115 3215 0.390783 -0.682178 -0.181068 -0.1317404 -0.8845656 0.0536001 0.4442017 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3117 3217 -0.494015 0.231180 0.162741 -0.5302946 -0.0766577 -0.7439447 0.3993213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3118 3218 0.125348 -0.189133 0.647138 -0.1847068 -0.7510239 0.0685423 0.6301972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3119 3219 0.008164 0.561069 -0.423003 -0.8648269 -0.1881619 0.1924042 0.4238516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3120 3220 -0.685162 -0.674744 -0.054060 -0.8849375 -0.2352733 0.2880160 0.2803193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3122 3222 0.489079 0.280360 -0.242382 -0.5048466 0.3979484 0.6192347 0.4509051 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3123 3223 -0.778059 0.289308 0.120516 -0.4065994 -0.5339537 0.7294454 0.1322107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3125 3225 -0.441383 -0.055010 0.733298 -0.1555060 -0.9588484 0.2352036 0.0332701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3126 3226 0.274310 0.269891 -0.350151 -0.6514035 0.1508809 0.3755414 0.6417765 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3127 3227 -0.524117 -0.156008 0.166667 -0.6943592 -0.3957463 -0.5826448 0.1475643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3128 3228 0.040314 0.081258 0.585869 -0.4840182 0.4200274 0.1757880 0.7472630 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3129 3229 -0.556047 0.392645 0.364785 -0.2059339 0.0003846 0.9104731 0.3586499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3130 3230 -0.082831 -0.342577 0.417250 -0.4626997 0.0118660 -0.8848847 0.0524139 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3131 3231 0.118477 0.482222 -0.037716 -0.7276720 0.0574364 0.4717840 0.4945850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3132 3232 0.190105 0.069452 -0.552744 0.6762389 0.0491314 0.0183593 0.7348129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3133 3233 -0.534344 0.304308 0.081316 -0.0075875 -0.1787399 0.9823784 0.0541034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3135 3235 -0.089963 0.403166 -0.088899 0.0746948 -0.3820229 -0.0118440 0.9210532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3136 3236 0.144517 0.244168 0.385323 0.3750257 0.0376278 -0.9175755 0.1264716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3137 3237 0.412381 0.265944 0.521677 0.1043182 0.0558690 -0.9118253 0.3931553 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3138 3238 -0.446145 -0.071680 -0.297453 -0.7705204 -0.2362764 0.5063051 0.3068010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3140 3240 0.242301 0.273167 -0.280696 -0.2505736 0.3076318 0.9090388 0.1273736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3141 3241 0.266528 -0.127728 0.314272 0.2709753 0.3651649 -0.3332229 0.8259476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3142 3242 0.134118 -0.017420 0.279232 -0.4014282 -0.7363427 0.2877248 0.4624601 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3143 3243 0.454903 -0.221291 0.398300 0.0378907 0.5115544 -0.1442475 0.8462087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3145 3245 0.215312 -0.180173 -0.325101 0.0205457 0.7550175 -0.6498687 0.0848355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3147 3247 -0.301989 -0.358198 0.083000 -0.2312972 -0.2720390 -0.9004508 0.2483643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3148 3248 -0.360028 0.353109 -0.124916 0.4897213 -0.0543640 -0.8124879 0.3115781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3150 3250 -0.536587 0.130505 -0.214025 0.1165801 -0.5937770 0.7777037 0.1703377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3152 3252 0.355934 0.089431 -0.395172 -0.0809791 0.0389786 -0.0040881 0.9959449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3153 3253 0.240480 0.021269 0.203199 0.3716867 -0.6182447 0.2073491 0.6607790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3154 3254 0.288056 0.196268 0.017171 0.5337700 0.5096250 0.2778289 0.6149659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3155 3255 -0.229402 0.551852 0.353539 0.3527350 0.1847031 -0.7630789 0.5090908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3156 3256 -0.005208 -0.534736 0.311598 -0.1649710 0.0741093 0.1880253 0.9653698 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3157 3257 0.196676 -0.366892 -0.127948 0.4538906 -0.0488826 0.4252558 0.7815058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3158 3258 0.138437 0.072921 -0.384488 0.4339849 0.5903190 0.1115914 0.6713628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3159 3259 -0.387747 0.023631 0.520115 -0.3779735 0.4526950 -0.6810794 0.4339748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3160 3260 -0.132831 -0.305458 0.628123 0.1976700 -0.7921294 -0.4730816 0.3311367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3162 3262 0.030042 -0.150460 0.656420 -0.2622998 -0.5063772 0.7908639 0.2220703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3163 3263 -0.254884 -0.261162 0.471253 -0.2329880 -0.6334720 -0.1508586 0.7222683 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3164 3264 0.149255 -0.205111 -0.612878 0.8075571 0.0488411 0.3997630 0.4308778 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3165 3265 0.321251 0.484109 0.212862 0.4938992 -0.3216336 -0.8014926 0.1011188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3166 3266 -0.113098 0.493194 -0.258900 -0.1738992 0.0307062 0.8859380 0.4288708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3167 3267 0.070566 -0.529007 0.343011 0.2903287 0.0466067 0.7972513 0.5271882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3168 3268 -0.110868 -0.602375 -0.053169 -0.5107560 -0.4917529 0.6905819 0.1428428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3169 3269 0.064057 0.069816 -0.459634 -0.6254272 0.2845469 0.2791601 0.6707783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3170 3270 0.512453 -0.021966 0.494074 -0.3739310 -0.7251466 -0.4212512 0.3960878 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3171 3271 -0.300838 -0.008757 -0.590529 0.1388519 -0.7761063 0.0777670 0.6101896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3172 3272 -0.380947 0.274267 -0.655100 -0.7402830 -0.3712283 0.2897367 0.4798160 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3173 3273 -0.442699 -0.164182 0.445489 0.5678769 -0.3920303 0.7069890 0.1549020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3174 3274 -0.018099 -0.111884 0.854886 -0.5538787 -0.0737953 0.8186971 0.1323164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3175 3275 -0.264548 0.412180 -0.261052 0.1878538 0.1669711 0.9667971 0.0462060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3177 3277 0.560219 -0.176727 -0.079639 -0.1070274 -0.4001702 0.3344851 0.8464802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3178 3278 -0.204425 0.459265 0.299079 -0.2774414 0.4389307 -0.5433653 0.6596365 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3179 3279 -0.653512 0.286774 -0.552442 0.5070932 -0.3403220 -0.6421978 0.4632703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3180 3280 -0.175744 -0.558715 0.682928 0.3037446 -0.8905858 -0.2575181 0.2197282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3181 3281 -0.680407 -0.377407 -0.131914 -0.5518441 -0.4108062 0.5095682 0.5167656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3184 3284 -0.059535 -0.719539 0.350077 0.2478361 -0.2836837 0.5730150 0.7278424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3185 3285 0.445889 -0.107817 0.506701 0.1836849 -0.1002939 0.9768668 0.0439583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3186 3286 -0.548481 0.403557 0.449807 -0.5078272 0.4042994 -0.7266661 0.2249663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3187 3287 0.300370 0.381773 0.495058 0.2420154 0.1634770 0.5231049 0.8006654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3188 3288 0.224437 0.449958 0.470866 -0.2799515 0.5677575 -0.7326991 0.2498614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3189 3289 0.430838 0.297167 0.644919 0.0135315 0.6922549 -0.4801560 0.5385632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3190 3290 0.781711 0.233862 0.578236 -0.0948848 -0.7290233 -0.6005536 0.3144158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3191 3291 -0.414835 0.606207 -0.049216 0.5838673 -0.5495972 -0.0181515 0.5972540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3192 3292 -0.835292 -0.203631 0.027409 0.0869198 -0.5919928 -0.3195405 0.7347675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3194 3294 0.515436 0.685926 -0.288245 0.5981584 -0.4598369 -0.5740854 0.3180919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3196 3296 -0.383609 0.125908 -0.630947 0.6342855 -0.5820818 0.4405193 0.2545690 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3197 3297 -0.228672 0.398537 0.727495 -0.4742905 -0.5341972 0.2106209 0.6673236 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3198 3298 0.635395 -0.449031 0.290680 -0.0877898 -0.6711352 -0.1474534 0.7211990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3199 3299 0.652398 -0.122974 -0.494804 -0.5605538 0.6424509 -0.3862895 0.3518758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3200 3300 -0.240322 -0.630314 0.207760 -0.0856767 -0.7147651 -0.1508482 0.6775065 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3201 3301 -0.147311 -0.301234 0.564172 0.9275108 0.0367953 0.3353022 0.1610662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3202 3302 -0.234299 0.326934 0.427386 0.2472439 0.1554770 -0.7361790 0.6105226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3204 3304 -0.464873 -0.769193 -0.431957 0.4736747 0.1403189 -0.6360411 0.5927854 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3206 3306 0.228602 -0.506927 -0.351074 0.0716975 0.1309802 0.3937310 0.9070168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3207 3307 0.543633 0.506529 -0.435381 -0.4367009 -0.7773243 -0.0613917 0.4486539 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3209 3309 0.216069 0.002851 -0.763486 0.1348511 0.6647575 0.0284687 0.7342358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3210 3310 0.534036 -0.193127 0.681412 0.3198744 -0.1181919 0.8889681 0.3056907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3213 3313 0.083267 -0.679988 0.602532 -0.7287455 -0.1272259 -0.1482879 0.6563188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3215 3315 -0.247314 -0.403950 -0.367034 0.1550282 -0.0600322 0.9222669 0.3489788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3217 3317 0.096451 -0.838275 -0.204952 0.1368942 0.3926353 -0.5480348 0.7257791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3218 3318 0.401235 -0.327271 -0.386627 -0.4371886 0.2700440 -0.7775737 0.3623831 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3219 3319 0.329330 0.025964 0.503004 0.0182373 -0.9915640 0.0221251 0.1264072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3220 3320 -0.719862 0.211948 -0.104596 -0.1167213 -0.0740395 -0.0329931 0.9898514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3221 3321 0.210041 0.675347 -0.314363 -0.3562581 0.0329656 -0.5176970 0.7771636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3222 3322 0.043905 -0.523090 0.164788 -0.0809542 0.2611834 -0.1712917 0.9465140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3224 3324 0.359333 0.181919 -0.446831 0.8573156 0.2593821 0.3146893 0.3141680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3228 3328 -0.376292 -0.446127 -0.074819 0.3660801 -0.2728571 0.8076283 0.3731901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3229 3329 0.070147 0.179096 0.554159 0.5423455 -0.0912062 0.3304720 0.7670274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3230 3330 0.538219 0.465199 0.161863 0.5362709 -0.3549651 0.0216099 0.7654713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3232 3332 0.461024 -0.516133 -0.219807 0.0220146 -0.0169258 -0.7664769 0.6416713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3233 3333 0.518214 -0.042664 -0.294320 0.5794225 -0.2189985 -0.7516244 0.2266497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3234 3334 -0.459428 -0.369030 -0.378118 -0.6304865 0.0900303 -0.7690703 0.0539650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3235 3335 -0.313539 0.336801 -0.004712 0.0988399 -0.4371589 0.6454121 0.6185192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3236 3336 -0.412233 -0.340834 0.248447 -0.6349640 -0.1586463 0.3589886 0.6654166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3237 3337 -0.565273 0.136423 0.256114 -0.0703535 0.3250798 -0.2879390 0.8980338 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3238 3338 0.163200 0.252554 0.384287 -0.5014686 -0.2784688 0.7119707 0.4050704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3239 3339 -0.574596 -0.009838 0.242775 -0.6742636 -0.5056750 -0.5318706 0.0823107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3240 3340 -0.117105 -0.558488 -0.057482 -0.2006934 -0.6015769 0.6654751 0.3936627 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3242 3342 0.107288 -0.385258 -0.350425 0.3629066 0.5658117 0.1557346 0.7238112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3243 3343 -0.045379 -0.092243 0.568281 0.1245717 -0.3703154 -0.1857629 0.9015767 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3244 3344 0.539434 0.339792 -0.254993 -0.0281042 -0.0656991 -0.9125136 0.4027563 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3245 3345 -0.270053 0.522687 0.026580 0.0878290 -0.5815927 0.5440591 0.5983608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3246 3346 0.167851 0.513598 -0.022574 -0.1116744 0.3429099 -0.2350548 0.9026023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3247 3347 0.440948 0.094114 -0.219206 -0.1251674 0.2645497 0.6145877 0.7325494 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3248 3348 0.100795 -0.500228 0.145422 0.0943997 0.0148043 -0.6375108 0.7644930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3250 3350 0.385571 0.457905 -0.266507 -0.2798591 0.6106999 -0.3217666 0.6672262 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3251 3351 -0.107947 0.110722 0.425948 0.2658971 0.3950751 0.2309929 0.8484437 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3252 3352 0.490633 0.225540 -0.199965 0.5308663 0.5767943 0.5588054 0.2706027 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3254 3354 0.360682 0.355929 0.019513 -0.6457227 0.0574365 0.3332893 0.6845885 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3255 3355 -0.222834 -0.392724 -0.084089 -0.0106802 0.8144506 -0.4158544 0.4045013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3257 3357 -0.241995 -0.317214 0.270308 0.3745432 0.1361320 -0.0609427 0.9151347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3260 3360 0.538121 0.234310 -0.050431 0.0134759 -0.9588592 -0.2457200 0.1415242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3261 3361 0.216245 0.434371 -0.026416 -0.7859754 -0.1208565 -0.5950140 0.1165964 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3262 3362 -0.250139 -0.386331 0.036488 0.1351782 -0.1604912 0.5254871 0.8245197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3263 3363 0.401663 -0.401816 0.296081 0.0817109 -0.0149120 0.8890513 0.4502097 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3264 3364 -0.405393 -0.297748 0.458801 0.2202486 0.2011076 0.4772752 0.8265922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3265 3365 -0.523291 -0.399986 -0.176896 -0.3348558 0.5881927 -0.5490343 0.4903696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3266 3366 0.510854 -0.254105 0.055664 -0.4934642 0.2539683 -0.8207208 0.1356857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3267 3367 -0.180971 0.373058 0.428672 0.5256059 -0.5924150 0.5558014 0.2527207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3268 3368 -0.256962 0.463397 0.272062 0.3125931 -0.7514560 0.5264641 0.2458352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3269 3369 0.571492 0.566288 -0.139753 0.0750275 -0.3166542 0.8366248 0.4406359 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3270 3370 -0.032568 0.657624 -0.299022 -0.1724811 0.0620344 0.8922487 0.4126673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3271 3371 -0.490776 -0.015064 0.689512 0.0755690 0.6916594 -0.3823051 0.6080620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3272 3372 0.005571 0.352278 0.460578 0.1019284 0.3367117 0.1006135 0.9306518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3273 3373 0.607142 0.138572 -0.019175 0.0379456 -0.0786958 -0.9961716 0.0030519 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3276 3376 -0.422981 0.240373 -0.337270 -0.3340812 0.0240533 0.3534292 0.8734409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3277 3377 0.353427 -0.410253 -0.693689 0.2387773 -0.4529538 -0.1339682 0.8484520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3278 3378 -0.488834 -0.386219 0.159070 0.0160794 0.9303530 -0.0072553 0.3662404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3279 3379 -0.005570 -0.307603 0.447274 0.0745796 -0.7462478 0.2791006 0.5997124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3281 3381 -0.502378 0.222907 0.534966 -0.4203274 0.6740733 -0.6073745 0.0068079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3285 3385 -0.132361 -0.296866 0.665373 -0.4236862 0.1626026 0.3898575 0.8012874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3286 3386 0.375171 -0.602239 -0.514352 0.4450306 0.0987030 -0.4087047 0.7906744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3288 3388 -0.325738 -0.677867 -0.141220 -0.6089791 0.2864161 -0.6813279 0.2879280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3289 3389 -0.750666 -0.241397 -0.140927 0.3642129 0.0989937 -0.9194334 0.1104150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3290 3390 -0.420952 0.767540 -0.069363 -0.0692019 0.2662571 -0.0775271 0.9582838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3291 3391 -0.449807 0.362386 0.025227 -0.2566491 0.1149260 -0.2022213 0.9380990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3293 3393 0.622155 -0.445538 -0.207133 -0.0466204 -0.7659894 0.6155143 0.1795241 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3294 3394 -0.495138 -0.546093 -0.176034 0.0238229 -0.9376427 -0.3126965 0.1499315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3296 3396 -0.560204 0.103236 0.296164 0.1071133 0.4108302 -0.5074650 0.7498164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3297 3397 0.394331 -0.425711 0.483310 -0.0583826 -0.0441896 -0.0859657 0.9936039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3299 3399 0.071601 0.231022 0.587320 0.1621506 0.2063022 -0.9208555 0.2883950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3300 3400 0.523553 -0.614156 0.016051 -0.1942499 -0.5844849 0.4199715 0.6665346 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3302 3402 -0.458475 -0.340208 0.376894 -0.3735063 -0.5672490 -0.6962950 0.2321527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3303 3403 -0.247351 -0.248985 0.359996 -0.5562930 -0.0797516 -0.4477759 0.6954672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3304 3404 0.661783 -0.128375 0.387454 0.1179048 -0.5794884 -0.7799399 0.2049033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3307 3407 0.128508 0.829439 0.153877 0.5870914 -0.4556254 0.5839395 0.3267168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3308 3408 -0.559023 -0.274181 -0.422406 0.4868415 -0.6885524 -0.4465979 0.2990506 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3309 3409 0.697846 0.046361 0.230272 0.1962108 -0.4640707 0.6694775 0.5458383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3310 3410 0.144632 -0.100717 0.573644 -0.2916528 0.5543229 0.4790475 0.6149620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3311 3411 0.235796 -0.554061 0.201012 0.0744103 -0.3386277 0.9282687 0.1345790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3312 3412 -0.323676 0.146587 0.690565 -0.1379780 -0.5329661 0.3930766 0.7364781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3314 3414 -0.424294 0.556278 0.026831 0.0331397 -0.7171417 0.6355072 0.2841483 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3315 3415 -0.083288 0.495579 -0.454100 0.4236242 0.5085868 -0.6952586 0.2801740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3318 3418 -0.201037 0.600933 0.315158 0.5515104 -0.3666772 0.2250345 0.7146633 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3321 3421 -0.613718 0.169360 0.144733 0.6481193 0.3670251 0.4448898 0.4972997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3322 3422 0.397743 -0.531811 0.217800 0.0957481 0.3607050 -0.9257556 0.0608348 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3323 3423 -0.519182 0.638230 0.184850 0.4142810 -0.0657649 0.4186251 0.8054808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3324 3424 0.114723 -0.506247 0.416369 0.3622058 0.5523335 -0.2659096 0.7021586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3325 3425 0.609124 0.101630 0.031173 -0.5249005 0.3472666 -0.0622976 0.7745995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3326 3426 0.375074 -0.493871 -0.373910 0.6756415 0.4835326 -0.4539570 0.3219129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3327 3427 -0.308749 -0.259530 0.440950 -0.3296260 0.1404521 -0.7384950 0.5711786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3328 3428 -0.169187 0.563455 0.161244 -0.3800797 0.1921339 0.6822393 0.5942840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3329 3429 0.532763 0.169631 0.230541 0.1184581 -0.6000344 0.1074605 0.7838231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3332 3432 0.365623 0.463226 -0.250610 -0.5122720 -0.1448978 -0.4159325 0.7372802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3333 3433 -0.078683 0.123671 -0.508995 0.2019011 0.6409747 0.4681346 0.5737922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3334 3434 -0.003506 0.323826 -0.378322 -0.1437907 -0.4513597 -0.8298972 0.2947360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3335 3435 0.191883 0.475018 -0.090244 -0.4953453 0.0095079 -0.8061629 0.3234873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3336 3436 -0.514023 -0.104979 -0.111828 0.6457887 -0.3812679 0.6527124 0.1075093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3337 3437 -0.424043 -0.315662 -0.045084 0.6261199 -0.3126120 0.2058424 0.6840150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3338 3438 0.256388 -0.508583 -0.233512 0.3049690 -0.6283274 0.6898567 0.1905158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3340 3440 -0.351323 -0.189037 0.179143 -0.6239902 0.1119424 -0.1814520 0.7517847 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3341 3441 0.174591 -0.203718 0.310458 -0.0073148 -0.5113562 -0.5511170 0.6593417 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3342 3442 0.100486 -0.371799 0.365903 -0.0103984 -0.5843023 -0.6205236 0.5229084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3343 3443 0.432001 0.236377 0.262508 0.2560007 -0.5906420 0.4946027 0.5839296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3345 3445 0.394873 0.303637 -0.195711 -0.3429673 0.1236140 0.2284042 0.9027317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3347 3447 0.220161 -0.397990 0.217713 -0.1429675 -0.0187791 -0.0820315 0.9861432 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3348 3448 0.571753 0.076488 0.303982 0.1143319 -0.1313192 0.7985272 0.5762273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3349 3449 -0.206313 0.446949 -0.015701 0.0555000 0.6854736 0.4229437 0.5900546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3350 3450 -0.361293 0.419554 0.335186 0.3273053 -0.5760263 0.2628032 0.7014267 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3351 3451 -0.176372 0.633992 0.039137 -0.0000047 0.0560382 -0.7165665 0.6952641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3352 3452 -0.034182 -0.133726 0.499385 -0.5620612 0.7378111 0.1196560 0.3541249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3353 3453 -0.177508 0.239686 -0.067734 -0.5699639 -0.4727284 0.5133524 0.4337491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3354 3454 0.321074 -0.118579 0.270188 0.7559016 -0.0239875 -0.0688633 0.6506114 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3355 3455 0.239530 -0.413361 0.078852 0.3991270 -0.3276129 0.4827981 0.7073001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3357 3457 -0.199154 -0.064556 0.400530 0.0233601 0.0788902 0.9844655 0.1551075 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3360 3460 -0.462950 0.082773 0.088848 -0.5440672 0.0728589 -0.1260851 0.8263081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3361 3461 -0.054210 -0.454008 0.264121 -0.6733505 -0.5471061 -0.4042896 0.2895238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3362 3462 -0.424886 -0.259714 0.313975 0.3173300 0.7129227 0.4971284 0.3793497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3363 3463 -0.457908 -0.153163 0.255626 0.1820600 0.1122770 -0.4211685 0.8813995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3364 3464 -0.289330 0.227905 0.270652 -0.6882777 -0.6364654 -0.1538183 0.3122909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3365 3465 0.598849 -0.135896 -0.346400 -0.7349650 -0.4029705 0.5418810 0.0616941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3366 3466 -0.188497 0.172283 0.371973 0.3140953 -0.5802364 0.5910077 0.4640903 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3368 3468 0.391212 0.095699 -0.431381 -0.3927004 -0.3131287 -0.8646189 0.0130790 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3369 3469 0.099482 -0.450949 -0.348850 0.1281268 0.6712754 -0.3837640 0.6210459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3370 3470 0.503518 -0.428083 -0.050976 0.0516153 -0.0717110 -0.7531150 0.6519288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3371 3471 -0.327672 -0.511641 -0.348575 -0.6935879 0.1257539 0.6774409 0.2102278 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3372 3472 -0.325483 0.292932 0.386607 0.0688664 0.4910412 0.0588633 0.8664128 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3373 3473 -0.440180 -0.380421 -0.100201 -0.0433288 -0.4415820 0.3801090 0.8115695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3374 3474 -0.345810 0.365754 -0.493373 0.1930365 -0.5470811 0.7520362 0.3128591 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3375 3475 0.445138 0.197807 -0.526866 0.2133412 0.8747859 -0.2739068 0.3379499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3376 3476 -0.095559 0.514111 0.217648 -0.0780236 -0.3107957 0.6650328 0.6745738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3379 3479 0.279814 -0.707206 0.206517 -0.5772090 0.4236808 0.6494392 0.2560333 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3380 3480 -0.064835 0.336899 0.443466 0.2608276 0.3065167 -0.6292877 0.6648409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3382 3482 -0.645496 0.438321 0.279719 0.6723276 0.5203424 0.2471032 0.4649294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3383 3483 -0.244337 -0.224842 0.664241 -0.4656482 0.0857845 0.5534312 0.6852201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3384 3484 0.502533 -0.247690 -0.142096 -0.4848023 0.1595874 -0.8403601 0.1824650 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3385 3485 -0.676512 -0.533130 0.202007 0.2108260 -0.2057912 0.1174293 0.9483737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3387 3487 0.805276 0.189595 -0.274044 0.7630056 0.0957810 0.1515495 0.6210323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3388 3488 0.425706 0.549843 -0.192276 0.0726255 0.5266739 0.6767098 0.5093172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3389 3489 0.642597 0.014820 0.369491 -0.2816827 -0.8306492 -0.4729511 0.0836305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3390 3490 -0.520303 0.496940 -0.153038 -0.0867453 -0.2318369 -0.5721950 0.7818694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3391 3491 -0.677570 0.012320 -0.213242 -0.3089362 0.4881166 -0.5317632 0.6192967 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3392 3492 -0.655895 -0.463250 0.227444 -0.6655126 0.0748090 -0.7315939 0.1275421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3393 3493 -0.669415 -0.368067 0.211913 -0.0268551 0.3327799 0.0482135 0.9413882 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3394 3494 0.255871 -0.470866 -0.281739 -0.6132261 0.6583128 -0.2611431 0.3498319 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3395 3495 0.516379 0.270951 -0.147327 -0.6627751 -0.1860452 -0.7212111 0.0772721 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3396 3496 -0.494796 -0.526631 0.102815 0.1840682 0.3717643 0.8033921 0.4271665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3398 3498 -0.238401 0.853940 -0.057253 0.0752295 0.4536065 -0.1753701 0.8705326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3399 3499 -0.481925 -0.304953 0.520752 -0.0571188 -0.3172779 -0.9458376 0.0382551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3400 3500 -0.497719 -0.497432 -0.330477 -0.3392031 0.4747244 -0.4828537 0.6530163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3401 3501 -0.197480 0.254870 -0.717864 -0.2271562 -0.8259600 -0.1371443 0.4973746 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3402 3502 0.517105 -0.044126 -0.394630 0.5664238 0.5253845 0.1610409 0.6141669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3403 3503 0.396989 -0.698712 -0.026359 -0.3585211 -0.4654653 -0.1871162 0.7872688 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3404 3504 -0.477327 0.604903 -0.224053 0.1932111 0.2648054 -0.5615204 0.7597647 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3405 3505 0.152696 -0.760665 -0.240359 -0.1388709 -0.2394749 -0.6404960 0.7163320 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3406 3506 0.594667 0.295847 0.264962 0.1554958 -0.0854236 0.4074378 0.8958339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3408 3508 0.521650 -0.141837 0.528432 -0.3875684 0.4748390 0.7580259 0.2229694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3409 3509 0.110932 -0.895131 0.108340 -0.2915901 0.5769842 -0.2181019 0.7310923 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3410 3510 -0.576365 -0.054734 -0.344861 0.3384949 -0.3035629 0.6878081 0.5658540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3411 3511 -0.364313 0.052085 0.508954 0.4727973 -0.1977052 -0.4662090 0.7211273 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3412 3512 0.441376 -0.028552 0.571377 -0.5877865 -0.3437280 0.1651781 0.7134945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3414 3514 0.649001 0.435400 -0.282871 0.2604865 -0.7251218 0.6086113 0.1895717 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3415 3515 0.713908 -0.122610 -0.443683 0.3900763 0.4066396 -0.6298075 0.5346281 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3416 3516 0.013859 -0.306667 0.470081 -0.4565184 0.3680339 0.3293913 0.7400293 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3417 3517 -0.297647 -0.174600 0.284410 0.1315056 0.3090690 0.8914802 0.3040487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3418 3518 0.132877 0.435908 -0.505985 -0.5257033 -0.4251764 -0.6517919 0.3435527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3419 3519 -0.009670 -0.526154 0.356784 -0.0677118 -0.2935497 0.7662102 0.5675963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3422 3522 -0.335878 0.311353 0.230305 0.2900250 0.7027618 0.4886816 0.4280206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3423 3523 -0.091726 0.437595 -0.195822 0.0768967 0.6995608 0.5715828 0.4218941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3424 3524 -0.420729 -0.200413 0.574820 -0.3018554 -0.2886816 -0.3102057 0.8540016 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3425 3525 0.602409 0.039402 0.512531 -0.2230827 -0.6188240 0.7186756 0.2253805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3426 3526 0.013635 0.490647 0.462282 -0.0141029 -0.5322236 0.4020831 0.7448948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3428 3528 0.120925 0.070532 0.501306 0.3156000 0.5943967 -0.4042553 0.6194084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3430 3530 0.093758 0.403209 0.267378 0.2142461 -0.0734635 0.6801817 0.6971762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3432 3532 -0.247627 0.391204 0.419732 -0.3969114 0.5258020 -0.5054908 0.5572008 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3433 3533 0.319450 -0.336572 -0.003911 -0.7850234 0.1009530 0.1809127 0.5837957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3434 3534 -0.268629 -0.501010 0.199719 -0.1606151 -0.3088833 0.8799339 0.3232805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3435 3535 -0.377264 -0.220846 0.356164 -0.2346268 0.3621959 0.5842016 0.6873666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3436 3536 0.017147 0.638709 -0.171062 -0.5024075 -0.3295899 -0.4743886 0.6433604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3437 3537 -0.455433 0.172853 0.186512 0.2994454 0.3556246 -0.3882778 0.7956783 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3438 3538 -0.211038 0.065827 0.572314 -0.3343088 -0.1352206 -0.9326060 0.0141072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3439 3539 -0.478853 0.092715 -0.154306 -0.3865500 0.2066667 -0.8961650 0.0689657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3441 3541 0.278891 0.363343 -0.069374 0.0082770 0.5379697 0.8161124 0.2109041 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3442 3542 0.264131 0.489110 -0.153124 0.0540894 -0.2398809 -0.4942243 0.8338308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3443 3543 0.300834 -0.434546 -0.277663 0.2775347 0.0916715 0.6562891 0.6955971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3444 3544 0.338988 -0.307502 0.357096 0.5380488 -0.1541866 -0.7379414 0.3770576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3445 3545 0.117716 -0.152288 0.251075 0.3818207 -0.1412077 -0.8028763 0.4355031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3446 3546 -0.415819 0.071385 0.470934 -0.2508127 -0.8268453 -0.4530464 0.2194739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3447 3547 0.331361 -0.461552 0.077965 -0.2879738 -0.4212639 0.8452680 0.1585238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3448 3548 0.027387 -0.275202 0.220134 0.0247030 -0.0146403 -0.8078556 0.5886805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3449 3549 0.348403 0.516222 -0.005343 0.1940417 -0.3992331 0.8914997 0.0904930 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3451 3551 -0.502629 -0.409832 -0.233904 0.2291537 0.7400248 -0.6189898 0.1292424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3453 3553 0.406353 0.070944 0.423857 0.8061471 -0.4505927 0.1423675 0.3561242 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3455 3555 0.045030 -0.459209 0.283109 0.1559091 0.2935185 -0.9336772 0.1333645 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3456 3556 -0.451458 -0.035015 0.232060 0.0393749 0.7817737 0.1086346 0.6127626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3457 3557 0.109836 0.359408 0.257596 -0.5754967 -0.5737923 0.5357992 0.2290963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3458 3558 -0.312301 0.502007 0.082466 -0.5236852 0.0673980 0.0944054 0.8439781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3459 3559 -0.562290 0.024254 0.224220 -0.7082607 0.2630506 -0.5068198 0.4150963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3462 3562 -0.106784 -0.180126 -0.465570 -0.3644134 -0.7512095 -0.3402079 0.4326034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3463 3563 -0.246139 -0.485476 0.233678 -0.0486760 0.1620384 -0.9821445 0.0822576 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3464 3564 0.445978 -0.530029 -0.176272 -0.6061751 -0.7041516 -0.3090828 0.2029534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3466 3566 0.558022 0.156164 0.013266 -0.1126864 0.5951075 -0.7795651 0.1594590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3467 3567 -0.393657 -0.002248 -0.212548 0.3465771 -0.2437925 0.8531945 0.3041524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3468 3568 -0.611134 -0.208961 0.356622 -0.6712999 0.4124236 0.5505325 0.2760022 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3469 3569 0.383283 -0.199566 0.215889 0.0073022 -0.2894796 0.5202494 0.8034231 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3470 3570 0.377651 0.622107 0.161672 0.2896900 0.5024263 0.3877893 0.7164265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3471 3571 0.205822 0.597183 -0.112604 0.3089623 -0.0047770 -0.6286161 0.7136955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3474 3574 -0.000904 0.612511 -0.384462 0.0663891 0.5946623 0.4621478 0.6545140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3475 3575 -0.043546 0.371893 0.298865 0.6154826 -0.1391461 -0.7669785 0.1164622 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3476 3576 0.656522 -0.092485 0.102703 0.1954780 0.1489543 -0.4708745 0.8472769 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3477 3577 0.465273 -0.625750 0.412038 0.0868695 0.2287224 -0.1016595 0.9642640 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3478 3578 -0.442902 -0.376173 0.268305 0.7912396 -0.0036043 0.2046859 0.5762210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3479 3579 0.047945 0.078328 -0.679679 -0.0334893 -0.5560741 0.1852234 0.8095383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3482 3582 0.136837 -0.035377 -0.830244 0.7431339 0.4489406 0.4590714 0.1883025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3483 3583 -0.715739 0.024031 0.343516 -0.0501786 -0.1431818 0.9380482 0.3115232 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3484 3584 -0.323442 0.341319 0.570089 0.5942935 0.2782570 0.0311367 0.7539356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3486 3586 0.183850 -0.576383 -0.461319 0.8382349 0.1650665 -0.0693496 0.5150786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3487 3587 0.747837 -0.268142 0.115004 -0.8687761 0.1838848 -0.3034616 0.3454352 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3488 3588 0.550693 -0.370287 0.353372 -0.3481897 0.5091548 0.4379527 0.6540052 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3489 3589 -0.271214 0.468336 -0.107587 -0.3708941 0.5228458 0.5114900 0.5722306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3490 3590 -0.561031 -0.382110 0.262863 -0.0487615 -0.0651809 0.9651144 0.2488532 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3491 3591 0.060334 -0.339034 -0.775319 0.0286436 -0.2611639 -0.9486378 0.1762364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3493 3593 -0.727556 -0.080118 -0.221231 0.0606550 -0.9389081 0.3349934 0.0505163 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3494 3594 0.529528 -0.273252 0.354221 -0.0257144 -0.1698779 -0.7374827 0.6531459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3495 3595 0.012029 -0.112660 0.641674 0.2216761 -0.7141821 -0.6522153 0.1241725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3496 3596 0.057058 0.296327 -0.619669 -0.8697930 0.1082785 -0.4447209 0.1842804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3497 3597 0.372326 0.487144 0.081578 -0.1703353 -0.1989657 0.8978810 0.3538477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3500 3600 0.541568 0.135637 -0.649979 0.6472716 0.4172242 0.6044861 0.2038626 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3501 3601 -0.296951 -0.054620 0.573241 0.3175416 0.7028648 -0.1236083 0.6243952 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3502 3602 0.623193 -0.064873 0.522263 -0.1339035 -0.8066496 -0.4642731 0.3403479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3505 3605 0.283721 0.012634 -0.756251 0.3975447 0.1243499 0.7098224 0.5680207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3506 3606 0.741734 -0.105879 0.270916 0.4849811 -0.3541086 -0.6555241 0.4579177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3509 3609 0.354397 -0.637351 0.042681 -0.1246393 -0.5387976 0.6355774 0.5387055 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3510 3610 -0.189501 0.658584 -0.055340 -0.1801631 0.0550008 0.2257038 0.9558106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3511 3611 -0.504834 0.195972 0.469719 0.6501443 0.2679238 0.2984289 0.6453445 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3513 3613 0.389040 -0.045058 -0.632220 0.6462510 0.5952099 -0.0146007 0.4773590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3514 3614 -0.551985 -0.123457 -0.273295 -0.2302280 0.2960060 -0.8909248 0.2561805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3515 3615 0.227387 0.506223 -0.154881 -0.6456829 0.1093979 -0.7546374 0.0405977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3516 3616 -0.261958 -0.420360 -0.152962 -0.3605304 0.4354943 -0.4734629 0.6754224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3517 3617 0.485648 0.567459 0.148803 -0.2453397 0.1045822 -0.7288372 0.6306087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3518 3618 -0.452106 -0.277962 0.447260 -0.7071657 0.4653541 -0.5319127 0.0207618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3519 3619 -0.429308 -0.119644 0.536951 0.2381458 0.0066083 -0.8779209 0.4153285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3520 3620 -0.691548 -0.291785 0.395576 -0.1367328 0.9315254 -0.3099426 0.1322879 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3522 3622 0.256312 0.447660 -0.311988 -0.4426820 -0.4624948 0.3888356 0.6625240 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3523 3623 0.511966 0.108551 0.495592 -0.1304679 -0.1185848 0.9843329 0.0021092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3524 3624 0.145839 -0.265715 0.373151 -0.0249823 0.4528476 0.5533692 0.6986326 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3525 3625 -0.397888 -0.400751 -0.370461 -0.4797270 0.8587962 -0.1797255 0.0054636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3526 3626 0.545472 0.216793 -0.055014 -0.2077505 -0.4105805 0.1859993 0.8681403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3527 3627 0.444256 -0.199161 0.192692 -0.0725934 0.1923351 -0.4341871 0.8770513 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3528 3628 -0.768042 0.125762 -0.026157 0.0959836 -0.7614518 0.6192939 0.1656907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3529 3629 -0.372311 0.281091 -0.319199 -0.3359285 -0.7536611 -0.2137744 0.5229221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3530 3630 0.571404 -0.078600 0.097384 0.5644062 0.2871774 0.7699047 0.0788763 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3531 3631 -0.661749 -0.004465 0.130198 -0.6991171 -0.3466028 0.5319526 0.3288286 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3532 3632 -0.449291 -0.226979 -0.123551 0.6479630 0.4857716 0.0675325 0.5827600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3533 3633 0.402430 0.330938 -0.297310 -0.5325356 0.2944741 -0.7892469 0.0823413 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3534 3634 -0.389883 0.366545 0.415395 0.1646137 -0.4050060 0.7464169 0.5017312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3535 3635 -0.501680 0.367346 0.047717 0.2878779 0.1923939 -0.9336311 0.0918908 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3537 3637 -0.432317 -0.260221 -0.093925 -0.4914924 -0.4406398 -0.7285271 0.1830846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3538 3638 0.448645 0.178735 0.285824 -0.3979802 -0.1653350 -0.8930219 0.1295685 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3539 3639 0.150904 -0.165095 -0.309018 0.8256606 0.3712622 0.1780471 0.3856789 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3540 3640 0.310190 -0.306182 0.270364 0.6180231 -0.5742440 -0.2161228 0.4915101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3541 3641 -0.246252 -0.428464 0.311767 0.4370757 -0.0351700 -0.8338362 0.3353282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3542 3642 -0.107144 0.258491 -0.503585 0.2983288 -0.5378760 -0.7572939 0.2195344 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3543 3643 -0.534963 -0.355625 -0.116325 0.6513044 0.5710622 0.4210247 0.2691260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3544 3644 -0.192222 0.464156 0.153148 0.5601786 0.3947226 0.7046785 0.1839082 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3545 3645 -0.118004 0.448471 -0.007019 -0.7357898 -0.3162137 -0.2166726 0.5582788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3546 3646 0.589964 0.193309 -0.255836 -0.5217308 -0.4246916 -0.0158129 0.7397188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3547 3647 -0.619165 0.103968 0.145968 -0.5309793 0.0173146 -0.8408028 0.1039799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3548 3648 0.312774 0.371228 0.090410 -0.7753536 -0.1608647 0.5081125 0.3387787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3549 3649 -0.222392 -0.451576 -0.291483 0.2694228 0.2405165 0.6494859 0.6691272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3550 3650 0.147088 0.460374 -0.363686 -0.1584680 -0.5117131 0.3646177 0.7616374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3551 3651 0.503859 -0.068589 0.282255 0.5353400 0.4017814 -0.3041876 0.6778294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3552 3652 0.254260 0.367296 0.012940 -0.2588889 -0.2148116 0.8806472 0.3336060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3553 3653 0.358753 0.168724 -0.164028 0.5286996 -0.3153395 0.7876549 0.0252467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3554 3654 0.162303 -0.394612 -0.316429 -0.3064845 -0.8961193 0.2141382 0.2391280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3555 3655 -0.065421 -0.000683 0.420641 0.1979880 -0.4980996 0.5110965 0.6719210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3556 3656 -0.393489 -0.093864 -0.395169 -0.3262734 -0.4681706 -0.2588052 0.7793470 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3557 3657 0.016367 -0.313645 -0.267300 -0.4460141 -0.3272624 0.2803045 0.7844744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3558 3658 -0.369970 -0.079954 0.378339 -0.4282421 0.8158263 -0.2189858 0.3210628 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3561 3661 0.512289 -0.201462 -0.322933 0.0854722 -0.0904663 0.9922249 0.0002475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3562 3662 -0.464921 -0.310240 0.509274 0.5733671 0.4043928 0.0540749 0.7104875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3564 3664 -0.601827 0.152279 -0.078417 -0.8620588 -0.3067231 -0.2570979 0.3109279 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3566 3666 -0.534180 -0.027706 0.171961 -0.0099907 0.3585796 -0.6514729 0.6685087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3567 3667 0.211805 0.268977 -0.537176 -0.6916047 0.0013055 0.5954265 0.4088380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3568 3668 -0.138103 0.593938 -0.139757 -0.3873460 -0.6269583 0.1229688 0.6646541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3569 3669 0.334294 -0.716423 0.223500 0.2827472 -0.1988637 -0.1972509 0.9173872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3571 3671 -0.462984 -0.079494 -0.451785 -0.5285265 -0.0636554 0.6593242 0.5309420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3573 3673 -0.690075 0.523572 -0.137653 0.2284743 -0.0977878 -0.2805651 0.9271032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3574 3674 0.598935 0.101546 -0.024407 -0.4800893 -0.1096977 0.1833588 0.8507997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3575 3675 -0.126894 -0.374619 0.005212 0.4051326 0.0808500 0.2266822 0.8820125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3576 3676 0.276857 0.755514 0.203929 0.7107621 0.4185699 -0.0493051 0.5631922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3577 3677 0.448924 -0.353569 0.672115 0.7860873 -0.1523886 -0.5368955 0.2656836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3578 3678 -0.370202 0.474143 0.057310 -0.1159464 0.6800065 0.6447011 0.3294056 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3579 3679 -0.545496 0.048557 -0.293169 0.6581981 0.3149398 0.0055205 0.6837819 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3580 3680 0.509110 0.115105 -0.097259 -0.4789320 0.1292751 0.7063989 0.5048889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3581 3681 -0.083808 0.293253 -0.338954 -0.5740782 0.3757269 -0.5441677 0.4828510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3582 3682 -0.366360 -0.471768 0.295094 -0.5124914 0.5060486 -0.5609124 0.4082213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3585 3685 -0.635126 0.533757 0.113626 -0.4839519 -0.3569607 -0.0361913 0.7981603 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3586 3686 0.259300 -0.017811 0.486891 -0.4919912 -0.2532649 0.4632613 0.6922358 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3587 3687 0.558679 0.158307 0.412312 0.3956376 -0.2049427 -0.0501155 0.8938444 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3588 3688 -0.613674 -0.732707 -0.054469 -0.5937000 -0.3050961 0.4881872 0.5622366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3589 3689 0.311806 0.600104 0.270204 0.3107822 0.1952379 0.6587059 0.6568129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3590 3690 0.321204 0.502422 0.525577 -0.1182501 -0.1662330 0.7482784 0.6312392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3591 3691 0.154333 0.157756 -0.677990 -0.2784209 0.7322227 -0.3499781 0.5136604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3592 3692 0.215499 -0.197857 0.743040 0.0976202 -0.6259210 -0.6005405 0.4878979 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3593 3693 0.715168 0.130617 0.273960 0.1814315 -0.5276155 0.5192946 0.6473311 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3594 3694 0.092980 0.686545 0.377373 0.2440450 0.2092540 0.5778552 0.7501587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3596 3696 -0.706264 -0.481328 0.440289 -0.2456073 0.8681753 -0.4307630 0.0197954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3598 3698 -0.087419 -0.303909 0.686824 -0.2033168 0.0558973 0.9623057 0.1717716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3599 3699 -0.368817 0.619081 0.098328 0.4153495 0.3997525 0.3460059 0.7402450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3602 3702 -0.125265 0.566017 -0.511218 -0.0505534 0.1689536 0.9687852 0.1742249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3603 3703 -0.534597 -0.119861 -0.407796 -0.1069298 -0.1800480 -0.9099501 0.3579659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3604 3704 0.661280 0.556493 -0.299158 0.3638976 0.2092891 -0.8702060 0.2579112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3605 3705 -0.137538 -0.781341 -0.457152 -0.1463060 0.1934050 -0.9537344 0.1777069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3607 3707 0.731204 -0.081357 0.040949 0.1587495 0.3914166 0.1288267 0.8972153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3608 3708 0.625194 0.271348 -0.390935 0.2327874 0.2760549 -0.5113705 0.7798102 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3609 3709 -0.814539 -0.249875 0.108171 0.0727026 -0.3489887 0.5057948 0.7855525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3610 3710 -0.001255 0.703348 0.358269 0.4683765 0.0000612 -0.6854811 0.5574398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3611 3711 -0.277508 0.713095 -0.388540 -0.8589498 0.0788271 -0.2797688 0.4215697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3612 3712 -0.236976 -0.588742 0.309748 -0.2196558 -0.1155828 -0.0403424 0.9678659 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3614 3714 0.405466 0.240277 -0.400774 0.1080561 -0.3083666 0.3818959 0.8645169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3615 3715 -0.190892 -0.614786 0.339524 0.1201602 0.0534212 -0.6974633 0.7044521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3617 3717 -0.740143 -0.056438 0.288008 0.3181917 0.3484511 0.6289513 0.6178642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3619 3719 -0.063640 -0.273514 0.705531 0.0064644 -0.4003623 -0.7812178 0.4789227 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3620 3720 0.470856 -0.122900 -0.212390 0.2756341 -0.6409405 0.3262123 0.6378140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3621 3721 -0.019541 -0.601434 0.404671 -0.1929982 0.3424753 -0.7515121 0.5298036 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3622 3722 0.554939 0.561088 -0.157957 0.2373908 0.4777271 -0.8406058 0.0938315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3623 3723 -0.635404 -0.031917 0.129613 0.2534589 0.0767678 -0.0214614 0.9640564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3625 3725 0.399671 0.241770 0.462426 0.6981372 0.5122617 -0.1934886 0.4612533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3626 3726 0.494645 0.358165 -0.599995 -0.7247173 0.6146757 -0.1873501 0.2487140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3627 3727 0.189848 0.274871 0.313421 0.2373352 -0.1794416 -0.0097748 0.9546608 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3629 3729 -0.196643 -0.060901 0.632468 -0.4203571 0.5622918 -0.6149245 0.3591598 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3631 3731 -0.367718 0.013778 0.457050 0.9210436 0.2956070 0.2524844 0.0233822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3632 3732 -0.469336 -0.457807 -0.174680 -0.6898434 0.0218859 -0.0081564 0.7235818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3633 3733 -0.368342 -0.177545 0.335766 -0.0119012 0.7004336 0.3393749 0.6277546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3634 3734 0.555217 0.102971 0.060926 0.3227651 -0.1984220 -0.5207465 0.7650323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3635 3735 0.383022 -0.185861 -0.076822 -0.0164532 -0.1766495 -0.8345705 0.5215518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3637 3737 0.335747 -0.177038 -0.443733 0.6400029 -0.0877542 0.7631786 0.0159306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3638 3738 -0.002014 -0.023481 0.508789 0.5222648 0.0272630 0.4981882 0.6915957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3639 3739 0.078508 -0.119804 0.644031 -0.4333877 -0.2716180 0.4118821 0.7541564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3640 3740 0.507446 0.171130 -0.319790 0.1478252 -0.1729883 0.1129053 0.9671996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3643 3743 -0.467240 -0.135526 -0.294773 -0.6841258 0.1183660 -0.3420615 0.6332103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3644 3744 0.367025 -0.244894 -0.053385 -0.3578010 -0.4100080 -0.8061317 0.2324296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3645 3745 -0.159096 -0.421075 0.395709 0.5217724 0.4138118 0.7179305 0.2027048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3646 3746 0.129602 0.497855 -0.015458 -0.4816389 -0.2855982 0.8212553 0.1095329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3647 3747 0.255726 0.011323 -0.511052 -0.5691707 0.3767920 -0.6327226 0.3656975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3648 3748 0.374773 -0.280433 -0.481590 0.0162754 -0.0024646 -0.7043856 0.7096266 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3650 3750 -0.004348 0.512289 -0.095727 -0.2652745 0.5856495 0.6945265 0.3229196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3651 3751 -0.391963 0.473619 0.348948 0.1023083 -0.6367743 0.3704322 0.6684545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3652 3752 0.120254 -0.447121 -0.293867 0.2241308 0.6042999 0.0147372 0.7644409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3653 3753 -0.407349 -0.107630 0.134584 -0.5078220 0.5279674 -0.6391043 0.2343351 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3654 3754 -0.408112 -0.240775 0.184313 0.6586058 -0.1139539 0.4883623 0.5610305 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3656 3756 -0.424352 -0.286173 0.021584 0.3220223 0.4633459 0.4585871 0.6865203 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3659 3759 0.225869 0.526592 0.246948 -0.5935474 -0.6757792 -0.0252107 0.4363353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3660 3760 -0.487912 -0.067330 -0.043273 -0.1127897 0.0134299 0.0324639 0.9929976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3661 3761 -0.504580 0.512358 -0.345614 0.0120226 -0.4082898 -0.7541695 0.5141821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3662 3762 -0.572349 0.235015 -0.026032 -0.3779870 0.0622847 -0.2394454 0.8921392 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3664 3764 -0.375448 -0.293491 0.098713 -0.1871089 0.7208103 -0.6510629 0.1467644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3665 3765 0.310587 -0.024015 -0.279802 -0.1546914 0.0819416 0.1499521 0.9730727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3666 3766 -0.053115 -0.710143 -0.094876 -0.4354737 -0.5162328 0.3463258 0.6510951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3667 3767 0.488010 0.169007 0.012432 0.8813687 -0.2298520 0.1033817 0.3995866 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3669 3769 0.366930 -0.400947 0.208901 -0.1417385 0.5632127 0.1151028 0.8058865 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3670 3770 0.425421 0.553151 0.099400 0.1641819 0.3060967 0.8665728 0.3583304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3671 3771 0.170801 0.624368 0.262954 -0.3852454 -0.4207934 -0.6741991 0.4690144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3673 3773 -0.490432 0.014131 0.109538 -0.0248476 -0.8178335 -0.5272014 0.2293243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3674 3774 0.540174 -0.221244 0.001936 -0.0782900 -0.3721361 0.8863735 0.2640594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3675 3775 -0.630307 -0.013755 0.381835 0.2279444 0.7841185 0.1958480 0.5429945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3676 3776 0.331398 0.283192 -0.514065 -0.0487894 0.3919690 0.2835075 0.8738440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3677 3777 -0.383776 0.638432 -0.301639 0.0557108 0.3498643 -0.8011630 0.4823165 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3678 3778 0.484941 0.614764 0.350918 0.2890113 -0.7553206 -0.5686564 0.1503103 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3679 3779 -0.491045 -0.589412 -0.500718 0.6922120 0.5367113 -0.4650975 0.1283271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3680 3780 0.370998 -0.558751 -0.379789 0.7685787 -0.3003095 0.3565250 0.4381677 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3681 3781 -0.624475 0.449724 -0.197008 0.1804252 0.2131439 0.5169819 0.8091638 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3682 3782 0.537080 -0.345020 -0.242976 0.0705815 -0.1750792 -0.9322719 0.3086012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3683 3783 0.138581 0.337044 -0.748730 -0.8539015 0.3009595 0.4215887 0.0503840 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3684 3784 0.070354 -0.652475 0.376593 -0.0149376 -0.2431114 0.7404031 0.6264798 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3685 3785 -0.520222 -0.321068 0.559321 0.2169348 -0.7685779 0.5678701 0.1993762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3686 3786 0.003984 -0.538126 -0.101460 -0.0226648 -0.3104297 0.0440063 0.9493067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3687 3787 0.508233 0.444041 -0.040942 0.7276256 0.0808438 0.4182667 0.5376600 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3688 3788 -0.532726 0.126021 0.143492 -0.4294744 -0.4602433 -0.7405095 0.2353159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3689 3789 0.773957 0.177561 0.316906 -0.4668147 0.3047490 0.8237537 0.1031596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3691 3791 0.178320 0.652287 0.325471 -0.6450492 0.0661550 0.4468857 0.6163021 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3692 3792 0.350550 0.443698 -0.123654 0.0424464 -0.5539612 0.0841348 0.8271920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3693 3793 0.595670 -0.677678 -0.360289 0.4185573 0.1754370 -0.0783687 0.8876317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3694 3794 0.814012 0.412613 0.193153 -0.3108278 0.1784228 -0.7817418 0.5103246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3695 3795 0.174877 -0.661752 -0.353851 0.2947987 0.0712269 0.7789303 0.5488972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3698 3798 -0.120588 0.386937 0.714927 0.2720020 0.1712565 -0.7780451 0.5397518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3699 3799 0.330707 0.659015 -0.496401 -0.7734729 0.0303563 0.0566877 0.6305590 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3700 3800 -0.277877 -0.272155 0.665340 0.3096591 0.6630627 0.6720484 0.1131814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3701 3801 0.374931 0.220826 0.602334 0.3057029 -0.0130538 0.8733036 0.3790990 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3703 3803 0.332346 -0.350952 -0.349746 0.3691341 -0.0603830 -0.7863090 0.4917439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3704 3804 -0.341894 0.067292 -0.603570 -0.5855366 -0.0630135 -0.2389745 0.7720540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3705 3805 0.293730 0.600218 0.180915 0.2767986 -0.0093434 -0.8527908 0.4427675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3707 3807 0.418679 -0.158191 0.574503 -0.4146854 0.7262785 0.2627638 0.4811556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3708 3808 0.160196 0.670282 -0.259487 0.4839785 0.6528724 0.5746734 0.0962961 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3709 3809 -0.269158 0.347611 0.782714 0.2674470 0.0854205 -0.6926874 0.6643490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3711 3811 -0.579891 -0.092965 0.383986 0.0663798 0.0679902 -0.5845542 0.8057713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3712 3812 0.114358 -0.530825 -0.249585 0.5626731 -0.3571694 -0.3921297 0.6340846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3713 3813 -0.488717 0.351787 -0.475413 -0.2437225 0.5099899 -0.2459181 0.7874224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3714 3814 0.274069 -0.003235 -0.754439 0.4758493 0.4588211 0.5131006 0.5475202 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3715 3815 0.558414 -0.286634 0.271034 -0.1152723 -0.1813009 -0.2472618 0.9448301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3716 3816 -0.743851 0.409977 0.052976 0.6680691 -0.4778981 0.5635139 0.0880289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3719 3819 0.451840 0.553785 0.173035 0.2072908 -0.3516417 0.6988776 0.5873233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3720 3820 -0.213111 -0.743951 -0.346246 0.2672781 -0.2754439 -0.3229387 0.8651032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3723 3823 -0.632389 0.024628 -0.184043 0.7477132 -0.1793512 0.6143237 0.1771001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3724 3824 -0.613876 0.336349 -0.022652 0.4596106 -0.0995601 0.7002739 0.5370869 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3725 3825 -0.064088 0.523620 -0.314494 -0.7857158 -0.0062129 0.3803231 0.4878180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3726 3826 -0.086699 -0.153127 0.550518 0.4589051 0.3785176 -0.5796635 0.5568848 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3727 3827 0.713961 0.596149 0.002865 0.2687250 0.3320504 -0.1961743 0.8826353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3728 3828 0.436034 -0.395894 -0.567147 0.6440318 -0.6203705 0.4290360 0.1276383 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3731 3831 -0.440044 0.115995 -0.555349 -0.5469734 -0.1504942 -0.7074620 0.4215081 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3732 3832 -0.412846 -0.009125 -0.410842 -0.0828509 -0.3151054 -0.5938429 0.7356596 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3733 3833 -0.226003 0.328902 -0.505979 -0.1278645 -0.4149399 0.5677059 0.6994180 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3734 3834 0.153213 0.548137 -0.093925 -0.0344697 0.7034697 -0.6832524 0.1926354 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3735 3835 0.143933 0.366238 -0.069952 -0.0477783 -0.2352552 -0.0716874 0.9681080 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3737 3837 -0.440074 0.016567 0.451644 -0.2973009 0.0087495 0.7066554 0.6420076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3739 3839 0.017946 -0.552462 0.105712 0.3065920 0.3348334 -0.2847510 0.8442777 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3741 3841 -0.176256 -0.033044 0.425812 0.0788334 0.1718885 0.2112427 0.9589662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3743 3843 -0.329286 -0.006576 -0.342594 0.8293169 -0.3484454 -0.0054711 0.4367944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3745 3845 -0.092038 0.502158 -0.137958 0.0475753 0.6320831 -0.7094889 0.3079497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3746 3846 0.277638 -0.277862 -0.316306 0.4768977 0.0433231 -0.4912207 0.7275946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3748 3848 0.397088 0.442290 -0.147415 0.7360748 0.4062078 -0.3337435 0.4263852 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3749 3849 -0.411135 -0.286795 -0.070763 0.2029401 -0.4256839 0.6972342 0.5398823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3750 3850 0.280402 -0.242068 0.319167 0.2329291 -0.4193533 -0.8400650 0.2533329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3751 3851 0.133741 0.228010 -0.082096 0.6432187 -0.3977878 0.6399297 0.1361048 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3752 3852 0.375657 -0.339706 0.294505 0.0595584 -0.2175410 0.6423410 0.7324799 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3753 3853 0.088340 -0.099248 -0.516873 0.3217524 0.4285167 0.4899577 0.6875975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3755 3855 0.524815 -0.117830 -0.210140 -0.7598736 0.3058668 0.5710661 0.0540463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3757 3857 0.156814 -0.429063 0.342509 -0.2223340 -0.0862636 0.0346051 0.9705301 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3758 3858 -0.341874 0.361646 -0.174261 -0.0059817 -0.0051566 -0.9940641 0.1085088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3759 3859 0.475217 0.285235 0.229344 -0.0600050 -0.0671052 0.9790407 0.1826898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3760 3860 -0.513155 0.029438 0.126538 0.1004242 0.2625537 -0.1496830 0.9479322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3761 3861 -0.222509 -0.373606 0.308258 0.5522397 -0.0663370 -0.8205127 0.1318694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3762 3862 -0.428727 -0.179924 -0.210632 0.5265597 0.0744368 0.4262510 0.7317815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3763 3863 0.454137 -0.699633 -0.184480 -0.3329188 0.4857337 0.8068752 0.0466935 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3765 3865 0.535833 -0.120006 -0.172023 -0.0859648 0.2160885 -0.8484937 0.4753675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3766 3866 -0.521386 -0.008534 -0.096255 0.6279404 0.4191330 -0.2599120 0.6020499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3767 3867 0.345094 -0.294029 -0.264883 -0.4116591 -0.1084344 -0.8690662 0.2519976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3769 3869 0.089959 -0.354962 0.416584 -0.5460544 -0.0168277 0.2333611 0.8044153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3770 3870 -0.095595 -0.658112 0.320069 0.1442296 0.9617842 0.1511478 0.1769838 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3772 3872 -0.537908 0.482154 0.144844 -0.9389681 0.1361152 -0.1013154 0.2992438 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3773 3873 0.600137 -0.096800 -0.050688 0.0346774 -0.5710535 -0.7445486 0.3440099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3774 3874 -0.560105 -0.197034 -0.189809 -0.5554409 0.2189929 -0.6273087 0.5000112 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3775 3875 -0.254157 0.183241 -0.743646 -0.3656708 0.5852921 -0.2230781 0.6884433 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3776 3876 0.594946 0.079043 -0.204531 -0.2587189 -0.1469097 -0.4686522 0.8317735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3777 3877 -0.163238 -0.119369 -0.664223 -0.4866559 0.2610461 -0.8298446 0.0798680 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3778 3878 -0.411952 0.120110 0.118473 -0.1154095 -0.3861295 -0.4871154 0.7747924 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3779 3879 -0.134089 0.156821 0.801530 0.5917330 0.1470133 0.3646290 0.7037648 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3780 3880 -0.082476 -0.289812 0.613660 0.4080319 0.0665962 0.8773138 0.2437118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3781 3881 0.363007 0.495719 -0.534001 -0.1157602 -0.4654529 -0.8128629 0.3304649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3782 3882 -0.382713 0.239507 -0.456819 0.3001451 0.2720085 0.7570179 0.5126872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3783 3883 0.326634 -0.416631 0.278994 0.2256685 -0.0384640 -0.0776216 0.9703449 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3784 3884 -0.456129 -0.370480 0.479260 -0.1951197 0.4650571 -0.3410481 0.7933073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3785 3885 0.720172 -0.006589 0.006054 -0.0550091 -0.7966958 -0.0708924 0.5976822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3786 3886 0.142521 -0.699449 -0.249907 -0.3658285 0.1317249 -0.5818181 0.7143569 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3787 3887 0.549150 -0.387083 0.149507 0.1100859 -0.3539353 -0.5483714 0.7495997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3789 3889 -0.741196 -0.313562 -0.180279 -0.3603136 -0.0905615 0.8087256 0.4559996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3790 3890 -0.253435 -0.528558 0.377011 0.5485804 -0.2359837 -0.8000267 0.0576941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3791 3891 0.405942 -0.436951 0.451024 -0.6086128 -0.1930385 -0.2286013 0.7348933 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3792 3892 0.265504 0.695991 -0.402005 -0.3408257 0.5036445 -0.3818217 0.6959829 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3794 3894 -0.252572 0.150746 0.617813 0.3271675 0.6800766 -0.1882219 0.6285140 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3795 3895 -0.683279 -0.020195 0.000076 0.2511062 0.2824011 0.9242315 0.0546932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3796 3896 -0.713245 0.248496 0.173136 -0.6947268 0.1778286 0.3649214 0.5937710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3797 3897 -0.659277 -0.029309 -0.370230 -0.0670539 -0.5979872 -0.3590729 0.7134296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3800 3900 -0.013420 0.619647 -0.234002 -0.0935001 -0.6440808 -0.5077464 0.5644566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3802 3902 -0.377757 -0.664974 -0.137558 -0.1239397 -0.9333029 -0.1880027 0.2797136 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3803 3903 0.343716 0.239600 -0.704901 -0.5537801 -0.7135739 -0.0408479 0.4271666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3804 3904 -0.431961 0.638088 -0.349984 0.6662671 0.3773757 -0.6393147 0.0703738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3806 3906 0.039325 0.800797 -0.052825 -0.3591830 -0.2098082 0.0698639 0.9066902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3807 3907 -0.369974 -0.507962 -0.047564 -0.7842396 -0.0325897 -0.2792111 0.5531251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3810 3910 0.361745 0.490259 -0.253719 -0.6375889 -0.5033443 0.1790766 0.5550284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3811 3911 -0.019112 -0.670338 0.336974 -0.1848936 0.6043872 0.5009715 0.5912343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3812 3912 0.688171 -0.134224 0.204492 -0.2484107 -0.7138038 -0.6527946 0.0513366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3813 3913 0.157317 0.457145 -0.476010 0.1764118 -0.2826190 -0.7181700 0.6109315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3814 3914 -0.014929 -0.468213 0.096447 0.5613665 -0.0636681 -0.3414958 0.7511289 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3815 3915 0.855429 0.271326 -0.003886 0.5257601 -0.0663631 -0.8172386 0.2264802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3818 3918 -0.087945 -0.080718 -0.664518 0.5453334 -0.6846765 0.3588217 0.3241551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3820 3920 0.141649 -0.585843 0.069088 -0.6016778 -0.2474587 -0.5751808 0.4958983 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3821 3921 -0.503359 -0.211862 0.488845 0.0057707 -0.5261524 0.8488686 0.0505212 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3823 3923 -0.171964 0.355932 -0.331857 -0.1564885 -0.9205087 -0.3576039 0.0171642 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3826 3926 -0.512797 -0.185482 0.296184 0.4154647 -0.4543647 -0.7323488 0.2908729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3827 3927 0.177370 0.470208 -0.228860 -0.3955371 -0.8479723 0.3188612 0.1510661 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3828 3928 -0.051035 -0.039713 0.436574 0.5449208 -0.0012554 0.2304339 0.8062010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3829 3929 0.280428 0.353435 -0.320323 0.1540745 0.4990296 -0.2205698 0.8237594 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3831 3931 -0.326907 -0.191739 -0.443051 -0.3187673 -0.0180836 -0.2484200 0.9145206 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3832 3932 -0.407516 -0.335479 -0.280330 0.0426915 0.8454956 -0.5112429 0.1481399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3833 3933 -0.079362 0.635836 -0.349085 -0.3188948 0.4681414 0.7621980 0.3133750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3834 3934 -0.183895 0.158113 -0.462938 0.5892786 -0.6092618 0.2585835 0.4633416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3835 3935 -0.375215 0.623694 -0.063337 0.1731207 0.1430176 -0.1413099 0.9641611 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3836 3936 -0.431957 -0.198879 -0.036267 -0.0843193 -0.2297235 -0.4687733 0.8487455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3837 3937 -0.101726 0.374516 0.374110 0.0250950 -0.9057436 0.3494664 0.2384785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3840 3940 -0.042327 -0.288566 0.428783 -0.1480119 0.7723734 0.5558585 0.2693568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3841 3941 -0.278306 0.157038 0.348832 0.3378545 -0.4679953 0.7518202 0.3187493 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3843 3943 -0.391278 -0.216129 0.411206 -0.5722655 0.0658360 -0.6190479 0.5338141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3844 3944 -0.556930 0.054366 -0.064553 0.8544016 -0.3001065 -0.3605198 0.2235161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3845 3945 -0.021281 0.180225 -0.574691 0.7906149 0.5944398 -0.0133904 0.1462536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3846 3946 0.462627 0.047198 0.038261 0.2488296 0.0608795 -0.5505607 0.7945190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3847 3947 -0.097396 -0.501284 0.195465 0.4892633 -0.7686510 -0.3957397 0.1148355 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3848 3948 0.252850 0.159913 -0.425043 0.3625177 0.5544246 0.6692359 0.3366268 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3849 3949 -0.039250 0.317372 0.320860 0.3172381 0.2364663 -0.4101771 0.8217046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3850 3950 -0.342470 0.343023 -0.094393 0.3209430 -0.1462082 0.6180405 0.7025985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3851 3951 -0.202948 -0.400952 -0.200038 0.6268641 0.3515089 -0.4649624 0.5170037 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3854 3954 -0.037664 -0.477655 -0.111016 0.2289871 0.2889231 -0.4181773 0.8301904 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3855 3955 0.091375 -0.348515 -0.430736 0.1108090 -0.8813960 -0.0133620 0.4590031 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3856 3956 -0.311425 -0.282581 0.080400 -0.5142075 0.1846619 -0.0653819 0.8349945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3857 3957 0.089186 -0.507957 -0.098191 -0.7125740 0.2623903 0.0540805 0.6484327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3858 3958 0.231774 -0.482646 -0.321779 0.6149107 -0.3362444 -0.4131354 0.5815013 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3859 3959 -0.333620 -0.180914 0.070404 0.0081813 -0.3915932 -0.2864651 0.8743715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3860 3960 -0.363616 -0.160758 -0.203584 0.6842102 -0.0002510 0.6269507 0.3725442 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3861 3961 -0.246652 0.392652 0.261559 0.1387792 -0.8271809 0.5143382 0.1787970 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3863 3963 -0.054847 -0.113496 -0.573585 -0.4357844 -0.7805906 0.0150211 0.4478220 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3864 3964 0.229380 -0.014589 0.590418 -0.8492890 -0.1525145 0.3561698 0.3585953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3865 3965 -0.138239 0.438555 -0.173289 0.1655102 -0.1998545 0.9525398 0.1591616 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3866 3966 0.057914 -0.662867 -0.021624 0.7337503 -0.1963013 -0.2759048 0.5890270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3867 3967 -0.160446 0.669664 0.069685 0.3125172 0.1965238 0.5377124 0.7580084 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3868 3968 -0.360952 -0.520519 -0.112927 0.4112121 0.7145901 0.1656985 0.5411188 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3869 3969 -0.254883 -0.484293 -0.304538 0.0415832 0.2628068 0.3715923 0.8894507 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3871 3971 -0.273205 -0.548048 0.315025 -0.5094214 -0.8269124 -0.2211104 0.0884073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3872 3972 -0.755219 -0.300726 -0.168077 0.7131838 0.3324991 -0.3827232 0.4840828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3873 3973 -0.378787 0.133253 -0.385108 -0.1282382 -0.3942227 0.0540709 0.9084161 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3874 3974 0.136524 -0.060666 -0.704762 0.9147212 -0.1898666 0.2644184 0.2394133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3876 3976 0.113995 0.670757 -0.249058 -0.0177687 -0.2515350 0.8414629 0.4778646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3877 3977 -0.457109 0.371216 -0.297950 -0.0816543 0.1028942 0.9784945 0.1590404 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3879 3979 0.020824 0.839287 -0.052551 0.3768761 0.1130893 0.7163682 0.5761873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3880 3980 0.412375 0.409643 0.408209 -0.1473678 0.8844651 -0.2214723 0.3833462 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3881 3981 -0.589175 -0.395797 0.231759 0.0211226 -0.1250168 -0.1995771 0.9716448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3882 3982 0.198078 -0.098356 -0.490242 -0.0007849 -0.2737638 0.9550079 0.1140733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3883 3983 0.470839 -0.040476 0.615898 0.1231707 -0.1170648 -0.7444384 0.6457060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3884 3984 -0.135108 -0.719675 -0.067772 -0.6275140 -0.1504528 0.6462526 0.4073668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3886 3986 0.728564 0.242950 -0.203883 0.5616740 0.0054745 0.3840515 0.7328007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3887 3987 0.445643 0.274368 -0.517222 -0.2043910 0.0959811 0.7279930 0.6473315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3888 3988 0.213187 -0.405041 0.722609 -0.7485561 0.1021686 0.1940046 0.6257695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3889 3989 0.087455 0.698297 -0.225047 -0.1284243 -0.8030984 0.0557489 0.5791651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3890 3990 -0.134575 0.642145 0.349292 0.6479697 0.5301807 -0.5323245 0.1251968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3892 3992 -0.256693 0.739098 0.152873 -0.0113243 -0.4689610 -0.7835375 0.4074511 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3893 3993 0.412454 -0.337923 0.348238 0.0710786 -0.4415788 0.2589274 0.8561032 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3894 3994 -0.694079 -0.218493 -0.359830 -0.7074622 0.4684464 0.5228531 0.0817302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3895 3995 0.818767 0.041828 -0.038616 -0.2339656 0.9091808 -0.2776795 0.2038247 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3896 3996 -0.439969 0.265517 0.208962 0.6260221 -0.0630301 -0.3672806 0.6850025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3897 3997 -0.225384 -0.744926 0.373209 -0.4627295 -0.1950800 -0.8644860 0.0221158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3899 3999 0.474093 -0.294948 0.214663 -0.0524306 -0.2362099 0.4686920 0.8495786 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3900 4000 -0.679705 0.146356 0.460319 -0.3193197 -0.6314014 -0.4550377 0.5406551 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3901 4001 -0.596144 -0.170685 -0.282331 0.1823515 0.1054288 0.9511084 0.2258884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3902 4002 0.406790 -0.548437 -0.137507 0.0417065 0.0997505 -0.0018809 0.9941362 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3904 4004 0.542177 -0.409285 0.190346 0.1350053 -0.1940640 -0.8284992 0.5076434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3905 4005 -0.129429 -0.578337 -0.248974 -0.2402489 -0.2005212 0.0833793 0.9461076 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3906 4006 0.133671 0.575723 0.210616 0.1770549 0.4436167 0.8009223 0.3610808 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3907 4007 -0.435114 0.010629 -0.719493 -0.0741524 0.0376438 -0.9953236 0.0491461 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3908 4008 0.400830 -0.289770 0.281260 0.3504284 0.4036679 -0.8425404 0.0661646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3909 4009 0.674340 0.209780 0.434001 -0.2314856 -0.4363287 -0.7630379 0.4168991 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3910 4010 0.408948 0.311849 0.140196 -0.1256511 0.4210998 -0.7131684 0.5461479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3911 4011 -0.313014 -0.233789 -0.534022 -0.1972308 -0.7572569 -0.2345117 0.5767723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3912 4012 -0.556649 0.469492 -0.080021 0.0011789 -0.7162119 -0.4627812 0.5223722 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3913 4013 -0.431173 -0.375982 -0.164122 -0.8362239 0.0490917 0.2243815 0.4979684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3914 4014 0.222711 0.254521 0.487010 -0.0679242 -0.1470345 -0.9803470 0.1126364 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3915 4015 -0.454538 -0.211182 -0.642801 0.5514971 -0.4137473 -0.7085247 0.1505221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3916 4016 -0.480245 0.168263 -0.552554 -0.2895151 -0.1804367 -0.6179862 0.7083196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3918 4018 -0.189207 0.096830 0.530361 -0.5850444 -0.5693485 -0.5697510 0.0946002 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3921 4021 0.472032 -0.212862 0.737523 0.1999588 0.5665074 -0.4294920 0.6742570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3922 4022 -0.199441 -0.474437 -0.252339 0.2823583 0.0797592 -0.2622469 0.9193143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3923 4023 0.195925 -0.114918 0.533756 0.0331119 -0.2752140 0.3530860 0.8935833 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3924 4024 0.200313 -0.236362 -0.413987 0.0526172 0.4480326 -0.4726436 0.7570378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3925 4025 -0.074393 -0.412031 -0.011987 -0.3544561 0.0026553 0.7225470 0.5935314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3926 4026 0.288422 0.344833 0.394042 0.7286447 -0.3989195 -0.2617078 0.4913747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3927 4027 0.363516 0.426571 -0.371687 0.1187032 0.5293007 0.2976725 0.7855835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3928 4028 -0.182113 0.495472 0.143735 -0.1184023 -0.4875661 0.7233014 0.4744421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3930 4030 -0.049585 -0.268144 0.463532 0.1528737 -0.3334592 -0.7519652 0.5477069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3931 4031 -0.508485 0.010589 -0.299334 0.3295436 -0.7684503 0.3672649 0.4074329 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3932 4032 0.349594 0.017113 0.393333 0.5515792 0.1506923 -0.7737588 0.2726710 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3933 4033 0.281937 -0.073835 0.452949 0.3138933 -0.4967713 -0.1064668 0.8020936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3934 4034 -0.355533 0.085272 0.170495 -0.2973342 -0.0985620 0.3766185 0.8718007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3935 4035 -0.289109 0.418250 -0.218811 -0.4435186 -0.4397013 0.4598922 0.6312315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3936 4036 0.230998 -0.479224 0.058516 -0.6495108 0.3938400 -0.2554356 0.5981459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3937 4037 0.265006 0.045534 -0.635030 0.1895772 -0.4627307 0.5795709 0.6434581 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3938 4038 0.274014 0.469158 -0.321784 0.1669246 -0.8566621 -0.4878526 0.0163125 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3939 4039 0.189241 0.321377 0.262134 0.6038966 0.5271244 -0.5418907 0.2525932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3940 4040 -0.346546 0.177806 -0.404821 -0.0650024 0.2313517 -0.5088277 0.8266471 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3942 4042 0.236444 -0.228975 -0.313137 0.3307699 0.1268719 0.7465443 0.5631753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3943 4043 0.392400 -0.364162 -0.055181 0.8048098 -0.0696638 -0.4075057 0.4258723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3944 4044 -0.267376 0.169782 0.479882 -0.5177066 0.5619502 -0.3127395 0.5642568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3945 4045 0.040532 -0.165194 0.454099 -0.1936661 -0.1081835 0.8111719 0.5411006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3947 4047 0.341446 -0.352697 -0.200096 -0.2664921 -0.4638952 -0.6267316 0.5665604 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3948 4048 0.026995 -0.341618 0.424901 -0.1311799 -0.1564301 -0.7482228 0.6312559 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3949 4049 -0.464637 0.231905 -0.144495 -0.6364631 0.3271877 0.1183560 0.6883711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3951 4051 0.089366 -0.222075 0.536556 -0.1364002 -0.2516235 -0.7408940 0.6075826 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3952 4052 -0.405278 -0.398526 0.001749 -0.6600083 -0.2570047 0.0859244 0.7006815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3953 4053 -0.242380 -0.216450 -0.072518 -0.7041954 0.1660988 0.1971001 0.6615675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3954 4054 0.418803 -0.255700 0.285555 -0.1889732 -0.5136430 0.6227127 0.5591859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3956 4056 -0.031858 -0.172835 -0.410839 0.3494058 -0.5682169 0.1029929 0.7378602 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3957 4057 0.248914 -0.069609 -0.358198 -0.3658111 0.0810006 -0.9243252 0.0724158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3958 4058 0.518712 0.080330 -0.002965 -0.5030224 -0.0402201 -0.8108940 0.2963137 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3959 4059 0.206325 -0.227254 0.349143 -0.3611808 -0.0076428 0.9152679 0.1782544 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3960 4060 -0.364615 0.121508 -0.261517 -0.7607386 0.4670320 0.4201284 0.1632480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3961 4061 0.167248 0.101007 -0.317463 0.1914402 -0.5602861 0.1808393 0.7853199 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3962 4062 0.118657 0.036977 -0.534439 -0.4573541 -0.1293457 -0.3504524 0.8070192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3964 4064 -0.225949 -0.472034 -0.453036 -0.2260984 -0.2607413 -0.5425884 0.7658272 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3967 4067 -0.022632 0.458569 -0.422234 -0.3811464 -0.3187805 -0.8374190 0.2276749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3968 4068 -0.351711 -0.463685 -0.271414 -0.4793818 -0.3845652 0.7672555 0.1833623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3969 4069 -0.385421 -0.431543 -0.405099 0.5629992 -0.0985943 -0.7256764 0.3830207 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3970 4070 0.053347 -0.568893 0.277449 -0.1993098 -0.2660701 0.6875226 0.6455966 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3971 4071 -0.080032 -0.372851 -0.754763 -0.1536495 0.2601170 -0.9420665 0.1457455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3972 4072 0.090311 -0.383459 0.407679 -0.4485858 -0.5295481 -0.5223479 0.4954818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3974 4074 -0.300683 -0.514652 0.438092 -0.1183438 0.4198650 -0.7727138 0.4611090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3975 4075 -0.083500 0.566291 0.245790 -0.4141491 0.1964561 0.6609323 0.5941835 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3976 4076 0.509149 -0.181994 -0.474252 -0.0911221 -0.3421324 -0.9147156 0.1947756 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3977 4077 0.802521 -0.450770 -0.165709 0.4297596 -0.2627078 0.3600944 0.7852537 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3979 4079 0.600819 -0.154036 -0.026429 -0.1423463 -0.3325035 -0.1245208 0.9239446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3980 4080 -0.595826 0.215788 -0.074774 0.4279662 -0.2034875 0.6266642 0.6186516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3981 4081 -0.212056 -0.699127 0.190494 -0.4377042 -0.3669641 -0.5686045 0.5919809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3983 4083 -0.006120 0.547970 0.358169 0.1216201 -0.4405760 0.8792038 0.1345441 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3985 4085 -0.398921 -0.397039 0.353135 -0.2077370 0.3711107 0.0118402 0.9049762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3986 4086 0.669825 -0.493005 -0.111423 -0.5395056 -0.5040206 -0.3723483 0.5623644 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3987 4087 0.334484 -0.455546 -0.475177 -0.1787901 0.4067401 0.0373305 0.8950995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3988 4088 -0.175059 -0.417860 -0.470379 -0.0156969 -0.5380671 0.1701398 0.8254029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3989 4089 0.315567 0.712571 0.249360 0.5223868 -0.3588338 0.5533839 0.5404781 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3990 4090 0.060755 -0.441746 -0.606937 -0.4716590 -0.7718752 0.1394388 0.4028689 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3991 4091 -0.282138 -0.104192 -0.579142 0.4701479 -0.5812549 -0.5212586 0.4115741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3992 4092 -0.036863 -0.403801 0.677096 -0.0635915 0.3749016 -0.4270314 0.8203957 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3993 4093 0.621391 -0.572090 0.094117 0.1900738 -0.2936817 0.1698321 0.9212926 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3994 4094 0.399616 0.410893 0.527144 -0.1103809 -0.3973190 -0.8813092 0.2307548 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3995 4095 -0.828400 -0.031397 0.128710 0.5444501 -0.4315970 0.7186800 0.0282343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3997 4097 0.075465 0.740978 -0.155818 0.4553507 -0.1229412 -0.6953644 0.5422265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3998 4098 -0.135329 -0.413634 -0.687152 0.7825954 0.1266464 -0.2730172 0.5449466 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 3999 4099 0.284619 -0.856378 0.254879 -0.1698421 -0.7340294 0.1680058 0.6357110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4000 4100 0.535500 -0.609524 0.183722 0.0777435 0.2267538 -0.4763176 0.8459670 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4001 4101 0.357981 0.390359 -0.511613 -0.2891575 -0.1313557 0.5172346 0.7947339 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4002 4102 0.486002 -0.499227 -0.035511 -0.5781047 -0.3394406 -0.4471058 0.5921751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4004 4104 0.228378 0.815052 -0.058849 -0.0679851 0.2178297 0.8413866 0.4898946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4005 4105 -0.574486 -0.385328 -0.380223 0.4124010 0.1415977 -0.7217987 0.5374775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4006 4106 0.282477 -0.102704 0.482795 0.0544970 0.3054037 0.5304700 0.7888981 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4007 4107 0.344923 0.062585 -0.648871 0.3267520 0.2215996 0.7787741 0.4874810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4011 4111 -0.375119 -0.565150 0.321967 0.0554621 0.9347174 -0.0906886 0.3391208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4012 4112 0.101588 -0.128926 0.718282 0.2419329 0.3037033 0.7232477 0.5710916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4013 4113 -0.216811 0.497206 -0.300210 -0.1150148 -0.9732137 -0.1035335 0.1700221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4016 4116 -0.437557 -0.327046 -0.225622 -0.0986433 0.1343198 -0.0627206 0.9840192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4017 4117 0.365625 0.610030 0.422889 -0.0715511 -0.6993404 0.4987672 0.5069859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4018 4118 0.463207 0.135931 -0.322828 0.3792004 0.0291211 -0.4473434 0.8094708 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4019 4119 0.346346 -0.025555 0.586305 -0.1952968 -0.3515891 0.3037259 0.8637099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4020 4120 -0.319623 -0.456216 -0.189959 -0.1273250 0.3229149 -0.8533352 0.3890159 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4021 4121 -0.529783 0.130104 0.472887 -0.8028942 -0.2628015 0.5283491 0.0845191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4023 4123 0.226753 -0.609565 0.354951 -0.3154812 -0.0037399 0.5046805 0.8035890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4025 4125 -0.420471 0.176942 -0.290575 -0.2961120 -0.3083107 -0.2931090 0.8551897 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4026 4126 -0.152129 0.001299 -0.539039 -0.1613517 -0.1360231 -0.9418965 0.2613318 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4027 4127 0.539811 0.166035 0.376365 0.0759119 0.1025927 -0.9851244 0.1150743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4028 4128 0.658838 -0.248706 -0.142062 0.2124326 0.3821261 0.8154472 0.3793388 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4029 4129 0.650939 0.201313 0.197918 0.7107228 -0.0884332 -0.6872748 0.1212684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4030 4130 0.499414 0.216704 0.334307 0.5363353 -0.5995479 -0.4065502 0.4331325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4031 4131 -0.324394 0.301712 0.352894 0.8199088 -0.2878994 0.4028848 0.2873105 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4032 4132 -0.446029 -0.075604 -0.220898 -0.5339995 0.3505063 0.0482871 0.7678920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4033 4133 0.435880 -0.003538 -0.214320 -0.1281946 0.0910761 0.9418608 0.2969337 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4034 4134 -0.509419 0.244307 0.288199 0.6948819 -0.1837573 0.6491837 0.2488632 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4035 4135 0.212153 0.553174 0.304908 0.2500854 -0.2085737 0.8465611 0.4210566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4036 4136 0.565082 -0.124655 0.036714 0.2013162 0.0318866 0.4812511 0.8525564 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4037 4137 -0.188810 -0.094135 -0.539015 0.2781583 -0.6243402 -0.2983280 0.6662039 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4038 4138 -0.068158 -0.178440 0.578874 -0.5202784 0.3257909 -0.7162828 0.3318277 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4039 4139 -0.296695 -0.294984 -0.492740 -0.7903173 -0.4065049 0.3102883 0.3374516 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4040 4140 -0.032456 0.001210 -0.629425 0.5430687 0.6519721 -0.3720085 0.3763222 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4041 4141 -0.004620 -0.290370 0.405873 -0.3165311 -0.6313413 -0.5189205 0.4815992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4042 4142 -0.516610 -0.450758 0.106616 0.5917748 0.3834326 -0.4952463 0.5074575 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4043 4143 0.349192 0.061867 -0.104967 -0.6512056 0.1858898 0.2428316 0.6945567 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4044 4144 -0.076376 -0.639666 -0.214111 -0.2773532 -0.2011924 0.7884083 0.5108906 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4045 4145 -0.331598 -0.166163 0.375650 -0.6341046 -0.0666637 -0.7535166 0.1602500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4046 4146 0.020238 -0.493838 0.215913 -0.1921336 -0.8399116 0.4959063 0.1082132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4047 4147 -0.377629 0.110615 -0.327242 -0.4618473 -0.3801947 0.1277318 0.7910965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4048 4148 0.422083 0.363956 0.235028 -0.0167725 0.5862885 0.6603148 0.4690083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4049 4149 -0.376393 0.417551 -0.157269 0.4883702 0.6730766 -0.5178778 0.2006615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4050 4150 -0.288372 -0.044902 -0.466508 0.0932173 -0.2792997 -0.5208351 0.8012696 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4052 4152 -0.512610 -0.181792 -0.164202 -0.0627189 0.0525940 -0.9672655 0.2402034 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4053 4153 -0.262538 0.232054 -0.219788 0.6712791 -0.0417756 -0.7378990 0.0560733 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4054 4154 -0.062744 -0.667571 0.014997 -0.1107512 0.2325413 -0.4552689 0.8522846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4055 4155 0.170062 0.121726 0.535631 -0.3480395 0.5093724 0.7458974 0.2510884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4057 4157 -0.513730 0.240999 -0.050429 -0.5838959 -0.3354037 0.3264319 0.6633341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4058 4158 -0.238096 0.306735 0.444780 0.2365892 0.5493107 0.5012082 0.6253587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4059 4159 -0.463843 0.187842 -0.016105 -0.0033240 -0.1609449 -0.9514823 0.2622350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4060 4160 0.146290 0.387386 0.385905 -0.0782965 -0.4564182 -0.6292896 0.6241368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4061 4161 -0.114415 -0.261021 -0.335705 -0.2514783 0.1994188 -0.9379530 0.1312818 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4062 4162 -0.404249 0.523507 -0.284925 0.1399366 0.4827130 0.6247575 0.5975651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4063 4163 0.533825 -0.166591 -0.445706 -0.6639509 0.1177504 -0.4322334 0.5987306 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4064 4164 0.097636 -0.317388 -0.462640 0.2675171 -0.7981354 0.4052452 0.3566382 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4065 4165 -0.074291 0.538234 -0.281878 -0.0959192 -0.6859127 0.3769176 0.6150256 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4066 4166 0.113418 0.413792 -0.381116 0.5099667 0.3300311 -0.0681888 0.7914314 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4067 4167 -0.549310 -0.289412 0.245020 0.0823730 0.6632237 -0.1287796 0.7326424 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4068 4168 -0.232976 0.567429 0.433913 -0.2968873 0.3098712 -0.9009258 0.0645791 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4070 4170 -0.598642 -0.164847 -0.036282 -0.5450317 0.6532862 -0.5159797 0.0996120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4071 4171 0.072230 0.368087 -0.506985 -0.5216509 0.1809247 0.3112329 0.7734861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4072 4172 0.449482 0.116788 -0.369045 0.1881926 0.1092431 0.5016400 0.8372615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4074 4174 0.624894 -0.277644 0.371451 -0.0977182 -0.2186270 -0.8760137 0.4186328 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4075 4175 0.457228 0.013266 0.648315 -0.5054876 0.5426764 0.3558798 0.5686248 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4076 4176 -0.631767 0.034380 -0.377677 0.1171239 0.3843724 0.0585186 0.9138465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4078 4178 0.432332 -0.630705 -0.175345 -0.6867568 0.1196420 0.7024703 0.1434795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4079 4179 0.390277 0.171174 -0.580130 -0.4669297 0.0259682 0.5294004 0.7078401 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4080 4180 -0.186780 0.616532 -0.609613 -0.2574536 0.2719663 0.5189777 0.7683841 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4082 4182 0.561181 0.183094 0.031735 -0.9022198 -0.2373689 -0.1944720 0.3030448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4083 4183 0.132806 -0.546792 -0.186675 -0.1144279 0.6307777 -0.5931458 0.4870357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4084 4184 0.261711 0.540417 -0.271938 -0.2830159 -0.1854836 -0.9401120 0.0410753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4086 4186 -0.109517 0.349771 -0.548380 -0.0605935 0.0794167 0.7413650 0.6636260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4090 4190 -0.677523 0.145682 -0.043057 0.6994853 0.3638771 -0.5641644 0.2450149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4091 4191 0.519119 -0.580863 0.302811 -0.7669361 0.0835558 0.4356576 0.4637132 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4092 4192 -0.140344 -0.379771 0.520057 -0.3611425 0.2771868 0.3710202 0.8093748 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4094 4194 -0.341974 0.180442 0.580642 0.7627996 0.1564929 -0.2429471 0.5784665 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4095 4195 0.532936 0.377349 -0.349751 -0.3186571 0.2890326 -0.6573770 0.6186867 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4096 4196 -0.691686 0.255524 0.314127 0.1992353 0.1543067 -0.9614652 0.1099068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4098 4198 0.412462 -0.246009 0.456002 -0.4934480 -0.6073903 0.1842248 0.5946825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4100 4200 0.597126 0.282014 0.358266 0.2167174 0.6683267 0.7044647 0.1005113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4101 4201 0.546947 0.359971 -0.513378 0.6920029 0.5133370 0.4186412 0.2869784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4102 4202 0.161267 0.341530 -0.473908 -0.7983835 0.2825064 0.0425257 0.5300617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4103 4203 0.461592 -0.519483 0.086876 -0.1853116 -0.2707047 0.8326553 0.4461656 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4104 4204 0.476235 -0.451387 0.405419 0.0804314 -0.5164587 0.5627616 0.6403909 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4105 4205 0.492844 -0.500526 0.350464 0.3859480 -0.5899003 0.2959559 0.6445711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4106 4206 -0.081334 0.071313 0.795483 0.1624909 0.5379379 0.8032095 0.1976716 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4107 4207 0.098084 -0.642261 -0.469261 0.2739295 0.3410456 0.5596380 0.7038862 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4108 4208 0.267493 -0.520989 0.426314 0.0357637 -0.2368374 0.6313206 0.7376064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4109 4209 0.555049 -0.129961 -0.574107 0.3313980 0.2760766 0.8039873 0.4093428 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4110 4210 0.737718 0.142533 -0.328572 -0.2109006 0.8684084 0.3094615 0.3249944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4111 4211 0.069005 -0.625672 -0.406113 0.0240565 -0.6047589 0.6457537 0.4654998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4112 4212 -0.159919 0.247666 0.652323 0.3411077 0.5501357 0.7313272 0.2148416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4113 4213 0.428498 0.419131 0.592408 0.9362988 -0.1155447 0.1756751 0.2813045 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4114 4214 -0.332877 0.000585 -0.807151 -0.0028216 -0.0669680 -0.1048069 0.9922312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4115 4215 -0.158456 -0.697795 -0.037776 -0.5011554 -0.5647734 0.4373043 0.4885072 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4116 4216 -0.341496 -0.221150 -0.507854 -0.1551702 0.1022294 -0.9125186 0.3643915 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4117 4217 0.425207 -0.218209 -0.463801 0.5370650 -0.1217285 -0.6338462 0.5431228 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4119 4219 0.506557 -0.573116 0.237227 0.2232952 0.0328430 -0.1335072 0.9650059 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4120 4220 0.681043 0.168391 -0.154038 0.3780633 -0.2622619 -0.8867711 0.0438620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4121 4221 -0.501669 -0.438077 0.393911 -0.6777678 0.5881567 0.2231939 0.3806403 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4122 4222 0.395362 -0.477098 0.273786 0.1182685 0.2730149 0.8546735 0.4254510 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4124 4224 0.058689 0.603854 -0.212837 -0.8263656 0.1384020 0.4796250 0.2606237 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4125 4225 -0.583146 -0.261681 -0.007808 0.0188053 -0.0333433 0.8821076 0.4694898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4126 4226 -0.208553 -0.167018 -0.579627 0.5262009 -0.6409955 0.5456230 0.1205528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4127 4227 -0.508829 -0.180194 0.349141 -0.3480704 -0.3130555 -0.0160734 0.8835071 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4129 4229 -0.294362 -0.155648 -0.719563 0.1035335 0.0783744 -0.4150570 0.9004809 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4131 4231 -0.006115 0.282401 -0.561301 -0.8432144 0.0042597 -0.3433361 0.4136324 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4132 4232 -0.539198 0.266330 -0.355096 0.1160431 -0.2521705 0.6337048 0.7220542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4134 4234 0.439468 0.061318 -0.467721 0.3007308 0.2353204 0.5983319 0.7044035 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4135 4235 0.435078 -0.363533 -0.037067 -0.6172920 -0.0200662 0.4188558 0.6656634 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4137 4237 -0.394111 -0.336380 0.124621 0.2959628 0.6111245 -0.0607401 0.7316033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4139 4239 -0.068894 0.240942 0.408554 -0.3897268 0.1199189 0.9028619 0.1362822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4142 4242 0.074803 -0.441324 0.482596 -0.3289858 0.2493346 -0.1770976 0.8934411 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4143 4243 0.607512 -0.340006 0.056912 -0.0682800 -0.6422766 0.6566802 0.3893453 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4144 4244 -0.220690 0.421928 -0.005938 -0.5334962 -0.3150012 0.5947759 0.5122476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4145 4245 0.503127 0.247628 -0.206074 0.7124710 -0.2105524 -0.1627402 0.6492830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4147 4247 -0.518943 0.272218 0.300974 -0.1621230 0.5714527 -0.7945264 0.1260384 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4148 4248 -0.361904 -0.124219 0.680250 0.0102538 0.5046264 -0.4943657 0.7077073 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4149 4249 0.231203 -0.014424 -0.115634 0.1171870 -0.4988151 0.6578315 0.5520040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4150 4250 -0.296248 -0.472860 -0.085645 0.0321241 -0.3474482 0.6032798 0.7171480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4152 4252 0.517705 -0.030306 -0.290507 -0.7377109 -0.3857804 -0.5476972 0.0835700 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4153 4253 0.403969 -0.076217 0.141660 0.4296314 -0.0494460 -0.3937517 0.8111298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4154 4254 0.518118 -0.429673 0.057415 -0.1260855 0.0449214 0.8741441 0.4668583 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4155 4255 -0.696553 0.071073 0.216086 -0.0723125 -0.2716095 -0.7876554 0.5482684 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4156 4256 0.222002 0.380581 -0.031156 -0.4218270 -0.4026790 -0.7335464 0.3490291 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4157 4257 -0.129487 0.009536 0.408821 -0.1893984 0.7713737 0.2481879 0.5545391 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4158 4258 -0.227839 0.609498 -0.116441 0.1866239 -0.0244702 0.9300493 0.3155646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4160 4260 0.034900 0.307459 0.578250 0.7719460 -0.0991350 0.1385682 0.6124300 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4161 4261 -0.172078 0.422061 -0.437655 -0.4116761 -0.2063845 -0.7456333 0.4816213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4162 4262 0.533268 0.022396 -0.196778 -0.2964582 0.0013111 0.0762124 0.9519992 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4163 4263 0.248492 0.368370 0.270786 0.8192279 0.0056339 0.1781097 0.5450787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4164 4264 -0.464246 -0.153743 0.258112 -0.8459911 0.3326726 -0.4160941 0.0222190 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4165 4265 0.092446 0.599018 -0.101568 -0.3208253 0.7012097 -0.2198743 0.5975210 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4166 4266 0.292525 -0.046860 -0.280835 -0.7325255 0.4905488 0.4505807 0.1405178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4167 4267 -0.212838 -0.512735 -0.316972 0.0329496 -0.6896565 0.7168220 0.0972343 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4168 4268 0.182482 -0.530227 -0.083301 0.0891274 0.0576484 0.0985359 0.9894562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4170 4270 0.436392 0.429466 -0.151350 0.4500757 0.3624520 0.4795385 0.6603812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4171 4271 0.196256 0.311340 0.277867 -0.2313703 0.2898878 0.9142324 0.1631317 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4172 4272 0.136757 -0.563791 -0.301917 0.3240771 -0.3879928 -0.4142182 0.7568744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4173 4273 -0.114559 0.138840 -0.392071 0.1222651 -0.4354053 -0.8823505 0.1301191 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4175 4275 -0.164176 -0.614937 0.049026 0.2966651 -0.3348314 0.4652246 0.7638350 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4176 4276 -0.241388 -0.260365 -0.744842 -0.0504053 -0.3219974 -0.2803309 0.9028796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4177 4277 -0.328317 -0.394792 -0.170982 0.0479723 0.2126398 -0.3956196 0.8921704 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4179 4279 0.570350 0.196066 -0.553406 0.6864498 0.1471268 -0.4265126 0.5702871 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4180 4280 0.502769 0.393740 -0.223293 0.1927914 -0.0303735 0.9777465 0.0769467 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4181 4281 -0.390210 -0.440611 -0.405029 -0.3714203 -0.1531027 0.5471174 0.7343495 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4182 4282 0.524120 0.278042 0.592329 0.7983596 0.4286440 -0.1270119 0.4034282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4183 4283 0.384360 0.182938 0.764323 -0.1761470 -0.4845384 0.5039942 0.6929535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4184 4284 -0.139386 -0.436948 0.444711 -0.2003714 -0.2492077 -0.2323079 0.9185749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4185 4285 0.198999 0.638553 -0.044427 0.5377835 -0.5399317 0.6414104 0.0886303 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4186 4286 0.704600 0.148323 -0.380292 -0.7727697 0.1283514 -0.6115067 0.1114107 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4187 4287 0.406655 0.096837 0.397617 0.3788087 -0.0560062 -0.4113477 0.8271398 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4188 4288 -0.033455 0.391861 -0.721224 -0.8142749 -0.0015180 0.1249218 0.5668762 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4189 4289 0.285068 -0.140790 0.668190 0.3530545 -0.3867332 0.4219491 0.7401006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4190 4290 0.146597 -0.654839 0.260807 0.1987548 0.0932422 0.9724026 0.0789658 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4191 4291 -0.172232 0.037172 -0.691762 0.1807387 0.0103010 0.8283517 0.5301518 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4193 4293 0.454525 0.406931 0.375816 -0.2115422 0.3381792 -0.9072260 0.1335130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4194 4294 -0.516564 0.182968 -0.166878 -0.4992703 0.2533965 -0.5181415 0.6465669 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4195 4295 -0.480298 0.674034 -0.075812 -0.2244231 -0.0480172 -0.9440043 0.2370325 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4196 4296 0.504938 -0.416062 0.534637 0.1391842 0.0652521 0.9859169 0.0658620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4197 4297 0.311614 0.725623 0.276382 -0.1084912 -0.0330911 -0.5919094 0.7979836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4200 4300 -0.205691 0.638031 0.766861 -0.1117751 0.1236831 -0.3095253 0.9361639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4201 4301 0.230596 -0.118305 0.724867 -0.1206072 0.1351213 -0.7510301 0.6349409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4203 4303 -0.593009 -0.174806 -0.124451 -0.4863610 0.2657461 0.7237310 0.4111514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4205 4305 0.400928 -0.641510 -0.162867 -0.7877209 -0.0529442 -0.6102934 0.0650747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4206 4306 -0.294789 0.770089 0.271639 -0.3990683 -0.5731898 0.7114565 0.0776378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4207 4307 -0.421393 -0.629190 -0.194906 0.5145011 -0.1408449 -0.3062774 0.7884450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4208 4308 -0.144458 -0.572933 0.448487 -0.6188145 0.4024282 -0.1659777 0.6538896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4209 4309 -0.366317 -0.619847 0.035991 0.0081206 -0.6054158 -0.4370341 0.6651368 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4210 4310 -0.315494 -0.235007 0.445162 -0.7661837 0.3006373 0.0834311 0.5617997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4211 4311 -0.571723 -0.031738 0.099961 0.4093254 0.5466977 -0.3285691 0.6523931 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4212 4312 0.416900 0.460877 0.117199 0.4372233 -0.0961022 -0.5756753 0.6842500 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4213 4313 0.347346 0.056141 -0.520315 -0.5049641 0.1081269 -0.0146689 0.8562153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4214 4314 -0.420178 -0.179454 -0.509242 0.1967739 -0.5843173 -0.2404320 0.7496971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4215 4315 -0.542896 -0.032445 0.312812 -0.2946433 0.5362004 -0.0768644 0.7872524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4216 4316 0.360074 0.451778 -0.589705 -0.4518320 -0.1448839 -0.5105623 0.7170653 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4217 4317 0.479541 -0.170164 -0.440670 0.0442918 0.2129485 0.8954894 0.3883168 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4218 4318 0.472849 -0.553902 0.342968 -0.2259982 -0.2805371 0.8413117 0.4030115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4219 4319 0.326443 -0.264231 0.374605 -0.6694104 0.0947082 0.6389125 0.3670298 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4220 4320 -0.527273 -0.276824 -0.278457 -0.6355547 -0.4823199 -0.4290905 0.4234609 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4222 4322 -0.565108 0.090349 0.374736 -0.7710803 -0.4587843 -0.3488075 0.2707130 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4223 4323 0.387561 0.502089 0.355758 0.3619967 -0.1227046 0.8014612 0.4599586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4224 4324 0.225861 -0.059098 0.433237 -0.0400588 -0.5914052 0.4232839 0.6851758 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4227 4327 -0.077942 -0.540349 0.343078 0.7832133 0.0921993 0.1401264 0.5986993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4229 4329 0.152601 -0.126037 -0.283920 0.2235730 0.7700504 0.0228226 0.5970902 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4230 4330 0.293167 0.505280 -0.326097 0.4548069 0.1767100 -0.7611532 0.4272822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4232 4332 -0.084280 0.295750 -0.436086 -0.6258371 0.1350125 -0.2933381 0.7099664 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4233 4333 -0.504039 -0.520076 -0.226793 0.0420628 -0.6761684 0.5712496 0.4633582 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4234 4334 0.254034 -0.392517 0.088370 -0.0243482 0.6635959 -0.6585907 0.3539857 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4235 4335 -0.114271 -0.406105 -0.513267 0.5977203 0.0271710 -0.6971965 0.3948535 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4236 4336 0.263223 -0.220657 -0.355491 0.5601998 -0.1195552 0.0428480 0.8185639 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4237 4337 -0.274411 -0.433347 0.174780 0.0939130 0.3786731 -0.9038968 0.1753784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4240 4340 -0.182878 0.206638 0.264935 -0.8131338 -0.2424052 -0.3210122 0.4207187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4241 4341 0.517722 -0.307234 -0.058508 0.4615828 0.0851262 0.4068097 0.7837096 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4242 4342 -0.055940 -0.533894 0.151884 -0.1781790 -0.4266094 0.8835473 0.0748379 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4243 4343 -0.490913 -0.570820 -0.302195 -0.3719301 0.5353212 -0.5375476 0.5349223 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4244 4344 0.323363 0.120877 0.368525 0.8719380 -0.3891867 0.1112928 0.2754484 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4245 4345 0.514288 -0.184938 -0.242101 0.4860353 0.7846343 0.2732471 0.2710255 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4246 4346 -0.230661 -0.287887 0.070977 0.0250903 -0.4378173 -0.7347744 0.5174873 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4247 4347 0.290845 -0.109986 -0.303213 -0.1593976 -0.4499362 -0.1424486 0.8670976 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4248 4348 -0.299443 -0.486262 0.106823 0.0347099 0.6066683 0.7766010 0.1662521 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4249 4349 -0.129406 -0.303549 -0.032346 -0.0162479 0.4572700 0.4966518 0.7375481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4250 4350 -0.463449 0.169215 0.410284 -0.0204027 0.3437377 0.8704424 0.3517928 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4251 4351 -0.242990 0.387404 0.216143 -0.2700213 -0.6017405 0.5133073 0.5491015 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4252 4352 -0.206241 0.034777 0.457260 -0.1334911 0.0409025 0.0636683 0.9881566 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4253 4353 0.195433 0.221008 -0.092987 0.2703594 -0.2200190 -0.4784303 0.8059788 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4254 4354 -0.425819 -0.104372 -0.224824 -0.2682620 0.5879804 0.3187175 0.6933496 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4256 4356 -0.489632 -0.141037 0.246441 -0.0208888 -0.0978381 0.5107787 0.8538715 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4257 4357 -0.402769 0.135043 -0.142935 0.6173350 0.2214563 -0.0241969 0.7544993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4258 4358 0.157277 -0.623154 -0.258197 -0.5767928 0.4622176 0.5694676 0.3596825 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4259 4359 0.745011 -0.146682 0.195082 -0.6475908 -0.0161866 0.6406341 0.4122524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4263 4363 0.271497 0.193553 -0.385605 -0.0894062 0.3974544 0.8309699 0.3788476 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4264 4364 0.096215 0.091328 -0.586643 -0.0512476 0.1689652 0.6898508 0.7020899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4265 4365 -0.396354 0.334944 0.412588 0.3370855 -0.1510332 0.0438079 0.9282474 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4266 4366 0.466261 -0.337980 0.125396 -0.0226818 0.6057474 -0.7873601 0.1123374 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4267 4367 -0.046684 0.348137 0.602947 -0.6747189 -0.3716463 -0.6165933 0.1626226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4268 4368 0.166093 -0.686883 0.018646 0.0807980 -0.0311544 0.9804709 0.1765729 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4269 4369 -0.361496 0.547762 -0.028642 -0.7613049 -0.2992494 0.5747140 0.0238431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4270 4370 0.404458 -0.032897 0.285782 0.3364345 -0.5437840 -0.7687879 0.0087138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4272 4372 0.466145 -0.302072 -0.239925 0.0775339 0.5772780 0.5109583 0.6321868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4273 4373 0.175814 -0.547868 0.067971 0.2571479 -0.5839374 0.2087687 0.7411530 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4274 4374 -0.382449 0.005708 0.420558 -0.1116721 -0.0130914 0.7825347 0.6123703 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4275 4375 -0.269316 0.083340 0.713633 -0.7062781 0.2631012 0.6412225 0.1441624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4276 4376 -0.409837 -0.252517 -0.273368 -0.2796863 0.4814584 0.7738733 0.3018169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4277 4377 0.471656 -0.345372 0.076458 -0.0024895 0.5608348 -0.8273438 0.0309907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4278 4378 -0.187996 -0.626239 0.012155 0.0996379 -0.6688784 -0.5589792 0.4798085 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4279 4379 0.497462 0.164759 -0.425092 0.0359687 0.3935894 0.5666175 0.7230064 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4280 4380 -0.461774 -0.633842 0.177579 0.4163924 0.4311918 -0.7386445 0.3083754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4281 4381 -0.507041 0.295721 -0.251226 0.6457996 -0.6856275 0.2483098 0.2262744 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4283 4383 0.525170 -0.212433 0.166317 0.6300748 -0.4722094 -0.0934625 0.6093347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4284 4384 0.642471 -0.619640 -0.001741 -0.0738656 -0.2167992 0.5504339 0.8028477 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4286 4386 -0.107737 -0.096050 0.620915 -0.1321363 0.4947116 0.7485620 0.4212545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4288 4388 0.092155 0.394062 0.719103 0.2243901 0.1839412 -0.4859827 0.8244001 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4289 4389 0.651442 -0.171902 0.279842 -0.6766078 -0.2155471 -0.6822109 0.1741542 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4290 4390 -0.284932 0.775457 0.248940 0.5643687 0.3725008 0.7365650 0.0142517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4291 4391 -0.212773 -0.015988 -0.588655 -0.5472668 0.7413011 0.2723347 0.2771380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4292 4392 0.488886 -0.591587 -0.478864 -0.2611354 0.0500093 -0.5834574 0.7673883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4293 4393 -0.628808 -0.434963 0.244344 0.5838261 -0.2754636 0.2578400 0.7188779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4294 4394 -0.481522 -0.423936 -0.672733 -0.2978498 -0.2054527 -0.1657002 0.9173975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4295 4395 0.390408 -0.517132 -0.019387 0.3942998 0.7272427 0.4675371 0.3115360 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4296 4396 -0.391331 0.352123 0.635388 0.1534826 -0.4657314 0.7818219 0.3850868 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4298 4398 0.338914 0.622848 0.152913 0.0283289 0.4821250 0.6846202 0.5459378 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4299 4399 0.688660 0.218563 -0.434601 -0.1315411 0.8622940 0.4365485 0.2203892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4300 4400 -0.707174 0.037902 0.375731 -0.2892696 0.5029674 -0.7594997 0.2941208 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4302 4402 0.687499 0.135458 -0.219734 -0.3060470 -0.4255060 0.8393174 0.1443127 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4304 4404 0.515528 -0.641944 -0.079431 0.1710634 -0.4774064 -0.8320025 0.2249271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4305 4405 -0.171853 0.721801 0.342146 0.8451193 -0.0166513 0.4232298 0.3261482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4306 4406 0.448456 -0.552826 -0.455238 0.8754648 0.1975533 -0.3890973 0.2076951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4307 4407 0.051963 -0.710031 0.377915 -0.0679043 -0.9266046 -0.3640681 0.0651713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4309 4409 0.410666 -0.631771 0.036033 -0.1596167 0.1010610 -0.1067661 0.9761712 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4312 4412 -0.332066 0.261552 -0.440650 0.4465281 -0.1616444 0.0150121 0.8799195 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4313 4413 0.270876 0.644809 -0.096899 -0.3198038 0.1190028 -0.0333674 0.9393884 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4314 4414 -0.613595 -0.490773 0.202513 0.1328744 0.1809818 0.9373552 0.2663741 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4315 4415 -0.534770 0.061160 -0.604597 0.2837876 0.4658361 -0.1812388 0.8182993 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4316 4416 -0.243805 0.647487 0.283338 -0.0414854 -0.4417735 -0.8906398 0.0993780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4317 4417 -0.326997 -0.475621 -0.245095 -0.1515910 0.1038866 0.9582347 0.2191211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4318 4418 -0.490235 -0.242232 0.100490 -0.5710528 0.2009949 -0.4355751 0.6661636 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4319 4419 -0.382935 -0.208434 -0.714084 -0.0460081 0.8089011 -0.5428649 0.2210429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4320 4420 -0.415720 -0.332909 -0.382977 0.7795215 -0.3305255 0.2545952 0.4672049 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4321 4421 -0.310590 -0.042411 0.594629 -0.5723177 0.6763477 -0.4539599 0.0944806 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4322 4422 0.200147 -0.353869 -0.505806 0.1781145 0.7497055 -0.0213973 0.6369922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4323 4423 0.348843 -0.288147 0.179195 0.0971877 0.3793247 -0.6127168 0.6864732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4324 4424 0.346614 -0.774706 -0.006884 0.0974924 -0.4803156 0.6794542 0.5460166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4326 4426 0.189470 0.585601 -0.145614 -0.0439781 -0.2059985 -0.2427455 0.9469452 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4328 4428 0.073441 0.494203 -0.305592 0.1638169 -0.6330490 -0.7274008 0.2080890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4329 4429 0.218198 -0.259932 0.335911 0.5150037 0.7637579 -0.3634749 0.1390361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4332 4432 -0.219870 0.538645 0.194869 -0.0230813 0.1234593 0.9901412 0.0620116 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4333 4433 -0.141444 0.065554 0.496581 0.4564109 0.7277000 -0.3690990 0.3548349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4334 4434 0.026365 0.188717 0.494843 0.2910866 0.1932383 0.2010374 0.9151565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4336 4436 0.156921 -0.431359 -0.071346 0.4979889 0.5625969 -0.2595989 0.6067126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4338 4438 -0.357256 -0.299520 0.397544 -0.6902627 0.0399733 -0.2137507 0.6901088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4339 4439 -0.294041 -0.403411 -0.041090 0.1655239 0.1527484 0.6781931 0.6995169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4341 4441 0.138848 -0.288547 0.383558 0.3798203 -0.8109736 -0.3781049 0.2347233 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4343 4443 0.496701 0.089958 -0.194014 0.8836112 0.1999450 0.3269457 0.2689978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4344 4444 0.290151 0.002550 -0.216956 -0.2058146 -0.5181297 -0.5182900 0.6485040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4345 4445 -0.289873 -0.106418 0.507747 -0.8753381 -0.3455913 -0.2161098 0.2600892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4346 4446 0.433034 -0.365778 -0.071689 -0.4380656 -0.0766876 0.8237464 0.3516524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4347 4447 0.018076 -0.002870 -0.687605 0.5235554 -0.6766462 0.3986512 0.3303285 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4348 4448 0.011320 0.200758 -0.290057 -0.4297262 -0.1415655 -0.3920432 0.8009973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4349 4449 -0.289838 0.143834 -0.538940 -0.3364618 0.1700210 0.9195815 0.1107077 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4350 4450 0.204292 0.331066 0.133524 0.5318631 -0.3608145 -0.2754350 0.7148917 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4351 4451 0.434497 0.097395 0.206436 0.1099530 0.3141398 -0.5749258 0.7474536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4352 4452 -0.344497 0.027412 0.335013 0.5320705 0.3609303 0.5292523 0.5536446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4353 4453 -0.359847 0.485125 -0.317380 -0.5354267 -0.3984609 -0.3422528 0.6613699 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4354 4454 -0.063213 0.203975 -0.295761 0.0404354 -0.6331354 -0.1922322 0.7486998 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4356 4456 -0.064113 0.154806 0.423155 0.1795861 0.3599314 -0.9146411 0.0403713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4357 4457 -0.047137 -0.497832 -0.288934 0.3678622 0.0914102 -0.8929443 0.2428415 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4358 4458 0.309887 -0.245297 -0.233419 0.1084463 -0.6377153 0.5095163 0.5674078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4359 4459 -0.193095 -0.233081 -0.427992 -0.2914119 -0.1780796 -0.7285737 0.5937568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4360 4460 -0.111094 0.293070 -0.378293 -0.7304108 -0.6144613 0.1738731 0.2422922 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4361 4461 0.387987 -0.130593 0.535646 -0.6081503 0.4676808 -0.2018931 0.6088243 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4362 4462 -0.226603 0.481605 0.202017 0.1965131 0.5499147 -0.6805365 0.4425455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4363 4463 0.160001 -0.543181 -0.029361 -0.2368527 -0.8520298 0.1155221 0.4523280 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4364 4464 0.346253 -0.098477 -0.549384 0.7404065 -0.3893192 0.5440285 0.0652830 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4365 4465 -0.436152 0.410926 -0.215651 -0.2539443 -0.7470305 0.6140766 0.0191753 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4368 4468 -0.452095 0.495054 0.088123 -0.3516224 0.1841660 0.1512360 0.9053023 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4369 4469 0.337848 -0.509777 0.252410 0.6798082 -0.4360870 -0.1560122 0.5686380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4370 4470 -0.465555 0.084730 -0.308591 -0.2691592 0.2603516 0.1870754 0.9081702 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4371 4471 -0.247339 0.125308 0.558040 0.4488094 -0.6262115 -0.5565984 0.3108497 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4372 4472 0.035609 -0.496949 0.094421 -0.4619731 0.5457617 -0.6372354 0.2874997 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4373 4473 0.220097 -0.515435 0.453107 -0.4638018 -0.1861438 0.1764194 0.8480062 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4374 4474 0.045880 0.343969 0.407686 0.6934365 -0.4497982 -0.5178496 0.2205883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4375 4475 -0.719471 0.345136 0.233368 0.5837544 -0.0887169 0.4327316 0.6812514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4376 4476 0.470601 0.287046 -0.084007 0.0965012 -0.6251321 -0.7694918 0.0882028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4377 4477 -0.475968 0.167077 0.422459 -0.5981122 0.2772630 -0.4281685 0.6181090 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4378 4478 0.305387 -0.189459 -0.324554 -0.4882258 0.6157730 0.0311681 0.6176469 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4379 4479 0.319965 -0.755522 -0.023090 -0.0820761 -0.0178483 -0.2494290 0.9647436 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4380 4480 0.136604 0.116904 0.608664 0.0842443 0.2408137 -0.9376426 0.2360890 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4381 4481 -0.321235 0.383137 -0.020378 0.8397837 0.0161211 0.5185376 0.1600695 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4382 4482 0.593741 0.114194 0.073236 -0.0400340 -0.0663941 -0.9709694 0.2262910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4383 4483 0.834912 -0.413210 -0.340065 0.1997293 0.4481580 0.5223985 0.6973969 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4384 4484 -0.226176 -0.662629 -0.163317 0.6469925 0.3517049 0.6577833 0.1581948 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4385 4485 -0.333839 0.209414 0.613484 -0.2558976 0.1366315 0.5101351 0.8096978 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4386 4486 -0.467135 0.451124 -0.049543 -0.1727068 0.1030391 -0.3771708 0.9040451 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4388 4488 -0.590944 0.321248 0.571582 -0.5444579 -0.4617269 -0.6219891 0.3217193 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4390 4490 0.638664 -0.276759 0.237689 -0.6790993 -0.0378319 0.2465884 0.6903529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4391 4491 0.526029 0.226817 0.632818 0.7419655 0.2773714 -0.5971552 0.1263245 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4393 4493 -0.360906 0.326339 0.601976 -0.8765891 -0.0477511 -0.4483958 0.1680849 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4395 4495 -0.765474 -0.395740 -0.038068 -0.0336752 0.5937182 0.7049932 0.3864573 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4396 4496 0.541421 -0.228799 0.306578 0.3468279 0.8122672 -0.0788476 0.4622937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4397 4497 -0.305758 0.446801 -0.458228 -0.0223936 0.8042897 0.2797149 0.5238093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4398 4498 0.363675 0.281298 0.631700 0.0766114 0.3521459 0.9292151 0.0817508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4399 4499 -0.246163 -0.333692 0.329211 -0.4031441 -0.2179968 0.8624741 0.2146872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4400 4500 0.495846 -0.560739 -0.086401 0.2751678 0.2220503 0.7315131 0.5829793 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4401 4501 0.234017 -0.444060 -0.377980 0.4237681 -0.3630891 0.6991547 0.4469560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4403 4503 -0.827320 -0.142468 -0.178079 0.0710039 -0.4600533 0.7300310 0.5003641 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4404 4504 -0.299560 0.412435 -0.761786 -0.2745491 -0.5264644 -0.8044603 0.0173675 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4405 4505 0.473454 -0.344521 -0.523415 0.0710937 0.0660361 -0.9952705 0.0046369 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4406 4506 0.208478 0.705935 0.177848 0.5177923 -0.2949677 -0.5738654 0.5617505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4407 4507 -0.263260 0.150595 -0.727335 -0.8906361 0.0821071 0.0526654 0.4441308 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4409 4509 0.503803 -0.311750 0.002360 0.1564048 -0.1084573 0.9420876 0.2761260 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4410 4510 -0.279499 -0.211705 -0.751142 0.4171474 -0.4482453 0.6184853 0.4924836 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4411 4511 -0.020915 0.641716 -0.458643 0.2768087 -0.3148348 -0.8574779 0.2983079 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4412 4512 -0.496381 -0.254293 -0.338127 0.3622830 -0.1302683 0.4519326 0.8046975 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4415 4515 0.291423 -0.384108 -0.503851 0.2564039 -0.6891390 0.5747966 0.3591007 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4416 4516 0.374588 -0.102265 0.302868 -0.0337408 -0.1596137 -0.5319537 0.8309093 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4417 4517 -0.019189 0.683692 -0.449574 -0.5689327 -0.2577073 -0.7261658 0.2873775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4418 4518 -0.183482 -0.265289 -0.616021 0.4136629 -0.7461623 0.4324800 0.2916949 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4419 4519 0.600309 0.588626 -0.037267 0.0994908 0.3546285 0.4679805 0.8033271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4420 4520 -0.270011 0.035070 0.566190 0.0044560 -0.1974550 0.9203415 0.3375843 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4421 4521 0.494413 0.011376 -0.315353 0.5637749 0.6223394 -0.4372910 0.3219133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4423 4523 0.084578 0.109027 0.494209 0.4492216 -0.3275816 -0.7697117 0.3137422 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4424 4524 -0.534612 -0.206481 0.166155 0.9797941 0.0616245 0.1416379 0.1270614 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4425 4525 -0.178659 0.191024 -0.443779 0.1806112 -0.8342770 -0.2703227 0.4452944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4427 4527 -0.604917 0.177937 -0.049437 -0.5285713 -0.0422244 0.3182375 0.7858463 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4428 4528 -0.368598 -0.607233 0.470963 -0.3047504 -0.3997315 0.4369967 0.7459060 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4429 4529 -0.579823 0.146091 -0.166889 0.4141770 -0.6702711 0.1470433 0.5979735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4431 4531 0.507198 -0.197161 0.243927 0.8110325 0.2112143 0.1504363 0.5243889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4432 4532 0.497809 -0.509332 0.291074 -0.6037013 -0.2624738 0.1008735 0.7459737 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4434 4534 -0.293434 0.382557 0.285762 0.2248935 -0.6677854 0.4851329 0.5178143 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4436 4536 -0.007563 0.055331 0.445975 -0.2101639 -0.9610102 0.0713959 0.1649033 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4437 4537 0.200504 0.374612 0.039901 0.5450081 -0.1321218 0.6967337 0.4472944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4438 4538 -0.039497 -0.309678 -0.302780 -0.0437788 0.7715793 -0.0551986 0.6322198 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4440 4540 0.353595 -0.382798 0.309859 0.5795918 -0.3166607 -0.4167536 0.6245925 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4441 4541 0.310892 0.118997 -0.473409 -0.4235604 -0.2631775 -0.5735593 0.6498953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4442 4542 0.575654 -0.146516 -0.162009 0.2768257 -0.2940777 -0.2784042 0.8714224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4443 4543 0.179077 -0.068260 0.505981 -0.3187300 0.5176345 0.3016951 0.7344697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4444 4544 -0.477021 0.119024 -0.167475 -0.2722940 -0.2345472 -0.2277594 0.9049692 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4445 4545 0.233375 -0.055128 -0.233926 -0.0070677 0.7234487 -0.5999974 0.3414310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4446 4546 -0.277077 -0.179259 -0.497523 -0.6872007 0.3190583 0.5629544 0.3302110 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4447 4547 -0.371105 0.106750 0.133445 0.3533941 -0.1357630 -0.9248688 0.0360385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4448 4548 -0.358106 0.464815 0.252660 0.2563826 0.2270525 -0.6791407 0.6492172 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4449 4549 0.448033 -0.063809 0.129144 0.3209897 0.0468449 -0.7896578 0.5207800 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4450 4550 -0.249374 0.115592 -0.254962 -0.7508973 0.3637173 0.4978337 0.2366950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4451 4551 -0.114411 0.356382 0.189866 0.4034899 -0.2640836 -0.7056303 0.5191740 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4452 4552 0.071052 0.353548 -0.053825 -0.1503863 0.5226676 -0.8348910 0.0846141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4453 4553 -0.459140 0.216354 0.415708 0.6000400 0.1733564 0.2686603 0.7332947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4454 4554 -0.498067 -0.122890 0.098754 -0.0231491 -0.4421871 -0.5092928 0.7379400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4455 4555 0.599232 0.049076 -0.222647 0.5328426 0.1978206 0.8141484 0.1187779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4456 4556 0.044224 -0.331065 0.292592 0.7295129 0.0934632 -0.6528110 0.1814204 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4457 4557 0.405887 0.249021 -0.152769 0.1111411 0.2764609 0.8948130 0.3324557 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4458 4558 -0.555823 -0.097639 -0.201348 0.2290239 0.6700837 -0.6168569 0.3435455 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4459 4559 0.206165 0.074265 -0.605222 0.5070644 0.1057442 0.8541837 0.0455412 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4460 4560 0.266346 0.045674 0.501872 0.2792274 -0.4406970 0.8103051 0.2668779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4461 4561 0.486738 -0.525675 0.091276 0.1113202 0.2723780 0.8926972 0.3413353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4462 4562 0.005475 -0.171191 -0.495330 0.4362054 0.3236171 -0.7815176 0.3069643 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4463 4563 -0.406139 -0.282642 -0.424370 -0.4243986 -0.3967531 0.8123434 0.0507040 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4464 4564 -0.489260 -0.154095 0.433438 0.1429093 -0.2975004 -0.9071726 0.2609757 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4465 4565 0.594377 -0.043925 0.003539 0.2677488 0.7402101 0.0873363 0.6105505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4466 4566 -0.146694 -0.332583 -0.568416 0.3126826 0.2076785 -0.6890339 0.6199447 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4467 4567 -0.156587 0.677059 -0.315224 -0.2928797 0.1226766 -0.9307741 0.1811946 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4468 4568 -0.362970 0.572970 0.134920 -0.0749255 -0.4470470 0.8181444 0.3538006 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4469 4569 0.661108 0.267618 -0.096201 -0.3252394 -0.6133774 -0.6745308 0.2509895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4470 4570 -0.112081 0.228124 -0.282893 0.3414537 -0.7516920 -0.5594576 0.0733186 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4471 4571 -0.189956 0.488969 -0.014721 0.2072413 -0.1427046 -0.7812778 0.5712192 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4472 4572 0.653126 0.146185 0.289768 0.3142313 -0.7341620 0.5177098 0.3069877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4473 4573 -0.044635 -0.524400 -0.432567 -0.2958892 0.0890237 -0.9098623 0.2769024 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4474 4574 -0.554035 0.159119 -0.101560 -0.0342589 -0.4260324 -0.5977768 0.6782224 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4477 4577 -0.234711 -0.768859 -0.346079 -0.2850909 0.3801141 -0.8024681 0.3609450 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4478 4578 0.597958 -0.228547 0.075446 0.5262987 -0.1009735 0.6666372 0.5180820 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4480 4580 -0.451760 -0.271417 0.478128 0.5489304 0.5199214 0.3409732 0.5586541 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4482 4582 -0.763401 0.152310 0.309388 -0.5883565 0.4989784 -0.3553748 0.5277934 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4483 4583 0.047970 -0.564969 0.431605 0.2972625 0.1019962 -0.6802126 0.6622254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4484 4584 -0.521498 0.212131 -0.687253 -0.0819502 0.3741973 -0.0731800 0.9208177 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4485 4585 -0.339872 0.022767 0.804616 -0.5562798 -0.4147595 0.6975454 0.1787674 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4486 4586 -0.810427 -0.050396 0.061082 0.1541813 -0.3155018 0.0448886 0.9352389 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4487 4587 -0.117911 -0.334431 -0.702225 -0.3138849 -0.5988981 0.3481598 0.6492936 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4488 4588 0.499099 -0.414498 0.005559 -0.3592384 0.6789426 -0.3639646 0.5267963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4489 4589 -0.607100 -0.428080 0.295524 0.1867538 0.5357903 0.3988137 0.7204162 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4490 4590 0.503130 -0.398073 -0.263039 0.4322445 0.4460522 -0.4884569 0.6128719 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4491 4591 -0.310614 -0.220806 -0.701301 0.5724139 -0.1456533 0.7695474 0.2427431 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4492 4592 0.618261 -0.060126 0.209772 -0.0252300 -0.6941801 -0.3628665 0.6211323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4493 4593 0.130008 -0.582928 -0.338076 -0.5774728 0.0207350 -0.4525023 0.6792178 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4494 4594 0.480251 0.643554 -0.125283 -0.0686168 -0.5609670 0.8242222 0.0355749 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4495 4595 0.316376 0.539055 -0.487614 0.0742152 -0.6053918 -0.5358923 0.5837913 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4496 4596 -0.476408 0.521091 0.422468 -0.0132794 0.2897276 -0.9489813 0.1237579 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4497 4597 0.792395 0.415193 -0.244663 0.3581819 -0.6688406 -0.6490708 0.0553629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4498 4598 -0.223034 0.191819 0.722464 0.6153149 0.0552295 -0.4419813 0.6503766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4499 4599 -0.596598 0.100171 0.708012 -0.0007759 -0.1367586 0.9381662 0.3180261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4500 4600 -0.565806 -0.209432 0.446472 -0.4582543 0.1984696 0.7688135 0.3994230 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4501 4601 -0.497306 -0.231174 0.414043 0.5145422 -0.0261777 0.8500914 0.1091133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4502 4602 0.670036 -0.214578 0.489000 -0.3517369 0.2003965 -0.2164303 0.8884145 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4503 4603 0.217272 0.812016 0.239446 -0.0398724 -0.2372235 -0.9704972 0.0164416 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4505 4605 -0.546432 0.245475 -0.536261 -0.7712188 -0.0511237 0.5775588 0.2627427 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4506 4606 -0.847976 -0.003356 -0.265813 -0.2027012 0.0671409 -0.6815074 0.6999657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4507 4607 -0.129483 0.400635 0.385836 0.2066749 0.6535011 -0.5919296 0.4240768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4508 4608 0.327513 0.716153 -0.052614 0.4979843 0.2452165 0.7835800 0.2790751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4509 4609 -0.533165 -0.063583 0.289621 -0.0009671 -0.0958242 0.9951925 0.0202164 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4511 4611 -0.029191 -0.661094 -0.074924 0.2699569 -0.1447462 0.4760251 0.8243615 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4512 4612 -0.634381 0.224321 -0.185907 -0.4281905 0.3684558 0.8044525 0.1837100 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4513 4613 0.653825 -0.358861 0.238789 -0.4339158 0.3341980 0.7795097 0.3039629 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4515 4615 -0.560669 -0.258152 0.400946 0.0589229 0.0255782 -0.1888903 0.9798950 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4516 4616 0.487293 0.351197 0.437706 0.3681767 0.0126552 0.6449688 0.6695528 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4517 4617 -0.423674 -0.399961 0.478440 0.3813853 0.1741743 -0.6746435 0.6075069 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4518 4618 -0.399075 0.196243 0.475134 0.5782747 -0.2550018 -0.3194623 0.7060568 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4520 4620 0.500295 -0.089692 0.500371 -0.5297681 -0.5115452 0.6613583 0.1423814 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4521 4621 0.198948 0.484960 0.322085 -0.8071838 -0.3089322 0.4389949 0.2455578 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4522 4622 0.369308 0.029816 0.380724 -0.4274640 -0.1778737 0.8760999 0.1344787 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4523 4623 -0.480807 0.095048 0.304797 -0.1571425 0.7379958 0.0002587 0.6562533 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4524 4624 -0.351905 0.505452 -0.195471 -0.0435487 0.3314957 0.7900440 0.5138527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4527 4627 -0.264257 0.321215 0.371600 0.1346126 -0.4095019 0.8153906 0.3864270 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4528 4628 -0.147775 -0.417579 0.304533 0.3355935 0.2188435 0.1499423 0.9038815 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4529 4629 -0.388173 0.210392 0.343941 0.0582903 0.7212716 0.4289643 0.5407025 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4530 4630 -0.564541 -0.141737 -0.268302 0.2478408 0.3356651 0.3012463 0.8574115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4531 4631 0.429674 0.327388 0.292994 0.7384338 -0.6163023 -0.2427680 0.1262963 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4532 4632 0.310125 -0.223139 -0.418711 -0.8462078 0.2227804 -0.4514100 0.1747290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4533 4633 -0.024568 0.207361 -0.402636 -0.0167532 0.6277013 0.0568879 0.7761921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4534 4634 0.653088 0.142949 -0.262881 -0.5871572 0.4709101 0.4529544 0.4778310 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4535 4635 -0.361871 -0.189029 0.298783 -0.0386085 0.2977652 -0.8323730 0.4658331 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4536 4636 0.117211 -0.087667 -0.571700 0.0261915 0.7370824 -0.2840880 0.6126316 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4537 4637 0.412641 -0.148993 -0.322803 -0.1183864 0.0060502 0.4617584 0.8790491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4538 4638 0.480086 -0.246841 0.124672 -0.0790898 -0.2742736 0.9583050 0.0130545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4539 4639 -0.078092 -0.083314 -0.495286 -0.3810150 0.7291488 0.2992621 0.4833341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4540 4640 0.378679 0.506366 -0.208107 -0.5517364 -0.2147544 0.5727468 0.5669468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4541 4641 -0.368051 0.383486 -0.157121 -0.0901608 0.2323450 0.9606307 0.1227823 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4542 4642 0.243768 -0.142471 -0.419103 0.0630846 -0.0006389 0.6121323 0.7882347 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4543 4643 -0.172007 -0.447758 0.137278 0.2880387 0.0731004 -0.3366847 0.8934951 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4546 4646 0.267353 0.378648 0.085874 0.6124615 -0.0759815 -0.7868053 0.0074274 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4547 4647 0.200984 0.071307 0.448503 -0.0791978 0.8731266 -0.0131791 0.4808367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4548 4648 -0.149309 -0.403996 0.069063 0.2143085 -0.5072438 0.0919229 0.8296540 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4550 4650 0.136575 0.154804 0.604177 -0.8310368 -0.4226513 0.2110350 0.2936120 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4551 4651 -0.345195 -0.135514 0.048467 -0.1619379 -0.2491476 -0.6738374 0.6764944 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4552 4652 -0.011730 -0.088396 -0.545303 0.4408121 -0.7673685 0.0881692 0.4572269 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4553 4653 -0.323172 0.408631 0.011867 -0.5840009 0.2659027 0.2637901 0.7201761 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4554 4654 -0.042430 -0.495361 0.376291 0.1536036 0.4908873 0.7762190 0.3645816 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4556 4656 -0.285555 0.279096 0.150346 -0.7142782 -0.2083193 0.6458432 0.1711618 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4558 4658 0.367486 -0.366801 0.087311 -0.8778272 -0.0079216 0.4013987 0.2612197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4559 4659 -0.494626 -0.081392 -0.021689 -0.0502273 0.3454054 0.8994279 0.2630624 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4560 4660 0.365646 -0.446135 -0.056072 -0.3831182 -0.0911353 0.8721098 0.2904124 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4561 4661 -0.510100 -0.060963 0.105247 0.2453458 -0.7499519 -0.6112915 0.0608296 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4562 4662 0.386477 0.399175 0.003167 -0.3312986 -0.1029286 0.3286947 0.8784115 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4563 4663 0.240597 0.368809 0.240718 0.3700513 0.2200863 -0.8074916 0.4032138 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4565 4665 -0.026721 0.181940 0.353044 -0.3011709 0.0349466 0.7560604 0.5800409 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4566 4666 0.527016 -0.178361 -0.493146 -0.7316399 0.1101973 0.2076035 0.6398910 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4567 4667 -0.340199 -0.521131 -0.434338 0.6580439 0.5627773 -0.3440842 0.3631335 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4568 4668 0.586480 -0.153063 -0.235477 -0.2499061 -0.0549277 0.2085142 0.9439554 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4569 4669 -0.436583 0.230686 0.187998 0.0386625 0.6301769 -0.3615278 0.6860612 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4570 4670 -0.002480 0.040209 0.708613 -0.0073657 0.6602629 0.6843919 0.3092028 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4571 4671 -0.437919 -0.351180 0.203072 -0.4283994 -0.4594689 0.1380109 0.7657123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4572 4672 0.035020 -0.522825 -0.172481 0.3285675 -0.3020404 0.2699696 0.8531889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4573 4673 0.023679 0.578164 -0.516412 -0.3932698 -0.5103569 -0.7616324 0.0692158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4574 4674 0.054595 -0.503048 0.396877 0.0246092 0.2507805 0.9614154 0.1103812 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4575 4675 -0.272536 0.177145 -0.641230 -0.8661828 -0.2598338 0.2903293 0.3129259 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4576 4676 0.267988 -0.165272 0.662840 0.5974049 0.4151348 -0.6290579 0.2739649 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4579 4679 -0.206408 -0.569095 -0.467003 0.1221454 -0.3246935 0.2876417 0.8927020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4581 4681 -0.623154 0.071774 -0.490766 -0.3611134 0.2767677 0.8895499 0.0412030 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4582 4682 -0.153626 -0.115230 -0.477699 -0.0894771 -0.6325119 0.5322856 0.5555129 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4583 4683 0.507048 0.278174 0.570841 -0.8367940 -0.1899457 -0.2416993 0.4530760 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4584 4684 -0.029158 0.282347 -0.602620 -0.1728425 -0.0400368 -0.4359525 0.8823083 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4585 4685 -0.106394 -0.625546 0.101567 -0.2053399 -0.6391094 0.6100976 0.4208986 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4586 4686 -0.552287 -0.160201 0.696559 0.5547644 0.4919393 0.5351000 0.4048459 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4587 4687 -0.661616 0.245683 0.125466 0.0318451 -0.6620653 0.7404110 0.1115654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4588 4688 0.283738 -0.284533 0.700228 -0.0237282 0.5404253 -0.8386190 0.0639973 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4589 4689 -0.636866 0.128203 -0.364721 -0.4834972 0.1486114 0.3402074 0.7927194 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4590 4690 0.487016 0.667454 0.096573 0.3170072 -0.1186271 -0.3080804 0.8891122 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4591 4691 -0.787497 0.153861 -0.064408 -0.4574368 0.2634094 0.0645025 0.8468804 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4592 4692 -0.090804 0.517173 -0.441345 -0.7281414 0.3902690 0.5579049 0.0790086 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4593 4693 0.140050 0.585669 -0.387081 0.1091792 -0.4867912 0.8337536 0.2365779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4595 4695 -0.583822 -0.311534 -0.131852 0.4647047 -0.6882758 -0.3694621 0.4169218 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4596 4696 0.514031 -0.487125 0.056039 0.7256589 0.4773972 0.3680767 0.3317088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4597 4697 -0.455563 -0.397410 -0.149666 -0.2755966 0.2493386 0.8464641 0.3812810 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4598 4698 -0.764404 0.351844 -0.004543 -0.3151701 0.1642805 -0.6597741 0.6621011 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4599 4699 0.444558 0.136934 0.506570 -0.4673180 -0.1877050 -0.7885119 0.3530294 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4600 4700 -0.512896 0.616421 0.208034 -0.5294801 0.0551060 -0.8103134 0.2449620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4601 4701 0.644338 0.253589 -0.067990 0.7453048 -0.2639417 0.3147276 0.5251687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4602 4702 0.463437 -0.214348 0.446215 0.2004788 -0.2022909 -0.6805764 0.6750574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4605 4705 0.330605 0.437436 0.398057 -0.1868856 0.1559462 -0.9504983 0.1931514 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4607 4707 -0.549926 -0.193775 -0.327763 -0.1429368 -0.5119739 0.6660735 0.5232570 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4609 4709 0.465019 -0.025230 0.387824 -0.5469284 -0.2403021 0.8010104 0.0388153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4611 4711 -0.456837 -0.215126 0.345795 -0.0785482 0.6139299 0.2164047 0.7550426 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4612 4712 0.346627 0.383918 0.707999 0.0180407 0.1992422 -0.5912994 0.7812440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4613 4713 -0.521366 -0.294831 -0.468552 0.3613260 0.6351270 -0.6597172 0.1755861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4614 4714 -0.660690 0.282286 0.228647 0.5825770 0.0482210 0.7802280 0.2225377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4615 4715 -0.416722 -0.312052 0.277479 0.6587942 0.2312319 0.6231594 0.3524121 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4616 4716 0.608658 -0.331502 0.211107 -0.2129546 0.8186158 0.4659249 0.2596775 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4617 4717 0.147869 -0.286886 0.659840 0.1968591 -0.0066569 0.3330972 0.9220892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4618 4718 -0.319990 0.321815 0.306471 0.0040895 -0.0609586 -0.1229682 0.9905282 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4619 4719 0.219109 0.485433 0.339469 0.1678031 -0.5646782 0.4503338 0.6709546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4620 4720 -0.573324 -0.500831 -0.262503 -0.3723073 0.2357439 -0.2796940 0.8529850 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4622 4722 -0.346494 -0.479394 -0.085300 0.1008953 -0.1430531 0.9548469 0.2400487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4624 4724 0.559767 0.173153 0.078718 -0.0107919 0.3462297 -0.2066083 0.9150527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4625 4725 -0.178413 -0.509922 0.171404 -0.6508653 -0.0170329 0.1019818 0.7521196 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4626 4726 -0.130781 0.469624 -0.103493 -0.0874656 -0.4693459 0.7178024 0.5067780 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4627 4727 0.576959 -0.101729 -0.159152 0.2397193 -0.7703167 -0.5896381 0.0383899 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4628 4728 -0.449088 0.096900 0.138422 0.3868602 0.8210956 0.3019278 0.2915147 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4629 4729 -0.246551 0.456947 -0.300541 -0.4105182 -0.2618743 0.4918202 0.7218099 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4631 4731 -0.332875 -0.227516 -0.332491 -0.2642240 -0.8959287 -0.2006803 0.2953385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4632 4732 -0.074863 0.175267 0.537175 0.7405114 -0.4728163 0.4760314 0.0384932 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4633 4733 0.507113 0.273389 -0.057082 -0.4488577 -0.7299557 -0.0425359 0.5136947 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4634 4734 0.415143 -0.339312 0.162099 -0.7834529 0.1943581 0.5433811 0.2305720 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4635 4735 0.418342 -0.509735 0.136260 -0.1307180 0.3534945 -0.7931666 0.4783734 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4636 4736 0.403868 0.255621 -0.034007 -0.1624061 -0.4627973 -0.1537019 0.8577987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4637 4737 0.092081 -0.235274 -0.518730 -0.0504568 0.8945160 -0.1238997 0.4265491 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4638 4738 -0.418442 0.244944 0.159740 0.4504949 0.3647773 0.2106788 0.7871508 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4639 4739 0.491071 0.068600 0.117952 0.3749779 -0.2414408 -0.8799789 0.1635087 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4640 4740 0.477863 -0.035804 -0.126502 -0.2214947 0.4513552 -0.7734407 0.3860155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4641 4741 0.476495 0.014768 0.164886 0.1894822 0.0514724 -0.6355237 0.7466972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4644 4744 -0.035348 -0.052908 0.626435 -0.0288666 -0.9372986 -0.3311183 0.1048743 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4645 4745 0.449919 -0.328418 -0.066721 0.2441870 -0.0782727 0.8517042 0.4569968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4646 4746 -0.107774 -0.164681 -0.216646 0.6212539 -0.1403638 0.6772535 0.3683330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4647 4747 -0.232923 0.035675 0.120345 -0.4292636 -0.0551133 0.7748938 0.4606895 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4648 4748 -0.104348 -0.084223 0.437396 -0.1662430 0.3445617 0.6796854 0.6258341 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4650 4750 0.319976 -0.154078 -0.551108 0.2104275 -0.0841561 0.0449151 0.9729443 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4651 4751 0.284743 -0.213367 0.245219 -0.6477129 0.0449932 -0.5833598 0.4879907 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4653 4753 0.025183 0.446602 0.353137 0.4177456 -0.6197294 -0.5677015 0.3451652 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4654 4754 -0.258831 0.450798 0.006883 0.1798436 -0.1223874 -0.5773682 0.7869711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4655 4755 -0.236794 0.086615 0.130892 0.6727242 -0.0017561 0.7011139 0.2363861 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4656 4756 0.207273 -0.328562 0.364205 0.1074271 -0.3312537 0.4918235 0.7980226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4657 4757 0.240766 0.479623 0.095253 0.7920611 0.3938921 0.4256117 0.1906380 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4659 4759 0.371021 0.482755 -0.056652 0.0544972 0.7100840 0.1047878 0.6941399 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4660 4760 -0.573259 0.189154 -0.075017 0.2628688 -0.6848580 0.1015286 0.6719832 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4661 4761 0.339050 0.262716 0.349967 0.1491473 -0.7166877 -0.6670659 0.1383363 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4663 4763 -0.706479 0.342685 -0.086071 0.7376393 0.0136656 -0.3174687 0.5957475 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4664 4764 -0.148042 -0.596853 0.286504 -0.5946299 -0.6573325 0.4622018 0.0264349 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4665 4765 -0.007394 -0.176195 0.676049 -0.7123762 0.6646450 0.1034994 0.2001375 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4666 4766 0.553905 0.170051 -0.072165 0.0537372 0.4821587 -0.3582767 0.7976673 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4667 4767 0.060858 -0.093339 0.539019 -0.6835539 0.5154860 0.4236478 0.2958898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4668 4768 0.604154 -0.083421 -0.098652 -0.0841230 -0.1138314 0.9368744 0.3197376 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4669 4769 -0.310798 -0.076878 -0.455066 -0.2178378 -0.6088354 -0.0564401 0.7607106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4670 4770 -0.373706 0.328467 0.429427 -0.4300468 -0.6413951 -0.6024732 0.2017377 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4672 4772 -0.309319 -0.452822 0.224427 0.3327640 0.7563088 -0.1115172 0.5521133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4673 4773 -0.047512 -0.669140 0.434683 -0.7579019 0.4202257 -0.4730889 0.1586883 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4674 4774 -0.233093 0.718957 0.122796 -0.1314939 0.5965803 -0.0632963 0.7891735 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4675 4775 0.114096 0.191002 0.895916 -0.4326650 -0.3322118 0.6669584 0.5075458 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4676 4776 -0.579951 -0.101025 0.004202 -0.3451182 -0.0857811 0.9342063 0.0281727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4677 4777 0.193824 0.110035 -0.418820 0.0190081 0.0174168 0.5868949 0.8092525 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4678 4778 -0.728960 0.069356 -0.457951 0.4011289 -0.1411044 -0.0794211 0.9015972 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4679 4779 -0.651370 -0.331266 -0.292432 -0.3872021 -0.1634789 -0.6884684 0.5910672 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4680 4780 -0.777188 -0.109339 0.079725 0.7059959 -0.1053560 0.4836202 0.5065386 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4681 4781 0.546006 -0.153114 0.070026 0.1025710 0.6692036 -0.7292320 0.0993302 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4682 4782 -0.403402 0.366974 0.166065 -0.0194053 -0.4087363 0.6573359 0.6328251 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4683 4783 0.671955 -0.389397 0.248940 0.3334580 0.3022062 -0.8627606 0.2304807 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4684 4784 -0.549690 0.133175 -0.624404 0.3155166 -0.5031767 0.5439202 0.5928012 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4685 4785 -0.448066 -0.338947 0.319278 -0.2756175 -0.0058290 -0.3055708 0.9113877 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4686 4786 -0.007891 0.208224 -0.703252 -0.2582477 0.5902097 0.5490035 0.5324995 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4687 4787 0.792717 0.126816 -0.235644 0.0433298 0.0937175 -0.2377642 0.9658197 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4688 4788 -0.399582 -0.384138 0.491877 0.4577585 -0.5724678 0.4904285 0.4713996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4689 4789 -0.303293 0.696193 -0.182651 0.5897946 -0.4890643 0.2409747 0.5957261 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4690 4790 -0.288668 0.718348 -0.354531 0.2982763 -0.1829492 -0.1137006 0.9298565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4691 4791 -0.675010 0.568085 -0.101792 -0.6118591 -0.1462651 -0.7404168 0.2366811 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4692 4792 0.295859 -0.355875 0.677762 0.4404947 0.0754441 -0.8941410 0.0280078 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4693 4793 -0.069081 -0.049043 -0.736959 0.2016544 -0.2620069 0.9102883 0.2491246 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4694 4794 -0.177008 -0.792092 0.057976 -0.1367078 -0.5869557 0.1511312 0.7835517 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4695 4795 0.322724 0.173482 0.535450 0.0089204 -0.2321353 -0.8402294 0.4899472 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4696 4796 -0.411554 0.339377 0.621183 -0.3943011 -0.0932424 -0.6038985 0.6863958 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4697 4797 -0.018498 0.825325 -0.075333 0.3261225 -0.1193364 -0.9375918 0.0180149 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4698 4798 -0.189379 -0.578397 -0.017765 -0.6998843 -0.6489272 0.2661905 0.1349004 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4699 4799 0.231525 0.222447 0.728630 0.2894774 0.0176468 -0.6666535 0.6866327 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4700 4800 0.109515 -0.622395 -0.280274 -0.4317581 0.5445448 -0.6065064 0.3862718 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4702 4802 0.190769 0.601479 0.393262 -0.1109789 0.4786863 0.3790886 0.7841141 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4703 4803 -0.152598 0.278907 -0.479845 -0.1547194 0.7631451 -0.3970984 0.4857822 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4704 4804 -0.619893 -0.018232 -0.435794 0.4942700 -0.7488631 -0.4389387 0.0472662 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4706 4806 0.198756 0.672541 0.135310 -0.4305483 -0.6324908 -0.5509634 0.3332010 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4707 4807 -0.214227 0.618515 0.425673 -0.7261042 -0.3026166 -0.5994406 0.1478747 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4709 4809 -0.696416 -0.173784 -0.264886 -0.2703398 -0.2964395 0.8792514 0.2568211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4710 4810 -0.043240 -0.587813 -0.520343 0.3981310 -0.2303402 -0.8105361 0.3625828 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4711 4811 -0.553962 -0.153215 -0.465903 -0.4548739 -0.7865067 0.1405916 0.3933586 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4712 4812 -0.424453 0.226319 0.608890 -0.0157207 -0.0094870 0.7327400 0.6802610 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4713 4813 0.579531 0.181213 0.664445 -0.0648794 -0.4321052 0.3010878 0.8475977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4715 4815 -0.054518 0.775885 -0.326412 0.3876357 0.7897951 0.3980257 0.2598805 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4716 4816 -0.576069 -0.600792 -0.148116 0.0306715 -0.0242663 0.2875812 0.9569574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4717 4817 0.110519 -0.157175 0.520645 0.3317672 0.4984359 0.1842627 0.7794482 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4719 4819 0.526665 -0.004672 -0.409983 -0.1562346 -0.6308573 -0.6119885 0.4506439 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4720 4820 0.026825 -0.017341 -0.665714 -0.1446910 -0.5605569 0.0280035 0.8148965 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4721 4821 0.043485 -0.035771 0.498081 0.7271501 -0.6310970 -0.2259199 0.1480859 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4722 4822 -0.004994 0.495692 0.117881 -0.6608611 0.2967647 0.3614392 0.5869880 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4723 4823 -0.824115 -0.289747 -0.182658 0.3508148 0.5882589 -0.5333934 0.4963587 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4724 4824 0.271509 0.652421 0.343744 0.6959521 -0.1456059 0.3032694 0.6344109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4725 4825 -0.516992 -0.273365 -0.451431 -0.6120480 -0.2047843 0.6664211 0.3732875 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4728 4828 -0.049750 0.242699 -0.695635 -0.4184195 -0.1863488 -0.1725693 0.8720201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4729 4829 0.104447 0.348876 0.220002 0.0516314 -0.3602860 0.9269594 0.0909646 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4730 4830 0.322212 0.194228 -0.258076 -0.4813617 0.3318178 0.8008410 0.1297750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4732 4832 0.231343 -0.248008 -0.405860 0.0836629 0.0422783 0.6152886 0.7827088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4733 4833 0.302899 0.630991 -0.077156 0.5860517 0.1200786 0.1508795 0.7869943 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4737 4837 0.009345 -0.051286 0.336685 0.7953511 -0.1941698 -0.2333501 0.5246547 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4739 4839 -0.423580 -0.004471 -0.146575 -0.3638122 -0.4989951 -0.4474945 0.6468332 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4740 4840 -0.332094 0.182517 0.477207 0.6341512 0.3617356 -0.5497922 0.4058671 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4741 4841 -0.196385 0.500517 -0.466930 0.8562290 0.1063592 -0.5047060 0.0288366 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4742 4842 -0.214186 0.373151 -0.043530 -0.5346469 -0.1336941 -0.6329713 0.5437150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4743 4843 0.137864 -0.010824 0.233993 0.1507039 -0.2360645 -0.7301970 0.6231968 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4745 4845 -0.257440 -0.261621 0.194211 0.0891966 -0.1797771 -0.9706609 0.1324446 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4746 4846 -0.380574 0.220883 0.193815 -0.8304701 -0.2396433 -0.4740073 0.1679512 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4747 4847 -0.050194 0.373355 0.356327 -0.1978109 0.8867418 -0.3821899 0.1687920 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4748 4848 -0.461262 0.072834 0.165747 0.3931005 0.1212460 0.7150283 0.5652485 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4749 4849 0.050496 -0.505883 0.482714 0.1488357 -0.2250104 -0.9628946 0.0072221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4750 4850 0.037254 -0.476094 -0.084263 0.2232141 0.2162027 -0.7594945 0.5714892 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4751 4851 0.470721 0.219126 0.183720 0.6811288 0.1798815 -0.4929136 0.5106295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4753 4853 -0.179375 0.120365 0.344009 0.3879223 0.5496241 0.1662632 0.7209620 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4754 4854 -0.371836 -0.342944 0.206758 -0.4800795 -0.5669256 -0.5758373 0.3413655 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4756 4856 0.175661 -0.332473 0.320030 -0.6474530 0.0118626 -0.7480465 0.1452253 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4757 4857 0.407898 -0.161785 0.017890 -0.0802033 -0.1132395 -0.9428766 0.3028663 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4758 4858 -0.019442 0.294368 0.413984 -0.1531214 -0.1414940 0.4988106 0.8412617 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4759 4859 -0.004600 0.294286 0.407976 -0.1512121 -0.6956174 0.3171173 0.6266481 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4761 4861 -0.427650 0.149431 0.136819 -0.5692800 0.0633825 0.0452328 0.8184479 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4762 4862 0.442635 0.024521 -0.371365 0.0407007 0.0803124 0.9506433 0.2969356 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4766 4866 0.037149 0.438293 0.181025 0.2048213 0.7090256 -0.6297195 0.2424545 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4768 4868 -0.434045 -0.260776 -0.431421 0.2319432 0.0140818 0.9648150 0.1230290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4770 4870 0.403557 -0.136520 0.135238 -0.6207373 0.2116523 -0.3606223 0.6632044 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4772 4872 -0.263759 -0.276197 -0.049560 -0.3881259 0.8107399 0.3350236 0.2825213 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4773 4873 0.629316 0.145390 -0.222856 0.6115785 -0.2704346 0.4734007 0.5733487 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4774 4874 -0.367268 0.575842 0.000297 -0.1890942 0.3232320 0.6943157 0.6145651 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4775 4875 -0.125354 -0.717598 0.008508 -0.1525791 -0.2851319 0.2750107 0.9054217 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4776 4876 0.489427 0.078455 0.241309 0.6975862 0.0675572 -0.6543119 0.2840520 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4778 4878 -0.468190 -0.269405 -0.234069 0.4615110 -0.2898480 -0.2318953 0.8057421 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4779 4879 0.269610 -0.095731 -0.625470 -0.2218381 0.0554531 -0.5597358 0.7964977 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4780 4880 -0.550331 0.523371 -0.219534 -0.4722946 -0.1856085 0.4076362 0.7591574 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4781 4881 -0.673882 -0.024283 0.186382 0.7539721 -0.2660111 -0.3005626 0.5200252 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4783 4883 -0.537535 0.310792 0.195467 0.5481476 0.2386494 0.5291163 0.6021766 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4784 4884 -0.659971 0.382373 -0.182863 -0.0362705 0.6386231 0.3394410 0.6896556 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4785 4885 0.019386 -0.697580 -0.093413 0.7280665 0.3159623 0.3913115 0.4657921 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4787 4887 0.674018 0.487428 0.081995 -0.1679371 0.5019403 -0.8012479 0.2790249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4789 4889 -0.479916 0.478800 -0.433708 -0.6449589 0.5197405 0.5571640 0.0588732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4790 4890 -0.463134 0.278140 -0.667499 0.1442167 -0.6228722 -0.3077125 0.7046593 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4791 4891 -0.023971 -0.695728 -0.325368 0.2917649 -0.7592643 0.4727305 0.3389939 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4792 4892 -0.678493 0.125282 0.106725 0.2528176 0.0931443 0.0217707 0.9627738 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4796 4896 0.051689 -0.627450 0.428431 0.0105101 0.4513065 0.0630418 0.8900774 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4797 4897 -0.145156 -0.832867 0.304172 0.0877285 0.1003500 -0.4481799 0.8839504 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4799 4899 -0.349723 0.384791 0.341479 -0.1729763 -0.3743340 -0.2467083 0.8769768 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4800 4900 0.593382 0.181649 0.417865 0.2093149 -0.6447792 0.0542185 0.7331490 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4801 4901 -0.044302 0.132408 -0.612570 -0.3013599 -0.3804359 -0.0930588 0.8693623 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4802 4902 0.094546 0.363911 0.595501 0.4034227 0.0155085 -0.6607478 0.6327891 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4803 4903 0.317042 0.569233 -0.224151 -0.5915952 -0.1762988 0.6602334 0.4278150 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4804 4904 0.351635 0.098591 0.803465 0.0597238 -0.5052997 0.2874868 0.8114534 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4805 4905 0.127700 -0.392307 -0.211001 -0.2789032 0.5554793 -0.5778530 0.5289061 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4809 4909 0.293723 0.564657 0.255112 0.4267664 0.3351281 0.8325858 0.1111779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4811 4911 -0.204529 -0.336705 0.654650 0.4766992 -0.2750337 0.7853611 0.2834119 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4813 4913 0.634180 -0.168318 -0.014017 0.1635560 0.5741423 -0.5546663 0.5796166 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4814 4914 0.552719 -0.211738 0.361262 -0.7282012 0.0773723 -0.4715048 0.4913448 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4815 4915 0.657627 0.107947 0.294069 -0.8673404 -0.3796692 -0.1840971 0.2639701 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4816 4916 -0.694186 -0.184293 -0.008750 0.4380514 -0.3068462 -0.5417653 0.6484187 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4817 4917 -0.500049 0.150299 0.225853 0.6277797 -0.0968178 0.7654691 0.1028400 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4819 4919 -0.714347 -0.179371 -0.197228 0.1347438 0.1996153 -0.7915787 0.5616058 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4820 4920 -0.559933 -0.015422 -0.150742 0.7526613 -0.3223913 0.4855499 0.3062779 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4821 4921 0.061165 0.160065 -0.622010 -0.1730805 0.6739803 0.5139441 0.5016524 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4823 4923 0.206000 -0.528688 0.193914 -0.2325397 0.6194368 0.7152561 0.2250157 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4824 4924 0.324172 0.123642 -0.479185 -0.5584622 0.1682789 0.2919700 0.7579945 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4826 4926 0.004537 0.282234 -0.562503 -0.8598001 -0.2848440 -0.2019784 0.3725754 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4827 4927 0.479771 -0.247216 0.024788 -0.8535963 0.2956099 -0.1873895 0.3858410 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4828 4928 -0.153392 0.521805 -0.074302 0.6409930 0.6613545 0.3844280 0.0628750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4829 4929 -0.329753 -0.474104 -0.296455 -0.2126998 0.0762218 -0.3985527 0.8888784 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4830 4930 0.071295 -0.662070 -0.211484 0.6972855 -0.0826555 0.3833941 0.5999750 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4831 4931 -0.594040 0.374666 -0.012149 0.3499177 0.1942494 0.7275624 0.5572053 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4832 4932 0.006198 -0.599363 -0.271716 0.3991436 0.0579747 -0.9128458 0.0635288 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4833 4933 0.318267 -0.048426 -0.328446 -0.4756519 0.3380310 0.6278981 0.5150089 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4834 4934 0.430997 -0.100588 0.297445 0.0752980 -0.0499704 -0.9935707 0.0681941 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4835 4935 -0.025410 -0.499909 0.235198 -0.0524797 -0.4912332 -0.6682715 0.5561916 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4838 4938 -0.520166 0.058087 0.092569 -0.1411562 0.4315040 -0.0608091 0.8889215 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4839 4939 -0.301275 -0.271830 0.321630 -0.0737414 0.4126343 0.4809884 0.7700295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4841 4941 0.125198 -0.583294 0.090329 0.4288934 0.1097555 0.2060514 0.8726666 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4844 4944 -0.267650 0.450297 -0.249039 0.2325229 0.4492808 -0.8239329 0.2553713 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4845 4945 0.384416 0.204451 0.083671 0.0041687 0.0375054 -0.7681372 0.6391723 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4846 4946 -0.015099 -0.367614 -0.239876 -0.1655634 -0.1792093 0.8772178 0.4134751 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4847 4947 -0.204571 -0.134772 -0.387453 0.7536512 -0.0248499 0.2127903 0.6213796 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4848 4948 0.173686 0.412389 -0.255963 -0.1706772 -0.0356034 0.8427213 0.5093353 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4849 4949 -0.074698 0.495824 0.049936 -0.6777252 0.3154627 0.5748210 0.3327953 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4850 4950 0.387197 0.097128 -0.030466 -0.0131798 -0.1444244 -0.7641094 0.6285736 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4851 4951 0.170645 0.319964 -0.273420 0.2034132 -0.6794561 -0.3766552 0.5958971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4853 4953 -0.137780 0.293948 -0.356557 0.3227688 0.1158456 0.6342493 0.6929126 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4854 4954 0.313182 -0.237921 -0.324427 -0.3276144 0.3728242 -0.6856568 0.5324901 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4855 4955 0.454931 -0.068203 -0.044120 0.6838358 -0.5777436 0.0485764 0.4429687 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4856 4956 0.505008 0.225128 0.087034 -0.0327812 0.5590819 -0.5307057 0.6361637 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4857 4957 -0.260929 0.384598 0.188254 0.3055194 0.4025555 -0.5554042 0.6604038 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4858 4958 0.449840 -0.098411 0.422406 -0.6576689 0.3497237 0.6074322 0.2760271 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4859 4959 0.405459 0.160283 -0.290608 0.6826472 -0.0343497 0.6421468 0.3470739 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4860 4960 -0.391225 -0.042801 -0.189361 0.5432593 -0.2717246 -0.0149670 0.7942361 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4861 4961 -0.466660 -0.220788 0.170982 0.3245473 0.4521227 -0.8305928 0.0192265 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4862 4962 -0.282370 -0.500573 -0.269693 0.4582771 -0.0230213 -0.5950307 0.6598414 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4863 4963 -0.210398 0.520809 0.213562 0.3564741 -0.1184316 0.9083635 0.1837821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4864 4964 0.001102 -0.199413 -0.409182 0.5132267 -0.4058048 0.0257954 0.7558144 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4865 4965 -0.064380 0.439710 -0.326530 -0.2777952 -0.0063506 0.2088111 0.9376499 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4867 4967 0.120964 0.573395 -0.008528 -0.1408290 0.4101293 -0.0717339 0.8982290 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4868 4968 -0.109617 0.441899 -0.483601 -0.3475386 0.6312615 -0.3763350 0.5823211 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4870 4970 0.569492 0.020244 0.274920 -0.0220144 -0.6097726 0.6640216 0.4321668 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4871 4971 -0.543778 0.286697 0.404796 -0.0990420 0.9274966 -0.0175287 0.3600465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4872 4972 0.304908 -0.060158 -0.563341 -0.8797539 0.4151932 -0.1038898 0.2070133 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4873 4973 0.254185 -0.345678 0.142421 0.3382027 0.4599561 0.7058158 0.4193846 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4875 4975 0.047843 -0.638910 0.163598 0.1461573 -0.1907942 0.7016062 0.6708088 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4877 4977 0.100898 -0.810923 -0.475330 0.6337326 -0.4920395 -0.5958230 0.0357092 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4878 4978 -0.088218 -0.621029 0.611320 0.3922406 0.5303044 0.2029371 0.7236996 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4879 4979 0.233784 0.429819 -0.716791 -0.5871227 -0.2524478 0.1985684 0.7430529 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4880 4980 -0.024016 0.543096 0.502271 0.1336815 -0.5385331 0.2918615 0.7790560 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4881 4981 -0.415487 0.116878 0.702101 -0.1234124 0.4735284 -0.3426076 0.8019727 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4882 4982 0.358153 -0.073103 -0.565674 -0.5957133 -0.0458170 -0.7803245 0.1847167 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4883 4983 0.146869 0.286971 -0.717190 0.6449736 0.1191022 0.7218810 0.2207068 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4884 4984 0.202511 0.672114 -0.379284 -0.4794760 -0.2867719 -0.2236865 0.7986420 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4885 4985 -0.479793 0.219833 0.264565 -0.0150813 0.8723827 0.4291777 0.2335113 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4886 4986 -0.373095 -0.077391 0.603994 -0.4673184 -0.1844950 0.5915213 0.6306169 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4887 4987 -0.691806 -0.099832 -0.023874 0.4000035 -0.1300699 -0.7338762 0.5333898 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4888 4988 0.143411 -0.207838 -0.553841 -0.2769896 0.7412980 -0.2973739 0.5341562 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4889 4989 0.151709 -0.255666 0.815383 0.1730171 0.9010711 -0.3968813 0.0249221 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4890 4990 -0.618664 -0.052945 0.502676 -0.2973174 0.8601518 0.1405839 0.3898429 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4891 4991 -0.110970 0.108221 0.764745 0.6595353 -0.3345017 0.0761184 0.6688257 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4892 4992 -0.574145 0.015401 -0.275948 0.1414189 -0.0753743 0.4053294 0.9000153 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4893 4993 -0.161904 -0.437483 -0.567994 -0.3974689 0.1424093 -0.3461392 0.8378101 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4894 4994 -0.484494 0.020985 -0.355935 -0.3304660 -0.2938149 -0.8384750 0.3184725 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4895 4995 0.411819 0.031666 -0.624034 -0.1634905 0.1437107 -0.9233849 0.3161937 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4896 4996 -0.278391 -0.651700 0.417969 0.3189456 -0.1608982 -0.4987055 0.7897330 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4897 4997 0.373523 -0.293240 0.495055 0.0868383 -0.1947794 0.6920924 0.6895856 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4900 0 0.364500 0.106421 -0.442949 -0.1150685 0.5416606 -0.5617922 0.6146158 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4902 2 -0.729257 -0.010234 -0.087142 0.0992984 -0.2889593 -0.0294365 0.9517226 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4904 4 0.587719 0.001519 -0.334149 0.0231182 -0.7685347 -0.5666430 0.2962020 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4907 7 0.335125 0.604894 0.468488 0.1613082 0.2315867 -0.9590102 0.0254295 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4908 8 0.423392 0.273800 0.504375 0.6134732 -0.3717464 0.1072915 0.6884357 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4910 10 -0.092341 -0.210219 -0.689138 -0.3604657 -0.2743007 -0.0370719 0.8907577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4911 11 0.547693 0.451256 0.269672 0.3905846 -0.1134428 -0.3800768 0.8307322 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4913 13 -0.189075 0.347187 0.383610 0.6997771 -0.3337848 0.6092741 0.1663872 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4914 14 0.355925 -0.058826 0.350379 0.1884093 -0.0221911 -0.5815812 0.7910580 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4915 15 0.583219 0.452261 -0.284472 0.4324103 0.2116614 0.7636719 0.4301465 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4916 16 0.107690 -0.309834 0.565847 -0.8359959 0.5098621 0.1527295 0.1335106 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4917 17 0.364234 0.272311 -0.411534 -0.0245380 -0.1754297 -0.9715674 0.1570955 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4918 18 0.199971 0.425277 0.439051 0.0080272 0.2061481 -0.7467972 0.6322440 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4919 19 0.356511 -0.409281 -0.194898 -0.1634059 0.3580707 -0.7875734 0.4741434 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4920 20 -0.386368 0.462260 -0.046265 0.0753827 0.4092256 0.1635158 0.8944911 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4921 21 0.499574 -0.068055 0.114134 0.2339672 0.0863104 -0.2335217 0.9398284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4922 22 -0.286888 0.435797 -0.190284 -0.4924130 0.5968519 0.0798673 0.6284254 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4923 23 -0.434802 -0.020507 -0.407917 0.7414382 -0.1832471 -0.6276942 0.1506315 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4924 24 0.690651 -0.001813 0.178249 -0.0920874 -0.3482491 0.5515585 0.7523468 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4925 25 0.210145 0.124532 -0.564082 0.6135976 -0.5053783 -0.5911196 0.1366323 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4926 26 -0.384502 -0.038453 0.437256 0.1971781 -0.6719760 -0.1278588 0.7022971 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4928 28 0.405604 -0.385670 0.007858 -0.7512325 0.4548603 -0.1654017 0.4487694 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4929 29 0.335475 -0.416196 -0.396906 -0.4926373 0.6177925 0.0074257 0.6128505 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4930 30 -0.098405 0.188881 0.555089 -0.8042360 -0.5442727 -0.1838122 0.1522654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4931 31 0.254656 0.273777 -0.367917 0.4522327 0.3244844 -0.1779115 0.8115066 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4934 34 -0.440501 0.181786 0.275910 -0.3111628 0.5914317 -0.0042284 0.7438874 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4935 35 0.481037 0.181374 -0.031191 0.3352858 0.3677828 0.6359535 0.5898155 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4936 36 -0.294502 0.181990 -0.492620 0.8629637 0.1710108 -0.4750283 0.0199263 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4937 37 0.028292 0.563750 0.131217 -0.8039002 -0.1821979 0.2621702 0.5018118 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4938 38 -0.474619 -0.201674 -0.194839 0.5250868 -0.2640738 -0.7930867 0.1598821 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4940 40 0.423304 0.080901 0.075579 0.2260803 -0.5771909 0.7560329 0.2101249 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4941 41 0.083109 -0.254391 0.456055 -0.1511441 -0.7428093 0.1498570 0.6347697 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4944 44 0.429351 -0.158594 -0.487081 -0.1203538 -0.3509852 -0.7307830 0.5729577 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4945 45 -0.379238 0.216770 -0.153776 0.2767386 -0.0199508 0.1833595 0.9430785 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4946 46 -0.301884 0.364507 -0.090658 0.4942848 -0.3392100 0.6430949 0.4764956 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4948 48 0.575271 -0.227433 0.090729 0.4695285 0.2125295 -0.6424706 0.5671029 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4950 50 -0.349219 0.445749 0.068284 -0.3035737 0.1887341 0.0929696 0.9292896 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4951 51 -0.578401 -0.289997 0.106805 -0.7063877 0.2915959 0.3586041 0.5360889 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4952 52 -0.518570 0.076071 -0.465678 -0.3779041 -0.5615348 -0.5527600 0.4861312 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4953 53 0.124979 -0.077284 -0.448842 -0.1316719 0.6287783 -0.4717405 0.6039546 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4955 55 0.375391 -0.313783 -0.093253 0.0891465 -0.1993593 -0.8338101 0.5070201 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4957 57 -0.317389 -0.226017 -0.217278 -0.3822367 0.0556708 0.8247318 0.4130536 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4958 58 -0.412243 -0.138863 -0.466614 -0.0673708 0.0728001 -0.9352267 0.3398711 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4959 59 -0.122052 -0.410606 0.360649 -0.2870982 0.4013328 0.7562214 0.4296927 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4960 60 -0.359787 -0.041026 0.439764 0.0299150 0.4922866 0.8298086 0.2611067 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4961 61 0.244950 -0.225161 0.299875 0.7444421 0.3032188 -0.5768771 0.1451795 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4964 64 -0.269244 -0.458176 -0.033488 -0.5245296 0.0381742 -0.0586369 0.8485123 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4965 65 0.101841 0.649817 0.147024 -0.4680103 0.4637599 0.4895872 0.5711370 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4966 66 0.225085 -0.140948 -0.393345 -0.0404207 -0.1238362 -0.9702782 0.2039385 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4968 68 -0.107085 0.565633 -0.078895 -0.3833718 -0.6697058 0.0148338 0.6358460 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4969 69 -0.459080 -0.027467 0.642341 0.7012649 0.3324805 0.4139700 0.4757238 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4970 70 -0.024071 -0.633136 -0.250788 -0.5040249 -0.2023967 -0.8309081 0.1207732 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4973 73 -0.495343 0.076531 -0.010737 0.3666518 0.5910207 0.4252908 0.5791276 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4977 77 0.719682 0.179930 -0.426254 -0.2208706 0.3956752 0.2583913 0.8531654 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4978 78 -0.578548 -0.056789 0.289465 -0.5030886 0.5652709 0.5929282 0.2753304 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4979 79 0.372562 0.448762 0.136493 0.5681453 -0.2603942 0.2528560 0.7385592 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4980 80 0.753770 0.288788 0.286309 0.0218083 0.6743111 -0.0359779 0.7372480 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4982 82 -0.663840 0.362230 0.312036 -0.1546822 0.1966971 0.6011395 0.7589565 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4983 83 -0.503264 -0.426111 0.006911 0.4273438 -0.4262512 0.6641899 0.4410657 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4984 84 -0.180709 0.418307 0.376912 -0.4687633 -0.1362883 -0.8697897 0.0717802 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4985 85 0.229191 0.563647 -0.393524 -0.7274777 0.2579682 0.5579663 0.3047987 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4986 86 -0.329577 -0.594040 0.511647 0.5577647 0.7676528 0.3151597 0.0167919 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4987 87 0.398865 -0.549209 0.351950 -0.5876410 -0.4197381 -0.3928907 0.5693284 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4989 89 -0.206692 -0.505840 -0.519792 -0.2617402 -0.1011895 -0.8150691 0.5068679 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4990 90 0.025819 0.289637 -0.404307 -0.4260088 0.1902100 0.8399071 0.2772954 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4991 91 0.147185 0.635818 0.064290 -0.5573100 0.0835380 -0.6759158 0.4749367 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4992 92 -0.315889 0.600588 -0.027245 -0.1335588 0.9181398 0.0463448 0.3701803 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4993 93 0.371615 0.425771 -0.619725 0.0935106 0.4129086 -0.4977010 0.7570046 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4994 94 0.213857 -0.363748 -0.838163 -0.3379352 0.1709633 -0.8985281 0.2218527 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4995 95 -0.669778 0.064536 -0.230214 -0.0873428 -0.4932427 -0.0579561 0.8635531 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4996 96 0.414156 0.173829 0.698495 -0.3944655 -0.3827311 0.3738420 0.7470985 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 +EDGE_SE3:QUAT 4997 97 -0.178777 -0.653848 0.611690 0.2419071 -0.1443965 0.3463294 0.8948109 100.000000 0.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 0.000000 100.000000 0.000000 0.000000 0.000000 400.000000 0.000000 0.000000 400.000000 0.000000 400.000000 diff --git a/pgo.py b/pgo.py index bc069d4..154b3db 100644 --- a/pgo.py +++ b/pgo.py @@ -1,27 +1,26 @@ -from functools import partial import os +import time import torch import argparse import pypose as pp from torch import nn -from torch.func import jacrev from bae.autograd.function import TrackingTensor, map_transform -from bae.autograd.graph import construct_sbt -from bae.sparse.py_ops import diagonal_op_ from bae.utils.pgo_dataset import G2OPGO -from bae.utils.pgo import plot_and_save -import pypose.optim.solver as ppos -import pypose.optim.kernel as ppok -import pypose.optim.corrector as ppoc -import pypose.optim.strategy as ppost +from bae.utils.pgo import plot_and_save, render_frame, save_gif from pypose.optim.scheduler import StopOnPlateau -from bae.utils.pysolvers import PCG, cuSolverSP +from bae.utils.pysolvers import PCG from bae.optim import LM OPTIMIZE_INTRINSICS = False USE_QUATERNIONS=True DTYPE = torch.float64 +DTYPE_CHOICES = { + 'float64': torch.float64, + 'fp64': torch.float64, + 'float32': torch.float32, + 'fp32': torch.float32, +} torch.set_printoptions(precision=6) @@ -62,46 +61,24 @@ def write_ceres_txt(nodes, filename='data.s'): 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 foo(poses, node1, node2, infos): - node1 = pp.SE3(node1) - node2 = pp.SE3(node2) - poses = pp.SE3(poses) - # The measured relative transform (Pose) is poses = z_ab = [hat{p}_{ab}, hat{q}_{ab}]. - # The predicted relative transform x_ab_est = x_a^-1 @ x_b - q_a = node1.rotation() - p_a = node1.translation() - q_b = node2.rotation() - p_b = node2.translation() - - q_ab_est = q_a.Inv() @ q_b - p_ab_est = q_a.Inv() @ (p_b - p_a) - - p_ab_meas = poses.translation() # hat{p}_{ab} - q_ab_meas = poses.rotation() # hat{q}_{ab} - - # Compute the position part of the residual: p_ab_est - p_ab_meas - r_p = p_ab_est - p_ab_meas - - # Compute the orientation part: - # 2 * vec( (q_ab_est) * (q_ab_meas^-1) ) - # where q_ab_est * q_ab_meas^-1 is a quaternion, and vec(...) is its imaginary part. - delta_q = q_ab_meas @ q_ab_est.Inv() - # PyPose quaternions by default have layout [w, x, y, z]; - # the imaginary part is q_res[..., 1:4]. - r_q = delta_q.tensor()[..., :3] - - # Concatenate into a 6D residual per edge: [ position_error | orientation_error ] - residual = torch.cat([r_p, r_q], dim=-1) +def _pose_graph_residual(poses, node1, node2, infos): + if isinstance(infos, TrackingTensor): + infos = infos.tensor() + + 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}). + delta_q = poses.rotation() @ pose_ab_est.rotation().Inv() + r_q = 2.0 * delta_q.tensor()[..., :3] + + residual = torch.cat((r_p, r_q), dim=-1) residual = infos @ residual[..., None] - residual = residual[..., 0] - return residual + return residual[..., 0] + @map_transform -def foo(poses, node1, node2, infos): - residual = (poses.Inv() @ node1.Inv() @ node2).Log().tensor() - residual = infos @ residual[..., None] - residual = residual[..., 0] - return residual +def _tracked_pose_graph_residual(poses, node1, node2, infos): + return _pose_graph_residual(poses, node1, node2, infos) class PoseGraph(nn.Module): @@ -112,10 +89,22 @@ def __init__(self, nodes): def forward(self, edges, poses, infos): node1 = self.nodes[edges[..., 0]] node2 = self.nodes[edges[..., 1]] - return foo(poses, node1, node2, infos) + return _tracked_pose_graph_residual(poses, node1, node2, infos) -from bae.optim import LM +class PoseGraphFixedFirst(nn.Module): + def __init__(self, nodes_rest): + super().__init__() + self.nodes_rest = nn.Parameter(TrackingTensor(nodes_rest)) + + def nodes_all(self, node_fixed): + return torch.cat([node_fixed, self.nodes_rest], dim=0) + + def forward(self, edges, poses, infos, node_fixed): + nodes = self.nodes_all(node_fixed) + node1 = nodes[edges[..., 0]] + node2 = nodes[edges[..., 1]] + return _tracked_pose_graph_residual(poses, node1, node2, infos) if __name__ == '__main__': @@ -128,54 +117,104 @@ def forward(self, edges, poses, infos): help="dataset location") parser.add_argument("--dataname", type=str, default='parking-garage.g2o', \ help="dataset name") # sphere_bignoise_vertex3, torus3D, grid3D, parking-garage + parser.add_argument('--gif', action='store_true', \ + help='save an animated GIF of optimization progress') + parser.add_argument('--gif-every', type=int, default=1, \ + help='capture every N optimization steps in the GIF') + parser.add_argument('--gif-duration', type=int, default=250, \ + help='GIF frame duration in milliseconds') parser.add_argument('--no-vectorize', dest='vectorize', action='store_false', \ help="to save memory") parser.add_argument('--vectorize', action='store_true', \ help='to accelerate computation') + parser.add_argument("--steps", type=int, default=80, \ + help="number of LM outer iterations") + parser.add_argument('--dtype', type=str, default='float64', choices=tuple(DTYPE_CHOICES.keys()), \ + help='parameter / residual dtype') + parser.add_argument('--no-gauge-fix', dest='gauge_fix', action='store_false', \ + help='optimize all nodes (disables fixed-first-node gauge constraint)') + parser.set_defaults(gauge_fix=True) parser.set_defaults(vectorize=True) args = parser.parse_args(); print(args) os.makedirs(os.path.join(args.save), exist_ok=True) + if args.gif_every < 1: + raise ValueError('--gif-every must be >= 1') + dtype = DTYPE_CHOICES[args.dtype] data = G2OPGO(args.dataroot, args.dataname, device=args.device, download=True) - data.nodes = data.nodes.to(DTYPE) - data.poses = data.poses.to(DTYPE) - data.infos = data.infos.to(DTYPE) + data.nodes = data.nodes.to(dtype) + data.poses = data.poses.to(dtype) + data.infos = data.infos.to(dtype) edges, poses, infos = data.edges, data.poses, data.infos infos = torch.linalg.cholesky(infos) - input = {'edges': edges, 'poses': poses, 'infos': infos} - - graph = PoseGraph(data.nodes).to(args.device) - # solver = PCG(tol=1e-5) - solver = cuSolverSP() - # solver = ppos.Cholesky() - # strategy = ppost.TrustRegion(radius=1e4, min=1e-32, max=1e16) - # strategy = pp.optim.strategy.TrustRegion(up=2.0, down=0.5**4) + if args.gauge_fix: + if data.nodes.shape[0] < 2: + raise ValueError("Gauge-fix mode requires at least two nodes.") + node_fixed = data.nodes[:1].clone() + input = {'edges': edges, 'poses': poses, 'infos': infos, 'node_fixed': node_fixed} + graph = PoseGraphFixedFirst(data.nodes[1:]).to(args.device) + else: + input = {'edges': edges, 'poses': poses, 'infos': infos} + graph = PoseGraph(data.nodes).to(args.device) + solver = PCG(tol=1e-5) strategy = pp.optim.strategy.Adaptive() optimizer = LM(graph, solver=solver, strategy=strategy, min=1e-10, reject=30) scheduler = StopOnPlateau(optimizer, steps=20, patience=3, decreasing=1e-7, verbose=True) - pngname = os.path.join(args.save, args.dataname+'.png') - plot_and_save(graph.nodes.translation(), pngname, args.dataname) - axlim = None - ### the 1st implementation: for customization and easy to extend - start = torch.cuda.Event(enable_timing=True) - end = torch.cuda.Event(enable_timing=True) - start.record() - for i in range(10): + if args.gauge_fix: + nodes_current = graph.nodes_all(input['node_fixed']) + else: + nodes_current = graph.nodes + + sample_prefix = os.path.join(args.save, os.path.splitext(args.dataname)[0]) + nodes_current = nodes_current if isinstance(nodes_current, pp.LieTensor) else pp.SE3(nodes_current) + plot_and_save(nodes_current.translation(), sample_prefix + '.png', args.dataname) + + gif_frames = [] + if args.gif: + frame, _ = render_frame(nodes_current.translation(), args.dataname) + gif_frames.append(frame) + + if args.device == 'cuda': + start = torch.cuda.Event(enable_timing=True) + end = torch.cuda.Event(enable_timing=True) + start.record() + else: + start = time.perf_counter() + for i in range(args.steps): loss = optimizer.step(input=input, weight=infos) scheduler.step(loss) - name = os.path.join(args.save, args.dataname + '_' + str(scheduler.steps)) + name = os.path.join(args.save, os.path.splitext(args.dataname)[0] + '_' + str(scheduler.steps)) title = 'PGO at the %d step(s) with loss %7f'%(scheduler.steps, loss.item()) - torch.cuda.synchronize() - end.record() - print('Time elapsed: %.3f ms'%(start.elapsed_time(end))) + if args.gif and ((i + 1) % args.gif_every == 0 or i == args.steps - 1): + if args.gauge_fix: + nodes_current = graph.nodes_all(input['node_fixed']) + else: + nodes_current = graph.nodes + nodes_current = nodes_current if isinstance(nodes_current, pp.LieTensor) else pp.SE3(nodes_current) + frame, _ = render_frame(nodes_current.translation(), title) + gif_frames.append(frame) + if args.device == 'cuda': + end.record() + torch.cuda.synchronize() + print('Time elapsed: %.3f ms'%(start.elapsed_time(end))) + else: + elapsed_ms = (time.perf_counter() - start) * 1000.0 + print('Time elapsed: %.3f ms'%(elapsed_ms)) print('Final loss: %7f'%(loss.item()/2)) - plot_and_save(graph.nodes.translation(), name+'.png', title, axlim=axlim) + if args.gauge_fix: + nodes_current = graph.nodes_all(input['node_fixed']) + else: + nodes_current = graph.nodes + nodes_current = nodes_current if isinstance(nodes_current, pp.LieTensor) else pp.SE3(nodes_current) + plot_and_save(nodes_current.translation(), name+'.png', title) torch.save(graph.state_dict(), name+'.pt') - write_ceres_txt(graph.nodes, name+'.txt') + write_ceres_txt(nodes_current.tensor() if isinstance(nodes_current, pp.LieTensor) else nodes_current, name+'.txt') + if args.gif: + save_gif(gif_frames, sample_prefix + '.gif', duration=args.gif_duration) ### The 2nd implementation: equivalent to the 1st one, but more compact # scheduler.optimize(input=(edges, poses, infos)) diff --git a/tests/autograd/test_bal_jacobian.py b/tests/autograd/test_bal_jacobian.py index 0360dbb..d277be5 100644 --- a/tests/autograd/test_bal_jacobian.py +++ b/tests/autograd/test_bal_jacobian.py @@ -19,6 +19,8 @@ if str(_REPO_ROOT) not in sys.path: sys.path.insert(0, str(_REPO_ROOT)) +os.environ.setdefault("BAE_USE_PYPOSE_AMBIENT_GRAD", "1") + from ba_example import Residual, project, least_square_error # noqa: E402 from bae.autograd.function import TrackingTensor, map_transform import bae.autograd.graph as autograd_graph # noqa: E402 diff --git a/tests/autograd/test_graph_jacobian.py b/tests/autograd/test_graph_jacobian.py index 7499915..ea67380 100644 --- a/tests/autograd/test_graph_jacobian.py +++ b/tests/autograd/test_graph_jacobian.py @@ -1,11 +1,24 @@ +import os + import pytest import pypose as pp import torch from torch import nn from torch.func import jacrev +os.environ.setdefault("BAE_USE_PYPOSE_AMBIENT_GRAD", "1") + from bae.autograd.function import TrackingTensor as Track, map_transform from bae.autograd.graph import jacobian as sparse_jacobian +from bae.utils.ceres_pose import se3_pose_plus_jacobian_xyzw +from bae.utils.pypose_ambient_grad import ( + install_pypose_ambient_grad_monkeypatch, + pypose_ambient_grad_enabled, +) + + +if pypose_ambient_grad_enabled(): + install_pypose_ambient_grad_monkeypatch() class ToyResidual(nn.Module): @@ -32,6 +45,12 @@ def _flatten_jac(J: torch.Tensor) -> torch.Tensor: return J.reshape(n * outdim, num * indim) +def _localize_pose_blocks_se3(jac_dense: torch.Tensor, nodes: torch.Tensor) -> torch.Tensor: + jac_dense = jac_dense.reshape(jac_dense.shape[0], nodes.shape[0], 7) + plus = se3_pose_plus_jacobian_xyzw(nodes) + return torch.einsum("bni,nij->bnj", jac_dense, plus).reshape(jac_dense.shape[0], nodes.shape[0] * 6) + + @map_transform def _relative_se3_residual(poses: pp.LieTensor, node1: pp.LieTensor, node2: pp.LieTensor) -> torch.Tensor: return (poses.Inv() @ node1.Inv() @ node2).Log().tensor() @@ -346,4 +365,8 @@ def f(nodes_data: torch.Tensor) -> torch.Tensor: return (poses.Inv() @ nodes[idx1].Inv() @ nodes[idx2]).Log().tensor() (J_dense,) = jacrev(f, argnums=(0,))(nodes_tensor) - torch.testing.assert_close(J_sparse.to_dense(), _flatten_jac(J_dense[..., :6]), rtol=1e-10, atol=1e-10) + if pypose_ambient_grad_enabled(): + J_ref = _localize_pose_blocks_se3(_flatten_jac(J_dense), nodes0.tensor()) + else: + J_ref = _flatten_jac(J_dense[..., :6]) + torch.testing.assert_close(J_sparse.to_dense(), J_ref, rtol=1e-10, atol=1e-10) diff --git a/tests/autograd/test_pgo_convergence.py b/tests/autograd/test_pgo_convergence.py new file mode 100644 index 0000000..5b8b398 --- /dev/null +++ b/tests/autograd/test_pgo_convergence.py @@ -0,0 +1,119 @@ +from __future__ import annotations + +import contextlib +import io +from pathlib import Path +import sys +from time import perf_counter +import warnings + +import pypose as pp +import pytest +import torch + +_REPO_ROOT = Path(__file__).resolve().parents[2] +if str(_REPO_ROOT) not in sys.path: + sys.path.insert(0, str(_REPO_ROOT)) + +from bae.optim import LM # noqa: E402 +from bae.utils.pgo_dataset import G2OPGO # noqa: E402 +from bae.utils.pysolvers import PCG # noqa: E402 +from pgo import PoseGraphFixedFirst # noqa: E402 + + +pytestmark = [ + pytest.mark.filterwarnings(r"ignore:CUDA initialization.*:UserWarning"), + pytest.mark.filterwarnings(r"ignore:Sparse BSR tensor support is in beta state.*:UserWarning"), + pytest.mark.skipif(not torch.cuda.is_available(), reason="CUDA required for PGO convergence regression"), +] + + +_PGO_DATA_DIR = _REPO_ROOT / "examples" / "module" / "pgo" / "data" +_DTYPE = torch.float64 +_PGO_STEPS = 80 + +# These reference costs were generated from Ceres +_PGO_EXPECTED_FINAL_COSTS: dict[str, float] = { + "sphere_bignoise_vertex3.g2o": 1478347.8373251208, + "torus3D.g2o": 22556.189328244574, + "grid3D.g2o": 42159.50839315247, +} +_PGO_CERES_TOTAL_RUNTIMES_S: dict[str, float] = { + "sphere_bignoise_vertex3.g2o": 4.880856, + "torus3D.g2o": 13.917892, + "grid3D.g2o": 141.117555, +} + + +def _run_pgo_final_cost_fixed_first(sample_name: str) -> tuple[float, float]: + sample_path = _PGO_DATA_DIR / sample_name + if not sample_path.exists(): + pytest.skip(f"Missing PGO dataset: {sample_path}") + + device = torch.device("cuda") + data = G2OPGO(str(_PGO_DATA_DIR), sample_name, device=str(device), download=False) + nodes = data.nodes.tensor() if isinstance(data.nodes, pp.LieTensor) else data.nodes + poses = data.poses.tensor() if isinstance(data.poses, pp.LieTensor) else data.poses + + nodes = nodes.to(dtype=_DTYPE) + poses = poses.to(dtype=_DTYPE) + infos = torch.linalg.cholesky(data.infos.to(dtype=_DTYPE)) + + if nodes.shape[0] < 2: + pytest.skip(f"PGO sample has <2 nodes: {sample_name}") + + node_fixed = nodes[:1].clone() + model = PoseGraphFixedFirst(nodes[1:].clone()).to(device) + solver = PCG(tol=1e-5) + strategy = pp.optim.strategy.Adaptive() + optimizer = LM(model, solver=solver, strategy=strategy, min=1e-10, reject=30) + input = { + "edges": data.edges, + "poses": poses, + "infos": infos, + "node_fixed": node_fixed, + } + + # LM emits per-step diagnostics; keep the regression test output quiet. + torch.cuda.synchronize(device) + start = perf_counter() + with contextlib.redirect_stdout(io.StringIO()): + for _ in range(_PGO_STEPS): + optimizer.step(input=input, weight=infos) + torch.cuda.synchronize(device) + runtime_s = perf_counter() - start + + with torch.no_grad(): + residual = model(data.edges, poses, infos, node_fixed) + return 0.5 * residual.square().sum().item(), runtime_s + + +@pytest.mark.parametrize( + "sample_name", + [ + "sphere_bignoise_vertex3.g2o", + "torus3D.g2o", + "grid3D.g2o", + ], +) +def test_pgo_convergence_matches_ceres_reference(sample_name: str): + final_cost, runtime_s = _run_pgo_final_cost_fixed_first(sample_name) + assert torch.isfinite(torch.tensor(final_cost)) + + expected = _PGO_EXPECTED_FINAL_COSTS.get(sample_name) + assert expected is not None + assert final_cost == pytest.approx(expected, abs=2.0) + + ceres_runtime_s = _PGO_CERES_TOTAL_RUNTIMES_S.get(sample_name) + assert ceres_runtime_s is not None + speedup_ratio = ceres_runtime_s / runtime_s + print( + f"{sample_name}: ours={runtime_s:.6f}s, ceres={ceres_runtime_s:.6f}s, " + f"speedup_vs_ceres={speedup_ratio:.3f}x" + ) + if speedup_ratio < 1.0: + warnings.warn( + f"{sample_name}: ours is slower than Ceres " + f"({runtime_s:.6f}s vs {ceres_runtime_s:.6f}s, speedup {speedup_ratio:.3f}x)", + stacklevel=2, + ) diff --git a/tests/autograd/test_pgo_jacobian.py b/tests/autograd/test_pgo_jacobian.py new file mode 100644 index 0000000..7ad259d --- /dev/null +++ b/tests/autograd/test_pgo_jacobian.py @@ -0,0 +1,164 @@ +from __future__ import annotations + +from pathlib import Path +import os +import sys + +import pypose as pp +import pytest +import torch +from torch.func import jacrev + +_REPO_ROOT = Path(__file__).resolve().parents[2] +if str(_REPO_ROOT) not in sys.path: + sys.path.insert(0, str(_REPO_ROOT)) + +os.environ.setdefault("BAE_USE_PYPOSE_AMBIENT_GRAD", "1") + +from bae.autograd.graph import jacobian as sparse_jacobian # noqa: E402 +from bae.utils.ceres_pose import se3_pose_plus_jacobian_xyzw # noqa: E402 +from bae.utils.pgo_dataset import G2OPGO # noqa: E402 +from pgo import PoseGraph, PoseGraphFixedFirst, _pose_graph_residual # noqa: E402 + + +pytestmark = [ + pytest.mark.filterwarnings(r"ignore:CUDA initialization.*:UserWarning"), + pytest.mark.filterwarnings(r"ignore:Sparse BSR tensor support is in beta state.*:UserWarning"), +] + + +_PARKING_DATAROOT = _REPO_ROOT / "examples" / "module" / "pgo" / "data" +_PARKING_FILENAME = "parking-garage.g2o" +_JACOBIAN_EDGE_SUBSET = 16 + + +def _dense_residual( + poses: torch.Tensor, + node1: torch.Tensor, + node2: torch.Tensor, + infos: torch.Tensor, +) -> torch.Tensor: + return _pose_graph_residual(poses, node1, node2, infos) + + +def _flatten_jac(jac: torch.Tensor) -> torch.Tensor: + # [num_edges, 6, num_nodes, 7] -> [num_edges*6, num_nodes*7] + return jac.reshape(jac.shape[0] * jac.shape[1], jac.shape[2] * jac.shape[3]) + + +def _localize_pose_blocks_se3(jac_dense: torch.Tensor, nodes: torch.Tensor) -> torch.Tensor: + jac_dense = jac_dense.reshape(jac_dense.shape[0], nodes.shape[0], 7) + plus = se3_pose_plus_jacobian_xyzw(nodes) + return torch.einsum("bni,nij->bnj", jac_dense, plus).reshape(jac_dense.shape[0], nodes.shape[0] * 6) + + +def _load_parking_subset(device: torch.device, dtype: torch.dtype): + path = _PARKING_DATAROOT / _PARKING_FILENAME + if not path.exists(): + pytest.skip(f"Missing PGO dataset: {path}") + + data = G2OPGO(str(_PARKING_DATAROOT), _PARKING_FILENAME, device=str(device), download=False) + nodes = data.nodes if isinstance(data.nodes, pp.LieTensor) else pp.SE3(data.nodes) + poses = data.poses if isinstance(data.poses, pp.LieTensor) else pp.SE3(data.poses) + + edges_full = data.edges[:_JACOBIAN_EDGE_SUBSET].to(torch.long) + unique_nodes = torch.unique(edges_full.reshape(-1), sorted=True) + + lut = torch.full((int(unique_nodes.max()) + 1,), -1, dtype=torch.long, device=device) + lut[unique_nodes] = torch.arange(unique_nodes.numel(), dtype=torch.long, device=device) + edges = lut[edges_full] + + nodes = nodes[unique_nodes].to(dtype=dtype) + poses = poses[:_JACOBIAN_EDGE_SUBSET].to(dtype=dtype) + infos = torch.linalg.cholesky(data.infos[:_JACOBIAN_EDGE_SUBSET].to(dtype=dtype)) + + return nodes, edges, poses, infos + + +def test_pose_graph_residual_matches_ceres_closed_form(): + device = torch.device("cuda" if torch.cuda.is_available() else "cpu") + dtype = torch.float64 + + nodes = pp.randn_SE3(2, sigma=0.2, device=device).to(dtype=dtype) + n1 = nodes[:1] + n2 = nodes[1:2] + poses = pp.randn_SE3(1, sigma=0.1, device=device).to(dtype=dtype) + infos = torch.eye(6, dtype=dtype, device=device).unsqueeze(0) + + q_a = n1.rotation() + p_a = n1.translation() + q_b = n2.rotation() + p_b = n2.translation() + q_ab_est = q_a.Inv() @ q_b + p_ab_est = q_a.Inv() @ (p_b - p_a) + delta_q = pp.SO3(poses[:, 3:7]) @ q_ab_est.Inv() + expected = torch.cat((p_ab_est - poses[:, :3], 2.0 * delta_q.tensor()[..., :3]), dim=-1) + + actual = _pose_graph_residual(poses, nodes[:1], nodes[1:2], infos) + torch.testing.assert_close(actual, expected, rtol=1e-7, atol=1e-7) + + +def test_se3_pose_plus_jacobian_matches_finite_difference(): + device = torch.device("cuda" if torch.cuda.is_available() else "cpu") + dtype = torch.float64 + pose = pp.randn_SE3(sigma=0.2, device=device).to(dtype=dtype) + plus = se3_pose_plus_jacobian_xyzw(pose.tensor()) + + eps = 1e-7 + fd = torch.zeros_like(plus) + for i in range(6): + delta = torch.zeros(6, dtype=dtype, device=device) + delta[i] = eps + forward = (pp.se3(delta).Exp() * pose).tensor() + backward = (pp.se3(-delta).Exp() * pose).tensor() + fd[:, i] = (forward - backward) / (2.0 * eps) + + torch.testing.assert_close(plus, fd, rtol=1e-8, atol=1e-8) + + +@pytest.mark.skipif(not torch.cuda.is_available(), reason="CUDA required (CPU sparse BSR add does not support 6x7 blocks)") +def test_pgo_jacobian_gauge_free_sparse_matches_dense(): + device = torch.device("cuda") + dtype = torch.float64 + + nodes0, edges, poses, infos = _load_parking_subset(device, dtype) + model = PoseGraph(nodes0.clone()).to(device) + residual = model(edges, poses, infos) + + (J_sparse,) = sparse_jacobian(residual, [model.nodes]) + assert J_sparse.layout == torch.sparse_bsr + + def f(nodes: torch.Tensor) -> torch.Tensor: + return _pose_graph_residual(poses, pp.SE3(nodes)[edges[:, 0]], pp.SE3(nodes)[edges[:, 1]], infos) + + J_dense = jacrev(f)(nodes0.tensor()) + J_dense = _localize_pose_blocks_se3(_flatten_jac(J_dense), nodes0.tensor()) + + assert J_sparse.shape == J_dense.shape + torch.testing.assert_close(J_sparse.to_dense(), J_dense, rtol=1e-10, atol=1e-10) + +@pytest.mark.skipif(not torch.cuda.is_available(), reason="CUDA required (CPU sparse BSR add does not support 6x7 blocks)") +def test_pgo_jacobian_fixed_first_sparse_matches_dense(): + device = torch.device("cuda") + dtype = torch.float64 + + nodes0, edges, poses, infos = _load_parking_subset(device, dtype) + assert nodes0.shape[0] >= 2 + + node_fixed = nodes0[:1].clone() + nodes_rest0 = nodes0[1:].clone() + model = PoseGraphFixedFirst(nodes_rest0.clone()).to(device) + residual = model(edges, poses, infos, node_fixed) + + (J_sparse,) = sparse_jacobian(residual, [model.nodes_rest]) + assert J_sparse.layout == torch.sparse_bsr + + def f(nodes_rest: torch.Tensor) -> torch.Tensor: + nodes = torch.cat([node_fixed, nodes_rest], dim=0) + return _pose_graph_residual(poses, pp.SE3(nodes)[edges[:, 0]], pp.SE3(nodes)[edges[:, 1]], infos) + + J_dense = jacrev(f)(nodes_rest0.tensor()) + J_dense = _localize_pose_blocks_se3(_flatten_jac(J_dense), nodes_rest0.tensor()) + + assert J_sparse.shape == J_dense.shape + torch.testing.assert_close(J_sparse.to_dense(), J_dense, rtol=1e-10, atol=1e-10) diff --git a/tests/autograd/test_pypose_ambient_grad.py b/tests/autograd/test_pypose_ambient_grad.py new file mode 100644 index 0000000..8aa7e0f --- /dev/null +++ b/tests/autograd/test_pypose_ambient_grad.py @@ -0,0 +1,85 @@ +from __future__ import annotations + +from pathlib import Path +import sys + +import pypose as pp +import pytest +import torch + +_REPO_ROOT = Path(__file__).resolve().parents[2] +if str(_REPO_ROOT) not in sys.path: + sys.path.insert(0, str(_REPO_ROOT)) + +from bae.utils.pypose_ambient_grad import install_pypose_ambient_grad_monkeypatch # noqa: E402 + + +pytestmark = [ + pytest.mark.filterwarnings(r"ignore:CUDA initialization.*:UserWarning"), +] + + +def _fd_jacobian(func, x: torch.Tensor, eps: float = 1e-7) -> torch.Tensor: + y0 = func(x) + jac = torch.zeros(y0.numel(), x.numel(), dtype=x.dtype, device=x.device) + for i in range(x.numel()): + xp = x.clone() + xm = x.clone() + xp.view(-1)[i] += eps + xm.view(-1)[i] -= eps + jac[:, i] = ((func(xp) - func(xm)) / (2.0 * eps)).reshape(-1) + return jac.reshape(*y0.shape, *x.shape) + + +def test_pypose_se3_act_monkeypatch_produces_ambient_gradient(): + install_pypose_ambient_grad_monkeypatch() + device = torch.device("cuda" if torch.cuda.is_available() else "cpu") + dtype = torch.float64 + + pose = pp.randn_SE3(1, sigma=0.2, device=device).tensor().to(dtype=dtype) + point = torch.randn(1, 3, device=device, dtype=dtype) + + jac = torch.func.jacrev(lambda x: pp.SE3(x).Act(point))(pose) + jac_fd = _fd_jacobian(lambda x: pp.SE3(x).Act(point), pose) + + torch.testing.assert_close(jac, jac_fd, rtol=1e-7, atol=1e-7) + + +def test_pypose_se3_mul_monkeypatch_produces_ambient_gradient(): + install_pypose_ambient_grad_monkeypatch() + device = torch.device("cuda" if torch.cuda.is_available() else "cpu") + dtype = torch.float64 + + x = pp.randn_SE3(1, sigma=0.2, device=device).tensor().to(dtype=dtype) + y = pp.randn_SE3(1, sigma=0.2, device=device).tensor().to(dtype=dtype) + + jac = torch.func.jacrev(lambda a: (pp.SE3(a) * pp.SE3(y)).tensor())(x) + jac_fd = _fd_jacobian(lambda a: (pp.SE3(a) * pp.SE3(y)).tensor(), x) + + torch.testing.assert_close(jac, jac_fd, rtol=1e-7, atol=1e-7) + + +def test_pypose_se3_log_monkeypatch_produces_ambient_gradient(): + install_pypose_ambient_grad_monkeypatch() + device = torch.device("cuda" if torch.cuda.is_available() else "cpu") + dtype = torch.float64 + + pose = pp.randn_SE3(1, sigma=0.2, device=device).tensor().to(dtype=dtype) + + jac = torch.func.jacrev(lambda x: pp.SE3(x).Log().tensor())(pose) + jac_fd = _fd_jacobian(lambda x: pp.SE3(x).Log().tensor(), pose) + + torch.testing.assert_close(jac, jac_fd, rtol=1e-7, atol=1e-7) + + +def test_pypose_se3_inv_monkeypatch_produces_ambient_gradient(): + install_pypose_ambient_grad_monkeypatch() + device = torch.device("cuda" if torch.cuda.is_available() else "cpu") + dtype = torch.float64 + + pose = pp.randn_SE3(1, sigma=0.2, device=device).tensor().to(dtype=dtype) + + jac = torch.func.jacrev(lambda x: pp.SE3(x).Inv().tensor())(pose) + jac_fd = _fd_jacobian(lambda x: pp.SE3(x).Inv().tensor(), pose) + + torch.testing.assert_close(jac, jac_fd, rtol=1e-7, atol=1e-7)